lib/zeroconf.cpp
Go to the documentation of this file.
1 
12 /*****************************************************************************
13  ** Includes
14  *****************************************************************************/
15 
16 #include <cstdio>
17 #include <ctime>
18 #include <avahi-common/alternative.h> // avahi_alternative_service_name
19 #include <avahi-common/timeval.h>
20 #include <avahi-common/thread-watch.h>
21 #include <boost/thread/thread.hpp> // sleep
22 #include <zeroconf_msgs/Protocols.h>
23 #include <ros/ros.h>
24 #include "../../include/zeroconf_avahi/zeroconf.hpp"
25 
26 /*****************************************************************************
27  ** Namespaces
28  *****************************************************************************/
29 
30 namespace zeroconf_avahi
31 {
32 
33 /*****************************************************************************
34  ** Implementation
35  *****************************************************************************/
36 
38  invalid_object(false), threaded_poll(NULL), client(NULL), interface(AVAHI_IF_UNSPEC), permitted_protocols(
39  AVAHI_PROTO_INET) // AVAHI_PROTO_UNSPEC, AVAHI_PROTO_INET, AVAHI_PROTO_INET6
40 {
41  int error;
42 
43  /* Allocate main loop object */
44  if (!(threaded_poll = avahi_threaded_poll_new()))
45  {
46  ROS_ERROR("Zeroconf: failed to create an avahi threaded poll.");
47  invalid_object = true;
48  return;
49  }
50  /* Allocate a new client */
51  client = avahi_client_new(avahi_threaded_poll_get(threaded_poll), static_cast<AvahiClientFlags>(0),
52  Zeroconf::client_callback, this, &error);
53 
54  /* Check whether creating the client object succeeded */
55  if (!client)
56  {
57  ROS_ERROR("Zeroconf: failed to create an avahi client.");
58  invalid_object = true;
59  return;
60  }
61 
62  /* Don't start spinning until client_callback detects AVAHI_CLIENT_S_RUNNING. This may mean the user has to wait a
63  * little bit before adding a service.
64  */
65 }
66 
68 {
69  /*********************
70  ** Listeners
71  **********************/
72  // note - this map will be empty if invalid_object is true
73  {
74  boost::mutex::scoped_lock lock(service_mutex);
75  for (discovery_bimap::left_const_iterator iter = discovery_service_types.left.begin();
76  iter != discovery_service_types.left.end(); ++iter)
77  {
78  avahi_service_browser_free(iter->first);
79  }
80  discovered_services.clear(); // avahi_service_resolver_free will get called on each here
82  }
83  if (threaded_poll)
84  {
85  avahi_threaded_poll_stop(threaded_poll);
86  }
87 
88  /*********************
89  ** Publishers
90  **********************/
91  // free'ing entry groups shouldn't be necessary (don't know exactly, but haven't seen it in any of the official
92  // code, so its probably done when calling avahi_client_free().
93  /*********************
94  ** General
95  **********************/
96  if (client)
97  {
98  avahi_client_free(client);
99  }
100  if (threaded_poll)
101  {
102  avahi_threaded_poll_free(threaded_poll);
103  }
104 }
105 
107 {
108  if (!invalid_object)
109  {
110  ROS_DEBUG("Zeroconf: starting the threaded poll.");
111  // does this have a return value I should check?
112  avahi_threaded_poll_start(threaded_poll);
113  }
114 }
115 
116 bool Zeroconf::add_listener(std::string &service_type)
117 {
118  if (invalid_object) {
119  ROS_WARN_STREAM("Zeroconf : not connected to the avahi client, aborting add_listener [" << service_type << "]");
120  return false;
121  }
122 
123  /* Check if we're already listening for it. */
124  {
125  boost::mutex::scoped_lock lock(service_mutex);
126  discovery_bimap::right_iterator browser_iter = discovery_service_types.right.find(service_type);
127  if (browser_iter != discovery_service_types.right.end())
128  {
129  ROS_WARN_STREAM("Zeroconf : already listening for services of type '" << service_type << "'");
130  return false;
131  }
132  }
133 
134  /* Create the service browser */
135  AvahiServiceBrowser *service_browser = NULL;
136  avahi_threaded_poll_lock(threaded_poll);
137  if (!(service_browser = avahi_service_browser_new(client, interface, permitted_protocols, service_type.c_str(), NULL,
138  static_cast<AvahiLookupFlags>(0), Zeroconf::discovery_callback,
139  this)))
140  {
142  "Zeroconf: failed to create an avahi service browser: " << avahi_strerror(avahi_client_errno(client)));
143  return false;
144  }
145  avahi_threaded_poll_unlock(threaded_poll);
146  /* Update the internal data */
147  {
148  boost::mutex::scoped_lock lock(service_mutex);
149  discovery_service_types.insert(discovery_bimap::value_type(service_browser, service_type));
150  }
151  ROS_INFO_STREAM("Zeroconf: added a listener [" << service_type << "]");
152  return true;
153 }
154 
155 bool Zeroconf::remove_listener(const std::string &service_type)
156 {
157  AvahiServiceBrowser *service_browser = NULL;
158 
159  /* Check if we're already listening for it. */
160  {
161  boost::mutex::scoped_lock lock(service_mutex);
162  discovery_bimap::right_iterator browser_iter = discovery_service_types.right.find(service_type);
163  if (browser_iter == discovery_service_types.right.end())
164  {
165  ROS_WARN_STREAM("Zeroconf : not currently listening for '" << service_type << "', aborting listener removal.");
166  return false;
167  }
168  else
169  {
170  ROS_INFO_STREAM("Zeroconf: removing a listener [" << service_type << "]");
171  service_browser = browser_iter->second;
172  // delete internal browser pointers and storage
173  discovery_service_types.right.erase(browser_iter);
174  // delete internally resolved list
175  discovered_service_set::iterator iter = discovered_services.begin();
176  while (iter != discovered_services.end())
177  {
178  if ((*iter)->service.type == service_type)
179  {
180  ROS_INFO_STREAM("Zeroconf: erasing element " << *iter);
181  discovered_services.erase(iter++);
182  }
183  else
184  {
185  ROS_INFO_STREAM("Zeroconf: not erasing element " << *iter);
186  ++iter;
187  }
188  }
189  }
190  }
191  /* Remove the avahi browser */
192  if (service_browser)
193  {
194  avahi_threaded_poll_lock(threaded_poll);
195  avahi_service_browser_free(service_browser);
196  avahi_threaded_poll_unlock(threaded_poll);
197  }
198  return true;
199 }
214 {
215 
216  avahi_threaded_poll_lock(threaded_poll);
217  bool result = add_service_non_threaded(service);
218  avahi_threaded_poll_unlock(threaded_poll);
219  return result;
220 }
221 
231 {
232  /*
233  * We may still be initialising (from constructor)...check that we're up and running."
234  */
235  if (avahi_client_get_state(client) != AVAHI_CLIENT_S_RUNNING)
236  {
237  ROS_ERROR("Zeroconf: avahi_client_state is not running (probably still registering with avahi daemon)");
238  return false;
239  }
240 
241  /*
242  * Check we're not already publishing this exact service
243  */
244  {
245  boost::mutex::scoped_lock lock(service_mutex);
246  service_bimap::right_const_iterator iter;
247  iter = committed_services.right.find(service);
248  if (iter != committed_services.right.end())
249  {
251  "Zeroconf: this node is currently already committing this service [" << service.name << "][" << service.type << "][" << service.port << "]");
252  return true;
253  }
254  iter = established_services.right.find(service);
255  if (iter != established_services.right.end())
256  {
258  "Zeroconf: this node has already established this service [" << service.name << "][" << service.type << "][" << service.port << "]");
259  return true;
260  }
261  }
262 
263  ROS_DEBUG_STREAM("Zeroconf: adding a new service [" << service.name << "][" << service.type << "]");
264  /* If this is the first time we're called, let's create a new
265  * entry group if necessary */
266  AvahiEntryGroup* group = NULL;
267  if (!(group = avahi_entry_group_new(client, entry_group_callback, this)))
268  {
269  ROS_ERROR_STREAM("Zeroconf: avahi_entry_group_new() failed: " << avahi_strerror(avahi_client_errno(client)));
270  fail();
271  return false;
272  }
273 
274  int ret = avahi_entry_group_add_service(group, interface, permitted_protocols, static_cast<AvahiPublishFlags>(0), // AVAHI_PUBLISH_USE_MULTICAST - we don't seem to need this, but others said they have needed it.
275  service.name.c_str(), service.type.c_str(), service.domain.c_str(), NULL, // automatically sets a hostname for us
276  static_cast<uint16_t>(service.port), NULL); // txt description
277  if (ret < 0)
278  {
279  avahi_entry_group_free(group);
280  if (ret == AVAHI_ERR_COLLISION)
281  {
282  std::string old_name = service.name;
283  PublishedService new_service = service;
284  service.name = avahi_alternative_service_name(service.name.c_str());
286  "Zeroconf: local service name collision, renaming [" << service.name << "][" << new_service.name << "]");
287  return add_service_non_threaded(service);
288  }
289  else
290  {
292  "Zeroconf: failed to add service [" << service.type.c_str() << "][" << avahi_strerror(ret) << "]");
293  fail();
294  return false;
295  }
296  }
297  /* Commit the entry group */
298  // add to the map first, just so that the callback doesn't fire before we can find it in the map
299  {
300  boost::mutex::scoped_lock lock(service_mutex);
301  committed_services.insert(service_bimap::value_type(group, service)); // should check the return value...
302  }
303  if ((ret = avahi_entry_group_commit(group)) < 0)
304  {
305  ROS_ERROR_STREAM("Zeroconf: failed to commit entry group [" << avahi_strerror(ret) << "]");
306  avahi_entry_group_free(group);
307  {
308  boost::mutex::scoped_lock lock(service_mutex);
309  committed_services.left.erase(group);
310  }
311  fail();
312  return false;
313  }
314  ROS_DEBUG("Zeroconf: service committed, waiting for callback...");
315  return true;
316 }
318 {
319 
320  AvahiEntryGroup *group = NULL;
321  bool erased = false;
322  {
323  boost::mutex::scoped_lock lock(service_mutex);
324  service_bimap::right_const_iterator iter = established_services.right.find(service);
325  if (iter != established_services.right.end())
326  {
327  group = iter->second;
328  established_services.right.erase(service);
329  erased = true;
330  ROS_INFO_STREAM("Zeroconf: removing service [" << service.name << "][" << service.type << "]");
331  }
332  else
333  {
335  "Zeroconf: couldn't remove not currently advertised service [" << service.name << "][" << service.type << "]");
336  }
337  }
338  if (group)
339  {
340  avahi_threaded_poll_lock(threaded_poll);
341  avahi_entry_group_reset(group);
342  avahi_entry_group_free(group);
343  avahi_threaded_poll_unlock(threaded_poll);
344  }
345  return erased;
346 }
355 void Zeroconf::list_discovered_services(const std::string &service_type,
356  std::vector<zeroconf_msgs::DiscoveredService> &list)
357 {
358  list.clear();
359  boost::mutex::scoped_lock lock(service_mutex);
360  if (service_type == "")
361  {
362  for (discovered_service_set::iterator iter = discovered_services.begin(); iter != discovered_services.end(); ++iter)
363  {
364  // ignore services that aren't currently resolved
365  if (((*iter)->service.ipv4_addresses.size() != 0) || ((*iter)->service.ipv6_addresses.size() != 0))
366  {
367  list.push_back((*iter)->service);
368  }
369  }
370  }
371  else
372  {
373  for (discovered_service_set::iterator iter = discovered_services.begin(); iter != discovered_services.end(); ++iter)
374  {
375  if ((*iter)->service.type == service_type)
376  {
377  // ignore services that aren't currently resolved
378  if (((*iter)->service.ipv4_addresses.size() != 0) || ((*iter)->service.ipv6_addresses.size() != 0))
379  {
380  list.push_back((*iter)->service);
381  }
382  }
383  }
384  }
385 }
386 void Zeroconf::list_published_services(const std::string &service_type,
387  std::vector<zeroconf_msgs::PublishedService> &list)
388 {
389  list.clear();
390  boost::mutex::scoped_lock lock(service_mutex);
391  if (service_type == "")
392  {
393  for (service_bimap::left_const_iterator iter = established_services.left.begin();
394  iter != established_services.left.end(); ++iter)
395  {
396  list.push_back(iter->second);
397  }
398  }
399  else
400  {
401  for (service_bimap::left_const_iterator iter = established_services.left.begin();
402  iter != established_services.left.end(); ++iter)
403  {
404  if (iter->second.type == service_type)
405  {
406  list.push_back(iter->second);
407  }
408  }
409  }
410 }
411 
412 /*****************************************************************************
413  ** Utilities
414  *****************************************************************************/
415 
416 int Zeroconf::ros_to_avahi_protocol(const int &protocol)
417 {
418  switch (protocol)
419  {
420  case (zeroconf_msgs::Protocols::UNSPECIFIED):
421  {
422  return AVAHI_PROTO_UNSPEC;
423  }
424  case (zeroconf_msgs::Protocols::IPV4):
425  {
426  return AVAHI_PROTO_INET;
427  }
428  case (zeroconf_msgs::Protocols::IPV6):
429  {
430  return AVAHI_PROTO_INET6;
431  }
432  default:
433  return AVAHI_PROTO_UNSPEC;
434  }
435 }
436 
437 std::string Zeroconf::ros_to_txt_protocol(const int &protocol)
438 {
439  switch (protocol)
440  {
441  case (zeroconf_msgs::Protocols::UNSPECIFIED):
442  {
443  return "unspecified";
444  }
445  case (zeroconf_msgs::Protocols::IPV4):
446  {
447  return "ipv4";
448  }
449  case (zeroconf_msgs::Protocols::IPV6):
450  {
451  return "ipv6";
452  }
453  default:
454  return "unspecified";
455  }
456 }
457 
458 int Zeroconf::avahi_to_ros_protocol(const int &protocol)
459 {
460  switch (protocol)
461  {
462  case (AVAHI_PROTO_UNSPEC):
463  {
464  return zeroconf_msgs::Protocols::UNSPECIFIED;
465  }
466  case (AVAHI_PROTO_INET):
467  {
468  return zeroconf_msgs::Protocols::IPV4;
469  }
470  case (AVAHI_PROTO_INET6):
471  {
472  return zeroconf_msgs::Protocols::IPV6;
473  }
474  default:
475  return zeroconf_msgs::Protocols::UNSPECIFIED;
476  }
477 }
478 
479 std::string Zeroconf::avahi_to_txt_protocol(const int &protocol)
480 {
481  switch (protocol)
482  {
483  case (AVAHI_PROTO_UNSPEC):
484  {
485  return "unspecified";
486  }
487  case (AVAHI_PROTO_INET):
488  {
489  return "ipv4";
490  }
491  case (AVAHI_PROTO_INET6):
492  {
493  return "ipv6";
494  }
495  default:
496  return "unspecified";
497  }
498 }
499 
508 Zeroconf::discovered_service_set::iterator Zeroconf::find_discovered_service(zeroconf_msgs::DiscoveredService &service)
509 {
510  discovered_service_set::iterator iter = discovered_services.begin();
511  while (iter != discovered_services.end())
512  {
513  if (((*iter)->service.name == service.name) && ((*iter)->service.type == service.type)
514  && ((*iter)->service.domain == service.domain))
515  {
516  return iter;
517  }
518  else
519  {
520  ++iter;
521  }
522  }
523  return discovered_services.end();
524 }
525 
526 /*****************************************************************************
527  ** Discovery Callbacks
528  *****************************************************************************/
543 void Zeroconf::discovery_callback(AvahiServiceBrowser *browser, AvahiIfIndex interface, AvahiProtocol protocol,
544  AvahiBrowserEvent event, const char *name, const char *type, const char *domain,
545  AvahiLookupResultFlags flags, void* userdata)
546 {
547 
548  Zeroconf *zeroconf = reinterpret_cast<Zeroconf*>(userdata);
549  assert(browser);
550 
551  switch (event)
552  {
553  case AVAHI_BROWSER_FAILURE:
555  "Zeroconf: browser failure [" << avahi_strerror(avahi_client_errno(avahi_service_browser_get_client(browser))));
556  avahi_threaded_poll_quit(zeroconf->threaded_poll);
557  return;
558 
559  case AVAHI_BROWSER_NEW:
560  {
561  zeroconf_msgs::DiscoveredService service;
562  service.name = name;
563  service.type = type;
564  service.domain = domain;
565 
566  AvahiServiceResolver* resolver = avahi_service_resolver_new(zeroconf->client, interface, protocol, name, type,
567  domain, zeroconf->permitted_protocols,
568  static_cast<AvahiLookupFlags>(0),
569  Zeroconf::resolve_callback, zeroconf);
570  if (!resolver)
571  {
573  "Zeroconf: avahi resolver failure (avahi daemon problem) [" << name << "][" << avahi_strerror(avahi_client_errno(zeroconf->client)) << "][" << interface << "][" << zeroconf->avahi_to_txt_protocol(protocol) << "]");
574  break;
575  }
576  {
577  boost::mutex::scoped_lock lock(zeroconf->service_mutex);
579  new DiscoveredAvahiService(service, resolver, interface, zeroconf->avahi_to_ros_protocol(protocol)));
580  if ((zeroconf->discovered_services.insert(new_service)).second)
581  {
583  "Zeroconf: discovered new service [" << name << "][" << type << "][" << domain << "][" << interface << "][" << zeroconf->avahi_to_txt_protocol(protocol) << "]");
584  // we signal in the resolver, not here...though this might be a bad design
585  // decision if the connection is up and down alot.
586  // if ( zeroconf->new_connection_signal ) {
587  // zeroconf->new_connection_signal(service);
588  // }
589  }
590  else
591  {
593  "Tried to insert a new service on top of an old stored one - probably a bug in zeroconf_avahi!");
594  }
595  }
596  break;
597  }
598 
599  case AVAHI_BROWSER_REMOVE:
600  {
601  zeroconf_msgs::DiscoveredService service;
602  service.name = name;
603  service.type = type;
604  service.domain = domain;
605  {
606  boost::mutex::scoped_lock lock(zeroconf->service_mutex);
607  discovered_service_set::iterator iter = zeroconf->find_discovered_service(service);
608  if (iter != zeroconf->discovered_services.end())
609  {
610  /*********************
611  ** Update
612  **********************/
613  zeroconf->discovered_services.erase(iter);
614  /*********************
615  ** Logging
616  **********************/
618  "Zeroconf: service was removed [" << service.name << "][" << service.type << "][" << service.domain << "][" << interface << "][" << zeroconf->ros_to_txt_protocol(zeroconf->avahi_to_ros_protocol(protocol)) << "]");
619  /*********************
620  ** Signal
621  **********************/
622  // we signal here...though this might get muddled if the connection is up/down alot
623  // I haven't road tested this much yet at all.
624  if (zeroconf->lost_connection_signal)
625  {
626  zeroconf->lost_connection_signal(service);
627  }
628  }
629  else
630  {
632  "Zeroconf: attempted to remove a non-discovered service (probably a bug in zeroconf_avahi!)");
633  }
634  }
635  break;
636  }
637  case AVAHI_BROWSER_ALL_FOR_NOW:
638  case AVAHI_BROWSER_CACHE_EXHAUSTED:
639  {
640  if (event == AVAHI_BROWSER_CACHE_EXHAUSTED)
641  {
642  ROS_DEBUG("Zeroconf: browser event occured [cache exhausted]");
643  }
644  else
645  {
646  ROS_DEBUG("Zeroconf: browser event occured [all for now]");
647  }
648  break;
649  }
650  }
651 }
683 void Zeroconf::resolve_callback(AvahiServiceResolver *resolver, AvahiIfIndex interface, AvahiProtocol protocol,
684  AvahiResolverEvent event, const char *name, const char *type, const char *domain,
685  const char *host_name, const AvahiAddress *address, uint16_t port, AvahiStringList *txt,
686  AvahiLookupResultFlags flags, void* userdata)
687 {
688 
689  Zeroconf *zeroconf = reinterpret_cast<Zeroconf*>(userdata);
690  assert(resolver);
691 
692  switch (event)
693  {
694  case AVAHI_RESOLVER_FAILURE:
695  {
696  zeroconf_msgs::DiscoveredService service;
697  service.name = name;
698  service.type = type;
699  service.domain = domain;
700  {
701  boost::mutex::scoped_lock lock(zeroconf->service_mutex);
702  discovered_service_set::iterator iter = zeroconf->find_discovered_service(service);
703  if (iter != zeroconf->discovered_services.end())
704  {
705  /*********************
706  ** Logging
707  **********************/
708  if ((*iter)->service.ipv4_addresses.size() != 0)
709  {
711  "Zeroconf: timed out resolving service [" << name << "][" << type << "][" << domain << "][" << interface << "][" << zeroconf->avahi_to_txt_protocol(protocol) << "][" << (*iter)->service.ipv4_addresses[0] << ":" << (*iter)->service.port << "]");
712  }
713  else if ((*iter)->service.ipv6_addresses.size() != 0)
714  {
716  "Zeroconf: timed out resolving service [" << name << "][" << type << "][" << domain << "][" << interface << "][" << zeroconf->avahi_to_txt_protocol(protocol) << "][" << (*iter)->service.ipv6_addresses[0] << ":" << (*iter)->service.port << "]");
717  }
718  else
719  {
721  "Zeroconf: timed out resolving service [" << name << "][" << type << "][" << domain << "][" << interface << "][" << zeroconf->avahi_to_txt_protocol(protocol) << "]");
722  }
723  /*********************
724  ** Update
725  **********************/
726  (*iter)->service.ipv4_addresses.clear();
727  (*iter)->service.ipv6_addresses.clear();
728  (*iter)->service.hostname = "";
729  (*iter)->service.port = 0;
730  // could reset all the other stuff too, but the above is important.
731  /*********************
732  ** Signals
733  **********************/
734  if (zeroconf->lost_connection_signal)
735  {
736  zeroconf->lost_connection_signal(service);
737  }
738  }
739  else
740  {
742  "Zeroconf: timed out resolving a service that was not saved, probably a zeroconf_avahi bug!");
743  }
744  }
745  break;
746  }
747  case AVAHI_RESOLVER_FOUND:
748  {
749  char a[AVAHI_ADDRESS_STR_MAX], *t;
750 
751  // workaround for avahi bug 1) above
752  boost::this_thread::sleep(boost::posix_time::milliseconds(500));
753 
754  t = avahi_string_list_to_string(txt);
755  avahi_address_snprint(a, sizeof(a), address);
756 
757  zeroconf_msgs::DiscoveredService service;
758  service.name = name;
759  service.type = type;
760  service.domain = domain;
761  bool error = false;
762  switch (zeroconf->avahi_to_ros_protocol(protocol))
763  {
764  case (zeroconf_msgs::Protocols::IPV4):
765  {
766  service.ipv4_addresses.push_back(a);
767  // workaround for avahi bug 2) above
768  size_t found = std::string(a).find(":");
769  if (found != std::string::npos)
770  {
772  "Zeroconf: avahi is behaving badly (bug) - set an ipv6 address for an ipv4 service, recovering...");
773  avahi_free(t);
774  error = true;
775  break;
776  }
777  break;
778  }
779  case (zeroconf_msgs::Protocols::IPV6):
780  {
781  service.ipv6_addresses.push_back(a);
782  break;
783  }
784  default:
785  break; // should never get here
786  }
787  if (error)
788  {
789  break;
790  }
791 
792  service.hostname = host_name;
793  service.port = port;
794  service.description = t;
795  service.cookie = avahi_string_list_get_service_cookie(txt);
796  service.is_local = ((flags & AVAHI_LOOKUP_RESULT_LOCAL) == 0 ? false : true);
797  service.our_own = ((flags & AVAHI_LOOKUP_RESULT_OUR_OWN) == 0 ? false : true);
798  service.wide_area = ((flags & AVAHI_LOOKUP_RESULT_WIDE_AREA) == 0 ? false : true);
799  service.multicast = ((flags & AVAHI_LOOKUP_RESULT_MULTICAST) == 0 ? false : true);
800  service.cached = ((flags & AVAHI_LOOKUP_RESULT_CACHED) == 0 ? false : true);
801  {
802  boost::mutex::scoped_lock lock(zeroconf->service_mutex);
803  discovered_service_set::iterator iter = zeroconf->find_discovered_service(service);
804  if (iter != zeroconf->discovered_services.end())
805  {
806  /*********************
807  ** Update service info
808  **********************/
809  (*iter)->service = service;
810  (*iter)->protocol = zeroconf->avahi_to_ros_protocol(protocol);
811 
812  /*********************
813  ** Logging
814  **********************/
816  "Zeroconf: resolved service [" << name << "][" << type << "][" << domain << "][" << interface << "][" << zeroconf->ros_to_txt_protocol((*iter)->protocol) << "][" << a << ":" << service.port << "]");
817  ROS_DEBUG_STREAM("Zeroconf: \tname: " << service.name);
818  ROS_DEBUG_STREAM("Zeroconf: \ttype: " << service.type);
819  ROS_DEBUG_STREAM("Zeroconf: \tdomain: " << service.domain);
820  ROS_DEBUG_STREAM("Zeroconf: \tinterface: " << interface);
821  ROS_DEBUG_STREAM("Zeroconf: \tprotocol: " << zeroconf->ros_to_txt_protocol((*iter)->protocol));
822  ROS_DEBUG_STREAM("Zeroconf: \thostname: " << service.hostname);
823  ROS_DEBUG_STREAM("Zeroconf: \taddress: " << a);
824  ROS_DEBUG_STREAM("Zeroconf: \tport: " << service.port);
825  ROS_DEBUG_STREAM("Zeroconf: \tdescription: " << service.description);
826  ROS_DEBUG_STREAM("Zeroconf: \tcookie: " << service.cookie);
827  ROS_DEBUG_STREAM("Zeroconf: \tis_local: " << (service.is_local ? 1 : 0 ));
828  ROS_DEBUG_STREAM("Zeroconf: \tour_own: " << (service.our_own ? 1 : 0 ));
829  ROS_DEBUG_STREAM("Zeroconf: \twide_area: " << (service.wide_area ? 1 : 0 ));
830  ROS_DEBUG_STREAM("Zeroconf: \tmulticast: " << (service.multicast ? 1 : 0 ));
831  /*********************
832  ** Signals
833  **********************/
834  if (zeroconf->new_connection_signal)
835  {
836  zeroconf->new_connection_signal(service);
837  }
838  }
839  else
840  {
842  "Zeroconf: timed out resolving a service that was not saved, probably a zeroconf_avahi bug!");
843  }
844  }
845 
846  avahi_free(t);
847  break;
848  }
849  }
850 }
851 
852 /*****************************************************************************
853  ** Publisher Callback
854  *****************************************************************************/
868 void Zeroconf::entry_group_callback(AvahiEntryGroup *g, AvahiEntryGroupState state, void *userdata)
869 {
870 
871  Zeroconf *zeroconf = static_cast<Zeroconf*>(userdata);
872  switch (state)
873  {
874  case AVAHI_ENTRY_GROUP_ESTABLISHED:
875  {
876  PublishedService service;
877  {
878  boost::mutex::scoped_lock lock(zeroconf->service_mutex);
879  service_bimap::left_const_iterator left = zeroconf->committed_services.left.find(g);
880  if (left != zeroconf->committed_services.left.end())
881  {
882  service = left->second;
883  }
884  else
885  {
886  ROS_ERROR(
887  "Zeroconf : should never reach here, please report a bug in zeroconf_avahi's entry_group_callback.");
888  return;
889  }
890  zeroconf->established_services.insert(service_bimap::value_type(g, service));
891  zeroconf->committed_services.left.erase(g);
892  }
894  "Zeroconf: service successfully established [" << service.name << "][" << service.type << "][" << service.port << "]");
895  break;
896  }
897  case AVAHI_ENTRY_GROUP_COLLISION:
898  {
899  /* A service name collision with a 'remote' service happened. Let's pick a new name */
900  PublishedService service;
901  {
902  boost::mutex::scoped_lock lock(zeroconf->service_mutex);
903  service_bimap::left_const_iterator left = zeroconf->committed_services.left.find(g);
904  if (left != zeroconf->committed_services.left.end())
905  {
906  service = left->second;
907  }
908  else
909  {
910  ROS_ERROR(
911  "Zeroconf : should never reach here, please report a bug in zeroconf_avahi's entry_group_callback.");
912  return;
913  }
914  zeroconf->committed_services.left.erase(g);
915  }
916  std::string alternative_name = avahi_alternative_service_name(service.name.c_str());
918  "Zeroconf: service name collision, renaming service [" << service.name << "]" << "][" << alternative_name << "]");
919  service.name = alternative_name;
920  avahi_entry_group_free(g);
921  /* And recreate the services - already in the poll thread, so don' tneed to lock. */
922  zeroconf->add_service_non_threaded(service);
923  break;
924  }
925 
926  case AVAHI_ENTRY_GROUP_FAILURE:
927  /* Some kind of failure happened while we were registering our services */
928  // drop our committed_service here.
930  "Zeroconf: group state changed, system failure when trying to register service [" << avahi_strerror(avahi_client_errno(avahi_entry_group_get_client(g))) << "]");
931  avahi_entry_group_free(g);
932  zeroconf->fail();
933  break;
934 
935  case AVAHI_ENTRY_GROUP_UNCOMMITED:
936  {
937  ROS_DEBUG_STREAM("Zeroconf: group state changed, service uncommitted");
938  // This is just mid-process, no need to handle committed_services
939  break;
940  }
941  case AVAHI_ENTRY_GROUP_REGISTERING:
942  {
943  // This is just mid-process, no need to handle committed_services
944  PublishedService service;
945  {
946  boost::mutex::scoped_lock lock(zeroconf->service_mutex);
947  service_bimap::left_const_iterator left = zeroconf->committed_services.left.find(g);
948  if (left != zeroconf->committed_services.left.end())
949  {
950  service = left->second;
951  }
952  else
953  {
954  ROS_ERROR(
955  "Zeroconf : should never reach here, please report a bug in zeroconf_avahi's entry_group_callback.");
956  return;
957  }
958  }
960  "Zeroconf: group state changed, service registering [" << service.name << "][" << service.type << "]");
961  break;
962  }
963  default:
964  {
965  ROS_DEBUG_STREAM("Zeroconf: group state changed, ended in an unknown state [" << state << "]");
966  break;
967  }
968  }
969 }
970 
971 /*****************************************************************************
972  ** Daemon Callbacks
973  *****************************************************************************/
983 void Zeroconf::client_callback(AvahiClient *c, AvahiClientState state, void *userdata)
984 {
985 
986  Zeroconf *zeroconf = static_cast<Zeroconf*>(userdata);
987  assert(c);
988 
989  /* Called whenever the client or server state changes */
990 
991  switch (state)
992  {
993  case AVAHI_CLIENT_S_RUNNING:
994  {
995  /* The server has startup successfully and registered its host
996  * name on the network, so it's time to fire up */
997  ROS_DEBUG("Zeroconf: avahi client up and running.");
998  zeroconf->spin();
999  break;
1000  }
1001  case AVAHI_CLIENT_FAILURE:
1002  {
1003  ROS_ERROR_STREAM("Zeroconf: avahi client failure [" << avahi_strerror(avahi_client_errno(c)) << "]");
1004  zeroconf->fail();
1005 
1006  break;
1007  }
1008  case AVAHI_CLIENT_S_COLLISION:
1009  {
1010  ROS_DEBUG("Zeroconf: avahi client collision.");
1011  /* Let's drop our registered services. When the server is back
1012  * in AVAHI_SERVER_RUNNING state we will register them
1013  * again with the new host name. */
1014  break;
1015  }
1016  case AVAHI_CLIENT_S_REGISTERING:
1017  {
1018  ROS_DEBUG("Zeroconf: avahi client registering.");
1019 
1020  /* The server records are now being established. This
1021  * might be caused by a host name change. We need to wait
1022  * for our own records to register until the host name is
1023  * properly established. */
1024 
1025  // official example resets the entry group here
1026  // since we have multiple groups, handling should be a bit more
1027  // complicated - ToDo
1028  break;
1029  }
1030  case AVAHI_CLIENT_CONNECTING:
1031  {
1032  ROS_DEBUG("Zeroconf: avahi client registering.");
1033  break;
1034  }
1035  }
1036 }
1037 
1038 } // namespace zeroconf_avahi
bool add_service_non_threaded(PublishedService &service)
Internal storage for linking discovered service info with active avahi resolvers. ...
Definition: zeroconf.hpp:78
boost::mutex service_mutex
Definition: zeroconf.hpp:203
static void discovery_callback(AvahiServiceBrowser *b, AvahiIfIndex interface, AvahiProtocol protocol, AvahiBrowserEvent event, const char *name, const char *type, const char *domain, AvahiLookupResultFlags flags, void *userdata)
int avahi_to_ros_protocol(const int &protocol)
static void entry_group_callback(AvahiEntryGroup *g, AvahiEntryGroupState state, void *userdata)
AvahiThreadedPoll * threaded_poll
Definition: zeroconf.hpp:197
std::string ros_to_txt_protocol(const int &protocol)
connection_signal_cb new_connection_signal
Definition: zeroconf.hpp:206
void list_discovered_services(const std::string &service_type, std::vector< zeroconf_msgs::DiscoveredService > &list)
discovery_bimap discovery_service_types
Definition: zeroconf.hpp:201
void list_published_services(const std::string &service_type, std::vector< zeroconf_msgs::PublishedService > &list)
bool add_listener(std::string &service_type)
const int permitted_protocols
Definition: zeroconf.hpp:205
service_bimap committed_services
Definition: zeroconf.hpp:199
bool add_service(PublishedService &service)
bool remove_service(const PublishedService &service)
int ros_to_avahi_protocol(const int &protocol)
AvahiClient * client
Definition: zeroconf.hpp:198
Ros interface to linux&#39;s avahi daemon.
Definition: zeroconf.hpp:162
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
bool remove_listener(const std::string &service_type)
zeroconf_msgs::PublishedService PublishedService
Definition: zeroconf.hpp:165
discovered_service_set::iterator find_discovered_service(zeroconf_msgs::DiscoveredService &service)
#define ROS_INFO_STREAM(args)
static void client_callback(AvahiClient *c, AvahiClientState state, void *userdata)
std::string avahi_to_txt_protocol(const int &protocol)
#define ROS_ERROR_STREAM(args)
service_bimap established_services
Definition: zeroconf.hpp:200
#define ROS_ERROR(...)
connection_signal_cb lost_connection_signal
Definition: zeroconf.hpp:206
static void resolve_callback(AvahiServiceResolver *r, AvahiIfIndex interface, AvahiProtocol protocol, AvahiResolverEvent event, const char *name, const char *type, const char *domain, const char *host_name, const AvahiAddress *address, uint16_t port, AvahiStringList *txt, AvahiLookupResultFlags flags, void *userdata)
discovered_service_set discovered_services
Definition: zeroconf.hpp:202
#define ROS_DEBUG(...)


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