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

Next Tutorial: Writing Gateway Launchers

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).

https://docs.google.com/drawings/pub?id=14GTqHBcsPemx3HKGV21o_LXUq7ZWubGSoMllum7kn9A&w=589&h=326

Code

Code

Firstly launch the gateway tutorial masters

> rocon_launch rocon_gateway_tutorials gateway_tutorials.concert

and then let's write a very simple example python program to do some advertising:

   1 import rospy
   2 import gateway_msgs.msg as gateway_msgs
   3 import gateway_msgs.srv as gateway_srvs
   4 import rocon_gateway
   5 
   6 rospy.init_node('advertise')
   7 rospy.wait_for_service('/gateway/advertise')
   8 advertise_service=rospy.ServiceProxy('/gateway/advertise', gateway_srvs.Advertise)
   9 req = gateway_srvs.AdvertiseRequest()
  10 rule = gateway_msgs.Rule()
  11 rule.name = '/chatter'
  12 rule.type = gateway_msgs.ConnectionType.PUBLISHER
  13 rule.node = '/talker'
  14 rospy.loginfo("Advertise : [%s,%s,%s]."%(rule.type, rule.name, rule.node))
  15 req.rules.append(rule)
  16 resp = advertise_service(req)
  17 if resp.result != 0:
  18     rospy.logerr("Advertise : %s"%resp.error_message)

and pulling:

   1 import rospy
   2 import gateway_msgs.msg as gateway_msgs
   3 import gateway_msgs.srv as gateway_srvs
   4 import rocon_gateway
   5 
   6 rospy.init_node('pull')
   7 rospy.wait_for_service('/gateway/pull')
   8 remote_gateway = rocon_gateway.samples.find_first_remote_gateway()
   9 pull_service = rospy.ServiceProxy('/gateway/pull', gateway_srvs.Remote)
  10 req = gateway_srvs.RemoteRequest()
  11 req.cancel = False
  12 req.remotes = []
  13 rule = gateway_msgs.Rule()
  14 rule.name = '/chatter'
  15 rule.type = gateway_msgs.ConnectionType.PUBLISHER
  16 rule.node = '/talker'
  17 req.remotes.append(RemoteRule(gateway, rule))
  18 rospy.loginfo("Pull : [%s,%s,%s,%s]."%(remote_gateway,
  19                                        rule.type,
  20                                        rule.name,
  21                                        rule.node or 'None'))
  22 resp = pull_service(req)
  23 if resp.result != 0:
  24     rospy.logerr("Pull : %s"%resp.error_message)

Open two new shells - in the first, export ROS_MASTER_URI=https://localhost:11312 and run the advertising script. In the second, export ROS_MASTER_URI=https://localhost:11313 and run the pulling script. You should be able to echo the chatter topic that has been pulled across.

Examples

As with flipping there are quite a few more complete examples in rocon_gateway_tutorials. Firstly, fire up the gateway tutorial masters:

> rocon_launch rocon_gateway_tutorials gateway_tutorials.concert

In two other shells, test advertising:

> export ROS_MASTER_URI=http://localhost:11312
> rosrun rocon_gateway_tutorials advertise_tutorials.py --pubonly

and to test pulling:

> export ROS_MASTER_URI=http://localhost:11313
> rosrun rocon_gateway_tutorials pull_tutorials.py --pubonly

Run the scripts with --help to find the other target operations.

Limitations

Same as those for Flipping

Wiki: rocon_gateway_tutorials/Tutorials/indigo/Advertising and Pulling (last edited 2014-03-25 00:24:09 by DanielStonier)