44 from std_msgs.msg
import Bool
53 subroutine for getting the topic type
54 (nearly identical to rostopic._get_topic_type, except it returns rest of name instead of fn)
56 :returns: topic type, real topic name, and rest of name referenced
57 if the topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
60 master = rosgraph.Master(
'/rosplot')
61 val = master.getTopicTypes()
63 raise RosPlotException(
"unable to get list of topics from master")
64 matches = [(t, t_type)
for t, t_type
in val
if t == topic
or topic.startswith(t +
'/')]
66 t, t_type = matches[0]
67 if t_type == roslib.names.ANYTYPE:
68 return None,
None,
None
71 return t_type, t, topic[len(t):]
73 return None,
None,
None
78 Get the topic type (nearly identical to rostopic.get_topic_type, except it doesn't return a fn)
80 :returns: topic type, real topic name, and rest of name referenced
81 if the \a topic points to a field within a topic, e.g. /rosout/msg, ``str, str, str``
85 return topic_type, real_topic, rest
87 return None,
None,
None
93 Subscriber to ROS topic that buffers incoming data
106 if topic_type
is not None:
108 data_class = roslib.message.get_message_class(topic_type)
109 self.
sub = rospy.Subscriber(real_topic, data_class, self.
_ros_cb)
114 self.
sub.unregister()
118 ROS subscriber callback
119 :param msg: ROS message data
126 if msg.__class__._has_header:
131 except AttributeError
as e:
138 Get the next data in the series
140 :returns: [xdata], [ydata]
152 return buff_x, buff_y
158 if isinstance(val, Bool):
167 "[%s] index error for: %s" % (self.
name, str(val).replace(
'\n',
', ')))
174 :param field_name: name of field to index into, ``str``
175 :param slot_num: index of slot to return, ``str``
176 :returns: fn(msg_field)->msg_field[slot_num]
179 return getattr(f, field_name).__getitem__(slot_num)
185 :param field_name: name of field to return, ``str``
186 :returns: fn(msg_field)->msg_field.field_name
189 return getattr(f, field_name)
196 fields = [f
for f
in fields.split(
'/')
if f]
199 field_name, rest = f.split(
'[')
200 slot_num = int(rest[:rest.find(
']')])
205 except Exception
as e:
206 raise RosPlotException(
"cannot parse field reference [%s]: %s" % (fields, str(e)))