Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #include "micros_rtt/topic_manager.h"
00020
00021 namespace micros_rtt
00022 {
00023
00024 TopicManagerPtr g_topic_manager;
00025
00026 const TopicManagerPtr& TopicManager::instance()
00027 {
00028 if (!g_topic_manager)
00029 {
00030 if (!g_topic_manager)
00031 {
00032 g_topic_manager.reset(new TopicManager);
00033 }
00034 }
00035
00036 return g_topic_manager;
00037 }
00038
00039 TopicManager::TopicManager()
00040 {
00041 xmlrpc_manager_ = ros::XMLRPCManager::instance();
00042
00043 ROS_WARN("Bind my own pubUpdateCallback");
00044 xmlrpc_manager_->unbind("publisherUpdate");
00045 xmlrpc_manager_->bind("publisherUpdate", boost::bind(&TopicManager::pubUpdateCallback, this, _1, _2));
00046 xmlrpc_manager_->unbind("requestTopic");
00047 xmlrpc_manager_->bind("requestTopic", boost::bind(&TopicManager::pubUpdateCallback, this, _1, _2));
00048 }
00049
00050 TopicManager::~TopicManager()
00051 {
00052 }
00053
00054 bool TopicManager::advertise(const std::string& topic, const std::string& data_type, uint32_t queue_size)
00055 {
00056 if (data_type == "*")
00057 {
00058 std::stringstream ss;
00059 ss << "Advertising with * as the datatype is not allowed. Topic [" << topic << "]";
00060 }
00061
00062 XmlRpc::XmlRpcValue args, result, payload;
00063 args[0] = ros::this_node::getName();
00064 args[1] = topic;
00065 args[2] = data_type;
00066 args[3] = xmlrpc_manager_->getServerURI();
00067 ros::master::execute("registerPublisher", args, result, payload, true);
00068
00069 return true;
00070 }
00071
00072 void TopicManager::addPubConnection(ConnectionBasePtr pub_connection)
00073 {
00074
00075 advertised_topics_.push_back(pub_connection);
00076 }
00077
00078 void TopicManager::addSubConnection(ConnectionBasePtr sub_connection)
00079 {
00080
00081 subscriptions_.push_back(sub_connection);
00082 }
00083
00084 ConnectionBasePtr TopicManager::findSubConnection(const std::string& topic)
00085 {
00086
00087 ConnectionBasePtr sub;
00088
00089 for (V_ConnectionBase::iterator s = subscriptions_.begin();
00090 s != subscriptions_.end(); ++s)
00091 {
00092 sub = *s;
00093 if (sub->getTopic() == topic)
00094 {
00095 break;
00096 }
00097 }
00098
00099 return sub;
00100 }
00101
00102 ConnectionBasePtr TopicManager::findPubConnection(const std::string& topic)
00103 {
00104 ConnectionBasePtr pub;
00105 for (V_ConnectionBase::iterator i = advertised_topics_.begin();
00106 !pub && i != advertised_topics_.end();
00107 ++i)
00108 {
00109 if ((*i)->getTopic() == topic)
00110 {
00111 pub = *i;
00112 break;
00113 }
00114 }
00115
00116 return pub;
00117 }
00118
00119
00120 void TopicManager::pubUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
00121 {
00122 ROS_WARN("Bind my own pubUpdateCallback");
00123 }
00124
00125 void TopicManager::requestTopicCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
00126 {
00127
00128 ConnFactory::createStream<M>(pub_connection, true);
00129 }
00130
00131 }
00132