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 from __future__ import with_statement
39 import yaml
40 
41 import roslib.message
42 import roslib.packages
43 
44 import rospy
45 
46 
47 def findros(pkg, resource):
48  """
49  Find ROS resource inside of a package.
50 
51  @param pkg: ROS package name
52  @type pkg: str
53  @param resource: resource filename
54  @type resource: str
55  """
56  val = roslib.packages.find_resource(pkg, resource)
57  if val:
58  return val[0]
59  else:
60  raise rospy.ROSException("cannot find resource")
61 
62 
63 def YAMLBag(object):
64  def __init__(self, filename):
65  self.filename = filename
66  self._fp = open(filename, 'w')
67 
68  def append(self, msg):
69  self._fp.write(to_yaml(msg))
70 
71  def close(self):
72  if self._fp is not None:
73  self._fp.close()
74  self._fp = None
75 
76 
77 def to_yaml(obj):
78  if isinstance(obj, roslib.message.Message):
79  return _message_to_yaml(obj)
80  pass
81  else:
82  return yaml.dump(obj)
83 
84 
85 def yaml_msg_str(type_, yaml_str, filename=None):
86  """
87  Load single message from YAML dictionary representation.
88 
89  @param type_: Message class
90  @type type_: class (Message subclass)
91  @param filename: Name of YAML file
92  @type filename: str
93  """
94  import yaml
95  if yaml_str.strip() == '':
96  msg_dict = {}
97  else:
98  msg_dict = yaml.safe_load(yaml_str)
99  if not isinstance(msg_dict, dict):
100  if filename:
101  raise ValueError("yaml file [%s] does not contain a dictionary" % filename)
102  else:
103  raise ValueError("yaml string does not contain a dictionary")
104  m = type_()
105  roslib.message.fill_message_args(m, [msg_dict])
106  return m
107 
108 
109 def yaml_msg(type_, filename):
110  """
111  Load single message from YAML dictionary representation.
112 
113  @param type_: Message class
114  @type type_: class (Message subclass)
115  @param filename: Name of YAML file
116  @type filename: str
117  """
118  with open(filename, 'r') as f:
119  return yaml_msg_str(type_, f.read(), filename=filename)
120 
121 
122 def yaml_msgs_str(type_, yaml_str, filename=None):
123  """
124  Load messages from YAML list-of-dictionaries representation.
125 
126  @param type_: Message class
127  @type type_: class (Message subclass)
128  @param filename: Name of YAML file
129  @type filename: str
130  """
131  import yaml
132  yaml_doc = yaml.safe_load(yaml_str)
133  msgs = []
134  for msg_dict in yaml_doc:
135  if not isinstance(msg_dict, dict):
136  if filename:
137  raise ValueError("yaml file [%s] does not contain a list of dictionaries" % filename)
138  else:
139  raise ValueError("yaml string does not contain a list of dictionaries")
140  m = type_()
141  roslib.message.fill_message_args(m, msg_dict)
142  msgs.append(m)
143  return msgs
144 
145 
146 def yaml_msgs(type_, filename):
147  """
148  Load messages from YAML list-of-dictionaries representation.
149 
150  @param type_: Message class
151  @type type_: class (Message subclass)
152  @param filename: Name of YAML file
153  @type filename: str
154  """
155  with open(filename, 'r') as f:
156  return yaml_msgs_str(type_, f.read(), filename=filename)
157 
158 
159 def _message_to_yaml(msg, indent='', time_offset=None):
160  """
161  convert value to YAML representation
162  @param val: to convert to string representation. Most likely a Message.
163  @type val: Value
164  @param indent: indentation
165  @type indent: str
166  @param time_offset: if not None, time fields will be displayed
167  as deltas from time_offset
168  @type time_offset: Time
169  """
170  if type(msg) in [int, long, float, str, bool]:
171  # TODO: need to actually escape
172  return msg
173  elif isinstance(msg, rospy.Time) or isinstance(msg, rospy.Duration):
174  if time_offset is not None and isinstance(msg, rospy.Time):
175  msg = msg-time_offset
176 
177  return '\n%ssecs: %s\n%snsecs: %s' % (indent, msg.secs, indent, msg.nsecs)
178 
179  elif type(msg) in [list, tuple]:
180  # have to convert tuple->list to be yaml-safe
181  if len(msg) == 0:
182  return str(list(msg))
183  msg0 = msg[0]
184  if type(msg0) in [int, float, str, bool] or \
185  isinstance(msg0, rospy.Time) or isinstance(msg0, rospy.Duration) or \
186  isinstance(msg0, list) or isinstance(msg0, tuple):
187  # no array-of-arrays support yet
188  return str(list(msg))
189  else:
190  indent = indent + ' '
191  return "["+','.join([roslib.message.strify_message(v, indent, time_offset) for v in msg])+"]"
192  elif isinstance(msg, rospy.Message):
193  if indent:
194  return '\n' + \
195  '\n'.join(['%s%s: %s' % (
196  indent, f, roslib.message.strify_message(getattr(msg, f), ' ' + indent, time_offset)) for f in msg.__slots__])
197  return '\n'.join(['%s%s: %s' % (indent, f, roslib.message.strify_message(getattr(msg, f), ' ' + indent, time_offset)) for f in msg.__slots__])
198  else:
199  return str(msg) # punt
def findros(pkg, resource)
Definition: library.py:47
def yaml_msgs(type_, filename)
Definition: library.py:146
def YAMLBag(object)
Definition: library.py:63
def _message_to_yaml(msg, indent='', time_offset=None)
Definition: library.py:159
def yaml_msgs_str(type_, yaml_str, filename=None)
Definition: library.py:122
def yaml_msg_str(type_, yaml_str, filename=None)
Definition: library.py:85
def yaml_msg(type_, filename)
Definition: library.py:109
def to_yaml(obj)
Definition: library.py:77


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Aug 24 2020 03:40:47