EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
RosSubscriberDouble.hpp
Go to the documentation of this file.
1 #ifndef ORG_EEROS_CONTROL_ROSSUBSCRIBER_DOUBLE_HPP
2 #define ORG_EEROS_CONTROL_ROSSUBSCRIBER_DOUBLE_HPP
3 
5 #include <eeros/core/System.hpp>
6 #include <std_msgs/Float64.h>
7 
8 namespace eeros {
9  namespace control {
10 
11  class RosSubscriberDouble : public RosSubscriber<std_msgs::Float64::Type, double> {
12  typedef std_msgs::Float64::Type TRosMsg;
13  public:
14  RosSubscriberDouble(const std::string& topic, const uint32_t queueSize=1000, const bool callNewest=false ) :
15  RosSubscriber<TRosMsg, double>(topic, queueSize, callNewest){ }
16 
17  void rosCallbackFct(const TRosMsg& msg) {
18  auto time = eeros::System::getTimeNs(); // use system time for timestamp
19  this->out.getSignal().setTimestamp( time );
20  this->out.getSignal().setValue(static_cast<double>(msg.data) );
21  }
22  };
23  };
24 };
25 
26 #endif // ORG_EEROS_CONTROL_ROSSUBSCRIBER_DOUBLE_HPP
virtual Signal< T > & getSignal()
Definition: Output.hpp:16
Definition: Config.hpp:14
static uint64_t getTimeNs()
Definition: System_POSIX.cpp:41
virtual void setValue(T newValue)
Definition: Signal.hpp:53
Output< double > out
Definition: Block1o.hpp:23
Type
Definition: HALFeatures.hpp:14
RosSubscriberDouble(const std::string &topic, const uint32_t queueSize=1000, const bool callNewest=false)
Definition: RosSubscriberDouble.hpp:14
const std::string & topic
Definition: RosSubscriber.hpp:51
virtual void setTimestamp(timestamp_t newTimestamp)
Definition: Signal.hpp:66
Definition: RosSubscriber.hpp:14
void rosCallbackFct(const TRosMsg &msg)
Definition: RosSubscriberDouble.hpp:17
Definition: RosSubscriberDouble.hpp:11