topic_manager.h
Go to the documentation of this file.
00001 #ifndef ROSRTT_TOPIC_MANAGER_H
00002 #define ROSRTT_TOPIC_MANAGER_H
00003 
00004 #include "ros/ros.h"
00005 #include "common.h"
00006 #include "hpcl_rtt/publication.h"
00007 #include "hpcl_rtt/subscription.h"
00008 #include "hpcl_rtt/connection_base.h"
00009 #include "hpcl_rtt/oro/connection_factory.hpp"
00010 
00011 namespace hpcl_rtt
00012 {
00013 class TopicManager;
00014 typedef boost::shared_ptr<TopicManager> TopicManagerPtr;
00015 
00016 class TopicManager
00017 {
00018 public:
00019   TopicManager();
00020   ~TopicManager();
00021   static const TopicManagerPtr& instance();
00022 
00023   template<class M> 
00024   ConnectionBasePtr advertise(const std::string topic)
00025   {
00026     ConnectionBasePtr pub;
00027     pub = lookupPublication(topic);
00028     if (pub) 
00029     {
00030       return pub;
00031     }
00032 
00033     pub.reset(new Publication<M>(topic));
00034     advertised_topics_.push_back(pub);
00035 
00036     // check whether we've already subscribed to this topic.
00037     bool found = false;
00038     ConnectionBasePtr sub;
00039     {
00040       V_ConnectionBase::iterator s;
00041       for (s = subscriptions_.begin(); s != subscriptions_.end() && !found; ++s) 
00042       {
00043         if ((*s)->getTopic() == topic) 
00044         {
00045           found = true;
00046           sub = *s;
00047           break;
00048         }
00049       }
00050     }
00051 
00052     if (found) 
00053     {
00054       ConnFactory::createConnection<M>(pub, sub);
00055     }
00056 
00057     return pub;
00058   }
00059   //template<class M> bool unadvertise(const std::string topic);
00060 
00061   template<class M> 
00062   ConnectionBasePtr subscribe(const std::string& topic, void(*fp)(M))
00063   {
00064     boost::function<void(M)> callback = fp;
00065     boost::shared_ptr< Subscription<M> > s(new Subscription<M>(topic, callback));
00066 
00067     //add local connection
00068     bool self_subscribed = false;
00069     ConnectionBasePtr pub;
00070     V_ConnectionBase::const_iterator it = advertised_topics_.begin();
00071     V_ConnectionBase::const_iterator end = advertised_topics_.end();
00072     for (; it != end; ++it)
00073     {
00074       pub = *it;
00075 
00076       if (pub->getTopic() == s->getTopic())
00077       {
00078         ROS_INFO("find topic.");
00079         self_subscribed = true;
00080         break;
00081       }
00082     }
00083     if (self_subscribed)
00084     {
00085       if (ConnFactory::createConnection<M>(pub, s))
00086         ROS_INFO("connected.");
00087     }
00088 
00089     subscriptions_.push_back(s);
00090     
00091     return s;
00092   }
00093   //bool unsubscribe(const std::string& topic, const std::string& data_type);
00094   
00095   ConnectionBasePtr lookupPublication(const std::string& topic);
00096   
00097 private:
00098   V_ConnectionBase advertised_topics_;
00099   V_ConnectionBase subscriptions_;
00100 
00101 };
00102 
00103 }
00104 
00105 #endif


hpcl_rtt
Author(s): sukha
autogenerated on Thu Aug 27 2015 16:43:53