Note: This tutorial assumes that you have completed the previous tutorials: Flipping. |
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. |
Advertising & Pulling
Description: Introduction to pulling from an advertised interface on a remote gateway.Keywords: rocon, multimaster, gateway, pull
Tutorial Level: BEGINNER
Contents
Overview
Pulling is the inverse operation of flip. Whereas a flip is initiated by the sender, a pull is initiated by the receiver of a connection.
It is actually a two step process. First a remote gateway has to publicly make available a topic (i.e. advertise). Once available, other gateways can freely pull and register that connection on their own ros system.
Workflow
The usual workflow for a pull is as follows (note that some of these steps are internal, but presented here for illustration):
- Remote gateway creates an advertisement with the following data:
- Connection name (e.g. '/chatter')
- Connection type (e.g. 'publisher')
- Connection node name (e.g. '/talker')
Note that each of the fields except for type may also be a python regex pattern, e.g. '/chat.*'.
- The local gateway creates a pull rule (like a flip rule).
- If a match is found on the specified remote gateway, the local gateway registers the remote connection on the local master.
- Pull rules can be activated and are periodically checked for new/lost connections (same as flips).
Code
Some example python code. Advertisements on ROS_MASTER_URI=http://localhost:11312:
1 req = AdvertiseRequest()
2 rule = Rule()
3 rule.name = '/chatter'
4 rule.type = gateway_msgs.ConnectionType.PUBLISHER
5 rule.node = '/talker'
6 rospy.loginfo("Advertise : [%s,%s,%s]."%(rule.type, rule.name, rule.node))
7 req.rules.append(self.rule)
8 resp = advertise_service(self.req)
9 if resp.result != 0:
10 rospy.logerr("Advertise : %s"%resp.error_message)
Then pulling on ROS_MASTER_URI=http://localhost:11313:
1 gateway = 'Pirate Gateway'
2 pull_service = rospy.ServiceProxy('/gateway/pull',Remote)
3 req = RemoteRequest()
4 req.cancel = False
5 req.remotes = []
6 rule = gateway_msgs.msg.Rule()
7 rule.name = '/chatter'
8 gateway_msgs.ConnectionType.PUBLISHER
9 rule.node = '/talker'
10 req.remotes.append(RemoteRule(gateway, rule))
11 rospy.loginfo("Pull : [%s,%s,%s,%s]."%(self.gateway,
12 rule.type,
13 rule.name,
14 rule.node or 'None'))
15 resp = pull_service(req)
16 if resp.result != 0:
17 rospy.logerr("Pull : %s"%resp.error_message)
18 req.remotes = []
Examples
In three separate shells, launch the hub, a gateway system with tutorials running, and an empty gateway system.
> roslaunch --port=11311 rocon_gateway_tutorials pirate_hub.launch
> roslaunch --port=11312 rocon_gateway_tutorials pirate_gateway_tutorials.launch
> roslaunch --port=11313 rocon_gateway_tutorials pirate_gateway.launch
To advertise the publisher /chatter only in the first gateway(ROS_MASTER_URI=http://localhost:11312):
> rosrun rocon_gateway_tutorials advertise_tutorials --pubonly
To pull the advertised connection into the second gateway, (ROS_MASTER_URI=http://localhost:11313):
> rosrun rocon_gateway_tutorials pull_tutorials --pubonly
Run pull_tutorials with --help to find the other target operations. For more code samples, check the source code of the advertise/pull scripts in rocon_gateway_tutorials.
Limitations
Same as those for Flipping