45 from std_msgs.msg
import Bool
54 subroutine for getting the topic type 55 (nearly identical to rostopic._get_topic_type, except it returns rest of name instead of fn) 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`` 61 master = rosgraph.Master(
'/rosplot')
62 val = master.getTopicTypes()
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 +
'/')]
67 t, t_type = matches[0]
68 if t_type == roslib.names.ANYTYPE:
69 return None,
None,
None 72 return t_type, t, topic[len(t):]
74 return None,
None,
None 79 Get the topic type (nearly identical to rostopic.get_topic_type, except it doesn't return a fn) 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`` 86 return topic_type, real_topic, rest
88 return None,
None,
None 94 Subscriber to ROS topic that buffers incoming data 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)
115 self.sub.unregister()
119 ROS subscriber callback 120 :param msg: ROS message data 127 if msg.__class__._has_header:
128 self.buff_x.append(msg.header.stamp.to_sec() - self.
start_time)
130 self.buff_x.append(rospy.get_time() - self.
start_time)
132 except AttributeError
as e:
139 Get the next data in the series 141 :returns: [xdata], [ydata] 153 return buff_x, buff_y
159 if isinstance(val, Bool):
168 "[%s] index error for: %s" % (self.
name, str(val).replace(
'\n',
', ')))
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] 180 return getattr(f, field_name).__getitem__(slot_num)
186 :param field_name: name of field to return, ``str`` 187 :returns: fn(msg_field)->msg_field.field_name 190 return getattr(f, field_name)
197 fields = [f
for f
in fields.split(
'/')
if f]
200 field_name, rest = f.split(
'[')
201 slot_num = string.atoi(rest[:rest.find(
']')])
206 except Exception
as e:
207 raise RosPlotException(
"cannot parse field reference [%s]: %s" % (fields, str(e)))
def generate_field_evals(fields)
def get_topic_type(topic)
def _array_eval(field_name, slot_num)
def __init__(self, topic, start_time)
def _get_topic_type(topic)
def _field_eval(field_name)