topic_manager.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_TOPIC_MANAGER_H
29 #define ROSCPP_TOPIC_MANAGER_H
30 
31 #include "forwards.h"
32 #include "common.h"
33 #include "ros/serialization.h"
34 #include "rosout_appender.h"
35 
36 #include "xmlrpcpp/XmlRpcValue.h"
37 
38 #include <boost/bind/bind.hpp>
39 #include <boost/thread/mutex.hpp>
40 #include <boost/thread/recursive_mutex.hpp>
41 
42 namespace ros
43 {
44 
45 class Message;
46 struct SubscribeOptions;
47 struct AdvertiseOptions;
48 
49 class TopicManager;
51 
52 class PollManager;
54 
55 class XMLRPCManager;
57 
58 class ConnectionManager;
60 
61 class SubscriptionCallbackHelper;
63 
64 class ROSCPP_DECL TopicManager
65 {
66 public:
67  static const TopicManagerPtr& instance();
68 
69  TopicManager();
70  ~TopicManager();
71 
72  void start();
73  void shutdown();
74 
75  bool subscribe(const SubscribeOptions& ops);
76  bool unsubscribe(const std::string &_topic, const SubscriptionCallbackHelperPtr& helper);
77 
78  bool advertise(const AdvertiseOptions& ops, const SubscriberCallbacksPtr& callbacks);
79  bool unadvertise(const std::string &topic, const SubscriberCallbacksPtr& callbacks);
80 
85  void getAdvertisedTopics(V_string& topics);
86 
91  void getSubscribedTopics(V_string& topics);
92 
103  PublicationPtr lookupPublication(const std::string& topic);
104 
111  size_t getNumSubscribers(const std::string &_topic);
112  size_t getNumSubscriptions();
113 
120  size_t getNumPublishers(const std::string &_topic);
121 
122  template<typename M>
123  void publish(const std::string& topic, const M& message)
124  {
125  using namespace serialization;
126 
128  publish(topic, boost::bind(serializeMessage<M>, boost::ref(message)), m);
129  }
130 
131  void publish(const std::string &_topic, const boost::function<SerializedMessage(void)>& serfunc, SerializedMessage& m);
132 
133  void incrementSequence(const std::string &_topic);
134  bool isLatched(const std::string& topic);
135 
136 private:
142  bool addSubCallback(const SubscribeOptions& ops);
143 
156  bool requestTopic(const std::string &topic, XmlRpc::XmlRpcValue &protos, XmlRpc::XmlRpcValue &ret);
157 
158  // Must lock the advertised topics mutex before calling this function
159  bool isTopicAdvertised(const std::string& topic);
160 
161  bool registerSubscriber(const SubscriptionPtr& s, const std::string& datatype);
162  bool unregisterSubscriber(const std::string& topic);
163  bool unregisterPublisher(const std::string& topic);
164 
165  PublicationPtr lookupPublicationWithoutLock(const std::string &topic);
166 
167  void processPublishQueues();
168 
175  void getBusStats(XmlRpc::XmlRpcValue &stats);
176 
183  void getBusInfo(XmlRpc::XmlRpcValue &info);
184 
191  void getSubscriptions(XmlRpc::XmlRpcValue &subscriptions);
192 
199  void getPublications(XmlRpc::XmlRpcValue &publications);
200 
211  bool pubUpdate(const std::string &topic, const std::vector<std::string> &pubs);
212 
213  void pubUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
214  void requestTopicCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
215  void getBusStatsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
216  void getBusInfoCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
217  void getSubscriptionsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
218  void getPublicationsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
219 
220  bool isShuttingDown() { return shutting_down_; }
221 
222  boost::mutex subs_mutex_;
224 
225  boost::recursive_mutex advertised_topics_mutex_;
227  std::list<std::string> advertised_topic_names_;
229 
230  volatile bool shutting_down_;
231  boost::mutex shutting_down_mutex_;
232 
236 };
237 
238 } // namespace ros
239 
240 #endif // ROSCPP_TOPIC_MANAGER_H
ros::SubscriptionCallbackHelperPtr
boost::shared_ptr< SubscriptionCallbackHelper > SubscriptionCallbackHelperPtr
Definition: message_deserializer.h:42
ros::SerializedMessage
ros::TopicManager::poll_manager_
PollManagerPtr poll_manager_
Definition: topic_manager.h:233
boost::shared_ptr< TopicManager >
forwards.h
ros
ros::shutdown
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:608
ros::TopicManager::subs_mutex_
boost::mutex subs_mutex_
Definition: topic_manager.h:222
ros::TopicManager::advertised_topic_names_
std::list< std::string > advertised_topic_names_
Definition: topic_manager.h:227
ros::AdvertiseOptions
Encapsulates all options available for creating a Publisher.
Definition: advertise_options.h:41
ros::TopicManager::connection_manager_
ConnectionManagerPtr connection_manager_
Definition: topic_manager.h:234
ros::TopicManager::subscriptions_
L_Subscription subscriptions_
Definition: topic_manager.h:223
ros::TopicManager::advertised_topics_
V_Publication advertised_topics_
Definition: topic_manager.h:226
serialization.h
ros::V_Publication
std::vector< PublicationPtr > V_Publication
Definition: forwards.h:68
XmlRpcValue.h
ros::TopicManagerPtr
boost::shared_ptr< TopicManager > TopicManagerPtr
Definition: forwards.h:191
ros::TopicManager::shutting_down_mutex_
boost::mutex shutting_down_mutex_
Definition: topic_manager.h:231
ros::start
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
Definition: init.cpp:294
ros::TopicManager::publish
void publish(const std::string &topic, const M &message)
Definition: topic_manager.h:123
ros::TopicManager::advertised_topic_names_mutex_
boost::mutex advertised_topic_names_mutex_
Definition: topic_manager.h:228
ros::SubscribeOptions
Encapsulates all options available for creating a Subscriber.
Definition: subscribe_options.h:43
ros::ConnectionManagerPtr
boost::shared_ptr< ConnectionManager > ConnectionManagerPtr
Definition: connection_manager.h:41
ros::this_node::getAdvertisedTopics
ROSCPP_DECL void getAdvertisedTopics(V_string &topics)
Get the list of topics advertised by this node.
Definition: this_node.cpp:84
ros::TopicManager
Definition: topic_manager.h:64
rosout_appender.h
ros::V_string
std::vector< std::string > V_string
ros::PollManagerPtr
boost::shared_ptr< PollManager > PollManagerPtr
Definition: connection_manager.h:38
ros::TopicManager::xmlrpc_manager_
XMLRPCManagerPtr xmlrpc_manager_
Definition: topic_manager.h:235
ros::this_node::getSubscribedTopics
ROSCPP_DECL void getSubscribedTopics(V_string &topics)
Get the list of topics subscribed to by this node.
Definition: this_node.cpp:89
ros::XMLRPCManagerPtr
boost::shared_ptr< XMLRPCManager > XMLRPCManagerPtr
Definition: forwards.h:195
ros::TopicManager::shutting_down_
volatile bool shutting_down_
Definition: topic_manager.h:230
ros::TopicManager::advertised_topics_mutex_
boost::recursive_mutex advertised_topics_mutex_
Definition: topic_manager.h:225
XmlRpc::XmlRpcValue
ros::L_Subscription
std::list< SubscriptionPtr > L_Subscription
Definition: forwards.h:75
ros::TopicManager::isShuttingDown
bool isShuttingDown()
Definition: topic_manager.h:220


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Tue May 20 2025 03:00:11