advertise_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, cancel_flag, regex):
00025         if cancel_flag:
00026             self.action_text = "cancelling"
00027         else:
00028             self.action_text = "advertising"
00029         self.advertise_service = rospy.ServiceProxy('/gateway/advertise',Advertise)
00030         self.req = AdvertiseRequest() 
00031         self.req.cancel = cancel_flag
00032         self.rule = Rule()
00033         self.names, self.nodes = rocon_gateway_tutorials.createTutorialDictionaries(regex)
00034         
00035     def advertise(self, type):
00036         self.req.rules = []
00037         self.rule.name = self.names[type]
00038         self.rule.type = type
00039         self.rule.node = self.nodes[type]
00040         rospy.loginfo("Advertise : %s [%s,%s,%s]."%(self.action_text,self.rule.type, self.rule.name, self.rule.node or 'None')) 
00041         self.req.rules.append(self.rule) 
00042         resp = self.advertise_service(self.req)
00043         if resp.result != 0:
00044             rospy.logerr("Advertise : %s"%resp.error_message)
00045 
00046 ##############################################################################
00047 # Main
00048 ##############################################################################
00049     
00050 """
00051   Tests advertisements, either for all tutorials (default) or one by one (via args).
00052   
00053   Usage:
00054     1 > roslaunch rocon_gateway_tutorials pirate_hub.launch
00055     2a> roslaunch rocon_gateway_tutorials pirate_gateway_tutorials.launch
00056     3a> roslaunch rocon_gateway_tutorials pirate_gateway.launch
00057     2b> rosrun rocon_gateway_tutorials advertise_tutorials.py
00058     2c> rosservice call /gateway/gateway_info
00059     3b> rosservice call /gateway/remote_gateway_info []
00060     2d> rosrun rocon_gateway_tutorials advertise_tutorials.py --cancel
00061     2e> rosrun rocon_gateway_tutorials advertise_tutorials.py --regex
00062     2f> rosrun rocon_gateway_tutorials advertise_tutorials.py --regex --cancel
00063 """
00064 
00065 if __name__ == '__main__':
00066 
00067     parser = argparse.ArgumentParser(description='Advertise tutorial connections (/chatter, /add_two_ints to a remote gateway')
00068     parser.add_argument('--pubonly', action='store_true', help='advertise /chatter publisher only')
00069     parser.add_argument('--subonly', action='store_true', help='advertise /chatter subscriber only')
00070     parser.add_argument('--serviceonly', action='store_true', help='advertise /add_two_ints service only')
00071     parser.add_argument('--actionclientonly', action='store_true', help='advertise /fibonacci action client only')
00072     parser.add_argument('--actionserveronly', action='store_true', help='advertise /averaging action server only')
00073     parser.add_argument('--regex', action='store_true', help='test with a regex pattern')
00074     parser.add_argument('--cancel', action='store_true', help='cancel the advertisement')
00075     args = parser.parse_args()
00076 
00077     advertise_all_connection_types = (not args.pubonly) and (not args.subonly) and (not args.serviceonly) and (not args.actionclientonly) and (not args.actionserveronly)
00078 
00079     rospy.init_node('advertise_tutorials')
00080 
00081     context = Context(args.cancel, args.regex)
00082 
00083     if args.pubonly or advertise_all_connection_types:
00084         context.advertise(ConnectionType.PUBLISHER)
00085 
00086     if args.subonly or advertise_all_connection_types:
00087         context.advertise(ConnectionType.SUBSCRIBER)
00088 
00089     if args.serviceonly or advertise_all_connection_types:
00090         context.advertise(ConnectionType.SERVICE)
00091 
00092     if args.actionclientonly or advertise_all_connection_types:
00093         context.advertise(ConnectionType.ACTION_CLIENT)
00094 
00095     if args.actionserveronly or advertise_all_connection_types:
00096         context.advertise(ConnectionType.ACTION_SERVER)
00097 
 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