def __init__(self): ''' Creates a new instance. Find the topic of the master_discovery node using U{fkie_master_discovery.interface_finder.get_changes_topic() <http://docs.ros.org/api/fkie_master_discovery/html/modules.html#interface-finder-module>}. Also the parameter C{~ignore_hosts} will be analyzed to exclude hosts from sync. ''' self.masters = {} # the connection to the local service master self.materuri = masteruri_from_master() '''@ivar: the ROS master URI of the C{local} ROS master. ''' self.__lock = threading.RLock() # load interface self._load_interface() # subscribe to changes notifier topics topic_names = interface_finder.get_changes_topic( masteruri_from_master()) self.sub_changes = dict() '''@ivar: `dict` with topics {name: U{rospy.Subscriber<http://docs.ros.org/api/rospy/html/rospy.topics.Subscriber-class.html>}} publishes the changes of the discovered ROS masters.''' for topic_name in topic_names: rospy.loginfo("listen for updates on %s", topic_name) self.sub_changes[topic_name] = rospy.Subscriber( topic_name, MasterState, self._rosmsg_callback_master_state) self.__timestamp_local = None self.__own_state = None self.update_timer = None self.own_state_getter = None self._join_threads = dict( ) # threads waiting for stopping the sync thread # initialize the ROS services rospy.Service('~get_sync_info', GetSyncInfo, self._rosservice_get_sync_info) rospy.on_shutdown(self.finish) self.obtain_masters()
def master_changed(msg, cb_args): param_cache, local_master = cb_args local_name = '' if local_master: local_name = local_master[0] if msg.master.uri != masteruri_from_master() and local_name in param_cache: master_to = rospy.MasterProxy(masteruri_from_master()) master_from = rospy.MasterProxy(msg.master.uri) rospy.logdebug("Getting params from {}...".format(msg.master.uri)) params_from = master_from['/'] rospy.logdebug("Got {} params.".format(len(msg.master.uri))) if local_name in params_from: del params_from[local_name] if '/' + local_name in params_from: del params_from['/' + local_name] rospy.logdebug("Syncing params from {} to {}...".format( msg.master.name, local_name)) if param_cache.get(msg.master.name, None) != params_from: param_cache[msg.master.name] = params_from master_to['/' + msg.master.name] = params_from rospy.logdebug("Done syncing params from {} to {}.".format( msg.master.name, local_name)) else: rospy.logdebug("Params have not changed from {} to {}.".format( msg.master.name, local_name)) else: local_name = msg.master.name local_master.append(local_name) master_from = rospy.MasterProxy(msg.master.uri) rospy.logdebug("Getting params from local {}...".format( msg.master.uri)) param_cache[local_name] = master_from['/'] rospy.logdebug("Got {} params.".format(len(msg.master.uri)))
def __init__(self, path, masteruri=''): ''' :param str path: absolute path of the launch file. :param str masteruri: ROS-Masteruri if empty the masteruri will be determine by :meth:`fkie_master_discovery.common.masteruri_from_master` ''' self.path = path self.masteruri = masteruri self._local = False if not masteruri: self.masteruri = masteruri_from_master(True) self._local = True elif url.equal_uri(self.masteruri, masteruri_from_master(True)): self._local = True
def main(): rospy.init_node('param_sync', log_level=rospy.DEBUG) param_cache = dict() local_master = list() masteruri_from_master() __add_ns = rospy.get_param('~add_ns', True) __ignore = rospy.get_param('~ignore', []) __only = rospy.get_param('~only', []) sub = rospy.Subscriber('master_discovery/changes', MasterState, master_changed, callback_args=(param_cache, local_master, __add_ns, __ignore, __only)) rospy.spin()
def main(): rospy.init_node('param_sync', log_level=rospy.DEBUG) param_cache = dict() local_master = list() masteruri_from_master() sub = rospy.Subscriber('master_discovery/changes', MasterState, master_changed, callback_args=(param_cache, local_master)) rospy.spin()
def __init__(self, parent=None, progress_queue=None, viewobj=None): ''' Creates a new list model. ''' QStandardItemModel.__init__(self, parent) self.viewobj = viewobj self.setColumnCount(len(LaunchListModel.header)) self.setHorizontalHeaderLabels( [label for label, _width in LaunchListModel.header]) self.pyqt_workaround = dict( ) # workaround for using with PyQt: store the python object to keep the defined attributes in the TopicItem subclass self.items = [] self._roots = {} self._current_path = nmdurl.nmduri() self._current_master = masteruri_from_master() self._current_master_name = '' self.ros_root_paths = {} # {url: [root pasth(str)]} self.ros_root_paths[self._current_path] = [ os.path.normpath(p) for p in os.getenv("ROS_PACKAGE_PATH").split(':') ] self._progress_queue = progress_queue nm.nmd().file.listed_path.connect(self._listed_path) nm.nmd().file.packages_available.connect(self._on_new_packages) nm.nmd().file.error.connect(self._nmd_error)
def obtain_masters(self): ''' This method use the service 'list_masters' of the master_discoverer to get the list of discovered ROS master. Based on this list the L{SyncThread} for synchronization will be created. @see: U{fkie_master_discovery.interface_finder.get_listmaster_service() <http://docs.ros.org/api/fkie_master_discovery/html/modules.html#interface-finder-module>} ''' if not rospy.is_shutdown(): service_names = interface_finder.get_listmaster_service(masteruri_from_master(), False, check_host=self._check_host) for service_name in service_names: try: with self.__lock: try: socket.setdefaulttimeout(5) discoverMasters = rospy.ServiceProxy(service_name, DiscoverMasters) resp = discoverMasters() masters = [] master_names = [m.name for m in resp.masters] rospy.loginfo("ROS masters obtained from '%s': %s", service_name, master_names) for m in resp.masters: if self._can_sync(m.name): # do not sync to the master, if it is in ignore list or not in filled sync list masters.append(m.name) self.update_master(m.name, m.uri, m.last_change.to_sec(), m.last_change_local.to_sec(), m.discoverer_name, m.monitoruri, m.online) for key in set(self.masters.keys()) - set(masters): self.remove_master(self.masters[key].name) except rospy.ServiceException as e: rospy.logwarn("ERROR Service call 'list_masters' failed: %s", str(e)) except: import traceback rospy.logwarn("ERROR while initial list masters: %s", traceback.format_exc()) finally: socket.setdefaulttimeout(None) self.update_timer = threading.Timer(self.UPDATE_INTERVALL, self.obtain_masters) self.update_timer.start()
def nmduri(uri='', prefix='grpc://'): ''' Determine for given url a gRPC-URI with `grpc://` scheme. If the given URI is a ROS-Master URI the method calculate new port by adding `NMD_SERVER_PORT_OFFSET`. If the given URI is empty we try to determine the ROS-Master URI from environment or from ROS-Master. :param str uri: empty or ROS-Master uri :param str prefix: the scheme can be replaced :return: URI with `grpc`-scheme. :rtype: str :raise ValueError: if uri is not empty and contains no scheme ('http', 'grpc') ''' muri = uri if not muri: muri = masteruri_from_master(True) o = urlparse(muri) port = o.port if o.scheme not in ['http', 'grpc']: raise ValueError( "uri parameter does not contain a scheme of ['http', ''grpc']: %s" % uri) if o.scheme == 'http': port += NMD_SERVER_PORT_OFFSET return "%s%s:%d" % (prefix, o.hostname, port)
def __init__(self, launch_file, package=None, masteruri='', host='', argv=None): ''' Creates the LaunchConfig object. The launch file will be not loaded on creation, first on request of roscfg value. :param str launch_file: The absolute or relative path with the launch file. By using relative path a package must be valid for remote launches. :param package: the package containing the launch file. If None the launch_file will be used to determine the launch file. No remote launches a possible without a valid package. :type package: str or None :param str masteruri: The URL of the ROS master. :param argv: the list the arguments needed for loading the given launch file :type argv: list(str) :raise roslaunch.XmlParseException: if the launch file can't be found. ''' self.__launchfile = launch_file self.__package = package_name(os.path.dirname(self.__launchfile))[0] if package is None else package self.__masteruri = masteruri if masteruri else masteruri_from_master(True) self.__roscfg = None self.argv = argv if self.argv is None: self.argv = [] self.__reqTested = False self.__argv_values = dict() self.global_param_done = [] # masteruri's where the global parameters are registered self.__launch_id = '%.9f' % time.time() self._robot_description = None self._capabilities = None self.host = host if host else None self.resolve_dict = {} self.changed = True
def master_changed(msg, cb_args): param_cache, local_master, __add_ns, __ignore, __only = cb_args local_name = '' if local_master: local_name = local_master[0] if msg.master.uri != masteruri_from_master() and local_name in param_cache: master_to = rospy.MasterProxy(masteruri_from_master()) master_from = rospy.MasterProxy(msg.master.uri) rospy.logdebug("Getting params from {}...".format(msg.master.uri)) params_from = master_from.getParam('/')[2] if not __add_ns: for key in ['run_id', 'rosversion', 'roslaunch', 'rosdistro', 'master_sync', 'master_discovery', 'capabilities', 'mastername', 'robots']: try: del params_from[key] except Exception: pass for key in __ignore + [local_name, '/'+local_name]: try: del params_from[key] except Exception: pass if __only: for key in params_from.keys(): if key not in __only: del params_from[key] rospy.logdebug("Syncing params from {} to {}...".format(msg.master.name, local_name)) if __add_ns: _ns = msg.master.name else: _ns = '' rospy.logdebug("Got {} params.".format(len(params_from))) if param_cache.get(_ns, None) != params_from: param_cache[_ns] = params_from for key, value in params_from.items(): master_to.setParam('/'+_ns+key, value) rospy.logdebug("Done syncing params from {} to {}.".format(msg.master.name, local_name)) else: rospy.logdebug("Params have not changed from {} to {}.".format(msg.master.name, local_name)) else: local_name = msg.master.name local_master.append(local_name) master_from = rospy.MasterProxy(msg.master.uri) rospy.logdebug("Getting params from local {}...".format(msg.master.uri)) param_cache[local_name] = master_from.getParam('/')[2] rospy.logdebug("Got {} local params.".format(len(param_cache[local_name])))
def set_current_master(self, masteruri, mastername): self._current_master = masteruri.rstrip(os.path.sep) self._current_master_name = mastername if self._is_root(self._current_path): nm.nmd().file.list_path_threaded(self._current_path) if nmdurl.equal_uri(self._current_path, masteruri_from_master()): self._add_path(nmdurl.nmduri(self._current_master), PathItem.REMOTE_DAEMON, 0, 0, get_hostname(self._current_master_name))
def nmdport(uri=''): ''' Determine the port for GRPC-server from given URI. If empty try to get the ROS-Master URI. ''' muri = uri if not muri: muri = masteruri_from_master(True) o = urlparse(muri) port = o.port if o.scheme == 'http': port += NMD_SERVER_PORT_OFFSET return port
def _listed_path(self, url, path, result): if not self.is_current_nmd(url): return root = self.invisibleRootItem() while root.rowCount(): root.removeRow(0) self.pyqt_workaround.clear() # test for ROS root paths and add these if it is in ROS_PACKAGE_PATH isroot = path in ['', os.path.sep] if isroot: self.ros_root_paths[url] = [] # append path items to the list model result_list = [] for path_item in result: if isroot and path_item.type in [FileItem.DIR, FileItem.PACKAGE]: self.ros_root_paths[url].append(path_item.path) item = os.path.normpath(os.path.join(path, path_item.path)) gpath = nmdurl.join(url, item) path_id = PathItem.NOT_FOUND if FileItem.FILE == path_item.type: _, ext = os.path.splitext(path_item.path) if ext in nm.settings( ).launch_view_file_ext or path_item.path.find('.launch.') > 0: path_id = PathItem.FILE elif FileItem.DIR == path_item.type: path_id = PathItem.FOLDER elif FileItem.SYMLINK == path_item.type: pass elif FileItem.PACKAGE == path_item.type: path_id = PathItem.PACKAGE if path_id != PathItem.NOT_FOUND and not os.path.basename( path_item.path).startswith('.'): # TODO: create filter for files result_list.append( (gpath, path_id, path_item.mtime, path_item.size, os.path.basename(path_item.path))) root_path = nmdurl.join(url, path) self._set_new_list(root_path, result_list) isroot = self._is_root(self._current_path) if isroot and not nmdurl.equal_uri(self._current_master, masteruri_from_master()): self._add_path(nmdurl.nmduri(self._current_master), PathItem.REMOTE_DAEMON, 0, 0, get_hostname(self._current_master_name)) self.pathlist_handled.emit(root_path)
def masteruri(grpc_path): ''' Determine ROS-Master uri from gRPC-URI by replacing the scheme and reducing the port by :const:`NMD_SERVER_PORT_OFFSET`. :param str grpc_path: an URI with `grpc://` scheme. :return: ROS-Master URI :rtype: str :raise ValueError: if uri is not empty and does not start with 'grpc://'. ''' if not grpc_path: return masteruri_from_master(True) if not grpc_path.startswith('grpc://'): raise ValueError("Invalid grpc path to get masteruri: %s; `grpc` scheme missed!" % grpc_path) o = urlparse(grpc_path) port = o.port if o.scheme == 'grpc': port -= NMD_SERVER_PORT_OFFSET return "http://%s:%d/" % (o.hostname, port)