Note: This tutorial assumes that you have completed the previous tutorials: Understanding Service Types, Discovering Ros Masters with Avahi. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Zeroconf Using Ros Api with Avahi
Description: Illustrates how to do generic publishing/discovery of zeroconf services using a ros style api with avahi.Keywords: zeroconf avahi
Tutorial Level: INTERMEDIATE
Contents
Node Startup
Usually its enough to launch just one zeroconf node for your whole system. To do so without any pre-configuration:
> roslaunch zeroconf_avahi zeroconf.launch
Alternatively, a launch file snippet to launch with some pre-configuration:
<launch> <node pkg="zeroconf_avahi" type="zeroconf" name="zeroconf" output="screen"> <rosparam file="$(find my_package)/zeroconf.yaml" </node> </launch>
Adding Services/Listeners
Pre-Launch Configuration
The node can be completely setup to publish and poll for discovery directly from parameter configuration if all of the parameters can be known before runtime. An example yaml file for startup configuration of the zeroconf node:
listeners: [ '_ros-master._tcp', '_concert-master._tcp' ] services: - name: Ros type: _ros-master._tcp domain: local # port: 3555 <- not defined, so will use ros master's port by default. description: dude - name: Rosette type: _ros-master._tcp domain: local port: 3554 description: Rosette - name: Concerto type: _concert-master._tcp domain: local port: 3556 description: concerto
Runtime Configuration
Often, it's not possible to know all of your service parameters at pre-launch. A usual example is the port number - many services must grab an unused port before running, so that can only be established after the zeroconf node is up and running.
Adding listeners or publishing services in this way is simply done via the ros api with the add_listener and add_service calls. From the command line:
> rosservice call /zeroconf/add_listener "_ros-master._tcp" > rosservice call /zeroconf/add_service '{ service: { name: Ros, type: _ros-master._tc p, domain: local, port: 5555, description: ros } }'
Topics & Services
This will set up a few topics and services that will be useful for resolving the available ros masters.
add_service, remove_service : adding and removing zeroconf services.
add_listener, remove_listener : adding and removing zeroconf listeners.
new_connections, lost_connections : topics that provide up-down status of services in (almost) real time.
list_discovered_services : service that returns a list of the currently discovered services.
# List all published/discovered services > rosservice call /zeroconf/list_published_services "" > rosservice call /zeroconf/list_discovered_services "" # List only _ros-master._tcp services > rosservice call /zeroconf/list_discovered_services "_ros-master._tcp" # Real time updates for any listened to service types > rostopic echo /zeroconf/new_connections > rostopic echo /zeroconf/lost_connections
Code Examples
Listening
It is usually a good idea to follow the 3 steps:
Call add_listener for the service type you want to listen to.
Subscribe to new_connections and lost_connections.
Call list_discovered_services.
If you do this, then you will be guaranteed to have a fully up to date list of the currently discovered services. Further, if you store them in a container that guarantees uniqueness, then you will make sure to avoid duplicates that may be generated by discoveries occurring between the new_connections subscription and the list_discovered_services call.
1 from zeroconf_comms.msg import *
2 from zeroconf_comms.srv import *
3
4 concert_clients = set([])
5
6 def listen_for_app_managers():
7 try:
8 rospy.wait_for_service('add_listener', 30.0)
9 add_listener=rospy.ServiceProxy('add_listener', AddListener)
10 request = zeroconf_comms.srv.AddListenerRequest()
11 request.service_type = '_app-manager._tcp'
12 response = add_listener(request)
13 if response.result == False:
14 rospy.logerr("Conductor: couldn't add a listener to the zeroconf node.")
15 except rospy.ROSException:
16 rospy.logerr("Conductor: couldn't find the zeroconf node.")
17
18 def new_connection_cb(new_zconf_client):
19 if new_zconf_client.service_type == "_app-manager._tcp":
20 concert_clients.add(new_zconf_client)
21 # ...
22
23 def main():
24 listen_for_app_managers()
25 rospy.Subscriber("new_connections",zeroconf_comms.msg.DiscoveredService,
26 self.new_connection_cb)
27 try:
28 discover_clients = rospy.ServiceProxy('list_discovered_services',
29 zeroconf_comms.srv.ListDiscoveredServices)
30 request = zeroconf_comms.srv.ListDiscoveredServicesRequest()
31 request.service_type = "_app-manager._tcp"
32 response = discover_clients(request)
33 for service in response.services
34 concert_clients.add(service)
35 except rospy.ServiceException, error:
36 rospy.logwarn("Conductor : could not get the list of concert clients via zeroconf [%s]"%error)
Publishing
A python snippet:
1 from zeroconf_comms.srv import *
2
3 def main():
4 rospy.init_node('concert_master')
5 request = AddServiceRequest()
6 request.service.name = rospy.get_param("~name","Concert Master")
7 request.service.type = "_concert-master._tcp"
8 request.service.domain = rospy.get_param("~domain","local")
9 request.service.port = roslib.network.parse_http_host_and_port(roslib.rosenv.get_master_uri())[1]
10 try:
11 rospy.wait_for_service('add_service', 30.0)
12 advertise_concert_master = rospy.ServiceProxy('add_service', zeroconf_comms.srv.AddService)
13 response = advertise_concert_master(request)
14 if response.result:
15 rospy.loginfo("Concert Master: advertising zeroconf information [%s][%s][%s]"%(request.service.name, request.service.domain, request.service.port))
16 else:
17 rospy.logwarn("Concert Master : failed to advertise this concert master on the zeroconf node")
18 except rospy.ROSException:
19 rospy.logerr("Concert Master: timed out waiting for the zeroconf node to become available.")