Go to the documentation of this file.00001 #ifndef __SHM_TOPIC_HPP__
00002 #define __SHM_TOPIC_HPP__
00003
00004 #include "ros/ros.h"
00005 #include "shm_publisher.hpp"
00006 #include "shm_subscriber.hpp"
00007
00008 namespace shm_transport
00009 {
00010
00011 class Topic
00012 {
00013 public:
00014 Topic(const ros::NodeHandle & parent) {
00015 nh_ = parent;
00016 }
00017
00018 ~Topic() {
00019 }
00020
00021 template < class M >
00022 Publisher advertise(const std::string & topic, uint32_t queue_size, uint32_t mem_size) {
00023 ros::Publisher pub = nh_.advertise< std_msgs::UInt64 >(topic, queue_size);
00024 return Publisher(pub, topic, mem_size);
00025 }
00026
00027 template < class M >
00028 Subscriber< M > subscribe(const std::string & topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< const M > &)) {
00029 SubscriberCallbackHelper< M > * phlp = new SubscriberCallbackHelper< M >(topic, fp);
00030 ros::Subscriber sub = nh_.subscribe(topic, queue_size, &SubscriberCallbackHelper< M >::callback, phlp);
00031 return Subscriber< M >(sub, phlp);
00032 }
00033
00034 private:
00035 ros::NodeHandle nh_;
00036 };
00037
00038 }
00039
00040 #endif // __SHM_TOPIC_HPP__
00041
00042