ros_parameters.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/license/LICENSE
00005 #
00006 
00007 import re
00008 
00009 import rospy
00010 from gateway_msgs.msg import Rule, RemoteRule
00011 
00012 from . import utils
00013 
00014 ###############################################################################
00015 # Functions
00016 ###############################################################################
00017 
00018 
00019 def setup_ros_parameters():
00020     '''
00021     Returns the gateway parameters from the ros param server.
00022     Most of these should be fairly self explanatory.
00023     '''
00024     param = {}
00025 
00026     # Hub
00027     param['hub_uri'] = rospy.get_param('~hub_uri', '')
00028     # Convert these back to accepting lists once https://github.com/ros/ros_comm/pull/218
00029     # goes through, for now we use semi-colon separated lists.
00030     param['hub_whitelist'] = rospy.get_param('~hub_whitelist', [])
00031     param['hub_blacklist'] = rospy.get_param('~hub_blacklist', [])
00032 
00033     # Gateway
00034     param['name'] = rospy.get_param('~name', 'gateway')
00035     param['watch_loop_period'] = rospy.get_param('~watch_loop_period', 10)  # in seconds
00036 
00037     # Blacklist used for advertise all, flip all and pull all commands
00038     param['default_blacklist'] = rospy.get_param('~default_blacklist', [])  # list of Rule objects
00039 
00040     # Used to block/permit remote gateway's from flipping to this gateway.
00041     param['firewall'] = rospy.get_param('~firewall', True)
00042 
00043     # The gateway can automagically detect zeroconf, but sometimes you want to force it off
00044     param['disable_zeroconf'] = rospy.get_param('~disable_zeroconf', False)
00045 
00046     # The gateway uses uui'd to guarantee uniqueness, but this can be disabled
00047     # if you want clean names without uuid's (but you have to manually
00048     # guarantee uniqueness)
00049     param['disable_uuids'] = rospy.get_param('~disable_uuids', False)
00050 
00051     # Make everything publicly available (excepting the default blacklist)
00052     param['advertise_all'] = rospy.get_param('~advertise_all', [])  # boolean
00053 
00054     # Topics and services for pre-initialisation/configuration
00055     param['default_advertisements'] = rospy.get_param('~default_advertisements', [])  # list of Rule objects
00056     param['default_flips'] = rospy.get_param('~default_flips', [])  # list of RemoteRule objects
00057     param['default_pulls'] = rospy.get_param('~default_pulls', [])  # list of RemoteRule objects
00058 
00059     # Network interface name (to be used when there are multiple active interfaces))
00060     param['network_interface'] = rospy.get_param('~network_interface', '')  # string
00061 
00062     # Let an external party (e.g. concert conductor) manually shutdown the gateway
00063     # so we can have control over when flips and pulls get deregistered (lets us do last
00064     # minute service calls across masters before our own master goes down)
00065     param['external_shutdown'] = rospy.get_param('~external_shutdown', False)
00066     param['external_shutdown_timeout'] = rospy.get_param('~external_shutdown_timeout', 15)  # seconds
00067 
00068     return param
00069 
00070 
00071 def generate_rules(param):
00072     '''
00073       Converts a param of the suitable type (see default_blacklist.yaml)
00074       into a dictionary of Rule types.
00075 
00076       @return all rules as gateway_msgs.msg.Rule objects in our usual keyed dictionary format
00077       @rtype type keyed dictionary of Rule lists
00078     '''
00079     rules = utils.create_empty_connection_type_dictionary()
00080     for value in param:
00081         rule = Rule()
00082         rule.name = value['name']
00083         # maybe also check for '' here?
00084         pattern = re.compile("None", re.IGNORECASE)
00085         if pattern.match(value['node']):
00086             rule.node = ''  # ROS Message fields should not be None, maybe not a problem here though, see below
00087         else:
00088             rule.node = value['node']
00089         rule.type = value['type']
00090         rules[rule.type].append(rule)
00091     return rules
00092 
00093 
00094 def generate_remote_rules(param):
00095     '''
00096        Converts a param of the suitable type (default_flips, default_pulls) into
00097        a list of RemoteRule objects and a list of target gateways for flip_all/pull_all.
00098 
00099        @param yaml object
00100        @type complicated
00101 
00102        @return list of remote rules
00103        @return RemoteRule[]
00104     '''
00105     remote_rules = []
00106     all_targets = []
00107     pattern = re.compile("None", re.IGNORECASE)
00108     for remote_rule in param:
00109         if 'rule' in remote_rule:
00110             # maybe also check for '' here?
00111             node = None if pattern.match(remote_rule['rule']['node']) else remote_rule['rule']['node']
00112             remote_rules.append(RemoteRule(remote_rule['gateway'],
00113                                            Rule(remote_rule['rule']['type'],
00114                                                 remote_rule['rule']['name'],
00115                                                 node
00116                                                 )
00117                                            )
00118                                 )
00119         else:
00120             all_targets.append(remote_rule['gateway'])
00121     return remote_rules, all_targets


rocon_gateway
Author(s): Daniel Stonier , Jihoon Lee , Piyush Khandelwal
autogenerated on Sat Jun 8 2019 18:48:44