node/zeroconf.cpp
Go to the documentation of this file.
1 
11 /*****************************************************************************
12  ** Includes
13  *****************************************************************************/
14 
15 #include <boost/function.hpp>
16 
17 #include <ros/ros.h>
18 #include <zeroconf_msgs/AddListener.h>
19 #include <zeroconf_msgs/RemoveListener.h>
20 #include <zeroconf_msgs/AddService.h>
21 #include <zeroconf_msgs/ListDiscoveredServices.h>
22 #include <zeroconf_msgs/ListPublishedServices.h>
23 
24 #include "../../include/zeroconf_avahi/zeroconf.hpp"
25 
26 /*****************************************************************************
27  ** Namespaces
28  *****************************************************************************/
29 
30 using namespace zeroconf_avahi;
31 using namespace zeroconf_msgs;
32 
33 /*****************************************************************************
34  ** Interface
35  *****************************************************************************/
36 
44 {
45 
46 private:
47  typedef boost::function<void(zeroconf_msgs::DiscoveredService)> connection_signal_cb;
48 
49 public:
50  /*********************
51  ** Checks
52  **********************/
54  {
55  if (!zeroconf.is_alive()) {
56  ROS_WARN_STREAM("Zeroconf: aborting node initialisation, avahi client is not alive.");
57  return;
58  }
59  /*********************
60  ** Ros Comms
61  **********************/
62  server_add_listener = nh.advertiseService("add_listener", &ZeroconfNode::add_listener, this);
63  server_remove_listener = nh.advertiseService("remove_listener", &ZeroconfNode::remove_listener, this);
64  server_add_service = nh.advertiseService("add_service", &ZeroconfNode::add_service, this);
65  server_remove_service = nh.advertiseService("remove_service", &ZeroconfNode::remove_service, this);
66  server_list_discovered_services = nh.advertiseService("list_discovered_services",
68  server_list_published_services = nh.advertiseService("list_published_services",
70  pub_new_connections = nh.advertise<DiscoveredService>("new_connections", 10);
71  pub_lost_connections = nh.advertise<DiscoveredService>("lost_connections", 10);
72 
73  /*********************
74  ** Signals
75  **********************/
76  // The callback functions use the publishers, so they must come after.
77  connection_signal_cb new_connection_signal = std::bind1st(std::mem_fun(&ZeroconfNode::new_connections), this);
78  connection_signal_cb old_connection_signal = std::bind1st(std::mem_fun(&ZeroconfNode::lost_connections), this);
79  zeroconf.connect_signal_callbacks(new_connection_signal, old_connection_signal);
80 
81  /*********************
82  ** Parameters
83  **********************/
84  ros::NodeHandle local_nh("~");
85  // listeners
86  XmlRpc::XmlRpcValue value;
88  if (local_nh.getParam("listeners", value))
89  {
91  {
92  ROS_ERROR_STREAM("Zeroconf: param variable 'listeners' has malformed type, should be of type array");
93  }
94  else
95  {
96  for (int i = 0; i < value.size(); ++i)
97  {
98  zeroconf.add_listener(value[i]);
99  }
100  }
101  }
102  // services
103  XmlRpc::XmlRpcValue value_services;
104  if (local_nh.getParam("services", value_services))
105  {
106  if (value_services.getType() != XmlRpc::XmlRpcValue::TypeArray)
107  {
108  ROS_ERROR_STREAM("Zeroconf: param variable 'services' has malformed type, should be of type array");
109  }
110  else
111  {
112  for (int i = 0; i < value_services.size(); ++i)
113  {
114  XmlRpc::XmlRpcValue value_service = value_services[i];
115  if (value_service.getType() != XmlRpc::XmlRpcValue::TypeStruct)
116  {
118  "Zeroconf: " << i << "th element of param variable 'services' has malformed type, should be of type struct");
119  break;
120  }
121  zeroconf_msgs::PublishedService service;
122  XmlRpc::XmlRpcValue value_name = value_service["name"];
123  if (value_name.getType() != XmlRpc::XmlRpcValue::TypeString)
124  {
125  ROS_ERROR_STREAM("Zeroconf: services[" << i << "]['name'] has malformed type, should be of type string");
126  break;
127  }
128  service.name = std::string(value_name);
129  if (service.name == "Ros Master")
130  {
131  // add some special ros magic to easily identify master's.
132  service.name = service.name + " (" + ros::master::getHost() + ")";
133  }
134  XmlRpc::XmlRpcValue value_type = value_service["type"];
135  if (value_type.getType() != XmlRpc::XmlRpcValue::TypeString)
136  {
137  ROS_ERROR_STREAM("Zeroconf: services[" << i << "]['type'] has malformed type, should be of type string");
138  break;
139  }
140  service.type = std::string(value_type);
141  XmlRpc::XmlRpcValue value_domain = value_service["domain"];
142  if (value_domain.getType() != XmlRpc::XmlRpcValue::TypeString)
143  {
144  ROS_ERROR_STREAM("Zeroconf: services[" << i << "]['domain'] has malformed type, should be of type string");
145  break;
146  }
147  service.domain = std::string(value_domain);
148  XmlRpc::XmlRpcValue value_port = value_service["port"];
149  if (value_port.getType() == XmlRpc::XmlRpcValue::TypeInvalid)
150  {
151  service.port = ros::master::getPort();
152  // wasn't set, so default to ros master's port
154  "Zeroconf: services[" << service.name << "]['port'] wasn't set, default to ros master's port [" << service.port << "]");
155  }
156  else if (value_port.getType() != XmlRpc::XmlRpcValue::TypeInt)
157  {
159  "Zeroconf: services[" << service.name << "]['port'] has malformed type, should be of type int");
160  break;
161  }
162  else
163  {
164  service.port = value_port;
165  }
166  XmlRpc::XmlRpcValue value_description = value_service["description"];
167  if (value_description.getType() != XmlRpc::XmlRpcValue::TypeString)
168  {
169  service.description = "";
170  }
171  else
172  {
173  service.description = std::string(value_description);
174  }
175  zeroconf.add_service(service);
176  }
177  }
178  }
179  }
180 
181 private:
182  bool add_listener(AddListener::Request &request, AddListener::Response &response)
183  {
184  ROS_DEBUG_STREAM("Zeroconf: serving an add_listener call... [" << request.service_type << "]");
185  response.result = zeroconf.add_listener(request.service_type);
186  return true;
187  }
188  bool remove_listener(RemoveListener::Request &request, RemoveListener::Response &response)
189  {
190  ROS_DEBUG_STREAM("Zeroconf: serving a remove_listener call... [" << request.service_type << "]");
191  response.result = zeroconf.remove_listener(request.service_type);
192  return true;
193  }
194  bool add_service(AddService::Request &request, AddService::Response &response)
195  {
196  response.result = zeroconf.add_service(request.service);
197  return true;
198  }
199  bool remove_service(AddService::Request &request, AddService::Response &response)
200  {
201  response.result = zeroconf.remove_service(request.service);
202  return true;
203  }
204  bool list_discovered_services(ListDiscoveredServices::Request &request, ListDiscoveredServices::Response &response)
205  {
206  ROS_DEBUG_STREAM("Zeroconf: serving a list_discovered_services call... [" << request.service_type << "]");
207  zeroconf.list_discovered_services(request.service_type, response.services);
208  return true;
209  }
210  bool list_published_services(ListPublishedServices::Request &request, ListPublishedServices::Response &response)
211  {
212  zeroconf.list_published_services(request.service_type, response.services);
213  return true;
214  }
215  void new_connections(DiscoveredService service)
216  {
217  pub_new_connections.publish(service);
218  }
219  void lost_connections(DiscoveredService service)
220  {
221  pub_lost_connections.publish(service);
222  }
223 
225  ros::ServiceServer server_add_listener, server_remove_listener, server_add_service, server_remove_service;
226  ros::ServiceServer server_list_discovered_services, server_list_published_services;
227  ros::Publisher pub_new_connections, pub_lost_connections;
228 };
229 
230 /*****************************************************************************
231  ** Main
232  *****************************************************************************/
233 
234 int main(int argc, char **argv)
235 {
236 
237  ros::init(argc, argv, "zeroconf");
238  ros::NodeHandle nh;
239  ZeroconfNode zeroconf_node;
240  zeroconf_node.init(nh);
241  ros::spin();
242  return 0;
243 }
bool remove_service(AddService::Request &request, AddService::Response &response)
ROSCPP_DECL uint32_t getPort()
void lost_connections(DiscoveredService service)
ros::ServiceServer server_remove_service
ValueStruct::iterator iterator
int size() const
void new_connections(DiscoveredService service)
bool add_service(AddService::Request &request, AddService::Response &response)
bool add_listener(AddListener::Request &request, AddListener::Response &response)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Type const & getType() const
Wraps the library api into a fully functional ros node with ros api.
bool list_discovered_services(ListDiscoveredServices::Request &request, ListDiscoveredServices::Response &response)
bool list_published_services(ListPublishedServices::Request &request, ListPublishedServices::Response &response)
ros::ServiceServer server_list_published_services
Zeroconf zeroconf
boost::function< void(zeroconf_msgs::DiscoveredService)> connection_signal_cb
Ros interface to linux&#39;s avahi daemon.
Definition: zeroconf.hpp:162
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
ROSCPP_DECL const std::string & getHost()
bool remove_listener(RemoveListener::Request &request, RemoveListener::Response &response)
ros::Publisher pub_new_connections
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
#define ROS_ERROR_STREAM(args)
void init(ros::NodeHandle &nh)


zeroconf_avahi
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 15:49:04