library.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2010, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Revision $Id: library.py 9993 2010-06-09 02:35:02Z kwc $
34 """
35 Top-level library routines we expose to the end-user
36 """
37 
38 
39 import yaml
40 import sys
41 
42 import roslib.message
43 import roslib.packages
44 
45 import rospy
46 
47 _NATIVE_YAML_TYPES = {int, float, str, bool}
48 if sys.version_info < (3, 0):
49  _NATIVE_YAML_TYPES.add(long)
50 
51 
52 def findros(pkg, resource):
53  """
54  Find ROS resource inside of a package.
55 
56  @param pkg: ROS package name
57  @type pkg: str
58  @param resource: resource filename
59  @type resource: str
60  """
61  val = roslib.packages.find_resource(pkg, resource)
62  if val:
63  return val[0]
64  else:
65  raise rospy.ROSException("cannot find resource")
66 
67 
68 def YAMLBag(object):
69  def __init__(self, filename):
70  self.filename = filename
71  self._fp = open(filename, 'w')
72 
73  def append(self, msg):
74  self._fp.write(to_yaml(msg))
75 
76  def close(self):
77  if self._fp is not None:
78  self._fp.close()
79  self._fp = None
80 
81 
82 def to_yaml(obj):
83  if isinstance(obj, roslib.message.Message):
84  return _message_to_yaml(obj)
85  pass
86  else:
87  return yaml.dump(obj)
88 
89 
90 def yaml_msg_str(type_, yaml_str, filename=None):
91  """
92  Load single message from YAML dictionary representation.
93 
94  @param type_: Message class
95  @type type_: class (Message subclass)
96  @param filename: Name of YAML file
97  @type filename: str
98  """
99  import yaml
100  if yaml_str.strip() == '':
101  msg_dict = {}
102  else:
103  msg_dict = yaml.safe_load(yaml_str)
104  if not isinstance(msg_dict, dict):
105  if filename:
106  raise ValueError("yaml file [%s] does not contain a dictionary" % filename)
107  else:
108  raise ValueError("yaml string does not contain a dictionary")
109  m = type_()
110  roslib.message.fill_message_args(m, [msg_dict])
111  return m
112 
113 
114 def yaml_msg(type_, filename):
115  """
116  Load single message from YAML dictionary representation.
117 
118  @param type_: Message class
119  @type type_: class (Message subclass)
120  @param filename: Name of YAML file
121  @type filename: str
122  """
123  with open(filename, 'r') as f:
124  return yaml_msg_str(type_, f.read(), filename=filename)
125 
126 
127 def yaml_msgs_str(type_, yaml_str, filename=None):
128  """
129  Load messages from YAML list-of-dictionaries representation.
130 
131  @param type_: Message class
132  @type type_: class (Message subclass)
133  @param filename: Name of YAML file
134  @type filename: str
135  """
136  import yaml
137  yaml_doc = yaml.safe_load(yaml_str)
138  msgs = []
139  for msg_dict in yaml_doc:
140  if not isinstance(msg_dict, dict):
141  if filename:
142  raise ValueError("yaml file [%s] does not contain a list of dictionaries" % filename)
143  else:
144  raise ValueError("yaml string does not contain a list of dictionaries")
145  m = type_()
146  roslib.message.fill_message_args(m, msg_dict)
147  msgs.append(m)
148  return msgs
149 
150 
151 def yaml_msgs(type_, filename):
152  """
153  Load messages from YAML list-of-dictionaries representation.
154 
155  @param type_: Message class
156  @type type_: class (Message subclass)
157  @param filename: Name of YAML file
158  @type filename: str
159  """
160  with open(filename, 'r') as f:
161  return yaml_msgs_str(type_, f.read(), filename=filename)
162 
163 
164 def _message_to_yaml(msg, indent='', time_offset=None):
165  """
166  convert value to YAML representation
167  @param val: to convert to string representation. Most likely a Message.
168  @type val: Value
169  @param indent: indentation
170  @type indent: str
171  @param time_offset: if not None, time fields will be displayed
172  as deltas from time_offset
173  @type time_offset: Time
174  """
175  if type(msg) in _NATIVE_YAML_TYPES:
176  # TODO: need to actually escape
177  return msg
178  elif isinstance(msg, rospy.Time) or isinstance(msg, rospy.Duration):
179  if time_offset is not None and isinstance(msg, rospy.Time):
180  msg = msg-time_offset
181 
182  return '\n%ssecs: %s\n%snsecs: %s' % (indent, msg.secs, indent, msg.nsecs)
183 
184  elif type(msg) in [list, tuple]:
185  # have to convert tuple->list to be yaml-safe
186  if len(msg) == 0:
187  return str(list(msg))
188  msg0 = msg[0]
189  if type(msg0) in [int, float, str, bool] or \
190  isinstance(msg0, rospy.Time) or isinstance(msg0, rospy.Duration) or \
191  isinstance(msg0, list) or isinstance(msg0, tuple):
192  # no array-of-arrays support yet
193  return str(list(msg))
194  else:
195  indent = indent + ' '
196  return "["+','.join([roslib.message.strify_message(v, indent, time_offset) for v in msg])+"]"
197  elif isinstance(msg, rospy.Message):
198  if indent:
199  return '\n' + \
200  '\n'.join(['%s%s: %s' % (
201  indent, f, roslib.message.strify_message(getattr(msg, f), ' ' + indent, time_offset)) for f in msg.__slots__])
202  return '\n'.join(['%s%s: %s' % (indent, f, roslib.message.strify_message(getattr(msg, f), ' ' + indent, time_offset)) for f in msg.__slots__])
203  else:
204  return str(msg) # punt
actionlib_tools.library.yaml_msg_str
def yaml_msg_str(type_, yaml_str, filename=None)
Definition: library.py:90
actionlib_tools.library.to_yaml
def to_yaml(obj)
Definition: library.py:82
actionlib_tools.library.yaml_msgs_str
def yaml_msgs_str(type_, yaml_str, filename=None)
Definition: library.py:127
actionlib_tools.library._message_to_yaml
def _message_to_yaml(msg, indent='', time_offset=None)
Definition: library.py:164
actionlib_tools.library.YAMLBag
def YAMLBag(object)
Definition: library.py:68
actionlib_tools.library.yaml_msg
def yaml_msg(type_, filename)
Definition: library.py:114
actionlib_tools.library.yaml_msgs
def yaml_msgs(type_, filename)
Definition: library.py:151
actionlib_tools.library.findros
def findros(pkg, resource)
Definition: library.py:52


actionlib_tools
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Thu Apr 10 2025 02:37:15