EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
RosPublisherDouble.hpp
Go to the documentation of this file.
1 #ifndef ORG_EEROS_CONTROL_ROSPUBLISHER_DOUBLE_HPP_
2 #define ORG_EEROS_CONTROL_ROSPUBLISHER_DOUBLE_HPP_
3 
4 #include <eeros/core/System.hpp>
6 #include <std_msgs/Float64.h>
7 
8 namespace eeros {
9  namespace control {
10 
11  class RosPublisherDouble : public RosPublisher<std_msgs::Float64::Type, double> {
12  typedef std_msgs::Float64::Type TRosMsg;
13  public:
14  RosPublisherDouble (const std::string& topic, const uint32_t queueSize=1000) :
15  RosPublisher<TRosMsg, double>(topic, queueSize) { }
16 
17  void setRosMsg(TRosMsg& msg) {
18  msg.data = in.getSignal().getValue();
19 // msg.header.stamp.sec = eeros::System::getTime();
20 // msg.header.stamp.nsec = eeros::System::getTimeNs() % static_cast<uint64_t>(1e9);
21  }
22  };
23  };
24 };
25 
26 #endif /* ORG_EEROS_CONTROL_ROSPUBLISHER_DOUBLE_HPP_ */
virtual T getValue() const
Definition: Signal.hpp:49
Definition: Config.hpp:14
Type
Definition: HALFeatures.hpp:14
Definition: RosPublisher.hpp:13
virtual Signal< T > & getSignal()
Definition: Input.hpp:38
std_msgs::Float64::Type msg
Definition: RosPublisher.hpp:37
const std::string & topic
Definition: RosPublisher.hpp:35
RosPublisherDouble(const std::string &topic, const uint32_t queueSize=1000)
Definition: RosPublisherDouble.hpp:14
Definition: RosPublisherDouble.hpp:11
void setRosMsg(TRosMsg &msg)
Definition: RosPublisherDouble.hpp:17
Input< double > in
Definition: Block1i.hpp:21