1 #ifndef ORG_EEROS_CONTROL_ROSSUBCRIBER_HPP_ 2 #define ORG_EEROS_CONTROL_ROSSUBCRIBER_HPP_ 5 #include <ros/callback_queue.h> 13 template <
typename TRosMsg,
typename SigOutType >
21 ros::NodeHandle handle;
23 ROS_DEBUG_STREAM(
"RosBlockSubscriber, reading from topic: '" << topic <<
"' created.");
43 ros::getGlobalCallbackQueue()->callAvailable();
45 ros::getGlobalCallbackQueue()->callOne();
virtual void rosCallbackFct(const TRosMsg &msg)=0
RosSubscriber(const std::string &topic, const uint32_t queueSize=1000, const bool callNewest=false)
Definition: RosSubscriber.hpp:17
bool callNewest
Definition: RosSubscriber.hpp:52
Definition: Block1o.hpp:12
Definition: Config.hpp:14
ros::Subscriber subscriber
Definition: RosSubscriber.hpp:50
virtual void run()
Definition: RosSubscriber.hpp:41
const std::string & topic
Definition: RosSubscriber.hpp:51
Definition: RosSubscriber.hpp:14