Go to the documentation of this file.00001
00011
00012
00013
00014
00015 #include <boost/function.hpp>
00016
00017 #include <ros/ros.h>
00018 #include <zeroconf_msgs/AddListener.h>
00019 #include <zeroconf_msgs/RemoveListener.h>
00020 #include <zeroconf_msgs/AddService.h>
00021 #include <zeroconf_msgs/ListDiscoveredServices.h>
00022 #include <zeroconf_msgs/ListPublishedServices.h>
00023
00024 #include "../../include/zeroconf_avahi/zeroconf.hpp"
00025
00026
00027
00028
00029
00030 using namespace zeroconf_avahi;
00031 using namespace zeroconf_msgs;
00032
00033
00034
00035
00036
00043 class ZeroconfNode
00044 {
00045
00046 private:
00047 typedef boost::function<void(zeroconf_msgs::DiscoveredService)> connection_signal_cb;
00048
00049 public:
00050
00051
00052
00053 void init(ros::NodeHandle &nh)
00054 {
00055 if (!zeroconf.is_alive()) {
00056 ROS_WARN_STREAM("Zeroconf: aborting node initialisation, avahi client is not alive.");
00057 return;
00058 }
00059
00060
00061
00062 server_add_listener = nh.advertiseService("add_listener", &ZeroconfNode::add_listener, this);
00063 server_remove_listener = nh.advertiseService("remove_listener", &ZeroconfNode::remove_listener, this);
00064 server_add_service = nh.advertiseService("add_service", &ZeroconfNode::add_service, this);
00065 server_remove_service = nh.advertiseService("remove_service", &ZeroconfNode::remove_service, this);
00066 server_list_discovered_services = nh.advertiseService("list_discovered_services",
00067 &ZeroconfNode::list_discovered_services, this);
00068 server_list_published_services = nh.advertiseService("list_published_services",
00069 &ZeroconfNode::list_published_services, this);
00070 pub_new_connections = nh.advertise<DiscoveredService>("new_connections", 10);
00071 pub_lost_connections = nh.advertise<DiscoveredService>("lost_connections", 10);
00072
00073
00074
00075
00076
00077 connection_signal_cb new_connection_signal = std::bind1st(std::mem_fun(&ZeroconfNode::new_connections), this);
00078 connection_signal_cb old_connection_signal = std::bind1st(std::mem_fun(&ZeroconfNode::lost_connections), this);
00079 zeroconf.connect_signal_callbacks(new_connection_signal, old_connection_signal);
00080
00081
00082
00083
00084 ros::NodeHandle local_nh("~");
00085
00086 XmlRpc::XmlRpcValue value;
00087 XmlRpc::XmlRpcValue::iterator iter;
00088 if (local_nh.getParam("listeners", value))
00089 {
00090 if (value.getType() != XmlRpc::XmlRpcValue::TypeArray)
00091 {
00092 ROS_ERROR_STREAM("Zeroconf: param variable 'listeners' has malformed type, should be of type array");
00093 }
00094 else
00095 {
00096 for (int i = 0; i < value.size(); ++i)
00097 {
00098 zeroconf.add_listener(value[i]);
00099 }
00100 }
00101 }
00102
00103 XmlRpc::XmlRpcValue value_services;
00104 if (local_nh.getParam("services", value_services))
00105 {
00106 if (value_services.getType() != XmlRpc::XmlRpcValue::TypeArray)
00107 {
00108 ROS_ERROR_STREAM("Zeroconf: param variable 'services' has malformed type, should be of type array");
00109 }
00110 else
00111 {
00112 for (int i = 0; i < value_services.size(); ++i)
00113 {
00114 XmlRpc::XmlRpcValue value_service = value_services[i];
00115 if (value_service.getType() != XmlRpc::XmlRpcValue::TypeStruct)
00116 {
00117 ROS_ERROR_STREAM(
00118 "Zeroconf: " << i << "th element of param variable 'services' has malformed type, should be of type struct");
00119 break;
00120 }
00121 zeroconf_msgs::PublishedService service;
00122 XmlRpc::XmlRpcValue value_name = value_service["name"];
00123 if (value_name.getType() != XmlRpc::XmlRpcValue::TypeString)
00124 {
00125 ROS_ERROR_STREAM("Zeroconf: services[" << i << "]['name'] has malformed type, should be of type string");
00126 break;
00127 }
00128 service.name = std::string(value_name);
00129 if (service.name == "Ros Master")
00130 {
00131
00132 service.name = service.name + " (" + ros::master::getHost() + ")";
00133 }
00134 XmlRpc::XmlRpcValue value_type = value_service["type"];
00135 if (value_type.getType() != XmlRpc::XmlRpcValue::TypeString)
00136 {
00137 ROS_ERROR_STREAM("Zeroconf: services[" << i << "]['type'] has malformed type, should be of type string");
00138 break;
00139 }
00140 service.type = std::string(value_type);
00141 XmlRpc::XmlRpcValue value_domain = value_service["domain"];
00142 if (value_domain.getType() != XmlRpc::XmlRpcValue::TypeString)
00143 {
00144 ROS_ERROR_STREAM("Zeroconf: services[" << i << "]['domain'] has malformed type, should be of type string");
00145 break;
00146 }
00147 service.domain = std::string(value_domain);
00148 XmlRpc::XmlRpcValue value_port = value_service["port"];
00149 if (value_port.getType() == XmlRpc::XmlRpcValue::TypeInvalid)
00150 {
00151 service.port = ros::master::getPort();
00152
00153 ROS_WARN_STREAM(
00154 "Zeroconf: services[" << service.name << "]['port'] wasn't set, default to ros master's port [" << service.port << "]");
00155 }
00156 else if (value_port.getType() != XmlRpc::XmlRpcValue::TypeInt)
00157 {
00158 ROS_ERROR_STREAM(
00159 "Zeroconf: services[" << service.name << "]['port'] has malformed type, should be of type int");
00160 break;
00161 }
00162 else
00163 {
00164 service.port = value_port;
00165 }
00166 XmlRpc::XmlRpcValue value_description = value_service["description"];
00167 if (value_description.getType() != XmlRpc::XmlRpcValue::TypeString)
00168 {
00169 service.description = "";
00170 }
00171 else
00172 {
00173 service.description = std::string(value_description);
00174 }
00175 zeroconf.add_service(service);
00176 }
00177 }
00178 }
00179 }
00180
00181 private:
00182 bool add_listener(AddListener::Request &request, AddListener::Response &response)
00183 {
00184 ROS_DEBUG_STREAM("Zeroconf: serving an add_listener call... [" << request.service_type << "]");
00185 response.result = zeroconf.add_listener(request.service_type);
00186 return true;
00187 }
00188 bool remove_listener(RemoveListener::Request &request, RemoveListener::Response &response)
00189 {
00190 ROS_DEBUG_STREAM("Zeroconf: serving a remove_listener call... [" << request.service_type << "]");
00191 response.result = zeroconf.remove_listener(request.service_type);
00192 return true;
00193 }
00194 bool add_service(AddService::Request &request, AddService::Response &response)
00195 {
00196 response.result = zeroconf.add_service(request.service);
00197 return true;
00198 }
00199 bool remove_service(AddService::Request &request, AddService::Response &response)
00200 {
00201 response.result = zeroconf.remove_service(request.service);
00202 return true;
00203 }
00204 bool list_discovered_services(ListDiscoveredServices::Request &request, ListDiscoveredServices::Response &response)
00205 {
00206 ROS_DEBUG_STREAM("Zeroconf: serving a list_discovered_services call... [" << request.service_type << "]");
00207 zeroconf.list_discovered_services(request.service_type, response.services);
00208 return true;
00209 }
00210 bool list_published_services(ListPublishedServices::Request &request, ListPublishedServices::Response &response)
00211 {
00212 zeroconf.list_published_services(request.service_type, response.services);
00213 return true;
00214 }
00215 void new_connections(DiscoveredService service)
00216 {
00217 pub_new_connections.publish(service);
00218 }
00219 void lost_connections(DiscoveredService service)
00220 {
00221 pub_lost_connections.publish(service);
00222 }
00223
00224 Zeroconf zeroconf;
00225 ros::ServiceServer server_add_listener, server_remove_listener, server_add_service, server_remove_service;
00226 ros::ServiceServer server_list_discovered_services, server_list_published_services;
00227 ros::Publisher pub_new_connections, pub_lost_connections;
00228 };
00229
00230
00231
00232
00233
00234 int main(int argc, char **argv)
00235 {
00236
00237 ros::init(argc, argv, "zeroconf");
00238 ros::NodeHandle nh;
00239 ZeroconfNode zeroconf_node;
00240 zeroconf_node.init(nh);
00241 ros::spin();
00242 return 0;
00243 }