Note: This tutorial assumes that you have completed the previous tutorials: Launching a Gateway Hub. |
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. |
Flipping
Description: Introduction to flipping connections across gateways.Keywords: rocon, multimaster, gateway, flip
Tutorial Level: BEGINNER
Next Tutorial: Advertising & Pulling
Contents
Overview
Flipping is a means of getting a local connection across to remote ros system via the gateway network. Note that the flipped connection is not a relay, it is a direct node to node connection where your local node's connection details get registered at the remote master via the instruction of the remote gateway.
Workflow
The usual workflow for a flip is as follows (note that some of these steps are internal, but presented here for illustration):
- You create a flip rule containing the following data:
- Target remote gateway name (e.g. 'Foobar Gateway')
- Local connection name (e.g. '/chatter')
- Local connection type (e.g. 'publisher')
- Local 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 flip rule gets added to a watchlist
- If a matching connection is available, it immediately sends a flip request.
- The local gateway periodically checks for matches against the flip rule and acts when it finds a match.
Any flip request is handled by the remote gateway before proceeding.
- If the remote gateway has a firewall flag configured, it blocks, otherwise
- It registers the connection with it's local master.
Code
Some example python code:
1 gateway = 'Foo Gateway'
2 flip_service = rospy.ServiceProxy('/gateway/flip',Remote)
3 gateway = 'Foo Gateway'
4 req = RemoteRequest()
5 req.cancel = False
6 req.remotes = []
7 rule = gateway_msgs.msg.Rule()
8 rule.name = '/chatter'
9 rule.type = gateway_msgs.ConnectionType.PUBLISHER
10 rule.node = '/talker'
11 req.remotes.append(RemoteRule(gateway,rule))
12 rospy.loginfo("Flip : [%s,%s,%s,%s]."%(gateway, rule.name, rule.type, rule.node)
13 resp = self.flip_service(req)
14 if resp.result != 0:
15 rospy.logerr("Flip : %s"%resp.error_message)
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 flip a the publisher /chatter only from the first gateway to the second, in a shell with ROS_MASTER_URI=http://localhost:11312:
> rosrun rocon_gateway_tutorials flip_tutorials --pubonly
Run flip_tutorials with --help to find the other target operations. For more code samples, check the source code of the flip scripts in rocon_gateway_tutorials.
Limitations
Gateways can't remap connection namespaces, beware of conflicts with flips from other gateways. You may need some infrastructure to ensure that you are flipping to a unique namespace on the remote system.
Flipping creates a direct registration/connection. It does not change the type (e.g. tcpros/udpros) of connection made. We are waiting for changes in the communication infrastructure before handling this.