00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 """
00040 Modifying rosaction.__init__.py to add functionality for ROS Action.
00041
00042 Implements rosaction command-line tools.
00043
00044 The code API of the rosaction module is unstable (inheriting the status of
00045 rosmsg)
00046
00047 (2/4/2013) Most of codes are not tested with actinlib. There's
00048 "#NOT_TESTED_FROM_HERE" sign in the code below.
00049 """
00050
00051 from __future__ import print_function
00052
00053 import collections
00054 import inspect
00055 import os
00056 import sys
00057 import yaml
00058 from optparse import OptionParser
00059
00060 import genmsg
00061
00062 import rosbag
00063 import roslib
00064 import roslib.message
00065 import rospkg
00066 import rospy
00067
00068 class ROSActionException(Exception): pass
00069 class ROSActionProtoException(Exception): pass
00070 class RosActionProtoArgsException(Exception): pass
00071
00072
00073
00074
00075 MAX_DEFAULT_NON_FLOW_ITEMS = 4
00076
00077 MODE_ACTION = '.action'
00078
00079
00080 def rosaction_cmd_list(mode, full, argv=None):
00081 if argv is None:
00082 argv = sys.argv[1:]
00083 parser = OptionParser(usage="usage: ros%s list" % mode[1:])
00084 options, args = parser.parse_args(argv[1:])
00085 if mode == MODE_ACTION:
00086 subdir = 'action'
00087 else:
00088 raise ValueError('Unknown mode for iterate_packages: %s' % mode)
00089
00090 rospack = rospkg.RosPack()
00091 packs = sorted([x for x in iterate_packages(rospack, mode)])
00092 for (p, direc) in packs:
00093 for file_ in _list_types(direc, subdir, mode):
00094 rospy.loginfo("%s/%s" % (p, file_))
00095
00096
00097 def _get_action_class_genpy(type_str, message_type, reload_on_error=False):
00098 """
00099 Taken from genpy.message._get_message_or_service_class
00100
00101 Utility for retrieving message/service class instances. Used by
00102 get_message_class and get_service_class.
00103 :param type_str: 'msg' or 'srv', ``str``
00104 :param message_type: type name of message/service, ``str``
00105 :returns: Message/Service for message/service type or None, ``class``
00106 :raises: :exc:`ValueError` If message_type is invalidly specified
00107 """
00108
00109 package, base_type = genmsg.package_resource_name(message_type)
00110 if not package:
00111 if base_type == 'Header':
00112 package = 'std_msgs'
00113 else:
00114 raise ValueError("message type is missing package name: %s"
00115 % str(message_type))
00116 pypkg = val = None
00117 try:
00118
00119 pypkg = __import__('%s.%s' % (package, type_str))
00120 val = getattr(getattr(pypkg, type_str), base_type)
00121 except ImportError:
00122 val = None
00123 except AttributeError:
00124 val = None
00125
00126 """
00127 Taken from genpy.message
00128 cache for get_message_class
00129 """
00130 _message_class_cache_genpy = {}
00131
00132
00133 def get_message_class_genpy(message_type, reload_on_error=False):
00134 """
00135 Taken from genpy.message.get_message_class
00136
00137 Get the message class. NOTE: this function maintains a
00138 local cache of results to improve performance.
00139 :param message_type: type name of message, ``str``
00140 :param reload_on_error: (optional). Attempt to reload the Python
00141 module if unable to load message the first time. Defaults to
00142 False. This is necessary if messages are built after the first load.
00143 :returns: Message class for message/service type, ``Message class``
00144 :raises :exc:`ValueError`: if message_type is invalidly specified
00145 """
00146 if message_type in _message_class_cache_genpy:
00147 return _message_class_cache_genpy[message_type]
00148 cls = _get_action_class_genpy('action', message_type,
00149 reload_on_error=reload_on_error)
00150 if cls:
00151 _message_class_cache_genpy[message_type] = cls
00152 return cls
00153
00154
00155 def _get_action_class(type_str, message_type, reload_on_error=False):
00156 """
00157 Taken from roslib.message._get_message_or_service_class
00158 """
00159
00160
00161 package, base_type = genmsg.package_resource_name(message_type)
00162 if not package:
00163 if base_type == 'Header':
00164 package = 'std_msgs'
00165 else:
00166 raise ValueError("message type is missing package name: %s" %
00167 str(message_type))
00168 pypkg = val = None
00169 try:
00170
00171 roslib.launcher.load_manifest(package)
00172
00173 rospy.loginfo('package={} type_str={} base_type={}'.format(
00174 package, type_str, base_type))
00175
00176
00177 pypkg = __import__('%s/%s' % (package, type_str))
00178
00179 val = getattr(getattr(pypkg, type_str), base_type)
00180
00181 except rospkg.ResourceNotFound:
00182 val = None
00183 rospy.loginfo('_get_action_class except 1')
00184 except ImportError:
00185 val = None
00186 rospy.loginfo('_get_action_class except 2')
00187 except AttributeError:
00188 val = None
00189 rospy.loginfo('_get_action_class except 3')
00190
00191
00192
00193 if val is None and reload_on_error:
00194 try:
00195 if pypkg:
00196 reload(pypkg)
00197 val = getattr(getattr(pypkg, type_str), base_type)
00198 except:
00199 val = None
00200 return val
00201
00202 """
00203 Taken from roslib.message
00204 """
00205
00206 _action_class_cache = {}
00207
00208
00209 def get_action_class(action_type, reload_on_error=False):
00210 """
00211 Taken from roslib.message.get_action_class
00212 """
00213
00214 if action_type in _action_class_cache:
00215 return _action_class_cache[action_type]
00216
00217 cls = get_message_class_genpy(action_type, reload_on_error=reload_on_error)
00218 if cls is None:
00219
00220 cls = _get_action_class('action', action_type,
00221 reload_on_error=reload_on_error)
00222 if cls:
00223 _action_class_cache[action_type] = cls
00224 return cls
00225
00226
00227 def iterate_packages(rospack, mode):
00228 """
00229 Iterator for packages that contain actions
00230 :param mode: .action, ``str``
00231 """
00232 if mode == MODE_ACTION:
00233 subdir = 'action'
00234 else:
00235 raise ValueError('Unknown mode for iterate_packages: %s' % mode)
00236 pkgs = rospack.list()
00237 for p in pkgs:
00238 d = os.path.join(rospack.get_path(p), subdir)
00239 if os.path.isdir(d):
00240 yield p, d
00241
00242
00243 def _msg_filter(ext):
00244 def mfilter(f):
00245 """
00246 Predicate for filtering directory list. matches message files
00247 :param f: filename, ``str``
00248 """
00249 return os.path.isfile(f) and f.endswith(ext)
00250 return mfilter
00251
00252
00253 def _list_resources(path, rfilter=os.path.isfile):
00254 """
00255 List resources in a package directory within a particular
00256 subdirectory. This is useful for listing messages, services, etc...
00257 :param rfilter: resource filter function that returns true if filename is
00258 the desired resource type, ``fn(filename)->bool``
00259 """
00260 resources = []
00261 if os.path.isdir(path):
00262 resources = [f for f in os.listdir(path) if rfilter(os.path.join(path, f))]
00263 else:
00264 resources = []
00265 return resources
00266
00267
00268 def _list_types(path, subdir, ext):
00269 """
00270 List all messages in the specified package
00271 :param package str: name of package to search
00272 :param include_depends bool: if True, will also list messages in package
00273 dependencies
00274 :returns [str]: message type names
00275 """
00276 types = _list_resources(path, _msg_filter(ext))
00277 result = [x[:-len(ext)] for x in types]
00278 result.sort()
00279
00280 rospy.loginfo('_list_types result={}'.format(result))
00281
00282 return result
00283
00284
00285 def list_types(package, mode=MODE_ACTION):
00286 """
00287 Lists msg/srvs contained in package
00288 :param package: package name, ``str``
00289 :param mode: MODE_ACTION. Defaults to msgs, ``str``
00290 :returns: list of msgs/srv in package, ``[str]``
00291 """
00292
00293 rospack = rospkg.RosPack()
00294 if mode == MODE_ACTION:
00295 subdir = 'action'
00296 else:
00297 raise ValueError('Unknown mode for list_types: %s' % mode)
00298 path = os.path.join(rospack.get_path(package), subdir)
00299
00300 rospy.loginfo('list_types package={} mode={} path={}'.format(package, mode,
00301 path))
00302
00303 return [genmsg.resource_name(package, t)
00304 for t in _list_types(path, subdir, mode)]
00305
00306
00307 def list_actions(package):
00308 """
00309 List actions contained in package
00310 :param package: package name, ``str``
00311 :returns: list of actions in package, ``[str]``
00312 """
00313 return list_types(package, mode=MODE_ACTION)
00314
00315
00316 def rosactionmain(mode=MODE_ACTION):
00317 """
00318 Main entry point for command-line tools (rosaction).
00319
00320 rosaction can interact with either ros messages or ros services. The mode
00321 param indicates which
00322 :param mode: MODE_ACTION or MODE_SRV, ``str``
00323 """
00324 try:
00325 if mode == MODE_ACTION:
00326 ext, full = mode, "message type"
00327 else:
00328 raise ROSActionException("Invalid mode: %s" % mode)
00329
00330 if len(sys.argv) == 1:
00331 rospy.loginfo(fullusage('ros' + mode[1:]))
00332 sys.exit(0)
00333
00334 command = sys.argv[1]
00335
00336
00337
00338
00339
00340
00341 if command == 'list':
00342 rosaction_cmd_list(ext, full)
00343
00344
00345 elif command == '--help':
00346 print(fullusage('ros' + mode[1:]))
00347 sys.exit(0)
00348 else:
00349 print(fullusage('ros' + mode[1:]))
00350 sys.exit(getattr(os, 'EX_USAGE', 1))
00351 except KeyError as e:
00352 print("Unknown message type: %s" % e, file=sys.stderr)
00353 sys.exit(getattr(os, 'EX_USAGE', 1))
00354 except rospkg.ResourceNotFound as e:
00355 print("Invalid package: %s" % e, file=sys.stderr)
00356 sys.exit(getattr(os, 'EX_USAGE', 1))
00357 except ValueError as e:
00358 print("Invalid type: '%s'" % e, file=sys.stderr)
00359 sys.exit(getattr(os, 'EX_USAGE', 1))
00360 except ROSActionException as e:
00361 print(str(e), file=sys.stderr)
00362 sys.exit(1)
00363 except KeyboardInterrupt:
00364 pass
00365
00366 """
00367 "#NOT_TESTED_FROM_HERE"----------------------------------------
00368 From here are what are copied from __init__.py that I don't know yet
00369 if they are necessary/useful.
00370 """
00371
00372 def construct_ordered_mapping(self, node, deep=False):
00373 if not isinstance(node, yaml.MappingNode):
00374 raise yaml.constructor.ConstructorError(None, None,
00375 "expected a mapping node, but found %s" % node.id,
00376 node.start_mark)
00377 mapping = collections.OrderedDict()
00378 for key_node, value_node in node.value:
00379 key = self.construct_object(key_node, deep=deep)
00380 if not isinstance(key, collections.Hashable):
00381 raise yaml.constructor.ConstructorError("while constructing a mapping",
00382 node.start_mark,
00383 "found unhashable key", key_node.start_mark)
00384 value = self.construct_object(value_node, deep=deep)
00385 mapping[key] = value
00386 return mapping
00387
00388 def construct_yaml_map_with_ordered_dict(self, node):
00389 data = collections.OrderedDict()
00390 yield data
00391 value = self.construct_mapping(node)
00392 data.update(value)
00393
00394 def represent_ordered_mapping(self, tag, mapping, flow_style=None):
00395 value = []
00396 node = yaml.MappingNode(tag, value, flow_style=flow_style)
00397 if self.alias_key is not None:
00398 self.represented_objects[self.alias_key] = node
00399 best_style = True
00400 if hasattr(mapping, 'items'):
00401 mapping = list(mapping.items())
00402 for item_key, item_value in mapping:
00403 node_key = self.represent_data(item_key)
00404 node_value = self.represent_data(item_value)
00405 if not (isinstance(node_key, yaml.ScalarNode) and not node_key.style):
00406 best_style = False
00407 if not (isinstance(node_value, yaml.ScalarNode) and not node_value.style):
00408 best_style = False
00409 value.append((node_key, node_value))
00410 if flow_style is None:
00411 if self.default_flow_style is not None:
00412 node.flow_style = self.default_flow_style
00413 else:
00414 node.flow_style = best_style
00415 return node
00416
00417
00418
00419
00420 def get_array_type_instance(field_type, default_package=None):
00421 """
00422 returns a single instance of field_type, where field_type can be a
00423 message or ros primitive or an flexible size array.
00424 """
00425 field_type = field_type.strip().rstrip("[]")
00426 if field_type == "empty":
00427 return None
00428 if not "/" in field_type:
00429
00430
00431 if field_type in ['byte', 'int8', 'int16', 'int32', 'int64', \
00432 'char', 'uint8', 'uint16', 'uint32', 'uint64']:
00433 return 0
00434 elif field_type in ['float32', 'float64']:
00435 return 0
00436 elif field_type in ['string']:
00437 return ""
00438 elif field_type == 'bool':
00439 return False
00440 elif field_type == 'time':
00441 field_type = "std_msgs/Time"
00442 elif field_type == 'duration':
00443 field_type = "std_msgs/Duration"
00444 elif field_type == 'Header':
00445 field_type = "std_msgs/Header"
00446 else:
00447 if default_package is None:
00448 return None
00449 field_type = default_package + "/" + field_type
00450 msg_class = roslib.message.get_message_class(field_type)
00451 if (msg_class == None):
00452
00453 return None
00454 instance = msg_class()
00455 return instance
00456
00457 def get_yaml_for_msg(msg, prefix='', time_offset=None, current_time=None,
00458 field_filter=None, flow_style_=None, fill_arrays_=False):
00459 """
00460 Builds a YAML string of message.
00461 @param msg: A object, dict or array
00462 @param flow_style_: if True, produces one line with brackets, if false uses multiple lines with indentation, if None uses both using heuristics
00463 @param prefix: prefixes all lines with this string
00464 @param fill_arrays_: if True, for all flexible size arrays an element will be generated
00465 @param current_time: currently not used. Only provided for API compatibility. current_time passes in the current time with respect to the message.
00466 @type current_time: Time
00467 @param field_filter: filter the fields that are strified for Messages.
00468 @type field_filter: fn(Message)->iter(str)
00469 @type flow_style_: bool
00470 @return: a string
00471 """
00472 def object_representer(dumper, obj):
00473 ndict = collections.OrderedDict()
00474 index = 0
00475
00476 if field_filter != None:
00477 fields = list(field_filter(obj))
00478 else:
00479 fields = obj.__slots__
00480 for key in fields:
00481 if not key.startswith('_'):
00482 val = getattr(obj, key)
00483 if type(val) == list and len(val) > MAX_DEFAULT_NON_FLOW_ITEMS:
00484 dumper.default_flow_style = flow_style_
00485 if time_offset is not None and isinstance(val, Time):
00486 ndict[key] = val - time_offset
00487
00488 elif fill_arrays_ == True and val == []:
00489 message_type = obj._slot_types[index]
00490 if (obj._type != None) and "/" in obj._type:
00491 def_pack = obj._type.split("/")[0]
00492 instance = get_array_type_instance(message_type, default_package=def_pack)
00493 if instance == None:
00494
00495 ndict[key] = val
00496 else:
00497 ndict[key] = [instance]
00498 elif not inspect.ismethod(val) and not inspect.isfunction(val):
00499 ndict[key] = val
00500 index += 1
00501
00502 if len(ndict) > MAX_DEFAULT_NON_FLOW_ITEMS:
00503 dumper.default_flow_style = flow_style_
00504 return dumper.represent_dict(ndict)
00505 yaml.representer.SafeRepresenter.add_representer(None, object_representer)
00506
00507
00508
00509
00510 initial_flow_style = False
00511 if flow_style_ == True:
00512 initial_flow_style = True
00513
00514
00515
00516
00517 txt = yaml.safe_dump(msg,
00518
00519 default_flow_style=initial_flow_style,
00520
00521 default_style='',
00522
00523
00524
00525
00526
00527
00528
00529
00530
00531
00532
00533
00534
00535 )
00536 if prefix != None and prefix != '':
00537 result = prefix + ("\n" + prefix).join(txt.splitlines())
00538 else:
00539 result = txt.rstrip('\n')
00540 return result
00541
00542
00543 def create_names_filter(names):
00544 """
00545 returns a function to use as filter that returns all objects slots except those with names in list.
00546 """
00547 return lambda obj : filter(lambda slotname : not slotname in names, obj.__slots__)
00548
00549
00550 def init_rosaction_proto():
00551 if "OrderedDict" in collections.__dict__:
00552 yaml.constructor.BaseConstructor.construct_mapping = construct_ordered_mapping
00553 yaml.constructor.Constructor.add_constructor(
00554 'tag:yaml.org,2002:map',
00555 construct_yaml_map_with_ordered_dict)
00556
00557 yaml.representer.BaseRepresenter.represent_mapping = represent_ordered_mapping
00558 yaml.representer.Representer.add_representer(collections.OrderedDict,
00559 yaml.representer.SafeRepresenter.represent_dict)
00560
00561 def rosaction_cmd_prototype(args):
00562 init_rosaction_proto()
00563 parser = OptionParser(usage="usage: rosactionproto msg/srv [options]",
00564 description="Produces output or a msg or service request, intended for tab completion support.")
00565 parser.add_option("-f", "--flow_style",
00566 dest="flow_style", type="int", default=None, action="store",
00567 help="if 1 always use brackets, if 0 never use brackets. Default is a heuristic mix.")
00568 parser.add_option("-e", "--empty-arrays",
00569 dest="empty_arrays", default=False, action="store_true",
00570 help="if true flexible size arrays are not filled with default instance")
00571 parser.add_option("-s", "--silent",
00572 dest="silent", default=False, action="store_true",
00573 help="if true supresses all error messages")
00574 parser.add_option("-p", "--prefix", metavar="prefix", default="",
00575 help="prefix to print before each line, can be used for indent")
00576 parser.add_option("-H", "--no-hyphens",
00577 dest="no_hyphens", default="", action="store_true",
00578 help="if true output has no outer hyphens")
00579 parser.add_option("-x", "--exclude-slots", metavar="exclude_slots", default="",
00580 help="comma separated list of slot names not to print")
00581
00582 options, args = parser.parse_args(args)
00583
00584 try:
00585 if len(args) < 2:
00586 raise RosActionProtoArgsException("Insufficient arguments")
00587 mode = ".%s" % args[0]
00588 message_type = args[1]
00589 field_filter = None
00590 if options.exclude_slots != None and options.exclude_slots.strip() != "":
00591 field_filter = create_names_filter(options.exclude_slots.split(','))
00592
00593
00594
00595
00596
00597
00598
00599 if '::' in message_type:
00600 if not options.silent:
00601 parser.error("rosactionproto does not understand C++-style namespaces (i.e. '::').\nPlease refer to msg/srv types as 'package_name/Type'.")
00602 elif '.' in message_type:
00603 if not options.silent:
00604 parser.error("invalid message type '%s'.\nPlease refer to msg/srv types as 'package_name/Type'." % message_type)
00605 if not '/' in message_type:
00606
00607 results = []
00608 for found in rosaction_search(rospkg.RosPack(), mode, message_type):
00609 results.append(found)
00610 if len(results) > 1:
00611 raise ROSActionProtoException("Ambiguous message name %s" % message_type)
00612 elif len(results) < 1:
00613 raise ROSActionProtoException("Unknown message name %s" % message_type)
00614 else:
00615 message_type = results[0]
00616
00617 if mode == MODE_ACTION:
00618 msg_class = roslib.message.get_message_class(message_type)
00619 if (msg_class == None):
00620 raise ROSActionProtoException("Unknown message class: %s" % message_type)
00621 instance = msg_class()
00622 else:
00623 raise ROSActionProtoException("Invalid mode: %s" % mode)
00624 txt = get_yaml_for_msg(instance,
00625 prefix=options.prefix,
00626 flow_style_=options.flow_style,
00627 fill_arrays_=not options.empty_arrays,
00628 field_filter=field_filter)
00629
00630 if options.no_hyphens == True:
00631 return txt
00632 else:
00633 return '"' + txt + '"'
00634
00635 except KeyError as e:
00636 if not options.silent:
00637 sys.stderr.write("Unknown message type: %s" % e, file=sys.stderr)
00638 sys.exit(getattr(os, 'EX_USAGE', 1))
00639
00640
00641
00642
00643 except ValueError as e:
00644 if not options.silent:
00645 sys.stderr.write("Invalid type: '%s'" % e)
00646 sys.exit(getattr(os, 'EX_USAGE', 1))
00647 except ROSActionProtoException as e:
00648 if not options.silent:
00649 sys.stderr.write(str(e))
00650 sys.exit(1)
00651 except RosActionProtoArgsException as e:
00652 if not options.silent:
00653 sys.stderr.write("%s" % e)
00654 sys.exit(getattr(os, 'EX_USAGE', 1))
00655 except KeyboardInterrupt:
00656 pass
00657
00658
00659
00660 try:
00661 from cStringIO import StringIO
00662 except ImportError:
00663 from io import StringIO
00664 def spec_to_str(action_context, spec, buff=None, indent=''):
00665 """
00666 Convert spec into a string representation. Helper routine for MsgSpec.
00667 :param indent: internal use only, ``str``
00668 :param buff: internal use only, ``StringIO``
00669 :returns: string representation of spec, ``str``
00670 """
00671 if buff is None:
00672 buff = StringIO()
00673 for c in spec.constants:
00674 buff.write("%s%s %s=%s\n" % (indent, c.type, c.name, c.val_text))
00675 for type_, name in zip(spec.types, spec.names):
00676 buff.write("%s%s %s\n" % (indent, type_, name))
00677 base_type = genmsg.msgs.bare_msg_type(type_)
00678 if not base_type in genmsg.msgs.BUILTIN_TYPES:
00679 subspec = msg_context.get_registered(base_type)
00680 spec_to_str(msg_context, subspec, buff, indent + ' ')
00681 return buff.getvalue()
00682
00683 def get_msg_text(type_, raw=False, rospack=None):
00684 """
00685 Get .msg file for type_ as text
00686 :param type_: message type, ``str``
00687 :param raw: if True, include comments and whitespace (default False), ``bool``
00688 :returns: text of .msg file, ``str``
00689 :raises :exc:`ROSActionException` If type_ is unknown
00690 """
00691 if rospack is None:
00692 rospack = rospkg.RosPack()
00693 search_path = {}
00694 for p in rospack.list():
00695 search_path[p] = [os.path.join(rospack.get_path(p), 'msg')]
00696
00697 context = genmsg.MsgContext.create_default()
00698 try:
00699 spec = genmsg.load_msg_by_type(context, type_, search_path)
00700 genmsg.load_depends(context, spec, search_path)
00701 except Exception as e:
00702 raise ROSActionException("Unable to load msg [%s]: %s" % (type_, e))
00703
00704 if raw:
00705 return spec.text
00706 else:
00707 return spec_to_str(context, spec)
00708
00709 def _msg_filter(ext):
00710 def mfilter(f):
00711 """
00712 Predicate for filtering directory list. matches message files
00713 :param f: filename, ``str``
00714 """
00715 return os.path.isfile(f) and f.endswith(ext)
00716 return mfilter
00717
00718
00719 def rosaction_search(rospack, mode, base_type):
00720 """
00721 Iterator for all packages that contain a message matching base_type
00722
00723 :param base_type: message base type to match, e.g. 'String' would match std_msgs/String, ``str``
00724 """
00725 for p, path in iterate_packages(rospack, mode):
00726 if os.path.isfile(os.path.join(path, "%s%s" % (base_type, mode))):
00727 yield genmsg.resource_name(p, base_type)
00728
00729 def _stdin_arg(parser, full):
00730 options, args = parser.parse_args(sys.argv[2:])
00731
00732 if not args:
00733 arg = None
00734 while not arg:
00735 arg = sys.stdin.readline().strip()
00736 return options, arg
00737 else:
00738 if len(args) > 1:
00739 parser.error("you may only specify one %s" % full)
00740 return options, args[0]
00741
00742 def rosaction_cmd_show(mode, full):
00743 cmd = "ros%s" % (mode[1:])
00744 parser = OptionParser(usage="usage: %s show [options] <%s>" % (cmd, full))
00745 parser.add_option("-r", "--raw",
00746 dest="raw", default=False, action="store_true",
00747 help="show raw message text, including comments")
00748 parser.add_option("-b", "--bag",
00749 dest="bag", default=None,
00750 help="show message from .bag file", metavar="BAGFILE")
00751 options, arg = _stdin_arg(parser, full)
00752 if arg.endswith(mode):
00753 arg = arg[:-(len(mode))]
00754
00755
00756 if '::' in arg:
00757 parser.error(cmd + " does not understand C++-style namespaces (i.e. '::').\nPlease refer to msg/srv types as 'package_name/Type'.")
00758 elif '.' in arg:
00759 parser.error("invalid message type '%s'.\nPlease refer to msg/srv types as 'package_name/Type'." % arg)
00760 if options.bag:
00761 bag_file = options.bag
00762 if not os.path.exists(bag_file):
00763 raise ROSActionException("ERROR: bag file [%s] does not exist" % bag_file)
00764 for topic, msg, t in rosbag.Bag(bag_file).read_messages(raw=True):
00765 datatype, _, _, _, pytype = msg
00766 if datatype == arg:
00767 print(get_msg_text(datatype, options.raw, pytype._full_text))
00768 break
00769 else:
00770 rospack = rospkg.RosPack()
00771 if '/' in arg:
00772 rosaction_debug(rospack, mode, arg, options.raw)
00773 else:
00774 for found in rosaction_search(rospack, mode, arg):
00775 print("[%s]:" % found)
00776 rosaction_debug(rospack, mode, found, options.raw)
00777
00778 def rosaction_md5(mode, type_):
00779 try:
00780 if mode == MODE_ACTION:
00781 msg_class = roslib.message.get_message_class(type_)
00782 else:
00783 msg_class = roslib.message.get_service_class(type_)
00784 except ImportError:
00785 raise IOError("cannot load [%s]" % (type_))
00786 if msg_class is not None:
00787 return msg_class._md5sum
00788 else:
00789 raise IOError("cannot load [%s]" % (type_))
00790
00791 def rosaction_cmd_md5(mode, full):
00792 parser = OptionParser(usage="usage: ros%s md5 <%s>" % (mode[1:], full))
00793 options, arg = _stdin_arg(parser, full)
00794
00795 if '/' in arg:
00796 try:
00797 md5 = rosaction_md5(mode, arg)
00798 print(md5)
00799 except IOError:
00800 print("Cannot locate [%s]" % arg, file=sys.stderr)
00801 else:
00802 rospack = rospkg.RosPack()
00803 matches = [m for m in rosaction_search(rospack, mode, arg)]
00804 for found in matches:
00805 try:
00806 md5 = rosaction_md5(mode, found)
00807 print("[%s]: %s" % (found, md5))
00808 except IOError:
00809 print("Cannot locate [%s]" % found, file=sys.stderr)
00810 if not matches:
00811 print("No messages matching the name [%s]" % arg, file=sys.stderr)
00812
00813 def rosaction_cmd_package(mode, full):
00814 parser = OptionParser(usage="usage: ros%s package <package>" % mode[1:])
00815 parser.add_option("-s",
00816 dest="single_line", default=False, action="store_true",
00817 help="list all msgs on a single line")
00818 options, arg = _stdin_arg(parser, full)
00819 joinstring = '\n'
00820 if options.single_line:
00821 joinstring = ' '
00822 print(joinstring.join(list_types(arg, mode=mode)))
00823
00824 def rosaction_cmd_packages(mode, full, argv=None):
00825 if argv is None:
00826 argv = sys.argv[1:]
00827 parser = OptionParser(usage="usage: ros%s packages" % mode[1:])
00828 parser.add_option("-s",
00829 dest="single_line", default=False, action="store_true",
00830 help="list all packages on a single line")
00831 options, args = parser.parse_args(argv[1:])
00832 rospack = rospkg.RosPack()
00833 joinstring = '\n'
00834 if options.single_line:
00835 joinstring = ' '
00836 p1 = [p for p, _ in iterate_packages(rospack, mode)]
00837 p1.sort()
00838 print(joinstring.join(p1))
00839
00840 def rosaction_debug(rospack, mode, type_, raw=False):
00841 """
00842 Prints contents of msg/srv file
00843 :param mode: MODE_ACTION or MODE_SRV, ``str``
00844 """
00845 if mode == MODE_ACTION:
00846 print(get_msg_text(type_, raw=raw, rospack=rospack))
00847 else:
00848 raise ROSActionException("Invalid mode for debug: %s" % mode)