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/thread/mutex.hpp>
39 #include <boost/thread/recursive_mutex.hpp>
40 
41 namespace ros
42 {
43 
44 class Message;
45 struct SubscribeOptions;
46 struct AdvertiseOptions;
47 
48 class TopicManager;
50 
51 class PollManager;
53 
54 class XMLRPCManager;
56 
57 class ConnectionManager;
59 
60 class SubscriptionCallbackHelper;
62 
63 class ROSCPP_DECL TopicManager
64 {
65 public:
66  static const TopicManagerPtr& instance();
67 
68  TopicManager();
69  ~TopicManager();
70 
71  void start();
72  void shutdown();
73 
74  bool subscribe(const SubscribeOptions& ops);
75  bool unsubscribe(const std::string &_topic, const SubscriptionCallbackHelperPtr& helper);
76 
77  bool advertise(const AdvertiseOptions& ops, const SubscriberCallbacksPtr& callbacks);
78  bool unadvertise(const std::string &topic, const SubscriberCallbacksPtr& callbacks);
79 
84  void getAdvertisedTopics(V_string& topics);
85 
90  void getSubscribedTopics(V_string& topics);
91 
102  PublicationPtr lookupPublication(const std::string& topic);
103 
110  size_t getNumSubscribers(const std::string &_topic);
111  size_t getNumSubscriptions();
112 
119  size_t getNumPublishers(const std::string &_topic);
120 
121  template<typename M>
122  void publish(const std::string& topic, const M& message)
123  {
124  using namespace serialization;
125 
127  publish(topic, boost::bind(serializeMessage<M>, boost::ref(message)), m);
128  }
129 
130  void publish(const std::string &_topic, const boost::function<SerializedMessage(void)>& serfunc, SerializedMessage& m);
131 
132  void incrementSequence(const std::string &_topic);
133  bool isLatched(const std::string& topic);
134 
135 private:
141  bool addSubCallback(const SubscribeOptions& ops);
142 
155  bool requestTopic(const std::string &topic, XmlRpc::XmlRpcValue &protos, XmlRpc::XmlRpcValue &ret);
156 
157  // Must lock the advertised topics mutex before calling this function
158  bool isTopicAdvertised(const std::string& topic);
159 
160  bool registerSubscriber(const SubscriptionPtr& s, const std::string& datatype);
161  bool unregisterSubscriber(const std::string& topic);
162  bool unregisterPublisher(const std::string& topic);
163 
164  PublicationPtr lookupPublicationWithoutLock(const std::string &topic);
165 
166  void processPublishQueues();
167 
174  void getBusStats(XmlRpc::XmlRpcValue &stats);
175 
182  void getBusInfo(XmlRpc::XmlRpcValue &info);
183 
190  void getSubscriptions(XmlRpc::XmlRpcValue &subscriptions);
191 
198  void getPublications(XmlRpc::XmlRpcValue &publications);
199 
210  bool pubUpdate(const std::string &topic, const std::vector<std::string> &pubs);
211 
212  void pubUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
213  void requestTopicCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
214  void getBusStatsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
215  void getBusInfoCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
216  void getSubscriptionsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
217  void getPublicationsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
218 
219  bool isShuttingDown() { return shutting_down_; }
220 
221  boost::mutex subs_mutex_;
223 
224  boost::recursive_mutex advertised_topics_mutex_;
226  std::list<std::string> advertised_topic_names_;
228 
229  volatile bool shutting_down_;
230  boost::mutex shutting_down_mutex_;
231 
232  PollManagerPtr poll_manager_;
233  ConnectionManagerPtr connection_manager_;
234  XMLRPCManagerPtr xmlrpc_manager_;
235 };
236 
237 } // namespace ros
238 
239 #endif // ROSCPP_TOPIC_MANAGER_H
XMLRPCManagerPtr xmlrpc_manager_
volatile bool shutting_down_
std::list< std::string > advertised_topic_names_
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
Definition: init.cpp:293
boost::mutex subs_mutex_
L_Subscription subscriptions_
XmlRpcServer s
boost::shared_ptr< XMLRPCManager > XMLRPCManagerPtr
Definition: forwards.h:194
PollManagerPtr poll_manager_
Encapsulates all options available for creating a Publisher.
std::vector< PublicationPtr > V_Publication
Definition: forwards.h:68
boost::shared_ptr< SubscriptionCallbackHelper > SubscriptionCallbackHelperPtr
boost::shared_ptr< ConnectionManager > ConnectionManagerPtr
boost::mutex shutting_down_mutex_
boost::shared_ptr< TopicManager > TopicManagerPtr
Definition: forwards.h:190
std::vector< std::string > V_string
const char * datatype()
boost::mutex advertised_topic_names_mutex_
Encapsulates all options available for creating a Subscriber.
V_Publication advertised_topics_
ROSCPP_DECL void getSubscribedTopics(V_string &topics)
Get the list of topics subscribed to by this node.
Definition: this_node.cpp:89
ROSCPP_DECL void getAdvertisedTopics(V_string &topics)
Get the list of topics advertised by this node.
Definition: this_node.cpp:84
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:594
std::list< SubscriptionPtr > L_Subscription
Definition: forwards.h:75
void publish(const std::string &topic, const M &message)
boost::shared_ptr< PollManager > PollManagerPtr
boost::recursive_mutex advertised_topics_mutex_
ConnectionManagerPtr connection_manager_


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:27