master.cpp
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 #include "ros/master.h"
29 #include "ros/xmlrpc_manager.h"
30 #include "ros/this_node.h"
31 #include "ros/init.h"
32 #include "ros/network.h"
33 
34 #include <ros/console.h>
35 #include <ros/assert.h>
36 
37 #include "xmlrpcpp/XmlRpc.h"
38 
39 namespace ros
40 {
41 
42 namespace master
43 {
44 
45 uint32_t g_port = 0;
46 std::string g_host;
47 std::string g_uri;
49 
50 void init(const M_string& remappings)
51 {
52  M_string::const_iterator it = remappings.find("__master");
53  if (it != remappings.end())
54  {
55  g_uri = it->second;
56  }
57 
58  if (g_uri.empty())
59  {
60  char *master_uri_env = NULL;
61  #ifdef _MSC_VER
62  _dupenv_s(&master_uri_env, NULL, "ROS_MASTER_URI");
63  #else
64  master_uri_env = getenv("ROS_MASTER_URI");
65  #endif
66  if (!master_uri_env)
67  {
68  ROS_FATAL( "ROS_MASTER_URI is not defined in the environment. Either " \
69  "type the following or (preferrably) add this to your " \
70  "~/.bashrc file in order set up your " \
71  "local machine as a ROS master:\n\n" \
72  "export ROS_MASTER_URI=http://localhost:11311\n\n" \
73  "then, type 'roscore' in another shell to actually launch " \
74  "the master program.");
75  ROS_BREAK();
76  }
77 
78  g_uri = master_uri_env;
79 
80 #ifdef _MSC_VER
81  // http://msdn.microsoft.com/en-us/library/ms175774(v=vs.80).aspx
82  free(master_uri_env);
83 #endif
84  }
85 
86  // Split URI into
87  if (!network::splitURI(g_uri, g_host, g_port))
88  {
89  ROS_FATAL( "Couldn't parse the master URI [%s] into a host:port pair.", g_uri.c_str());
90  ROS_BREAK();
91  }
92 }
93 
94 const std::string& getHost()
95 {
96  return g_host;
97 }
98 
99 uint32_t getPort()
100 {
101  return g_port;
102 }
103 
104 const std::string& getURI()
105 {
106  return g_uri;
107 }
108 
110 {
111  if (timeout < ros::WallDuration(0))
112  {
113  ROS_FATAL("retry timeout must not be negative.");
114  ROS_BREAK();
115  }
116  g_retry_timeout = timeout;
117 }
118 
119 bool check()
120 {
121  XmlRpc::XmlRpcValue args, result, payload;
122  args[0] = this_node::getName();
123  return execute("getPid", args, result, payload, false);
124 }
125 
126 bool getTopics(V_TopicInfo& topics)
127 {
128  XmlRpc::XmlRpcValue args, result, payload;
129  args[0] = this_node::getName();
130  args[1] = ""; //TODO: Fix this
131 
132  if (!execute("getPublishedTopics", args, result, payload, true))
133  {
134  return false;
135  }
136 
137  topics.clear();
138  for (int i = 0; i < payload.size(); i++)
139  {
140  topics.push_back(TopicInfo(std::string(payload[i][0]), std::string(payload[i][1])));
141  }
142 
143  return true;
144 }
145 
146 bool getNodes(V_string& nodes)
147 {
148  XmlRpc::XmlRpcValue args, result, payload;
149  args[0] = this_node::getName();
150 
151  if (!execute("getSystemState", args, result, payload, true))
152  {
153  return false;
154  }
155 
156  S_string node_set;
157  for (int i = 0; i < payload.size(); ++i)
158  {
159  for (int j = 0; j < payload[i].size(); ++j)
160  {
161  XmlRpc::XmlRpcValue val = payload[i][j][1];
162  for (int k = 0; k < val.size(); ++k)
163  {
164  std::string name = payload[i][j][1][k];
165  node_set.insert(name);
166  }
167  }
168  }
169 
170  nodes.insert(nodes.end(), node_set.begin(), node_set.end());
171 
172  return true;
173 }
174 
175 #if defined(__APPLE__)
176 boost::mutex g_xmlrpc_call_mutex;
177 #endif
178 
179 bool execute(const std::string& method, const XmlRpc::XmlRpcValue& request, XmlRpc::XmlRpcValue& response, XmlRpc::XmlRpcValue& payload, bool wait_for_master)
180 {
181  ros::SteadyTime start_time = ros::SteadyTime::now();
182 
183  std::string master_host = getHost();
184  uint32_t master_port = getPort();
185  XmlRpc::XmlRpcClient *c = XMLRPCManager::instance()->getXMLRPCClient(master_host, master_port, "/");
186  bool printed = false;
187  bool slept = false;
188  bool ok = true;
189  bool b = false;
190  do
191  {
192  {
193 #if defined(__APPLE__)
194  boost::mutex::scoped_lock lock(g_xmlrpc_call_mutex);
195 #endif
196 
197  b = c->execute(method.c_str(), request, response);
198  }
199 
200  ok = !ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown();
201 
202  if (!b && ok)
203  {
204  if (!printed && wait_for_master)
205  {
206  ROS_ERROR("[%s] Failed to contact master at [%s:%d]. %s", method.c_str(), master_host.c_str(), master_port, wait_for_master ? "Retrying..." : "");
207  printed = true;
208  }
209 
210  if (!wait_for_master)
211  {
212  XMLRPCManager::instance()->releaseXMLRPCClient(c);
213  return false;
214  }
215 
216  if (!g_retry_timeout.isZero() && (ros::SteadyTime::now() - start_time) >= g_retry_timeout)
217  {
218  ROS_ERROR("[%s] Timed out trying to connect to the master after [%f] seconds", method.c_str(), g_retry_timeout.toSec());
219  XMLRPCManager::instance()->releaseXMLRPCClient(c);
220  return false;
221  }
222 
223  ros::WallDuration(0.05).sleep();
224  slept = true;
225  }
226  else
227  {
228  if (!XMLRPCManager::instance()->validateXmlrpcResponse(method, response, payload))
229  {
230  XMLRPCManager::instance()->releaseXMLRPCClient(c);
231 
232  return false;
233  }
234 
235  break;
236  }
237 
238  ok = !ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown();
239  } while(ok);
240 
241  if (ok && slept)
242  {
243  ROS_INFO("Connected to master at [%s:%d]", master_host.c_str(), master_port);
244  }
245 
246  XMLRPCManager::instance()->releaseXMLRPCClient(c);
247 
248  return b;
249 }
250 
251 } // namespace master
252 
253 } // namespace ros
ROSCPP_DECL uint32_t getPort()
Get the port where the master runs.
Definition: master.cpp:99
ROSCPP_DECL void setRetryTimeout(ros::WallDuration timeout)
Set the max time this node should spend looping trying to connect to the master.
Definition: master.cpp:109
ROSCPP_DECL const std::string & getURI()
Get the full URI to the master (eg. http://host:port/)
Definition: master.cpp:104
#define ROS_FATAL(...)
ROSCPP_DECL bool check()
Check whether the master is up.
Definition: master.cpp:119
std::set< std::string > S_string
int size() const
std::string g_host
Definition: master.cpp:46
void init(const M_string &remappings)
Definition: master.cpp:50
ROSCPP_DECL bool splitURI(const std::string &uri, std::string &host, uint32_t &port)
Definition: network.cpp:55
ROSCPP_DECL const std::string & getName()
Returns the name of the current node.
Definition: this_node.cpp:81
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
Get the list of topics that are being published by all nodes.
Definition: master.cpp:126
std::string g_uri
Definition: master.cpp:47
std::vector< TopicInfo > V_TopicInfo
Definition: master.h:99
std::map< std::string, std::string > M_string
std::vector< std::string > V_string
bool sleep() const
static SteadyTime now()
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
Check whether it&#39;s time to exit.
Definition: init.cpp:573
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
Execute an XMLRPC call on the master.
Definition: master.cpp:179
ROSCPP_DECL bool isShuttingDown()
Returns whether or not ros::shutdown() has been (or is being) called.
Definition: init.cpp:115
ROSCPP_DECL const std::string & getHost()
Get the hostname where the master runs.
Definition: master.cpp:94
ros::WallDuration g_retry_timeout
Definition: master.cpp:48
bool execute(const char *method, XmlRpcValue const &params, XmlRpcValue &result)
static const XMLRPCManagerPtr & instance()
ROSCPP_DECL bool getNodes(V_string &nodes)
Retreives the currently-known list of nodes from the master.
Definition: master.cpp:146
#define ROS_BREAK()
#define ROS_ERROR(...)
Contains information retrieved from the master about a topic.
Definition: master.h:85
uint32_t g_port
Definition: master.cpp:45


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54