EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
RosPublisher.hpp
Go to the documentation of this file.
1 #ifndef ORG_EEROS_CONTROL_ROSPUBLISHER_HPP_
2 #define ORG_EEROS_CONTROL_ROSPUBLISHER_HPP_
3 
4 #include <ros/ros.h>
5 #include <ros/callback_queue.h>
6 // #include <eeros/core/System.hpp>
9 
10 namespace eeros {
11  namespace control {
12  template < typename TRosMsg, typename SigInType >
13  class RosPublisher : public Block1i<SigInType> {
14 
15  public:
16  RosPublisher(const std::string& topic, uint32_t queueSize=1000, bool callNewest=false) :
17  topic (topic)
18 // callNewest(callNewest)
19  {
20  ros::NodeHandle handle;
21  publisher = handle.advertise<TRosMsg>(topic, queueSize);
22  ROS_DEBUG_STREAM("RosBlockPublisher, reading from topic: '" << topic << "' created.");
23  }
24 
25  virtual void setRosMsg( TRosMsg& msg ) = 0;
26 
27  void run() {
28  setRosMsg(msg);
29  publisher.publish(msg);
30  }
31 
32 
33  protected:
34  ros::Publisher publisher;
35  const std::string& topic;
36 // bool callNewest;
37  TRosMsg msg;
38 
39  private:
40  };
41  }
42 }
43 
44 #endif /* ORG_EEROS_CONTROL_ROSPUBLISHER_HPP_ */
Definition: Block1i.hpp:12
virtual void setRosMsg(TRosMsg &msg)=0
Definition: Config.hpp:14
Definition: RosPublisher.hpp:13
ros::Publisher publisher
Definition: RosPublisher.hpp:34
TRosMsg msg
Definition: RosPublisher.hpp:37
const std::string & topic
Definition: RosPublisher.hpp:35
void run()
Definition: RosPublisher.hpp:27
RosPublisher(const std::string &topic, uint32_t queueSize=1000, bool callNewest=false)
Definition: RosPublisher.hpp:16