GenericSubscriber.hpp
Go to the documentation of this file.
00001 /*
00002  * GenericSubscriber.hpp
00003  *
00004  *  Created on: Feb 29, 2012
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef GENERICSUBSCRIBER_HPP_
00009 #define GENERICSUBSCRIBER_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 #include <boost/thread/mutex.hpp>
00013 
00014 #include <ros/node_handle.h>
00015 
00016 namespace TELEKYB_NAMESPACE
00017 {
00018 
00019 template <class T_>
00020 class GenericSubscriber {
00021 protected:
00022         T_ lastMsg;
00023         boost::mutex lastMsgLock;
00024 
00025         // Subscriber
00026         ros::Subscriber sub;
00027 
00028         void msgCallback(boost::shared_ptr<T_ const> msg) {
00029                 boost::mutex::scoped_lock(lastMsgLock);
00030                 lastMsg = *msg; // copy
00031         }
00032 
00033 public:
00034         GenericSubscriber(ros::NodeHandle handle, const std::string& topicName, int queue_size) {
00035                 sub = handle.subscribe(topicName, queue_size, &GenericSubscriber<T_>::msgCallback, this);
00036         }
00037 
00038         virtual ~GenericSubscriber() {};
00039 
00040         T_ getLastMsg() const {
00041                 boost::mutex::scoped_lock(lastMsgLock);
00042                 return lastMsg; // implicit copy. Maybe we can do this more efficient?
00043         }
00044 };
00045 
00046 }
00047 
00048 #endif /* GENERICSUBSCRIBER_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_base
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:12:34