rosplot.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2009, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Willow Garage, Inc. nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 
36 import string
37 import sys
38 import threading
39 import time
40 
41 import rosgraph
42 import roslib.message
43 import roslib.names
44 import rospy
45 from std_msgs.msg import Bool
46 
47 
48 class RosPlotException(Exception):
49  pass
50 
51 
52 def _get_topic_type(topic):
53  """
54  subroutine for getting the topic type
55  (nearly identical to rostopic._get_topic_type, except it returns rest of name instead of fn)
56 
57  :returns: topic type, real topic name, and rest of name referenced
58  if the topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
59  """
60  try:
61  master = rosgraph.Master('/rosplot')
62  val = master.getTopicTypes()
63  except:
64  raise RosPlotException("unable to get list of topics from master")
65  matches = [(t, t_type) for t, t_type in val if t == topic or topic.startswith(t + '/')]
66  if matches:
67  t, t_type = matches[0]
68  if t_type == roslib.names.ANYTYPE:
69  return None, None, None
70  if t_type == topic:
71  return t_type, None
72  return t_type, t, topic[len(t):]
73  else:
74  return None, None, None
75 
76 
77 def get_topic_type(topic):
78  """
79  Get the topic type (nearly identical to rostopic.get_topic_type, except it doesn't return a fn)
80 
81  :returns: topic type, real topic name, and rest of name referenced
82  if the \a topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
83  """
84  topic_type, real_topic, rest = _get_topic_type(topic)
85  if topic_type:
86  return topic_type, real_topic, rest
87  else:
88  return None, None, None
89 
90 
91 class ROSData(object):
92 
93  """
94  Subscriber to ROS topic that buffers incoming data
95  """
96 
97  def __init__(self, topic, start_time):
98  self.name = topic
99  self.start_time = start_time
100  self.error = None
101 
102  self.lock = threading.Lock()
103  self.buff_x = []
104  self.buff_y = []
105 
106  topic_type, real_topic, fields = get_topic_type(topic)
107  if topic_type is not None:
109  data_class = roslib.message.get_message_class(topic_type)
110  self.sub = rospy.Subscriber(real_topic, data_class, self._ros_cb)
111  else:
112  self.error = RosPlotException("Can not resolve topic type of %s" % topic)
113 
114  def close(self):
115  self.sub.unregister()
116 
117  def _ros_cb(self, msg):
118  """
119  ROS subscriber callback
120  :param msg: ROS message data
121  """
122  try:
123  self.lock.acquire()
124  try:
125  self.buff_y.append(self._get_data(msg))
126  # 944: use message header time if present
127  if msg.__class__._has_header:
128  self.buff_x.append(msg.header.stamp.to_sec() - self.start_time)
129  else:
130  self.buff_x.append(rospy.get_time() - self.start_time)
131  # self.axes[index].plot(datax, buff_y)
132  except AttributeError as e:
133  self.error = RosPlotException("Invalid topic spec [%s]: %s" % (self.name, str(e)))
134  finally:
135  self.lock.release()
136 
137  def next(self):
138  """
139  Get the next data in the series
140 
141  :returns: [xdata], [ydata]
142  """
143  if self.error:
144  raise self.error
145  try:
146  self.lock.acquire()
147  buff_x = self.buff_x
148  buff_y = self.buff_y
149  self.buff_x = []
150  self.buff_y = []
151  finally:
152  self.lock.release()
153  return buff_x, buff_y
154 
155  def _get_data(self, msg):
156  val = msg
157  try:
158  if not self.field_evals:
159  if isinstance(val, Bool):
160  # extract boolean field from bool messages
161  val = val.data
162  return float(val)
163  for f in self.field_evals:
164  val = f(val)
165  return float(val)
166  except IndexError:
167  self.error = RosPlotException(
168  "[%s] index error for: %s" % (self.name, str(val).replace('\n', ', ')))
169  except TypeError:
170  self.error = RosPlotException("[%s] value was not numeric: %s" % (self.name, val))
171 
172 
173 def _array_eval(field_name, slot_num):
174  """
175  :param field_name: name of field to index into, ``str``
176  :param slot_num: index of slot to return, ``str``
177  :returns: fn(msg_field)->msg_field[slot_num]
178  """
179  def fn(f):
180  return getattr(f, field_name).__getitem__(slot_num)
181  return fn
182 
183 
184 def _field_eval(field_name):
185  """
186  :param field_name: name of field to return, ``str``
187  :returns: fn(msg_field)->msg_field.field_name
188  """
189  def fn(f):
190  return getattr(f, field_name)
191  return fn
192 
193 
195  try:
196  evals = []
197  fields = [f for f in fields.split('/') if f]
198  for f in fields:
199  if '[' in f:
200  field_name, rest = f.split('[')
201  slot_num = string.atoi(rest[:rest.find(']')])
202  evals.append(_array_eval(field_name, slot_num))
203  else:
204  evals.append(_field_eval(f))
205  return evals
206  except Exception as e:
207  raise RosPlotException("cannot parse field reference [%s]: %s" % (fields, str(e)))
def generate_field_evals(fields)
Definition: rosplot.py:194
def get_topic_type(topic)
Definition: rosplot.py:77
def _array_eval(field_name, slot_num)
Definition: rosplot.py:173
def __init__(self, topic, start_time)
Definition: rosplot.py:97
def _get_data(self, msg)
Definition: rosplot.py:155
def _ros_cb(self, msg)
Definition: rosplot.py:117
def _get_topic_type(topic)
Definition: rosplot.py:52
def _field_eval(field_name)
Definition: rosplot.py:184


rqt_plot
Author(s): Dorian Scholz
autogenerated on Sun Mar 17 2019 02:21:35