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 # Revision $Id$
00036 
00037 # rosplot current exists as a support library for rxplot. rosplot is
00038 # incomplete as a general library for getting plottable ROS Topic
00039 # data. The rxplot module still contains much of the logic necessary
00040 # for this.
00041 
00042 import string
00043 import sys
00044 import threading
00045 import time
00046 
00047 import roslib.message
00048 import roslib.names
00049 import rosgraph
00050 import rospy
00051 
00052 class RosPlotException(Exception): pass
00053 
00054 def _get_topic_type(topic):
00055     """
00056     subroutine for getting the topic type
00057     (nearly identical to rostopic._get_topic_type, except it returns rest of name instead of fn)
00058     
00059     :returns: topic type, real topic name, and rest of name referenced
00060       if the topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
00061     """
00062     try:
00063         master = rosgraph.Master('/rosplot')
00064         val = master.getPublishedTopics('/')
00065     except:
00066         raise RosPlotException("unable to get list of topics from master")
00067     matches = [(t, t_type) for t, t_type in val if t == topic or topic.startswith(t+'/')]
00068     if matches:
00069         t, t_type = matches[0]
00070         if t_type == roslib.names.ANYTYPE:
00071             return None, None, None
00072         if t_type == topic:
00073             return t_type, None
00074         return t_type, t, topic[len(t):]
00075     else:
00076         return None, None, None
00077 
00078 def get_topic_type(topic):
00079     """
00080     Get the topic type (nearly identical to rostopic.get_topic_type, except it doesn't return a fn)
00081     
00082     :returns: topic type, real topic name, and rest of name referenced
00083       if the \a topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
00084     """
00085     topic_type, real_topic, rest = _get_topic_type(topic)
00086     if topic_type:
00087         return topic_type, real_topic, rest
00088     else:
00089         print >> sys.stderr, "WARNING: topic [%s] does not appear to be published yet"%topic
00090         while not rospy.is_shutdown():
00091             topic_type, real_topic, rest = _get_topic_type(topic)
00092             if topic_type:
00093                 return topic_type, real_topic, rest
00094             else:
00095                 time.sleep(0.1)
00096         return None, None, None
00097 
00098 
00099 class ROSData(object):
00100     """
00101     Subscriber to ROS topic that buffers incoming data
00102     """
00103     
00104     def __init__(self, topic, start_time):
00105         self.name = topic
00106         self.start_time = start_time
00107         self.error = None
00108         
00109         self.lock = threading.Lock()
00110         self.buff_x = []
00111         self.buff_y = []
00112         
00113         topic_type, real_topic, fields = get_topic_type(topic)
00114         self.field_evals = generate_field_evals(fields)
00115         data_class = roslib.message.get_message_class(topic_type)
00116         self.sub = rospy.Subscriber(real_topic, data_class, self._ros_cb)
00117 
00118     def close(self):
00119       self.sub.unregister()
00120 
00121     def _ros_cb(self, msg):
00122         """
00123         ROS subscriber callback
00124         :param msg: ROS message data
00125         """
00126         try:
00127             self.lock.acquire()
00128             try:
00129                 self.buff_y.append(self._get_data(msg))
00130                 # #944: use message header time if present
00131                 if msg.__class__._has_header:
00132                     self.buff_x.append(msg.header.stamp.to_sec() - self.start_time)
00133                 else:
00134                     self.buff_x.append(rospy.get_time() - self.start_time)                    
00135                 #self.axes[index].plot(datax, buff_y)
00136             except AttributeError, e:
00137                 self.error = RosPlotException("Invalid topic spec [%s]: %s"%(self.name, str(e)))
00138         finally:
00139             self.lock.release()
00140         
00141     def next(self):
00142         """
00143         Get the next data in the series
00144         
00145         :returns: [xdata], [ydata]
00146         """
00147         if self.error:
00148             raise self.error
00149         try:
00150             self.lock.acquire()
00151             buff_x = self.buff_x
00152             buff_y = self.buff_y
00153             self.buff_x = []
00154             self.buff_y = []
00155         finally:
00156             self.lock.release()
00157         return buff_x, buff_y
00158         
00159     def _get_data(self, msg):
00160         val = msg
00161         try:
00162             if not self.field_evals:
00163                 return float(val)
00164             for f in self.field_evals:
00165                 val = f(val)
00166             return float(val)
00167         except TypeError:
00168             print "[%s] value was not numeric: %s"%(self.name, val)
00169             #TODO: really, really shouldn't be doing this here
00170             sys.exit(1)
00171 
00172 _paused = False
00173 def toggle_ros_pause():
00174     global _paused
00175     _paused = not _paused
00176     
00177 # TODO: this should affect data collection, but it doesn't right now
00178 _stopped = False
00179 def set_ros_stop():
00180     global _stopped, _paused
00181     _stopped = True
00182     _paused = True
00183 
00184 def is_ros_pause():
00185     return _paused
00186 def is_ros_stop():
00187     return _stopped
00188 
00189 def _array_eval(field_name, slot_num):
00190     """
00191     :param field_name: name of field to index into, ``str``
00192     :param slot_num: index of slot to return, ``str``
00193     :returns: fn(msg_field)->msg_field[slot_num]
00194     """
00195     def fn(f):
00196         return getattr(f, field_name).__getitem__(slot_num)
00197     return fn
00198 
00199 def _field_eval(field_name):
00200     """
00201     :param field_name: name of field to return, ``str``
00202     :returns: fn(msg_field)->msg_field.field_name
00203     """
00204     def fn(f):
00205         return getattr(f, field_name)
00206     return fn
00207 
00208 def generate_field_evals(fields):
00209     try:
00210         evals = []
00211         fields = [f for f in fields.split('/') if f]
00212         for f in fields:
00213             if '[' in f:
00214                 field_name, rest = f.split('[')
00215                 slot_num = string.atoi(rest[:rest.find(']')])
00216                 evals.append(_array_eval(field_name, slot_num))
00217             else:
00218                 evals.append(_field_eval(f))
00219         return evals
00220     except Exception, e:
00221         raise RosPlotException("cannot parse field reference [%s]: %s"%(fields, str(e)))
00222     


rxtools
Author(s): Josh Faust, Rob Wheeler, Ken Conley
autogenerated on Mon Oct 6 2014 07:25:59