shm_subscriber.hpp
Go to the documentation of this file.
00001 #ifndef __SHM_SUBSCRIBER_HPP__
00002 #define __SHM_SUBSCRIBER_HPP__
00003 
00004 #include <boost/interprocess/managed_shared_memory.hpp>
00005 #include "ros/ros.h"
00006 #include "std_msgs/UInt64.h"
00007 #include "shm_object.hpp"
00008 
00009 namespace shm_transport
00010 {
00011 
00012 class Topic;
00013 
00014 template <class M>
00015 class Subscriber;
00016 
00017 template < class M >
00018 class SubscriberCallbackHelper
00019 {
00020   typedef void (*Func)(const boost::shared_ptr< const M > &);
00021 
00022 public:
00023   ~SubscriberCallbackHelper() {
00024   }
00025 
00026   void callback(const std_msgs::UInt64::ConstPtr & actual_msg) {
00027     if (!pobj_) {
00028       // If suscriber runs first, it will not die due to these code.
00029       mng_shm * pshm = new mng_shm(boost::interprocess::open_only, name_.c_str());
00030       pobj_ = ShmObjectPtr(new ShmObject(pshm, name_));
00031     }
00032     // get shm message
00033     ShmMessage * ptr = (ShmMessage *)pobj_->pshm_->get_address_from_handle(actual_msg->data);
00034     // take shm message
00035     ptr->take();
00036     // deserialize data
00037     boost::shared_ptr< M > msg(new M());
00038     ros::serialization::IStream in(ptr->data, ptr->len);
00039     ros::serialization::deserialize(in, *msg);
00040     // release shm message
00041     ptr->release();
00042     // call user callback
00043     fp_(msg);
00044   }
00045 
00046 private:
00047   SubscriberCallbackHelper(const std::string &topic, Func fp)
00048     : pobj_(), name_(topic), fp_(fp) {
00049     // change '/' in topic to '_'
00050     for (int i = 0; i < name_.length(); i++)
00051       if (name_[i] == '/')
00052         name_[i] = '_';
00053   }
00054 
00055   ShmObjectPtr pobj_;
00056   std::string name_;
00057   Func fp_;
00058 
00059 friend class Topic;
00060 friend class Subscriber<M>;
00061 };
00062 
00063 template <class M>
00064 class Subscriber
00065 {
00066 public:
00067   Subscriber() {
00068   }
00069 
00070   ~Subscriber() {
00071   }
00072 
00073   Subscriber(const Subscriber & s) {
00074     *this = s;
00075   }
00076 
00077   Subscriber & operator = (const Subscriber & s) {
00078     sub_ = s.sub_;
00079     phlp_ = s.phlp_;
00080     return *this;
00081   }
00082 
00083   void shutdown() {
00084     sub_.shutdown();
00085   }
00086 
00087   std::string getTopic() const {
00088     return sub_.getTopic();
00089   }
00090 
00091   uint32_t getNumPublishers() const {
00092     return sub_.getNumPublishers();
00093   }
00094 
00095 private:
00096   Subscriber(const ros::Subscriber & sub, SubscriberCallbackHelper< M > * phlp)
00097       : sub_(sub), phlp_(phlp) {
00098   }
00099 
00100   ros::Subscriber sub_;
00101   boost::shared_ptr< SubscriberCallbackHelper< M > > phlp_;
00102 
00103 friend class Topic;
00104 };
00105 
00106 } // namespace shm_transport
00107 
00108 #endif // __SHM_SUBSCRIBER_HPP__
00109 


shm_transport
Author(s): Jrdevil-Wang , Wende Tan
autogenerated on Thu Jun 6 2019 18:47:43