00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "ros/master.h"
00029 #include "ros/xmlrpc_manager.h"
00030 #include "ros/this_node.h"
00031 #include "ros/init.h"
00032 #include "ros/network.h"
00033
00034 #include <ros/console.h>
00035 #include <ros/assert.h>
00036
00037 #include "XmlRpc.h"
00038
00039 namespace ros
00040 {
00041
00042 namespace master
00043 {
00044
00045 uint32_t g_port = 0;
00046 std::string g_host;
00047 std::string g_uri;
00048 ros::WallDuration g_retry_timeout;
00049
00050 void init(const M_string& remappings)
00051 {
00052 M_string::const_iterator it = remappings.find("__master");
00053 if (it != remappings.end())
00054 {
00055 g_uri = it->second;
00056 }
00057
00058 if (g_uri.empty())
00059 {
00060 char *master_uri_env = getenv("ROS_MASTER_URI");
00061 if (!master_uri_env)
00062 {
00063 ROS_FATAL( "ROS_MASTER_URI is not defined in the environment. Either " \
00064 "type the following or (preferrably) add this to your " \
00065 "~/.bashrc file in order set up your " \
00066 "local machine as a ROS master:\n\n" \
00067 "export ROS_MASTER_URI=http://localhost:11311\n\n" \
00068 "then, type 'roscore' in another shell to actually launch " \
00069 "the master program.");
00070 ROS_BREAK();
00071 }
00072
00073 g_uri = master_uri_env;
00074 }
00075
00076
00077 if (!network::splitURI(g_uri, g_host, g_port))
00078 {
00079 ROS_FATAL( "Couldn't parse the master URI [%s] into a host:port pair.", g_uri.c_str());
00080 ROS_BREAK();
00081 }
00082 }
00083
00084 const std::string& getHost()
00085 {
00086 return g_host;
00087 }
00088
00089 uint32_t getPort()
00090 {
00091 return g_port;
00092 }
00093
00094 const std::string& getURI()
00095 {
00096 return g_uri;
00097 }
00098
00099 void setRetryTimeout(ros::WallDuration timeout)
00100 {
00101 g_retry_timeout = timeout;
00102 }
00103
00104 bool check()
00105 {
00106 XmlRpc::XmlRpcValue args, result, payload;
00107 args[0] = this_node::getName();
00108 return execute("getPid", args, result, payload, false);
00109 }
00110
00111 bool getTopics(V_TopicInfo& topics)
00112 {
00113 XmlRpc::XmlRpcValue args, result, payload;
00114 args[0] = this_node::getName();
00115 args[1] = "";
00116
00117 if (!execute("getPublishedTopics", args, result, payload, true))
00118 {
00119 return false;
00120 }
00121
00122 topics.clear();
00123 for (int i = 0; i < payload.size(); i++)
00124 {
00125 topics.push_back(TopicInfo(std::string(payload[i][0]), std::string(payload[i][1])));
00126 }
00127
00128 return true;
00129 }
00130
00131 bool getNodes(V_string& nodes)
00132 {
00133 XmlRpc::XmlRpcValue args, result, payload;
00134 args[0] = this_node::getName();
00135
00136 if (!execute("getSystemState", args, result, payload, true))
00137 {
00138 return false;
00139 }
00140
00141 S_string node_set;
00142 for (int i = 0; i < payload.size(); ++i)
00143 {
00144 for (int j = 0; j < payload[i].size(); ++j)
00145 {
00146 XmlRpc::XmlRpcValue val = payload[i][j][1];
00147 for (int k = 0; k < val.size(); ++k)
00148 {
00149 std::string name = payload[i][j][1][k];
00150 node_set.insert(name);
00151 }
00152 }
00153 }
00154
00155 nodes.insert(nodes.end(), node_set.begin(), node_set.end());
00156
00157 return true;
00158 }
00159
00160 #if defined(__APPLE__)
00161 boost::mutex g_xmlrpc_call_mutex;
00162 #endif
00163
00164 bool execute(const std::string& method, const XmlRpc::XmlRpcValue& request, XmlRpc::XmlRpcValue& response, XmlRpc::XmlRpcValue& payload, bool wait_for_master)
00165 {
00166 ros::WallTime start_time = ros::WallTime::now();
00167
00168 std::string master_host = getHost();
00169 uint32_t master_port = getPort();
00170 XmlRpc::XmlRpcClient *c = XMLRPCManager::instance()->getXMLRPCClient(master_host, master_port, "/");
00171 bool printed = false;
00172 bool slept = false;
00173 bool ok = true;
00174 do
00175 {
00176 bool b = false;
00177 {
00178 #if defined(__APPLE__)
00179 boost::mutex::scoped_lock lock(g_xmlrpc_call_mutex);
00180 #endif
00181
00182 b = c->execute(method.c_str(), request, response);
00183 }
00184
00185 ok = !ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown();
00186
00187 if (!b && ok)
00188 {
00189 if (!printed && wait_for_master)
00190 {
00191 ROS_ERROR("[%s] Failed to contact master at [%s:%d]. %s", method.c_str(), master_host.c_str(), master_port, wait_for_master ? "Retrying..." : "");
00192 printed = true;
00193 }
00194
00195 if (!wait_for_master)
00196 {
00197 XMLRPCManager::instance()->releaseXMLRPCClient(c);
00198 return false;
00199 }
00200
00201 if (g_retry_timeout.isZero())
00202 {
00203 if (g_retry_timeout > ros::WallDuration(0) && (ros::WallTime::now() - start_time) >= g_retry_timeout)
00204 {
00205 ROS_ERROR("[%s] Timed out trying to connect to the master after [%f] seconds", method.c_str(), g_retry_timeout.toSec());
00206 XMLRPCManager::instance()->releaseXMLRPCClient(c);
00207 return false;
00208 }
00209 }
00210
00211 ros::WallDuration(0.05).sleep();
00212 slept = true;
00213 }
00214 else
00215 {
00216 if (!XMLRPCManager::instance()->validateXmlrpcResponse(method, response, payload))
00217 {
00218 XMLRPCManager::instance()->releaseXMLRPCClient(c);
00219
00220 return false;
00221 }
00222
00223 break;
00224 }
00225
00226 ok = !ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown();
00227 } while(ok);
00228
00229 if (ok && slept)
00230 {
00231 ROS_INFO("Connected to master at [%s:%d]", master_host.c_str(), master_port);
00232 }
00233
00234 XMLRPCManager::instance()->releaseXMLRPCClient(c);
00235
00236 return true;
00237 }
00238
00239 }
00240
00241 }