00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
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 from std_msgs.msg import Bool
00046 
00047 
00048 class RosPlotException(Exception):
00049     pass
00050 
00051 
00052 def _get_topic_type(topic):
00053     """
00054     subroutine for getting the topic type
00055     (nearly identical to rostopic._get_topic_type, except it returns rest of name instead of fn)
00056 
00057     :returns: topic type, real topic name, and rest of name referenced
00058       if the topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
00059     """
00060     try:
00061         master = rosgraph.Master('/rosplot')
00062         val = master.getTopicTypes()
00063     except:
00064         raise RosPlotException("unable to get list of topics from master")
00065     matches = [(t, t_type) for t, t_type in val if t == topic or topic.startswith(t + '/')]
00066     if matches:
00067         t, t_type = matches[0]
00068         if t_type == roslib.names.ANYTYPE:
00069             return None, None, None
00070         if t_type == topic:
00071             return t_type, None
00072         return t_type, t, topic[len(t):]
00073     else:
00074         return None, None, None
00075 
00076 
00077 def get_topic_type(topic):
00078     """
00079     Get the topic type (nearly identical to rostopic.get_topic_type, except it doesn't return a fn)
00080 
00081     :returns: topic type, real topic name, and rest of name referenced
00082       if the \a topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
00083     """
00084     topic_type, real_topic, rest = _get_topic_type(topic)
00085     if topic_type:
00086         return topic_type, real_topic, rest
00087     else:
00088         return None, None, None
00089 
00090 
00091 class ROSData(object):
00092     """
00093     Subscriber to ROS topic that buffers incoming data
00094     """
00095 
00096     def __init__(self, topic, start_time):
00097         self.name = topic
00098         self.start_time = start_time
00099         self.error = None
00100 
00101         self.lock = threading.Lock()
00102         self.buff_x = []
00103         self.buff_y = []
00104 
00105         topic_type, real_topic, fields = get_topic_type(topic)
00106         if topic_type is not None:
00107             self.field_evals = generate_field_evals(fields)
00108             data_class = roslib.message.get_message_class(topic_type)
00109             self.sub = rospy.Subscriber(real_topic, data_class, self._ros_cb)
00110         else:
00111             self.error = RosPlotException("Can not resolve topic type of %s" % topic)
00112 
00113     def close(self):
00114         self.sub.unregister()
00115 
00116     def _ros_cb(self, msg):
00117         """
00118         ROS subscriber callback
00119         :param msg: ROS message data
00120         """
00121         try:
00122             self.lock.acquire()
00123             try:
00124                 self.buff_y.append(self._get_data(msg))
00125                 
00126                 if msg.__class__._has_header:
00127                     self.buff_x.append(msg.header.stamp.to_sec() - self.start_time)
00128                 else:
00129                     self.buff_x.append(rospy.get_time() - self.start_time)
00130                 
00131             except AttributeError as e:
00132                 self.error = RosPlotException("Invalid topic spec [%s]: %s" % (self.name, str(e)))
00133         finally:
00134             self.lock.release()
00135 
00136     def next(self):
00137         """
00138         Get the next data in the series
00139 
00140         :returns: [xdata], [ydata]
00141         """
00142         if self.error:
00143             raise self.error
00144         try:
00145             self.lock.acquire()
00146             buff_x = self.buff_x
00147             buff_y = self.buff_y
00148             self.buff_x = []
00149             self.buff_y = []
00150         finally:
00151             self.lock.release()
00152         return buff_x, buff_y
00153 
00154     def _get_data(self, msg):
00155         val = msg
00156         try:
00157             if not self.field_evals:
00158                 if isinstance(val, Bool):
00159                     
00160                     val = val.data
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 as e:
00205         raise RosPlotException("cannot parse field reference [%s]: %s" % (fields, str(e)))