pull_tutorials.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #       
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_multimaster/master/rocon_gateway_tutorials/LICENSE 
00005 #
00006 ##############################################################################
00007 # Imports
00008 ##############################################################################
00009 
00010 import roslib; roslib.load_manifest('rocon_gateway_tutorials')
00011 import rospy
00012 import rocon_gateway
00013 import rocon_gateway_tutorials
00014 from gateway_msgs.msg import *
00015 from gateway_msgs.srv import *
00016 import argparse
00017 import sys
00018 
00019 ##############################################################################
00020 # Utilities
00021 ##############################################################################
00022 
00023 class Context(object):
00024     def __init__(self, gateway, cancel_flag, regex):
00025         self.gateway = gateway
00026         if cancel_flag:
00027             self.action_text = "cancelling"
00028         else:
00029             self.action_text = "pulling"
00030         self.pull_service = rospy.ServiceProxy('/gateway/pull',Remote)
00031         self.req = RemoteRequest() 
00032         self.req.cancel = cancel_flag
00033         self.req.remotes = []
00034         self.names, self.nodes = rocon_gateway_tutorials.createTutorialDictionaries(regex)
00035 
00036     def pull(self, type):
00037         rule = gateway_msgs.msg.Rule()
00038         rule.name = self.names[type]
00039         rule.type = type
00040         rule.node = self.nodes[type]
00041         self.req.remotes.append(RemoteRule(self.gateway, rule))
00042         rospy.loginfo("Pull : %s [%s,%s,%s,%s]."%(self.action_text, 
00043                                                   self.gateway, 
00044                                                   rule.type, 
00045                                                   rule.name, 
00046                                                   rule.node or 'None')) 
00047         resp = self.pull_service(self.req)
00048         if resp.result != 0:
00049             rospy.logerr("Pull : %s"%resp.error_message)
00050         self.req.remotes = []
00051 
00052 ##############################################################################
00053 # Main
00054 ##############################################################################
00055 
00056 """
00057   Tests pulls, either for all tutorials (default) or one by one (via args).
00058   
00059   Usage:
00060     1 > roslaunch rocon_gateway_tutorials pirate.launch
00061     2a> roslaunch rocon_gateway_tutorials pirate_gateway_tutorials.launch
00062     3a> roslaunch rocon_gateway_tutorials pirate_gateway.launch
00063     2b> rosrun rocon_gateway_tutorials advertise_tutorials.py
00064     3b> rosrun rocon_gateway_tutorials pull_tutorials.py
00065     3c> rostopic echo /fibonacci/server/feedback
00066     3d> roslaunch rocon_gateway_tutorials fibonacci_client.launch
00067     3e> roslaunch rocon_gateway_tutorials fibonacci_server.launch
00068     2c> # wait for fibonnacci client to finish and close 
00069     3e> rosrun rocon_gateway_tutorials pull_tutorials.py --cancel
00070     2d> rosrun rocon_gateway_tutorials advertise_tutorials.py --cancel
00071     
00072   Variations in the options (singly, or by regex patterns).
00073 """
00074 
00075 if __name__ == '__main__':
00076 
00077     parser = argparse.ArgumentParser(description='Pull roscpp tutorial connections (/chatter, /add_two_ints to a remote gateway')
00078     parser.add_argument('--pubonly', action='store_true', help='pull /chatter publisher only')
00079     parser.add_argument('--subonly', action='store_true', help='pull /chatter subscriber only')
00080     parser.add_argument('--serviceonly', action='store_true', help='pull add_two_ints service only')
00081     parser.add_argument('--actionclientonly', action='store_true', help='pull /fibonacci action client only')
00082     parser.add_argument('--actionserveronly', action='store_true', help='pull /averaging action server only')
00083     parser.add_argument('--regex', action='store_true', help='test with a regex pattern')
00084     parser.add_argument('--cancel', action='store_true', help='cancel the pull')
00085     args = parser.parse_args()
00086     pull_all_connection_types = (not args.pubonly) and (not args.subonly) and (not args.serviceonly) and (not args.actionclientonly) and (not args.actionserveronly)
00087     if args.cancel:
00088         action_text = "cancelling"
00089     else:
00090         action_text = "pulling"
00091 
00092     rospy.init_node('pull_tutorials')
00093 
00094     try:
00095         gateway = "pirate_gateway.*"
00096     except rocon_gateway.GatewayError as e:
00097         rospy.logerr("Pull Test : %s, aborting."%(str(e)))
00098         sys.exit(1)
00099 
00100     context = Context(gateway, args.cancel, args.regex)
00101 
00102     if args.pubonly or pull_all_connection_types:
00103         context.pull(ConnectionType.PUBLISHER)
00104     
00105     if args.subonly or pull_all_connection_types:
00106         context.pull(ConnectionType.SUBSCRIBER)
00107 
00108     if args.serviceonly or pull_all_connection_types:
00109         context.pull(ConnectionType.SERVICE)
00110 
00111     if args.actionclientonly or pull_all_connection_types:
00112         context.pull(ConnectionType.ACTION_CLIENT)
00113 
00114     if args.actionserveronly or pull_all_connection_types:
00115         context.pull(ConnectionType.ACTION_SERVER)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rocon_gateway_tutorials
Author(s): Daniel Stonier
autogenerated on Tue Jan 15 2013 17:43:42