Go to the documentation of this file.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
00029
00030
00032
00033
00034 #include <cstdio>
00035 #include "topic_tools/shape_shifter.h"
00036 #include "topic_tools/parse.h"
00037 #include "XmlRpc.h"
00038 #include "ros/xmlrpc_manager.h"
00039 #include "ros/network.h"
00040
00041 using std::string;
00042 using std::vector;
00043 using namespace topic_tools;
00044
00045 ros::NodeHandle *g_node = NULL;
00046 static bool g_advertised = false;
00047 static string g_output_topic;
00048 static ros::Publisher g_pub;
00049 static string g_host;
00050 uint32_t g_port = 0;
00051 bool g_error = false;
00052
00053 ros::XMLRPCManagerPtr g_xmlrpc_manager = ros::XMLRPCManager::instance();
00054
00055 void foreign_advertise(const std::string &type)
00056 {
00057 XmlRpc::XmlRpcClient *client = g_xmlrpc_manager->getXMLRPCClient(g_host, g_port, "/");
00058 XmlRpc::XmlRpcValue args, result;
00059 args[0] = ros::this_node::getName();
00060 args[1] = g_output_topic;
00061 args[2] = type;
00062 args[3] = g_xmlrpc_manager->getServerURI();
00063 if (!client->execute("registerPublisher", args, result))
00064 {
00065 ROS_FATAL("Failed to contact foreign master at [%s:%d] to register [%s].", g_host.c_str(), g_port, g_output_topic.c_str());
00066 g_error = true;
00067 ros::shutdown();
00068 }
00069 ros::XMLRPCManager::instance()->releaseXMLRPCClient(client);
00070 }
00071
00072 void foreign_unadvertise()
00073 {
00074 XmlRpc::XmlRpcClient *client = g_xmlrpc_manager->getXMLRPCClient(g_host, g_port, "/");
00075 XmlRpc::XmlRpcValue args, result;
00076 args[0] = ros::this_node::getName();
00077 args[1] = g_output_topic;
00078 args[2] = g_xmlrpc_manager->getServerURI();
00079 if (!client->execute("unregisterPublisher", args, result))
00080 {
00081 ROS_ERROR("Failed to contact foreign master at [%s:%d] to unregister [%s].", g_host.c_str(), g_port, g_output_topic.c_str());
00082 g_error = true;
00083 }
00084 ros::XMLRPCManager::instance()->releaseXMLRPCClient(client);
00085 }
00086
00087 void in_cb(const boost::shared_ptr<ShapeShifter const>& msg)
00088 {
00089 if (!g_advertised)
00090 {
00091 g_pub = msg->advertise(*g_node, g_output_topic, 10, true);
00092 foreign_advertise((*(msg->__connection_header))["type"]);
00093 g_advertised = true;
00094 printf("advertised as %s\n", g_output_topic.c_str());
00095 }
00096 g_pub.publish(msg);
00097 }
00098
00099 int main(int argc, char **argv)
00100 {
00101 if (argc < 3)
00102 {
00103 printf("\nusage: unreliable_relay FOREIGN_MASTER_URI IN_TOPIC [OUT_TOPIC]\n\n");
00104 return 1;
00105 }
00106 std::string topic_name;
00107 if(!getBaseName(string(argv[2]), topic_name))
00108 return 1;
00109 ros::init(argc, argv, topic_name + string("_foreign_relay"),
00110 ros::init_options::AnonymousName);
00111 if (!ros::network::splitURI(string(argv[1]), g_host, g_port))
00112 {
00113 ROS_FATAL("Couldn't parse the foreign master URI [%s] into a host:port pair.", argv[1]);
00114 return 1;
00115 }
00116 if (argc == 3)
00117 g_output_topic = string(argv[2])+string("_foreign_relay");
00118 else
00119 g_output_topic = string(argv[3]);
00120 ros::NodeHandle n;
00121 ros::NodeHandle pnh("~");
00122 g_node = &pnh;
00123 ros::Subscriber sub = n.subscribe<ShapeShifter>(string(argv[2]), 10, &in_cb);
00124 ros::spin();
00125 foreign_unadvertise();
00126 return g_error;
00127 }
00128