rqt_roscomm_util.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Isaac Saito
00034 
00035 import os
00036 
00037 import genmsg
00038 import roslaunch
00039 from roslaunch import RLException
00040 import rospkg
00041 import rospy
00042 import rostopic
00043 
00044 
00045 class RqtRoscommUtil(object):
00046 
00047     @staticmethod
00048     def load_parameters(config, caller_id):
00049         """
00050         Load parameters onto the parameter server.
00051 
00052         Copied from ROSLaunchRunner.
00053 
00054         @type config: roslaunch.config.ROSLaunchConfig
00055         @raise RLException:
00056         """
00057 
00058         # XMLRPC proxy for communicating with master, 'xmlrpclib.ServerProxy'
00059         param_server = config.master.get()
00060 
00061         param = None
00062         try:
00063             # multi-call style xmlrpc
00064             # According to API doc, get_multi() returns
00065             # multicall XMLRPC proxy for communicating with master,
00066             # "xmlrpclib.MultiCall"
00067             param_server_multi = config.master.get_multi()
00068 
00069             # clear specified parameter namespaces
00070             # #2468 unify clear params to prevent error
00071             for param in roslaunch.launch._unify_clear_params(
00072                                                           config.clear_params):
00073                 if param_server.hasParam(caller_id, param)[2]:
00074                     param_server_multi.deleteParam(caller_id, param)
00075             r = param_server_multi()
00076             for code, msg, _ in r:
00077                 if code != 1:
00078                     raise RLException("Failed to clear parameter {}: ".format(
00079                                                                          msg))
00080         except RLException:
00081             raise
00082         except Exception, e:
00083             rospy.logerr("load_parameters: unable to set params " +
00084                          "(last param was [{}]): {}".format(param, e))
00085             raise  # re-raise as this is fatal
00086 
00087         try:
00088             # multi-call objects are not reusable
00089             param_server_multi = config.master.get_multi()
00090             for param in config.params.itervalues():
00091                 # suppressing this as it causes too much spam
00092                 # printlog("setting parameter [%s]"%param.key)
00093                 param_server_multi.setParam(caller_id, param.key, param.value)
00094             r = param_server_multi()
00095             for code, msg, _ in r:
00096                 if code != 1:
00097                     raise RLException("Failed to set parameter: " +
00098                                                 "%s" % (msg))
00099         except RLException:
00100             raise
00101         except Exception, e:
00102             print("load_parameters: unable to set params (last param was " +
00103                   "[%s]): %s" % (param, e))
00104             raise  # re-raise as this is fatal
00105         rospy.logdebug("... load_parameters complete")
00106 
00107     @staticmethod
00108     def iterate_packages(subdir):
00109         """
00110         Iterator for packages that contain the given subdir.
00111 
00112         This method is generalizing rosmsg.iterate_packages.
00113 
00114         @param subdir: eg. 'launch', 'msg', 'srv', 'action'
00115         @type subdir: str
00116         @raise ValueError:
00117         """
00118         if subdir == None or subdir == '':
00119             raise ValueError('Invalid package subdir = {}'.format(subdir))
00120 
00121         rospack = rospkg.RosPack()
00122 
00123         pkgs = rospack.list()
00124         rospy.logdebug('pkgs={}'.format(pkgs))
00125         for p in pkgs:
00126             d = os.path.join(rospack.get_path(p), subdir)
00127             rospy.logdebug('rospack dir={}'.format(d))
00128             if os.path.isdir(d):
00129                 yield p, d
00130 
00131     @staticmethod
00132     def list_files(package, subdir, file_extension='.launch'):
00133         """
00134         #TODO: Come up with better name of the method.
00135 
00136         Taken from rosmsg.
00137         Lists files contained in the specified package
00138 
00139         @param package: package name, ``str``
00140         @param file_extension: Defaults to '.launch', ``str``
00141         :returns: list of msgs/srv in package, ``[str]``
00142         """
00143         if subdir == None or subdir == '':
00144             raise ValueError('Invalid package subdir = {}'.format(subdir))
00145 
00146         rospack = rospkg.RosPack()
00147 
00148         path = os.path.join(rospack.get_path(package), subdir)
00149 
00150         return [genmsg.resource_name(package, t)
00151                 for t in RqtRoscommUtil._list_types(
00152                                                  path, file_extension)]
00153 
00154     @staticmethod
00155     def _list_types(path, ext):
00156         """
00157         Taken from rosmsg
00158 
00159         List all messages in the specified package
00160         :param package str: name of package to search
00161         :param include_depends bool: if True, will also list messages in
00162                                      package dependencies.
00163         :returns [str]: message type names
00164         """
00165         types = RqtRoscommUtil._list_resources(path,
00166                                                RqtRoscommUtil._msg_filter(ext))
00167 
00168         result = [x for x in types]
00169         # result = [x[:-len(ext)] for x in types]  # Remove extension
00170 
00171         result.sort()
00172         return result
00173 
00174     @staticmethod
00175     def _list_resources(path, rfilter=os.path.isfile):
00176         """
00177         Taken from rosmsg._list_resources
00178 
00179         List resources in a package directory within a particular
00180         subdirectory. This is useful for listing messages, services, etc...
00181         :param rfilter: resource filter function that returns true if filename
00182                         is the desired resource type, ``fn(filename)->bool``
00183         """
00184         resources = []
00185         if os.path.isdir(path):
00186             resources = [f for f
00187                          in os.listdir(path) if rfilter(os.path.join(path, f))]
00188         else:
00189             resources = []
00190         return resources
00191 
00192     @staticmethod
00193     def _msg_filter(ext):
00194         """
00195         Taken from rosmsg._msg_filter
00196         """
00197         def mfilter(f):
00198             """
00199             Predicate for filtering directory list. matches message files
00200             :param f: filename, ``str``
00201             """
00202             return os.path.isfile(f) and f.endswith(ext)
00203         return mfilter
00204 
00205     @staticmethod
00206     def is_roscore_running():
00207         """
00208         @rtype: bool
00209         """
00210         try:
00211             # Checkif rosmaster is running or not.
00212             rostopic.get_topic_class('/rosout')
00213             return True
00214         except rostopic.ROSTopicIOException as e:
00215             return False


rqt_py_common
Author(s): Dorian Scholz, Isaac Saito
autogenerated on Mon Oct 6 2014 07:15:13