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


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44