#################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= [[rocon_gateway_tutorials/Tutorials/groovy/Flipping|Flipping]] ## descriptive title for the tutorial ## title = Advertising & Pulling ## multi-line description to be displayed in search ## description = Introduction to pulling from an advertised interface on a remote gateway. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level= BeginnerCategory ## keywords = rocon, multimaster, gateway, pull #################################### <> <> == 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 == Some example python code. Advertisements on ROS_MASTER_URI=http://localhost:11312: {{{#!python req = AdvertiseRequest() rule = Rule() rule.name = '/chatter' rule.type = gateway_msgs.ConnectionType.PUBLISHER rule.node = '/talker' rospy.loginfo("Advertise : [%s,%s,%s]."%(rule.type, rule.name, rule.node)) req.rules.append(self.rule) resp = advertise_service(self.req) if resp.result != 0: rospy.logerr("Advertise : %s"%resp.error_message) }}} Then pulling on ROS_MASTER_URI=http://localhost:11313: {{{#!python gateway = 'Pirate Gateway' pull_service = rospy.ServiceProxy('/gateway/pull',Remote) req = RemoteRequest() req.cancel = False req.remotes = [] rule = gateway_msgs.msg.Rule() rule.name = '/chatter' gateway_msgs.ConnectionType.PUBLISHER rule.node = '/talker' req.remotes.append(RemoteRule(gateway, rule)) rospy.loginfo("Pull : [%s,%s,%s,%s]."%(self.gateway, rule.type, rule.name, rule.node or 'None')) resp = pull_service(req) if resp.result != 0: rospy.logerr("Pull : %s"%resp.error_message) 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 [[rocon_gateway_tutorials/Tutorials/Flipping|Flipping]] ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE