00001 """autogenerated by genmsg_py from ModelMsg.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import sensor_msgs.msg
00006 import geometry_msgs.msg
00007 import articulation_msgs.msg
00008 import std_msgs.msg
00009
00010 class ModelMsg(roslib.message.Message):
00011 _md5sum = "f668954d4ad5a57c58d0dab97e12a6f4"
00012 _type = "articulation_msgs/ModelMsg"
00013 _has_header = True
00014 _full_text = """# Single kinematic model
00015 #
00016 # A kinematic model is defined by its model class name, and a set of parameters.
00017 # The client may additionally specify a model id, that can be used to colorize the
00018 # model when visualized using the RVIZ model display.
00019 #
00020 # For a list of currently implemented models, see the documetation at
00021 # http://www.ros.org/wiki/articulation_models
00022 #
00023 #
00024
00025 Header header # frame and timestamp
00026
00027 int32 id # user specified model id
00028 string name # name of the model family (e.g. "rotational",
00029 # "prismatic", "pca-gp", "rigid")
00030 articulation_msgs/ParamMsg[] params # model parameters
00031 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or
00032 # that is evaluated using the model
00033
00034 ================================================================================
00035 MSG: std_msgs/Header
00036 # Standard metadata for higher-level stamped data types.
00037 # This is generally used to communicate timestamped data
00038 # in a particular coordinate frame.
00039 #
00040 # sequence ID: consecutively increasing ID
00041 uint32 seq
00042 #Two-integer timestamp that is expressed as:
00043 # * stamp.secs: seconds (stamp_secs) since epoch
00044 # * stamp.nsecs: nanoseconds since stamp_secs
00045 # time-handling sugar is provided by the client library
00046 time stamp
00047 #Frame this data is associated with
00048 # 0: no frame
00049 # 1: global frame
00050 string frame_id
00051
00052 ================================================================================
00053 MSG: articulation_msgs/ParamMsg
00054 # Single parameter passed to or from model fitting
00055 #
00056 # This mechanism allows to flexibly pass parameters to
00057 # model fitting (and vice versa). Note that these parameters
00058 # are model-specific: A client may supply additional
00059 # parameters to the model estimator, and, similarly, a estimator
00060 # may add the estimated model parameters to the model message.
00061 # When the model is then evaluated, for example to make predictions
00062 # or to compute the likelihood, the model class can then use
00063 # these parameters.
00064 #
00065 # A parameter has a name, a value, and a type. The type globally
00066 # indicates whether it is a prior parameter (prior to model fitting),
00067 # or a model parameter (found during model fitting, using a maximum-
00068 # likelihood estimator), or a cached evaluation (e.g., the likelihood
00069 # or the BIC are a typical "side"-product of model estimation, and
00070 # can therefore already be cached).
00071 #
00072 # For a list of currently used parameters, see the documentation at
00073 # http://www.ros.org/wiki/articulation_models
00074 #
00075
00076 uint8 PRIOR=0 # indicates a prior model parameter
00077 # (e.g., "sigma_position")
00078 uint8 PARAM=1 # indicates a estimated model parameter
00079 # (e.g., "rot_radius", the estimated radius)
00080 uint8 EVAL=2 # indicates a cached evaluation of the model, given
00081 # the current trajectory
00082 # (e.g., "loglikelihood", the log likelihood of the
00083 # data, given the model and its parameters)
00084
00085 string name # name of the parameter
00086 float64 value # value of the parameter
00087 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)
00088
00089
00090 ================================================================================
00091 MSG: articulation_msgs/TrackMsg
00092 # Single kinematic trajectory
00093 #
00094 # This message contains a kinematic trajectory. The trajectory is specified
00095 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00096 # the track is valid, and whether it includes orientation. The track id
00097 # can be used for automatic coloring in the RVIZ track plugin, and can be
00098 # freely chosen by the client.
00099 #
00100 # A model is fitting only from the trajectory stored in the pose[]-vector.
00101 # Additional information may be associated to each pose using the channels
00102 # vector, with arbitrary # fields (e.g., to include applied/measured forces).
00103 #
00104 # After model evaluation,
00105 # also the associated configurations of the object are stored in the channels,
00106 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00107 # Model evaluation also projects the poses in the pose vector onto the model,
00108 # and stores these ideal poses in the vector pose_projected. Further, during model
00109 # evaluation, a new set of (uniform) configurations over the valid configuration
00110 # range is sampled, and the result is stored in pose_resampled.
00111 # The vector pose_flags contains additional display flags for the poses in the
00112 # pose vector, for example, whether a pose is visible and/or
00113 # the end of a trajectory segment. At the moment, this is only used by the
00114 # prior_model_learner.
00115 #
00116
00117 Header header # Timestamp and frame
00118 int32 id # used-specified track id
00119
00120 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory
00121 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model
00122 # (after model evaluation)
00123 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in
00124 # the valid configuration range
00125 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00126
00127 uint32 POSE_VISIBLE=1
00128 uint32 POSE_END_OF_SEGMENT=2
00129
00130 # Each channel should have the same number of elements as pose array,
00131 # and the data in each channel should correspond 1:1 with each pose
00132 # possible channels: "width", "height", "rgb", ...
00133 sensor_msgs/ChannelFloat32[] channels
00134
00135
00136
00137 ================================================================================
00138 MSG: geometry_msgs/Pose
00139 # A representation of pose in free space, composed of postion and orientation.
00140 Point position
00141 Quaternion orientation
00142
00143 ================================================================================
00144 MSG: geometry_msgs/Point
00145 # This contains the position of a point in free space
00146 float64 x
00147 float64 y
00148 float64 z
00149
00150 ================================================================================
00151 MSG: geometry_msgs/Quaternion
00152 # This represents an orientation in free space in quaternion form.
00153
00154 float64 x
00155 float64 y
00156 float64 z
00157 float64 w
00158
00159 ================================================================================
00160 MSG: sensor_msgs/ChannelFloat32
00161 # This message is used by the PointCloud message to hold optional data
00162 # associated with each point in the cloud. The length of the values
00163 # array should be the same as the length of the points array in the
00164 # PointCloud, and each value should be associated with the corresponding
00165 # point.
00166
00167 # Channel names in existing practice include:
00168 # "u", "v" - row and column (respectively) in the left stereo image.
00169 # This is opposite to usual conventions but remains for
00170 # historical reasons. The newer PointCloud2 message has no
00171 # such problem.
00172 # "rgb" - For point clouds produced by color stereo cameras. uint8
00173 # (R,G,B) values packed into the least significant 24 bits,
00174 # in order.
00175 # "intensity" - laser or pixel intensity.
00176 # "distance"
00177
00178 # The channel name should give semantics of the channel (e.g.
00179 # "intensity" instead of "value").
00180 string name
00181
00182 # The values array should be 1-1 with the elements of the associated
00183 # PointCloud.
00184 float32[] values
00185
00186 """
00187 __slots__ = ['header','id','name','params','track']
00188 _slot_types = ['Header','int32','string','articulation_msgs/ParamMsg[]','articulation_msgs/TrackMsg']
00189
00190 def __init__(self, *args, **kwds):
00191 """
00192 Constructor. Any message fields that are implicitly/explicitly
00193 set to None will be assigned a default value. The recommend
00194 use is keyword arguments as this is more robust to future message
00195 changes. You cannot mix in-order arguments and keyword arguments.
00196
00197 The available fields are:
00198 header,id,name,params,track
00199
00200 @param args: complete set of field values, in .msg order
00201 @param kwds: use keyword arguments corresponding to message field names
00202 to set specific fields.
00203 """
00204 if args or kwds:
00205 super(ModelMsg, self).__init__(*args, **kwds)
00206 #message fields cannot be None, assign default values for those that are
00207 if self.header is None:
00208 self.header = std_msgs.msg._Header.Header()
00209 if self.id is None:
00210 self.id = 0
00211 if self.name is None:
00212 self.name = ''
00213 if self.params is None:
00214 self.params = []
00215 if self.track is None:
00216 self.track = articulation_msgs.msg.TrackMsg()
00217 else:
00218 self.header = std_msgs.msg._Header.Header()
00219 self.id = 0
00220 self.name = ''
00221 self.params = []
00222 self.track = articulation_msgs.msg.TrackMsg()
00223
00224 def _get_types(self):
00225 """
00226 internal API method
00227 """
00228 return self._slot_types
00229
00230 def serialize(self, buff):
00231 """
00232 serialize message into buffer
00233 @param buff: buffer
00234 @type buff: StringIO
00235 """
00236 try:
00237 _x = self
00238 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00239 _x = self.header.frame_id
00240 length = len(_x)
00241 buff.write(struct.pack('<I%ss'%length, length, _x))
00242 buff.write(_struct_i.pack(self.id))
00243 _x = self.name
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 length = len(self.params)
00247 buff.write(_struct_I.pack(length))
00248 for val1 in self.params:
00249 _x = val1.name
00250 length = len(_x)
00251 buff.write(struct.pack('<I%ss'%length, length, _x))
00252 _x = val1
00253 buff.write(_struct_dB.pack(_x.value, _x.type))
00254 _x = self
00255 buff.write(_struct_3I.pack(_x.track.header.seq, _x.track.header.stamp.secs, _x.track.header.stamp.nsecs))
00256 _x = self.track.header.frame_id
00257 length = len(_x)
00258 buff.write(struct.pack('<I%ss'%length, length, _x))
00259 buff.write(_struct_i.pack(self.track.id))
00260 length = len(self.track.pose)
00261 buff.write(_struct_I.pack(length))
00262 for val1 in self.track.pose:
00263 _v1 = val1.position
00264 _x = _v1
00265 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00266 _v2 = val1.orientation
00267 _x = _v2
00268 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00269 length = len(self.track.pose_projected)
00270 buff.write(_struct_I.pack(length))
00271 for val1 in self.track.pose_projected:
00272 _v3 = val1.position
00273 _x = _v3
00274 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00275 _v4 = val1.orientation
00276 _x = _v4
00277 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00278 length = len(self.track.pose_resampled)
00279 buff.write(_struct_I.pack(length))
00280 for val1 in self.track.pose_resampled:
00281 _v5 = val1.position
00282 _x = _v5
00283 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00284 _v6 = val1.orientation
00285 _x = _v6
00286 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00287 length = len(self.track.pose_flags)
00288 buff.write(_struct_I.pack(length))
00289 pattern = '<%sI'%length
00290 buff.write(struct.pack(pattern, *self.track.pose_flags))
00291 length = len(self.track.channels)
00292 buff.write(_struct_I.pack(length))
00293 for val1 in self.track.channels:
00294 _x = val1.name
00295 length = len(_x)
00296 buff.write(struct.pack('<I%ss'%length, length, _x))
00297 length = len(val1.values)
00298 buff.write(_struct_I.pack(length))
00299 pattern = '<%sf'%length
00300 buff.write(struct.pack(pattern, *val1.values))
00301 except struct.error, se: self._check_types(se)
00302 except TypeError, te: self._check_types(te)
00303
00304 def deserialize(self, str):
00305 """
00306 unpack serialized message in str into this message instance
00307 @param str: byte array of serialized message
00308 @type str: str
00309 """
00310 try:
00311 if self.header is None:
00312 self.header = std_msgs.msg._Header.Header()
00313 if self.track is None:
00314 self.track = articulation_msgs.msg.TrackMsg()
00315 end = 0
00316 _x = self
00317 start = end
00318 end += 12
00319 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00320 start = end
00321 end += 4
00322 (length,) = _struct_I.unpack(str[start:end])
00323 start = end
00324 end += length
00325 self.header.frame_id = str[start:end]
00326 start = end
00327 end += 4
00328 (self.id,) = _struct_i.unpack(str[start:end])
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 start = end
00333 end += length
00334 self.name = str[start:end]
00335 start = end
00336 end += 4
00337 (length,) = _struct_I.unpack(str[start:end])
00338 self.params = []
00339 for i in xrange(0, length):
00340 val1 = articulation_msgs.msg.ParamMsg()
00341 start = end
00342 end += 4
00343 (length,) = _struct_I.unpack(str[start:end])
00344 start = end
00345 end += length
00346 val1.name = str[start:end]
00347 _x = val1
00348 start = end
00349 end += 9
00350 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00351 self.params.append(val1)
00352 _x = self
00353 start = end
00354 end += 12
00355 (_x.track.header.seq, _x.track.header.stamp.secs, _x.track.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00356 start = end
00357 end += 4
00358 (length,) = _struct_I.unpack(str[start:end])
00359 start = end
00360 end += length
00361 self.track.header.frame_id = str[start:end]
00362 start = end
00363 end += 4
00364 (self.track.id,) = _struct_i.unpack(str[start:end])
00365 start = end
00366 end += 4
00367 (length,) = _struct_I.unpack(str[start:end])
00368 self.track.pose = []
00369 for i in xrange(0, length):
00370 val1 = geometry_msgs.msg.Pose()
00371 _v7 = val1.position
00372 _x = _v7
00373 start = end
00374 end += 24
00375 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00376 _v8 = val1.orientation
00377 _x = _v8
00378 start = end
00379 end += 32
00380 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00381 self.track.pose.append(val1)
00382 start = end
00383 end += 4
00384 (length,) = _struct_I.unpack(str[start:end])
00385 self.track.pose_projected = []
00386 for i in xrange(0, length):
00387 val1 = geometry_msgs.msg.Pose()
00388 _v9 = val1.position
00389 _x = _v9
00390 start = end
00391 end += 24
00392 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00393 _v10 = val1.orientation
00394 _x = _v10
00395 start = end
00396 end += 32
00397 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00398 self.track.pose_projected.append(val1)
00399 start = end
00400 end += 4
00401 (length,) = _struct_I.unpack(str[start:end])
00402 self.track.pose_resampled = []
00403 for i in xrange(0, length):
00404 val1 = geometry_msgs.msg.Pose()
00405 _v11 = val1.position
00406 _x = _v11
00407 start = end
00408 end += 24
00409 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00410 _v12 = val1.orientation
00411 _x = _v12
00412 start = end
00413 end += 32
00414 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00415 self.track.pose_resampled.append(val1)
00416 start = end
00417 end += 4
00418 (length,) = _struct_I.unpack(str[start:end])
00419 pattern = '<%sI'%length
00420 start = end
00421 end += struct.calcsize(pattern)
00422 self.track.pose_flags = struct.unpack(pattern, str[start:end])
00423 start = end
00424 end += 4
00425 (length,) = _struct_I.unpack(str[start:end])
00426 self.track.channels = []
00427 for i in xrange(0, length):
00428 val1 = sensor_msgs.msg.ChannelFloat32()
00429 start = end
00430 end += 4
00431 (length,) = _struct_I.unpack(str[start:end])
00432 start = end
00433 end += length
00434 val1.name = str[start:end]
00435 start = end
00436 end += 4
00437 (length,) = _struct_I.unpack(str[start:end])
00438 pattern = '<%sf'%length
00439 start = end
00440 end += struct.calcsize(pattern)
00441 val1.values = struct.unpack(pattern, str[start:end])
00442 self.track.channels.append(val1)
00443 return self
00444 except struct.error, e:
00445 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00446
00447
00448 def serialize_numpy(self, buff, numpy):
00449 """
00450 serialize message with numpy array types into buffer
00451 @param buff: buffer
00452 @type buff: StringIO
00453 @param numpy: numpy python module
00454 @type numpy module
00455 """
00456 try:
00457 _x = self
00458 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00459 _x = self.header.frame_id
00460 length = len(_x)
00461 buff.write(struct.pack('<I%ss'%length, length, _x))
00462 buff.write(_struct_i.pack(self.id))
00463 _x = self.name
00464 length = len(_x)
00465 buff.write(struct.pack('<I%ss'%length, length, _x))
00466 length = len(self.params)
00467 buff.write(_struct_I.pack(length))
00468 for val1 in self.params:
00469 _x = val1.name
00470 length = len(_x)
00471 buff.write(struct.pack('<I%ss'%length, length, _x))
00472 _x = val1
00473 buff.write(_struct_dB.pack(_x.value, _x.type))
00474 _x = self
00475 buff.write(_struct_3I.pack(_x.track.header.seq, _x.track.header.stamp.secs, _x.track.header.stamp.nsecs))
00476 _x = self.track.header.frame_id
00477 length = len(_x)
00478 buff.write(struct.pack('<I%ss'%length, length, _x))
00479 buff.write(_struct_i.pack(self.track.id))
00480 length = len(self.track.pose)
00481 buff.write(_struct_I.pack(length))
00482 for val1 in self.track.pose:
00483 _v13 = val1.position
00484 _x = _v13
00485 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00486 _v14 = val1.orientation
00487 _x = _v14
00488 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00489 length = len(self.track.pose_projected)
00490 buff.write(_struct_I.pack(length))
00491 for val1 in self.track.pose_projected:
00492 _v15 = val1.position
00493 _x = _v15
00494 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00495 _v16 = val1.orientation
00496 _x = _v16
00497 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00498 length = len(self.track.pose_resampled)
00499 buff.write(_struct_I.pack(length))
00500 for val1 in self.track.pose_resampled:
00501 _v17 = val1.position
00502 _x = _v17
00503 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00504 _v18 = val1.orientation
00505 _x = _v18
00506 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00507 length = len(self.track.pose_flags)
00508 buff.write(_struct_I.pack(length))
00509 pattern = '<%sI'%length
00510 buff.write(self.track.pose_flags.tostring())
00511 length = len(self.track.channels)
00512 buff.write(_struct_I.pack(length))
00513 for val1 in self.track.channels:
00514 _x = val1.name
00515 length = len(_x)
00516 buff.write(struct.pack('<I%ss'%length, length, _x))
00517 length = len(val1.values)
00518 buff.write(_struct_I.pack(length))
00519 pattern = '<%sf'%length
00520 buff.write(val1.values.tostring())
00521 except struct.error, se: self._check_types(se)
00522 except TypeError, te: self._check_types(te)
00523
00524 def deserialize_numpy(self, str, numpy):
00525 """
00526 unpack serialized message in str into this message instance using numpy for array types
00527 @param str: byte array of serialized message
00528 @type str: str
00529 @param numpy: numpy python module
00530 @type numpy: module
00531 """
00532 try:
00533 if self.header is None:
00534 self.header = std_msgs.msg._Header.Header()
00535 if self.track is None:
00536 self.track = articulation_msgs.msg.TrackMsg()
00537 end = 0
00538 _x = self
00539 start = end
00540 end += 12
00541 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00542 start = end
00543 end += 4
00544 (length,) = _struct_I.unpack(str[start:end])
00545 start = end
00546 end += length
00547 self.header.frame_id = str[start:end]
00548 start = end
00549 end += 4
00550 (self.id,) = _struct_i.unpack(str[start:end])
00551 start = end
00552 end += 4
00553 (length,) = _struct_I.unpack(str[start:end])
00554 start = end
00555 end += length
00556 self.name = str[start:end]
00557 start = end
00558 end += 4
00559 (length,) = _struct_I.unpack(str[start:end])
00560 self.params = []
00561 for i in xrange(0, length):
00562 val1 = articulation_msgs.msg.ParamMsg()
00563 start = end
00564 end += 4
00565 (length,) = _struct_I.unpack(str[start:end])
00566 start = end
00567 end += length
00568 val1.name = str[start:end]
00569 _x = val1
00570 start = end
00571 end += 9
00572 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00573 self.params.append(val1)
00574 _x = self
00575 start = end
00576 end += 12
00577 (_x.track.header.seq, _x.track.header.stamp.secs, _x.track.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00578 start = end
00579 end += 4
00580 (length,) = _struct_I.unpack(str[start:end])
00581 start = end
00582 end += length
00583 self.track.header.frame_id = str[start:end]
00584 start = end
00585 end += 4
00586 (self.track.id,) = _struct_i.unpack(str[start:end])
00587 start = end
00588 end += 4
00589 (length,) = _struct_I.unpack(str[start:end])
00590 self.track.pose = []
00591 for i in xrange(0, length):
00592 val1 = geometry_msgs.msg.Pose()
00593 _v19 = val1.position
00594 _x = _v19
00595 start = end
00596 end += 24
00597 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00598 _v20 = val1.orientation
00599 _x = _v20
00600 start = end
00601 end += 32
00602 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00603 self.track.pose.append(val1)
00604 start = end
00605 end += 4
00606 (length,) = _struct_I.unpack(str[start:end])
00607 self.track.pose_projected = []
00608 for i in xrange(0, length):
00609 val1 = geometry_msgs.msg.Pose()
00610 _v21 = val1.position
00611 _x = _v21
00612 start = end
00613 end += 24
00614 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00615 _v22 = val1.orientation
00616 _x = _v22
00617 start = end
00618 end += 32
00619 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00620 self.track.pose_projected.append(val1)
00621 start = end
00622 end += 4
00623 (length,) = _struct_I.unpack(str[start:end])
00624 self.track.pose_resampled = []
00625 for i in xrange(0, length):
00626 val1 = geometry_msgs.msg.Pose()
00627 _v23 = val1.position
00628 _x = _v23
00629 start = end
00630 end += 24
00631 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00632 _v24 = val1.orientation
00633 _x = _v24
00634 start = end
00635 end += 32
00636 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00637 self.track.pose_resampled.append(val1)
00638 start = end
00639 end += 4
00640 (length,) = _struct_I.unpack(str[start:end])
00641 pattern = '<%sI'%length
00642 start = end
00643 end += struct.calcsize(pattern)
00644 self.track.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
00645 start = end
00646 end += 4
00647 (length,) = _struct_I.unpack(str[start:end])
00648 self.track.channels = []
00649 for i in xrange(0, length):
00650 val1 = sensor_msgs.msg.ChannelFloat32()
00651 start = end
00652 end += 4
00653 (length,) = _struct_I.unpack(str[start:end])
00654 start = end
00655 end += length
00656 val1.name = str[start:end]
00657 start = end
00658 end += 4
00659 (length,) = _struct_I.unpack(str[start:end])
00660 pattern = '<%sf'%length
00661 start = end
00662 end += struct.calcsize(pattern)
00663 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00664 self.track.channels.append(val1)
00665 return self
00666 except struct.error, e:
00667 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00668
00669 _struct_I = roslib.message.struct_I
00670 _struct_i = struct.Struct("<i")
00671 _struct_3I = struct.Struct("<3I")
00672 _struct_dB = struct.Struct("<dB")
00673 _struct_4d = struct.Struct("<4d")
00674 _struct_3d = struct.Struct("<3d")