TypedSubscriber.h
Go to the documentation of this file.
00001 #ifndef CONVENIENCE_ROS_FUNCTIONS_TYPEDSUBSCRIBER_H
00002 #define CONVENIENCE_ROS_FUNCTIONS_TYPEDSUBSCRIBER_H
00003 
00004 #include <ros/ros.h>
00005 #include <baselib_binding/Thread.h>
00006 
00007 #include <map>
00008 
00009 namespace convenience_ros_functions {
00010 
00018 template<class MessageType>
00019 class TypedSubscriber {
00020 private:
00021     typedef TypedSubscriber<MessageType> Self;
00022 public:
00025     TypedSubscriber(ros::NodeHandle& _node):
00026         node(_node),
00027         running(false),
00028         subscriberActive(false),
00029         lastUpdateTime(0)
00030     {}
00031 
00032     ~TypedSubscriber(){}
00033 
00034     void start(const std::string& _topic);
00035 
00036     void stop();
00037 
00045     void setActive(bool flag);
00046 
00052     bool isActive() const;
00053     
00058     bool isRunning() const;
00059 
00064     bool getLastMessage(MessageType& msg) const;
00065 
00075     bool waitForNextMessage(MessageType& msg, float timeout = -1, float wait_step=0.05) const;
00076 
00077 private:
00078     typedef baselib_binding::recursive_mutex recursive_mutex;
00079     typedef baselib_binding::mutex mutex;
00080     typedef baselib_binding::unique_lock<mutex>::type unique_lock;
00081     typedef baselib_binding::unique_lock<recursive_mutex>::type unique_recursive_lock;
00082     typedef baselib_binding::condition_variable condition_variable;
00083 
00084     ros::Time getLastUpdateTime() const;
00085 
00086     void msgCallback(const MessageType& _msg);
00087 
00088     // mutex to be used for all excepte messageArrivedCondition.
00089     // has to be locked *after* messageArrivedCondition *always*.
00090     mutable recursive_mutex generalMutex;
00091     
00092     mutable condition_variable messageArrivedCondition;
00093     // mutex to be used for messageArrivedCondition
00094     mutable mutex messageArrivedMutex;
00095     
00096     MessageType lastArrivedMessage;
00097     
00098     ros::Time lastUpdateTime;
00099 
00100     bool running;        
00101     bool subscriberActive;
00102 
00103     std::string topic;
00104 
00105     ros::NodeHandle& node;
00106 
00107     ros::Subscriber sub;
00108 };
00109 
00110 #include <convenience_ros_functions/TypedSubscriber.hpp>
00111 
00112 }
00113 
00114 #endif  // CONVENIENCE_ROS_FUNCTIONS_TYPEDSUBSCRIBER_H


convenience_ros_functions
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:21:42