rosplot.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2009, Willow Garage, Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of Willow Garage, Inc. nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 #
00035 
00036 import string
00037 import sys
00038 import threading
00039 import time
00040 
00041 import rosgraph
00042 import roslib.message
00043 import roslib.names
00044 import rospy
00045 
00046 
00047 class RosPlotException(Exception):
00048     pass
00049 
00050 
00051 def _get_topic_type(topic):
00052     """
00053     subroutine for getting the topic type
00054     (nearly identical to rostopic._get_topic_type, except it returns rest of name instead of fn)
00055 
00056     :returns: topic type, real topic name, and rest of name referenced
00057       if the topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
00058     """
00059     try:
00060         master = rosgraph.Master('/rosplot')
00061         val = master.getPublishedTopics('/')
00062     except:
00063         raise RosPlotException("unable to get list of topics from master")
00064     matches = [(t, t_type) for t, t_type in val if t == topic or topic.startswith(t + '/')]
00065     if matches:
00066         t, t_type = matches[0]
00067         if t_type == roslib.names.ANYTYPE:
00068             return None, None, None
00069         if t_type == topic:
00070             return t_type, None
00071         return t_type, t, topic[len(t):]
00072     else:
00073         return None, None, None
00074 
00075 
00076 def get_topic_type(topic):
00077     """
00078     Get the topic type (nearly identical to rostopic.get_topic_type, except it doesn't return a fn)
00079 
00080     :returns: topic type, real topic name, and rest of name referenced
00081       if the \a topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
00082     """
00083     topic_type, real_topic, rest = _get_topic_type(topic)
00084     if topic_type:
00085         return topic_type, real_topic, rest
00086     else:
00087         print >> sys.stderr, "WARNING: topic [%s] does not appear to be published yet. Waiting..." % topic
00088         while not rospy.is_shutdown():
00089             topic_type, real_topic, rest = _get_topic_type(topic)
00090             if topic_type:
00091                 return topic_type, real_topic, rest
00092             else:
00093                 time.sleep(0.1)
00094         return None, None, None
00095 
00096 
00097 class ROSData(object):
00098     """
00099     Subscriber to ROS topic that buffers incoming data
00100     """
00101 
00102     def __init__(self, topic, start_time):
00103         self.name = topic
00104         self.start_time = start_time
00105         self.error = None
00106 
00107         self.lock = threading.Lock()
00108         self.buff_x = []
00109         self.buff_y = []
00110 
00111         topic_type, real_topic, fields = get_topic_type(topic)
00112         self.field_evals = generate_field_evals(fields)
00113         data_class = roslib.message.get_message_class(topic_type)
00114         self.sub = rospy.Subscriber(real_topic, data_class, self._ros_cb)
00115 
00116     def close(self):
00117         self.sub.unregister()
00118 
00119     def _ros_cb(self, msg):
00120         """
00121         ROS subscriber callback
00122         :param msg: ROS message data
00123         """
00124         try:
00125             self.lock.acquire()
00126             try:
00127                 self.buff_y.append(self._get_data(msg))
00128                 # #944: use message header time if present
00129                 if msg.__class__._has_header:
00130                     self.buff_x.append(msg.header.stamp.to_sec() - self.start_time)
00131                 else:
00132                     self.buff_x.append(rospy.get_time() - self.start_time)
00133                 #self.axes[index].plot(datax, buff_y)
00134             except AttributeError, e:
00135                 self.error = RosPlotException("Invalid topic spec [%s]: %s" % (self.name, str(e)))
00136         finally:
00137             self.lock.release()
00138 
00139     def next(self):
00140         """
00141         Get the next data in the series
00142 
00143         :returns: [xdata], [ydata]
00144         """
00145         if self.error:
00146             raise self.error
00147         try:
00148             self.lock.acquire()
00149             buff_x = self.buff_x
00150             buff_y = self.buff_y
00151             self.buff_x = []
00152             self.buff_y = []
00153         finally:
00154             self.lock.release()
00155         return buff_x, buff_y
00156 
00157     def _get_data(self, msg):
00158         val = msg
00159         try:
00160             if not self.field_evals:
00161                 return float(val)
00162             for f in self.field_evals:
00163                 val = f(val)
00164             return float(val)
00165         except IndexError:
00166             self.error = RosPlotException("[%s] index error for: %s" % (self.name, str(val).replace('\n', ', ')))
00167         except TypeError:
00168             self.error = RosPlotException("[%s] value was not numeric: %s" % (self.name, val))
00169 
00170 
00171 def _array_eval(field_name, slot_num):
00172     """
00173     :param field_name: name of field to index into, ``str``
00174     :param slot_num: index of slot to return, ``str``
00175     :returns: fn(msg_field)->msg_field[slot_num]
00176     """
00177     def fn(f):
00178         return getattr(f, field_name).__getitem__(slot_num)
00179     return fn
00180 
00181 
00182 def _field_eval(field_name):
00183     """
00184     :param field_name: name of field to return, ``str``
00185     :returns: fn(msg_field)->msg_field.field_name
00186     """
00187     def fn(f):
00188         return getattr(f, field_name)
00189     return fn
00190 
00191 
00192 def generate_field_evals(fields):
00193     try:
00194         evals = []
00195         fields = [f for f in fields.split('/') if f]
00196         for f in fields:
00197             if '[' in f:
00198                 field_name, rest = f.split('[')
00199                 slot_num = string.atoi(rest[:rest.find(']')])
00200                 evals.append(_array_eval(field_name, slot_num))
00201             else:
00202                 evals.append(_field_eval(f))
00203         return evals
00204     except Exception, e:
00205         raise RosPlotException("cannot parse field reference [%s]: %s" % (fields, str(e)))


rqt_plot
Author(s): Dorian Scholz
autogenerated on Fri Jan 3 2014 11:55:13