void foreign_unadvertise() { XmlRpc::XmlRpcClient *client = g_xmlrpc_manager->getXMLRPCClient(g_host, g_port, "/"); XmlRpc::XmlRpcValue args, result; args[0] = ros::this_node::getName(); args[1] = g_output_topic; args[2] = g_xmlrpc_manager->getServerURI(); if (!client->execute("unregisterPublisher", args, result)) { ROS_ERROR("Failed to contact foreign master at [%s:%d] to unregister [%s].", g_host.c_str(), g_port, g_output_topic.c_str()); g_error = true; } ros::XMLRPCManager::instance()->releaseXMLRPCClient(client); }
bool execute(const std::string& method, const XmlRpc::XmlRpcValue& request, XmlRpc::XmlRpcValue& response, XmlRpc::XmlRpcValue& payload, bool wait_for_master) { ros::WallTime start_time = ros::WallTime::now(); std::string master_host = getHost(); uint32_t master_port = getPort(); XmlRpc::XmlRpcClient *c = XMLRPCManager::instance()->getXMLRPCClient(master_host, master_port, "/"); bool printed = false; bool slept = false; bool ok = true; do { bool b = false; { #if defined(__APPLE__) boost::mutex::scoped_lock lock(g_xmlrpc_call_mutex); #endif b = c->execute(method.c_str(), request, response); } ok = !ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown(); if (!b && ok) { if (!printed && wait_for_master) { ROS_ERROR("[%s] Failed to contact master at [%s:%d]. %s", method.c_str(), master_host.c_str(), master_port, wait_for_master ? "Retrying..." : ""); printed = true; } if (!wait_for_master) { XMLRPCManager::instance()->releaseXMLRPCClient(c); return false; } if (!g_retry_timeout.isZero() && (ros::WallTime::now() - start_time) >= g_retry_timeout) { ROS_ERROR("[%s] Timed out trying to connect to the master after [%f] seconds", method.c_str(), g_retry_timeout.toSec()); XMLRPCManager::instance()->releaseXMLRPCClient(c); return false; } ros::WallDuration(0.05).sleep(); slept = true; } else { if (!XMLRPCManager::instance()->validateXmlrpcResponse(method, response, payload)) { XMLRPCManager::instance()->releaseXMLRPCClient(c); return false; } break; } ok = !ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown(); } while(ok); if (ok && slept) { ROS_INFO("Connected to master at [%s:%d]", master_host.c_str(), master_port); } XMLRPCManager::instance()->releaseXMLRPCClient(c); return true; }