00001 """autogenerated by genmsg_py from TrackMsg.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import sensor_msgs.msg
00006 import geometry_msgs.msg
00007 import std_msgs.msg
00008
00009 class TrackMsg(roslib.message.Message):
00010 _md5sum = "4d31433dbfca9abee6e8969e22b59c72"
00011 _type = "articulation_msgs/TrackMsg"
00012 _has_header = True
00013 _full_text = """# Single kinematic trajectory
00014 #
00015 # This message contains a kinematic trajectory. The trajectory is specified
00016 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00017 # the track is valid, and whether it includes orientation. The track id
00018 # can be used for automatic coloring in the RVIZ track plugin, and can be
00019 # freely chosen by the client.
00020 #
00021 # A model is fitting only from the trajectory stored in the pose[]-vector.
00022 # Additional information may be associated to each pose using the channels
00023 # vector, with arbitrary # fields (e.g., to include applied/measured forces).
00024 #
00025 # After model evaluation,
00026 # also the associated configurations of the object are stored in the channels,
00027 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00028 # Model evaluation also projects the poses in the pose vector onto the model,
00029 # and stores these ideal poses in the vector pose_projected. Further, during model
00030 # evaluation, a new set of (uniform) configurations over the valid configuration
00031 # range is sampled, and the result is stored in pose_resampled.
00032 # The vector pose_flags contains additional display flags for the poses in the
00033 # pose vector, for example, whether a pose is visible and/or
00034 # the end of a trajectory segment. At the moment, this is only used by the
00035 # prior_model_learner.
00036 #
00037
00038 Header header # Timestamp and frame
00039 int32 id # used-specified track id
00040
00041 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory
00042 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model
00043 # (after model evaluation)
00044 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in
00045 # the valid configuration range
00046 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00047
00048 uint32 POSE_VISIBLE=1
00049 uint32 POSE_END_OF_SEGMENT=2
00050
00051 # Each channel should have the same number of elements as pose array,
00052 # and the data in each channel should correspond 1:1 with each pose
00053 # possible channels: "width", "height", "rgb", ...
00054 sensor_msgs/ChannelFloat32[] channels
00055
00056
00057
00058 ================================================================================
00059 MSG: std_msgs/Header
00060 # Standard metadata for higher-level stamped data types.
00061 # This is generally used to communicate timestamped data
00062 # in a particular coordinate frame.
00063 #
00064 # sequence ID: consecutively increasing ID
00065 uint32 seq
00066 #Two-integer timestamp that is expressed as:
00067 # * stamp.secs: seconds (stamp_secs) since epoch
00068 # * stamp.nsecs: nanoseconds since stamp_secs
00069 # time-handling sugar is provided by the client library
00070 time stamp
00071 #Frame this data is associated with
00072 # 0: no frame
00073 # 1: global frame
00074 string frame_id
00075
00076 ================================================================================
00077 MSG: geometry_msgs/Pose
00078 # A representation of pose in free space, composed of postion and orientation.
00079 Point position
00080 Quaternion orientation
00081
00082 ================================================================================
00083 MSG: geometry_msgs/Point
00084 # This contains the position of a point in free space
00085 float64 x
00086 float64 y
00087 float64 z
00088
00089 ================================================================================
00090 MSG: geometry_msgs/Quaternion
00091 # This represents an orientation in free space in quaternion form.
00092
00093 float64 x
00094 float64 y
00095 float64 z
00096 float64 w
00097
00098 ================================================================================
00099 MSG: sensor_msgs/ChannelFloat32
00100 # This message is used by the PointCloud message to hold optional data
00101 # associated with each point in the cloud. The length of the values
00102 # array should be the same as the length of the points array in the
00103 # PointCloud, and each value should be associated with the corresponding
00104 # point.
00105
00106 # Channel names in existing practice include:
00107 # "u", "v" - row and column (respectively) in the left stereo image.
00108 # This is opposite to usual conventions but remains for
00109 # historical reasons. The newer PointCloud2 message has no
00110 # such problem.
00111 # "rgb" - For point clouds produced by color stereo cameras. uint8
00112 # (R,G,B) values packed into the least significant 24 bits,
00113 # in order.
00114 # "intensity" - laser or pixel intensity.
00115 # "distance"
00116
00117 # The channel name should give semantics of the channel (e.g.
00118 # "intensity" instead of "value").
00119 string name
00120
00121 # The values array should be 1-1 with the elements of the associated
00122 # PointCloud.
00123 float32[] values
00124
00125 """
00126 # Pseudo-constants
00127 POSE_VISIBLE = 1
00128 POSE_END_OF_SEGMENT = 2
00129
00130 __slots__ = ['header','id','pose','pose_projected','pose_resampled','pose_flags','channels']
00131 _slot_types = ['Header','int32','geometry_msgs/Pose[]','geometry_msgs/Pose[]','geometry_msgs/Pose[]','uint32[]','sensor_msgs/ChannelFloat32[]']
00132
00133 def __init__(self, *args, **kwds):
00134 """
00135 Constructor. Any message fields that are implicitly/explicitly
00136 set to None will be assigned a default value. The recommend
00137 use is keyword arguments as this is more robust to future message
00138 changes. You cannot mix in-order arguments and keyword arguments.
00139
00140 The available fields are:
00141 header,id,pose,pose_projected,pose_resampled,pose_flags,channels
00142
00143 @param args: complete set of field values, in .msg order
00144 @param kwds: use keyword arguments corresponding to message field names
00145 to set specific fields.
00146 """
00147 if args or kwds:
00148 super(TrackMsg, self).__init__(*args, **kwds)
00149 #message fields cannot be None, assign default values for those that are
00150 if self.header is None:
00151 self.header = std_msgs.msg._Header.Header()
00152 if self.id is None:
00153 self.id = 0
00154 if self.pose is None:
00155 self.pose = []
00156 if self.pose_projected is None:
00157 self.pose_projected = []
00158 if self.pose_resampled is None:
00159 self.pose_resampled = []
00160 if self.pose_flags is None:
00161 self.pose_flags = []
00162 if self.channels is None:
00163 self.channels = []
00164 else:
00165 self.header = std_msgs.msg._Header.Header()
00166 self.id = 0
00167 self.pose = []
00168 self.pose_projected = []
00169 self.pose_resampled = []
00170 self.pose_flags = []
00171 self.channels = []
00172
00173 def _get_types(self):
00174 """
00175 internal API method
00176 """
00177 return self._slot_types
00178
00179 def serialize(self, buff):
00180 """
00181 serialize message into buffer
00182 @param buff: buffer
00183 @type buff: StringIO
00184 """
00185 try:
00186 _x = self
00187 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00188 _x = self.header.frame_id
00189 length = len(_x)
00190 buff.write(struct.pack('<I%ss'%length, length, _x))
00191 buff.write(_struct_i.pack(self.id))
00192 length = len(self.pose)
00193 buff.write(_struct_I.pack(length))
00194 for val1 in self.pose:
00195 _v1 = val1.position
00196 _x = _v1
00197 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00198 _v2 = val1.orientation
00199 _x = _v2
00200 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00201 length = len(self.pose_projected)
00202 buff.write(_struct_I.pack(length))
00203 for val1 in self.pose_projected:
00204 _v3 = val1.position
00205 _x = _v3
00206 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00207 _v4 = val1.orientation
00208 _x = _v4
00209 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00210 length = len(self.pose_resampled)
00211 buff.write(_struct_I.pack(length))
00212 for val1 in self.pose_resampled:
00213 _v5 = val1.position
00214 _x = _v5
00215 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00216 _v6 = val1.orientation
00217 _x = _v6
00218 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00219 length = len(self.pose_flags)
00220 buff.write(_struct_I.pack(length))
00221 pattern = '<%sI'%length
00222 buff.write(struct.pack(pattern, *self.pose_flags))
00223 length = len(self.channels)
00224 buff.write(_struct_I.pack(length))
00225 for val1 in self.channels:
00226 _x = val1.name
00227 length = len(_x)
00228 buff.write(struct.pack('<I%ss'%length, length, _x))
00229 length = len(val1.values)
00230 buff.write(_struct_I.pack(length))
00231 pattern = '<%sf'%length
00232 buff.write(struct.pack(pattern, *val1.values))
00233 except struct.error, se: self._check_types(se)
00234 except TypeError, te: self._check_types(te)
00235
00236 def deserialize(self, str):
00237 """
00238 unpack serialized message in str into this message instance
00239 @param str: byte array of serialized message
00240 @type str: str
00241 """
00242 try:
00243 if self.header is None:
00244 self.header = std_msgs.msg._Header.Header()
00245 end = 0
00246 _x = self
00247 start = end
00248 end += 12
00249 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00250 start = end
00251 end += 4
00252 (length,) = _struct_I.unpack(str[start:end])
00253 start = end
00254 end += length
00255 self.header.frame_id = str[start:end]
00256 start = end
00257 end += 4
00258 (self.id,) = _struct_i.unpack(str[start:end])
00259 start = end
00260 end += 4
00261 (length,) = _struct_I.unpack(str[start:end])
00262 self.pose = []
00263 for i in xrange(0, length):
00264 val1 = geometry_msgs.msg.Pose()
00265 _v7 = val1.position
00266 _x = _v7
00267 start = end
00268 end += 24
00269 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00270 _v8 = val1.orientation
00271 _x = _v8
00272 start = end
00273 end += 32
00274 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00275 self.pose.append(val1)
00276 start = end
00277 end += 4
00278 (length,) = _struct_I.unpack(str[start:end])
00279 self.pose_projected = []
00280 for i in xrange(0, length):
00281 val1 = geometry_msgs.msg.Pose()
00282 _v9 = val1.position
00283 _x = _v9
00284 start = end
00285 end += 24
00286 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00287 _v10 = val1.orientation
00288 _x = _v10
00289 start = end
00290 end += 32
00291 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00292 self.pose_projected.append(val1)
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 self.pose_resampled = []
00297 for i in xrange(0, length):
00298 val1 = geometry_msgs.msg.Pose()
00299 _v11 = val1.position
00300 _x = _v11
00301 start = end
00302 end += 24
00303 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00304 _v12 = val1.orientation
00305 _x = _v12
00306 start = end
00307 end += 32
00308 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00309 self.pose_resampled.append(val1)
00310 start = end
00311 end += 4
00312 (length,) = _struct_I.unpack(str[start:end])
00313 pattern = '<%sI'%length
00314 start = end
00315 end += struct.calcsize(pattern)
00316 self.pose_flags = struct.unpack(pattern, str[start:end])
00317 start = end
00318 end += 4
00319 (length,) = _struct_I.unpack(str[start:end])
00320 self.channels = []
00321 for i in xrange(0, length):
00322 val1 = sensor_msgs.msg.ChannelFloat32()
00323 start = end
00324 end += 4
00325 (length,) = _struct_I.unpack(str[start:end])
00326 start = end
00327 end += length
00328 val1.name = str[start:end]
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 pattern = '<%sf'%length
00333 start = end
00334 end += struct.calcsize(pattern)
00335 val1.values = struct.unpack(pattern, str[start:end])
00336 self.channels.append(val1)
00337 return self
00338 except struct.error, e:
00339 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00340
00341
00342 def serialize_numpy(self, buff, numpy):
00343 """
00344 serialize message with numpy array types into buffer
00345 @param buff: buffer
00346 @type buff: StringIO
00347 @param numpy: numpy python module
00348 @type numpy module
00349 """
00350 try:
00351 _x = self
00352 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00353 _x = self.header.frame_id
00354 length = len(_x)
00355 buff.write(struct.pack('<I%ss'%length, length, _x))
00356 buff.write(_struct_i.pack(self.id))
00357 length = len(self.pose)
00358 buff.write(_struct_I.pack(length))
00359 for val1 in self.pose:
00360 _v13 = val1.position
00361 _x = _v13
00362 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00363 _v14 = val1.orientation
00364 _x = _v14
00365 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00366 length = len(self.pose_projected)
00367 buff.write(_struct_I.pack(length))
00368 for val1 in self.pose_projected:
00369 _v15 = val1.position
00370 _x = _v15
00371 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00372 _v16 = val1.orientation
00373 _x = _v16
00374 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00375 length = len(self.pose_resampled)
00376 buff.write(_struct_I.pack(length))
00377 for val1 in self.pose_resampled:
00378 _v17 = val1.position
00379 _x = _v17
00380 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00381 _v18 = val1.orientation
00382 _x = _v18
00383 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00384 length = len(self.pose_flags)
00385 buff.write(_struct_I.pack(length))
00386 pattern = '<%sI'%length
00387 buff.write(self.pose_flags.tostring())
00388 length = len(self.channels)
00389 buff.write(_struct_I.pack(length))
00390 for val1 in self.channels:
00391 _x = val1.name
00392 length = len(_x)
00393 buff.write(struct.pack('<I%ss'%length, length, _x))
00394 length = len(val1.values)
00395 buff.write(_struct_I.pack(length))
00396 pattern = '<%sf'%length
00397 buff.write(val1.values.tostring())
00398 except struct.error, se: self._check_types(se)
00399 except TypeError, te: self._check_types(te)
00400
00401 def deserialize_numpy(self, str, numpy):
00402 """
00403 unpack serialized message in str into this message instance using numpy for array types
00404 @param str: byte array of serialized message
00405 @type str: str
00406 @param numpy: numpy python module
00407 @type numpy: module
00408 """
00409 try:
00410 if self.header is None:
00411 self.header = std_msgs.msg._Header.Header()
00412 end = 0
00413 _x = self
00414 start = end
00415 end += 12
00416 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00417 start = end
00418 end += 4
00419 (length,) = _struct_I.unpack(str[start:end])
00420 start = end
00421 end += length
00422 self.header.frame_id = str[start:end]
00423 start = end
00424 end += 4
00425 (self.id,) = _struct_i.unpack(str[start:end])
00426 start = end
00427 end += 4
00428 (length,) = _struct_I.unpack(str[start:end])
00429 self.pose = []
00430 for i in xrange(0, length):
00431 val1 = geometry_msgs.msg.Pose()
00432 _v19 = val1.position
00433 _x = _v19
00434 start = end
00435 end += 24
00436 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00437 _v20 = val1.orientation
00438 _x = _v20
00439 start = end
00440 end += 32
00441 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00442 self.pose.append(val1)
00443 start = end
00444 end += 4
00445 (length,) = _struct_I.unpack(str[start:end])
00446 self.pose_projected = []
00447 for i in xrange(0, length):
00448 val1 = geometry_msgs.msg.Pose()
00449 _v21 = val1.position
00450 _x = _v21
00451 start = end
00452 end += 24
00453 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00454 _v22 = val1.orientation
00455 _x = _v22
00456 start = end
00457 end += 32
00458 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00459 self.pose_projected.append(val1)
00460 start = end
00461 end += 4
00462 (length,) = _struct_I.unpack(str[start:end])
00463 self.pose_resampled = []
00464 for i in xrange(0, length):
00465 val1 = geometry_msgs.msg.Pose()
00466 _v23 = val1.position
00467 _x = _v23
00468 start = end
00469 end += 24
00470 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00471 _v24 = val1.orientation
00472 _x = _v24
00473 start = end
00474 end += 32
00475 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00476 self.pose_resampled.append(val1)
00477 start = end
00478 end += 4
00479 (length,) = _struct_I.unpack(str[start:end])
00480 pattern = '<%sI'%length
00481 start = end
00482 end += struct.calcsize(pattern)
00483 self.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
00484 start = end
00485 end += 4
00486 (length,) = _struct_I.unpack(str[start:end])
00487 self.channels = []
00488 for i in xrange(0, length):
00489 val1 = sensor_msgs.msg.ChannelFloat32()
00490 start = end
00491 end += 4
00492 (length,) = _struct_I.unpack(str[start:end])
00493 start = end
00494 end += length
00495 val1.name = str[start:end]
00496 start = end
00497 end += 4
00498 (length,) = _struct_I.unpack(str[start:end])
00499 pattern = '<%sf'%length
00500 start = end
00501 end += struct.calcsize(pattern)
00502 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00503 self.channels.append(val1)
00504 return self
00505 except struct.error, e:
00506 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00507
00508 _struct_I = roslib.message.struct_I
00509 _struct_i = struct.Struct("<i")
00510 _struct_3I = struct.Struct("<3I")
00511 _struct_4d = struct.Struct("<4d")
00512 _struct_3d = struct.Struct("<3d")