00001 """autogenerated by genmsg_py from TrackModelSrvRequest.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 TrackModelSrvRequest(roslib.message.Message):
00011 _md5sum = "056375d531bc6dcbc8a3fedb4b45371f"
00012 _type = "articulation_msgs/TrackModelSrvRequest"
00013 _has_header = False
00014 _full_text = """
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 articulation_msgs/ModelMsg model
00026
00027
00028 ================================================================================
00029 MSG: articulation_msgs/ModelMsg
00030 # Single kinematic model
00031 #
00032 # A kinematic model is defined by its model class name, and a set of parameters.
00033 # The client may additionally specify a model id, that can be used to colorize the
00034 # model when visualized using the RVIZ model display.
00035 #
00036 # For a list of currently implemented models, see the documetation at
00037 # http://www.ros.org/wiki/articulation_models
00038 #
00039 #
00040
00041 Header header # frame and timestamp
00042
00043 int32 id # user specified model id
00044 string name # name of the model family (e.g. "rotational",
00045 # "prismatic", "pca-gp", "rigid")
00046 articulation_msgs/ParamMsg[] params # model parameters
00047 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or
00048 # that is evaluated using the model
00049
00050 ================================================================================
00051 MSG: std_msgs/Header
00052 # Standard metadata for higher-level stamped data types.
00053 # This is generally used to communicate timestamped data
00054 # in a particular coordinate frame.
00055 #
00056 # sequence ID: consecutively increasing ID
00057 uint32 seq
00058 #Two-integer timestamp that is expressed as:
00059 # * stamp.secs: seconds (stamp_secs) since epoch
00060 # * stamp.nsecs: nanoseconds since stamp_secs
00061 # time-handling sugar is provided by the client library
00062 time stamp
00063 #Frame this data is associated with
00064 # 0: no frame
00065 # 1: global frame
00066 string frame_id
00067
00068 ================================================================================
00069 MSG: articulation_msgs/ParamMsg
00070 # Single parameter passed to or from model fitting
00071 #
00072 # This mechanism allows to flexibly pass parameters to
00073 # model fitting (and vice versa). Note that these parameters
00074 # are model-specific: A client may supply additional
00075 # parameters to the model estimator, and, similarly, a estimator
00076 # may add the estimated model parameters to the model message.
00077 # When the model is then evaluated, for example to make predictions
00078 # or to compute the likelihood, the model class can then use
00079 # these parameters.
00080 #
00081 # A parameter has a name, a value, and a type. The type globally
00082 # indicates whether it is a prior parameter (prior to model fitting),
00083 # or a model parameter (found during model fitting, using a maximum-
00084 # likelihood estimator), or a cached evaluation (e.g., the likelihood
00085 # or the BIC are a typical "side"-product of model estimation, and
00086 # can therefore already be cached).
00087 #
00088 # For a list of currently used parameters, see the documentation at
00089 # http://www.ros.org/wiki/articulation_models
00090 #
00091
00092 uint8 PRIOR=0 # indicates a prior model parameter
00093 # (e.g., "sigma_position")
00094 uint8 PARAM=1 # indicates a estimated model parameter
00095 # (e.g., "rot_radius", the estimated radius)
00096 uint8 EVAL=2 # indicates a cached evaluation of the model, given
00097 # the current trajectory
00098 # (e.g., "loglikelihood", the log likelihood of the
00099 # data, given the model and its parameters)
00100
00101 string name # name of the parameter
00102 float64 value # value of the parameter
00103 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)
00104
00105
00106 ================================================================================
00107 MSG: articulation_msgs/TrackMsg
00108 # Single kinematic trajectory
00109 #
00110 # This message contains a kinematic trajectory. The trajectory is specified
00111 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00112 # the track is valid, and whether it includes orientation. The track id
00113 # can be used for automatic coloring in the RVIZ track plugin, and can be
00114 # freely chosen by the client.
00115 #
00116 # A model is fitting only from the trajectory stored in the pose[]-vector.
00117 # Additional information may be associated to each pose using the channels
00118 # vector, with arbitrary # fields (e.g., to include applied/measured forces).
00119 #
00120 # After model evaluation,
00121 # also the associated configurations of the object are stored in the channels,
00122 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00123 # Model evaluation also projects the poses in the pose vector onto the model,
00124 # and stores these ideal poses in the vector pose_projected. Further, during model
00125 # evaluation, a new set of (uniform) configurations over the valid configuration
00126 # range is sampled, and the result is stored in pose_resampled.
00127 # The vector pose_flags contains additional display flags for the poses in the
00128 # pose vector, for example, whether a pose is visible and/or
00129 # the end of a trajectory segment. At the moment, this is only used by the
00130 # prior_model_learner.
00131 #
00132
00133 Header header # Timestamp and frame
00134 int32 id # used-specified track id
00135
00136 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory
00137 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model
00138 # (after model evaluation)
00139 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in
00140 # the valid configuration range
00141 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00142
00143 uint32 POSE_VISIBLE=1
00144 uint32 POSE_END_OF_SEGMENT=2
00145
00146 # Each channel should have the same number of elements as pose array,
00147 # and the data in each channel should correspond 1:1 with each pose
00148 # possible channels: "width", "height", "rgb", ...
00149 sensor_msgs/ChannelFloat32[] channels
00150
00151
00152
00153 ================================================================================
00154 MSG: geometry_msgs/Pose
00155 # A representation of pose in free space, composed of postion and orientation.
00156 Point position
00157 Quaternion orientation
00158
00159 ================================================================================
00160 MSG: geometry_msgs/Point
00161 # This contains the position of a point in free space
00162 float64 x
00163 float64 y
00164 float64 z
00165
00166 ================================================================================
00167 MSG: geometry_msgs/Quaternion
00168 # This represents an orientation in free space in quaternion form.
00169
00170 float64 x
00171 float64 y
00172 float64 z
00173 float64 w
00174
00175 ================================================================================
00176 MSG: sensor_msgs/ChannelFloat32
00177 # This message is used by the PointCloud message to hold optional data
00178 # associated with each point in the cloud. The length of the values
00179 # array should be the same as the length of the points array in the
00180 # PointCloud, and each value should be associated with the corresponding
00181 # point.
00182
00183 # Channel names in existing practice include:
00184 # "u", "v" - row and column (respectively) in the left stereo image.
00185 # This is opposite to usual conventions but remains for
00186 # historical reasons. The newer PointCloud2 message has no
00187 # such problem.
00188 # "rgb" - For point clouds produced by color stereo cameras. uint8
00189 # (R,G,B) values packed into the least significant 24 bits,
00190 # in order.
00191 # "intensity" - laser or pixel intensity.
00192 # "distance"
00193
00194 # The channel name should give semantics of the channel (e.g.
00195 # "intensity" instead of "value").
00196 string name
00197
00198 # The values array should be 1-1 with the elements of the associated
00199 # PointCloud.
00200 float32[] values
00201
00202 """
00203 __slots__ = ['model']
00204 _slot_types = ['articulation_msgs/ModelMsg']
00205
00206 def __init__(self, *args, **kwds):
00207 """
00208 Constructor. Any message fields that are implicitly/explicitly
00209 set to None will be assigned a default value. The recommend
00210 use is keyword arguments as this is more robust to future message
00211 changes. You cannot mix in-order arguments and keyword arguments.
00212
00213 The available fields are:
00214 model
00215
00216 @param args: complete set of field values, in .msg order
00217 @param kwds: use keyword arguments corresponding to message field names
00218 to set specific fields.
00219 """
00220 if args or kwds:
00221 super(TrackModelSrvRequest, self).__init__(*args, **kwds)
00222 #message fields cannot be None, assign default values for those that are
00223 if self.model is None:
00224 self.model = articulation_msgs.msg.ModelMsg()
00225 else:
00226 self.model = articulation_msgs.msg.ModelMsg()
00227
00228 def _get_types(self):
00229 """
00230 internal API method
00231 """
00232 return self._slot_types
00233
00234 def serialize(self, buff):
00235 """
00236 serialize message into buffer
00237 @param buff: buffer
00238 @type buff: StringIO
00239 """
00240 try:
00241 _x = self
00242 buff.write(_struct_3I.pack(_x.model.header.seq, _x.model.header.stamp.secs, _x.model.header.stamp.nsecs))
00243 _x = self.model.header.frame_id
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 buff.write(_struct_i.pack(self.model.id))
00247 _x = self.model.name
00248 length = len(_x)
00249 buff.write(struct.pack('<I%ss'%length, length, _x))
00250 length = len(self.model.params)
00251 buff.write(_struct_I.pack(length))
00252 for val1 in self.model.params:
00253 _x = val1.name
00254 length = len(_x)
00255 buff.write(struct.pack('<I%ss'%length, length, _x))
00256 _x = val1
00257 buff.write(_struct_dB.pack(_x.value, _x.type))
00258 _x = self
00259 buff.write(_struct_3I.pack(_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.track.header.stamp.nsecs))
00260 _x = self.model.track.header.frame_id
00261 length = len(_x)
00262 buff.write(struct.pack('<I%ss'%length, length, _x))
00263 buff.write(_struct_i.pack(self.model.track.id))
00264 length = len(self.model.track.pose)
00265 buff.write(_struct_I.pack(length))
00266 for val1 in self.model.track.pose:
00267 _v1 = val1.position
00268 _x = _v1
00269 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00270 _v2 = val1.orientation
00271 _x = _v2
00272 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00273 length = len(self.model.track.pose_projected)
00274 buff.write(_struct_I.pack(length))
00275 for val1 in self.model.track.pose_projected:
00276 _v3 = val1.position
00277 _x = _v3
00278 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00279 _v4 = val1.orientation
00280 _x = _v4
00281 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00282 length = len(self.model.track.pose_resampled)
00283 buff.write(_struct_I.pack(length))
00284 for val1 in self.model.track.pose_resampled:
00285 _v5 = val1.position
00286 _x = _v5
00287 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00288 _v6 = val1.orientation
00289 _x = _v6
00290 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00291 length = len(self.model.track.pose_flags)
00292 buff.write(_struct_I.pack(length))
00293 pattern = '<%sI'%length
00294 buff.write(struct.pack(pattern, *self.model.track.pose_flags))
00295 length = len(self.model.track.channels)
00296 buff.write(_struct_I.pack(length))
00297 for val1 in self.model.track.channels:
00298 _x = val1.name
00299 length = len(_x)
00300 buff.write(struct.pack('<I%ss'%length, length, _x))
00301 length = len(val1.values)
00302 buff.write(_struct_I.pack(length))
00303 pattern = '<%sf'%length
00304 buff.write(struct.pack(pattern, *val1.values))
00305 except struct.error, se: self._check_types(se)
00306 except TypeError, te: self._check_types(te)
00307
00308 def deserialize(self, str):
00309 """
00310 unpack serialized message in str into this message instance
00311 @param str: byte array of serialized message
00312 @type str: str
00313 """
00314 try:
00315 if self.model is None:
00316 self.model = articulation_msgs.msg.ModelMsg()
00317 end = 0
00318 _x = self
00319 start = end
00320 end += 12
00321 (_x.model.header.seq, _x.model.header.stamp.secs, _x.model.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00322 start = end
00323 end += 4
00324 (length,) = _struct_I.unpack(str[start:end])
00325 start = end
00326 end += length
00327 self.model.header.frame_id = str[start:end]
00328 start = end
00329 end += 4
00330 (self.model.id,) = _struct_i.unpack(str[start:end])
00331 start = end
00332 end += 4
00333 (length,) = _struct_I.unpack(str[start:end])
00334 start = end
00335 end += length
00336 self.model.name = str[start:end]
00337 start = end
00338 end += 4
00339 (length,) = _struct_I.unpack(str[start:end])
00340 self.model.params = []
00341 for i in xrange(0, length):
00342 val1 = articulation_msgs.msg.ParamMsg()
00343 start = end
00344 end += 4
00345 (length,) = _struct_I.unpack(str[start:end])
00346 start = end
00347 end += length
00348 val1.name = str[start:end]
00349 _x = val1
00350 start = end
00351 end += 9
00352 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00353 self.model.params.append(val1)
00354 _x = self
00355 start = end
00356 end += 12
00357 (_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.track.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00358 start = end
00359 end += 4
00360 (length,) = _struct_I.unpack(str[start:end])
00361 start = end
00362 end += length
00363 self.model.track.header.frame_id = str[start:end]
00364 start = end
00365 end += 4
00366 (self.model.track.id,) = _struct_i.unpack(str[start:end])
00367 start = end
00368 end += 4
00369 (length,) = _struct_I.unpack(str[start:end])
00370 self.model.track.pose = []
00371 for i in xrange(0, length):
00372 val1 = geometry_msgs.msg.Pose()
00373 _v7 = val1.position
00374 _x = _v7
00375 start = end
00376 end += 24
00377 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00378 _v8 = val1.orientation
00379 _x = _v8
00380 start = end
00381 end += 32
00382 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00383 self.model.track.pose.append(val1)
00384 start = end
00385 end += 4
00386 (length,) = _struct_I.unpack(str[start:end])
00387 self.model.track.pose_projected = []
00388 for i in xrange(0, length):
00389 val1 = geometry_msgs.msg.Pose()
00390 _v9 = val1.position
00391 _x = _v9
00392 start = end
00393 end += 24
00394 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00395 _v10 = val1.orientation
00396 _x = _v10
00397 start = end
00398 end += 32
00399 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00400 self.model.track.pose_projected.append(val1)
00401 start = end
00402 end += 4
00403 (length,) = _struct_I.unpack(str[start:end])
00404 self.model.track.pose_resampled = []
00405 for i in xrange(0, length):
00406 val1 = geometry_msgs.msg.Pose()
00407 _v11 = val1.position
00408 _x = _v11
00409 start = end
00410 end += 24
00411 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00412 _v12 = val1.orientation
00413 _x = _v12
00414 start = end
00415 end += 32
00416 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00417 self.model.track.pose_resampled.append(val1)
00418 start = end
00419 end += 4
00420 (length,) = _struct_I.unpack(str[start:end])
00421 pattern = '<%sI'%length
00422 start = end
00423 end += struct.calcsize(pattern)
00424 self.model.track.pose_flags = struct.unpack(pattern, str[start:end])
00425 start = end
00426 end += 4
00427 (length,) = _struct_I.unpack(str[start:end])
00428 self.model.track.channels = []
00429 for i in xrange(0, length):
00430 val1 = sensor_msgs.msg.ChannelFloat32()
00431 start = end
00432 end += 4
00433 (length,) = _struct_I.unpack(str[start:end])
00434 start = end
00435 end += length
00436 val1.name = str[start:end]
00437 start = end
00438 end += 4
00439 (length,) = _struct_I.unpack(str[start:end])
00440 pattern = '<%sf'%length
00441 start = end
00442 end += struct.calcsize(pattern)
00443 val1.values = struct.unpack(pattern, str[start:end])
00444 self.model.track.channels.append(val1)
00445 return self
00446 except struct.error, e:
00447 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00448
00449
00450 def serialize_numpy(self, buff, numpy):
00451 """
00452 serialize message with numpy array types into buffer
00453 @param buff: buffer
00454 @type buff: StringIO
00455 @param numpy: numpy python module
00456 @type numpy module
00457 """
00458 try:
00459 _x = self
00460 buff.write(_struct_3I.pack(_x.model.header.seq, _x.model.header.stamp.secs, _x.model.header.stamp.nsecs))
00461 _x = self.model.header.frame_id
00462 length = len(_x)
00463 buff.write(struct.pack('<I%ss'%length, length, _x))
00464 buff.write(_struct_i.pack(self.model.id))
00465 _x = self.model.name
00466 length = len(_x)
00467 buff.write(struct.pack('<I%ss'%length, length, _x))
00468 length = len(self.model.params)
00469 buff.write(_struct_I.pack(length))
00470 for val1 in self.model.params:
00471 _x = val1.name
00472 length = len(_x)
00473 buff.write(struct.pack('<I%ss'%length, length, _x))
00474 _x = val1
00475 buff.write(_struct_dB.pack(_x.value, _x.type))
00476 _x = self
00477 buff.write(_struct_3I.pack(_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.track.header.stamp.nsecs))
00478 _x = self.model.track.header.frame_id
00479 length = len(_x)
00480 buff.write(struct.pack('<I%ss'%length, length, _x))
00481 buff.write(_struct_i.pack(self.model.track.id))
00482 length = len(self.model.track.pose)
00483 buff.write(_struct_I.pack(length))
00484 for val1 in self.model.track.pose:
00485 _v13 = val1.position
00486 _x = _v13
00487 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00488 _v14 = val1.orientation
00489 _x = _v14
00490 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00491 length = len(self.model.track.pose_projected)
00492 buff.write(_struct_I.pack(length))
00493 for val1 in self.model.track.pose_projected:
00494 _v15 = val1.position
00495 _x = _v15
00496 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00497 _v16 = val1.orientation
00498 _x = _v16
00499 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00500 length = len(self.model.track.pose_resampled)
00501 buff.write(_struct_I.pack(length))
00502 for val1 in self.model.track.pose_resampled:
00503 _v17 = val1.position
00504 _x = _v17
00505 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00506 _v18 = val1.orientation
00507 _x = _v18
00508 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00509 length = len(self.model.track.pose_flags)
00510 buff.write(_struct_I.pack(length))
00511 pattern = '<%sI'%length
00512 buff.write(self.model.track.pose_flags.tostring())
00513 length = len(self.model.track.channels)
00514 buff.write(_struct_I.pack(length))
00515 for val1 in self.model.track.channels:
00516 _x = val1.name
00517 length = len(_x)
00518 buff.write(struct.pack('<I%ss'%length, length, _x))
00519 length = len(val1.values)
00520 buff.write(_struct_I.pack(length))
00521 pattern = '<%sf'%length
00522 buff.write(val1.values.tostring())
00523 except struct.error, se: self._check_types(se)
00524 except TypeError, te: self._check_types(te)
00525
00526 def deserialize_numpy(self, str, numpy):
00527 """
00528 unpack serialized message in str into this message instance using numpy for array types
00529 @param str: byte array of serialized message
00530 @type str: str
00531 @param numpy: numpy python module
00532 @type numpy: module
00533 """
00534 try:
00535 if self.model is None:
00536 self.model = articulation_msgs.msg.ModelMsg()
00537 end = 0
00538 _x = self
00539 start = end
00540 end += 12
00541 (_x.model.header.seq, _x.model.header.stamp.secs, _x.model.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.model.header.frame_id = str[start:end]
00548 start = end
00549 end += 4
00550 (self.model.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.model.name = str[start:end]
00557 start = end
00558 end += 4
00559 (length,) = _struct_I.unpack(str[start:end])
00560 self.model.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.model.params.append(val1)
00574 _x = self
00575 start = end
00576 end += 12
00577 (_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.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.model.track.header.frame_id = str[start:end]
00584 start = end
00585 end += 4
00586 (self.model.track.id,) = _struct_i.unpack(str[start:end])
00587 start = end
00588 end += 4
00589 (length,) = _struct_I.unpack(str[start:end])
00590 self.model.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.model.track.pose.append(val1)
00604 start = end
00605 end += 4
00606 (length,) = _struct_I.unpack(str[start:end])
00607 self.model.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.model.track.pose_projected.append(val1)
00621 start = end
00622 end += 4
00623 (length,) = _struct_I.unpack(str[start:end])
00624 self.model.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.model.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.model.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.model.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.model.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")
00675 """autogenerated by genmsg_py from TrackModelSrvResponse.msg. Do not edit."""
00676 import roslib.message
00677 import struct
00678
00679 import sensor_msgs.msg
00680 import geometry_msgs.msg
00681 import articulation_msgs.msg
00682 import std_msgs.msg
00683
00684 class TrackModelSrvResponse(roslib.message.Message):
00685 _md5sum = "056375d531bc6dcbc8a3fedb4b45371f"
00686 _type = "articulation_msgs/TrackModelSrvResponse"
00687 _has_header = False #flag to mark the presence of a Header object
00688 _full_text = """articulation_msgs/ModelMsg model
00689
00690
00691
00692
00693
00694
00695 ================================================================================
00696 MSG: articulation_msgs/ModelMsg
00697 # Single kinematic model
00698 #
00699 # A kinematic model is defined by its model class name, and a set of parameters.
00700 # The client may additionally specify a model id, that can be used to colorize the
00701 # model when visualized using the RVIZ model display.
00702 #
00703 # For a list of currently implemented models, see the documetation at
00704 # http://www.ros.org/wiki/articulation_models
00705 #
00706 #
00707
00708 Header header # frame and timestamp
00709
00710 int32 id # user specified model id
00711 string name # name of the model family (e.g. "rotational",
00712 # "prismatic", "pca-gp", "rigid")
00713 articulation_msgs/ParamMsg[] params # model parameters
00714 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or
00715 # that is evaluated using the model
00716
00717 ================================================================================
00718 MSG: std_msgs/Header
00719 # Standard metadata for higher-level stamped data types.
00720 # This is generally used to communicate timestamped data
00721 # in a particular coordinate frame.
00722 #
00723 # sequence ID: consecutively increasing ID
00724 uint32 seq
00725 #Two-integer timestamp that is expressed as:
00726 # * stamp.secs: seconds (stamp_secs) since epoch
00727 # * stamp.nsecs: nanoseconds since stamp_secs
00728 # time-handling sugar is provided by the client library
00729 time stamp
00730 #Frame this data is associated with
00731 # 0: no frame
00732 # 1: global frame
00733 string frame_id
00734
00735 ================================================================================
00736 MSG: articulation_msgs/ParamMsg
00737 # Single parameter passed to or from model fitting
00738 #
00739 # This mechanism allows to flexibly pass parameters to
00740 # model fitting (and vice versa). Note that these parameters
00741 # are model-specific: A client may supply additional
00742 # parameters to the model estimator, and, similarly, a estimator
00743 # may add the estimated model parameters to the model message.
00744 # When the model is then evaluated, for example to make predictions
00745 # or to compute the likelihood, the model class can then use
00746 # these parameters.
00747 #
00748 # A parameter has a name, a value, and a type. The type globally
00749 # indicates whether it is a prior parameter (prior to model fitting),
00750 # or a model parameter (found during model fitting, using a maximum-
00751 # likelihood estimator), or a cached evaluation (e.g., the likelihood
00752 # or the BIC are a typical "side"-product of model estimation, and
00753 # can therefore already be cached).
00754 #
00755 # For a list of currently used parameters, see the documentation at
00756 # http://www.ros.org/wiki/articulation_models
00757 #
00758
00759 uint8 PRIOR=0 # indicates a prior model parameter
00760 # (e.g., "sigma_position")
00761 uint8 PARAM=1 # indicates a estimated model parameter
00762 # (e.g., "rot_radius", the estimated radius)
00763 uint8 EVAL=2 # indicates a cached evaluation of the model, given
00764 # the current trajectory
00765 # (e.g., "loglikelihood", the log likelihood of the
00766 # data, given the model and its parameters)
00767
00768 string name # name of the parameter
00769 float64 value # value of the parameter
00770 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)
00771
00772
00773 ================================================================================
00774 MSG: articulation_msgs/TrackMsg
00775 # Single kinematic trajectory
00776 #
00777 # This message contains a kinematic trajectory. The trajectory is specified
00778 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00779 # the track is valid, and whether it includes orientation. The track id
00780 # can be used for automatic coloring in the RVIZ track plugin, and can be
00781 # freely chosen by the client.
00782 #
00783 # A model is fitting only from the trajectory stored in the pose[]-vector.
00784 # Additional information may be associated to each pose using the channels
00785 # vector, with arbitrary # fields (e.g., to include applied/measured forces).
00786 #
00787 # After model evaluation,
00788 # also the associated configurations of the object are stored in the channels,
00789 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00790 # Model evaluation also projects the poses in the pose vector onto the model,
00791 # and stores these ideal poses in the vector pose_projected. Further, during model
00792 # evaluation, a new set of (uniform) configurations over the valid configuration
00793 # range is sampled, and the result is stored in pose_resampled.
00794 # The vector pose_flags contains additional display flags for the poses in the
00795 # pose vector, for example, whether a pose is visible and/or
00796 # the end of a trajectory segment. At the moment, this is only used by the
00797 # prior_model_learner.
00798 #
00799
00800 Header header # Timestamp and frame
00801 int32 id # used-specified track id
00802
00803 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory
00804 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model
00805 # (after model evaluation)
00806 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in
00807 # the valid configuration range
00808 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00809
00810 uint32 POSE_VISIBLE=1
00811 uint32 POSE_END_OF_SEGMENT=2
00812
00813 # Each channel should have the same number of elements as pose array,
00814 # and the data in each channel should correspond 1:1 with each pose
00815 # possible channels: "width", "height", "rgb", ...
00816 sensor_msgs/ChannelFloat32[] channels
00817
00818
00819
00820 ================================================================================
00821 MSG: geometry_msgs/Pose
00822 # A representation of pose in free space, composed of postion and orientation.
00823 Point position
00824 Quaternion orientation
00825
00826 ================================================================================
00827 MSG: geometry_msgs/Point
00828 # This contains the position of a point in free space
00829 float64 x
00830 float64 y
00831 float64 z
00832
00833 ================================================================================
00834 MSG: geometry_msgs/Quaternion
00835 # This represents an orientation in free space in quaternion form.
00836
00837 float64 x
00838 float64 y
00839 float64 z
00840 float64 w
00841
00842 ================================================================================
00843 MSG: sensor_msgs/ChannelFloat32
00844 # This message is used by the PointCloud message to hold optional data
00845 # associated with each point in the cloud. The length of the values
00846 # array should be the same as the length of the points array in the
00847 # PointCloud, and each value should be associated with the corresponding
00848 # point.
00849
00850 # Channel names in existing practice include:
00851 # "u", "v" - row and column (respectively) in the left stereo image.
00852 # This is opposite to usual conventions but remains for
00853 # historical reasons. The newer PointCloud2 message has no
00854 # such problem.
00855 # "rgb" - For point clouds produced by color stereo cameras. uint8
00856 # (R,G,B) values packed into the least significant 24 bits,
00857 # in order.
00858 # "intensity" - laser or pixel intensity.
00859 # "distance"
00860
00861 # The channel name should give semantics of the channel (e.g.
00862 # "intensity" instead of "value").
00863 string name
00864
00865 # The values array should be 1-1 with the elements of the associated
00866 # PointCloud.
00867 float32[] values
00868
00869 """
00870 __slots__ = ['model']
00871 _slot_types = ['articulation_msgs/ModelMsg']
00872
00873 def __init__(self, *args, **kwds):
00874 """
00875 Constructor. Any message fields that are implicitly/explicitly
00876 set to None will be assigned a default value. The recommend
00877 use is keyword arguments as this is more robust to future message
00878 changes. You cannot mix in-order arguments and keyword arguments.
00879
00880 The available fields are:
00881 model
00882
00883 @param args: complete set of field values, in .msg order
00884 @param kwds: use keyword arguments corresponding to message field names
00885 to set specific fields.
00886 """
00887 if args or kwds:
00888 super(TrackModelSrvResponse, self).__init__(*args, **kwds)
00889 #message fields cannot be None, assign default values for those that are
00890 if self.model is None:
00891 self.model = articulation_msgs.msg.ModelMsg()
00892 else:
00893 self.model = articulation_msgs.msg.ModelMsg()
00894
00895 def _get_types(self):
00896 """
00897 internal API method
00898 """
00899 return self._slot_types
00900
00901 def serialize(self, buff):
00902 """
00903 serialize message into buffer
00904 @param buff: buffer
00905 @type buff: StringIO
00906 """
00907 try:
00908 _x = self
00909 buff.write(_struct_3I.pack(_x.model.header.seq, _x.model.header.stamp.secs, _x.model.header.stamp.nsecs))
00910 _x = self.model.header.frame_id
00911 length = len(_x)
00912 buff.write(struct.pack('<I%ss'%length, length, _x))
00913 buff.write(_struct_i.pack(self.model.id))
00914 _x = self.model.name
00915 length = len(_x)
00916 buff.write(struct.pack('<I%ss'%length, length, _x))
00917 length = len(self.model.params)
00918 buff.write(_struct_I.pack(length))
00919 for val1 in self.model.params:
00920 _x = val1.name
00921 length = len(_x)
00922 buff.write(struct.pack('<I%ss'%length, length, _x))
00923 _x = val1
00924 buff.write(_struct_dB.pack(_x.value, _x.type))
00925 _x = self
00926 buff.write(_struct_3I.pack(_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.track.header.stamp.nsecs))
00927 _x = self.model.track.header.frame_id
00928 length = len(_x)
00929 buff.write(struct.pack('<I%ss'%length, length, _x))
00930 buff.write(_struct_i.pack(self.model.track.id))
00931 length = len(self.model.track.pose)
00932 buff.write(_struct_I.pack(length))
00933 for val1 in self.model.track.pose:
00934 _v25 = val1.position
00935 _x = _v25
00936 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00937 _v26 = val1.orientation
00938 _x = _v26
00939 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00940 length = len(self.model.track.pose_projected)
00941 buff.write(_struct_I.pack(length))
00942 for val1 in self.model.track.pose_projected:
00943 _v27 = val1.position
00944 _x = _v27
00945 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00946 _v28 = val1.orientation
00947 _x = _v28
00948 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00949 length = len(self.model.track.pose_resampled)
00950 buff.write(_struct_I.pack(length))
00951 for val1 in self.model.track.pose_resampled:
00952 _v29 = val1.position
00953 _x = _v29
00954 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00955 _v30 = val1.orientation
00956 _x = _v30
00957 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00958 length = len(self.model.track.pose_flags)
00959 buff.write(_struct_I.pack(length))
00960 pattern = '<%sI'%length
00961 buff.write(struct.pack(pattern, *self.model.track.pose_flags))
00962 length = len(self.model.track.channels)
00963 buff.write(_struct_I.pack(length))
00964 for val1 in self.model.track.channels:
00965 _x = val1.name
00966 length = len(_x)
00967 buff.write(struct.pack('<I%ss'%length, length, _x))
00968 length = len(val1.values)
00969 buff.write(_struct_I.pack(length))
00970 pattern = '<%sf'%length
00971 buff.write(struct.pack(pattern, *val1.values))
00972 except struct.error, se: self._check_types(se)
00973 except TypeError, te: self._check_types(te)
00974
00975 def deserialize(self, str):
00976 """
00977 unpack serialized message in str into this message instance
00978 @param str: byte array of serialized message
00979 @type str: str
00980 """
00981 try:
00982 if self.model is None:
00983 self.model = articulation_msgs.msg.ModelMsg()
00984 end = 0
00985 _x = self
00986 start = end
00987 end += 12
00988 (_x.model.header.seq, _x.model.header.stamp.secs, _x.model.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00989 start = end
00990 end += 4
00991 (length,) = _struct_I.unpack(str[start:end])
00992 start = end
00993 end += length
00994 self.model.header.frame_id = str[start:end]
00995 start = end
00996 end += 4
00997 (self.model.id,) = _struct_i.unpack(str[start:end])
00998 start = end
00999 end += 4
01000 (length,) = _struct_I.unpack(str[start:end])
01001 start = end
01002 end += length
01003 self.model.name = str[start:end]
01004 start = end
01005 end += 4
01006 (length,) = _struct_I.unpack(str[start:end])
01007 self.model.params = []
01008 for i in xrange(0, length):
01009 val1 = articulation_msgs.msg.ParamMsg()
01010 start = end
01011 end += 4
01012 (length,) = _struct_I.unpack(str[start:end])
01013 start = end
01014 end += length
01015 val1.name = str[start:end]
01016 _x = val1
01017 start = end
01018 end += 9
01019 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
01020 self.model.params.append(val1)
01021 _x = self
01022 start = end
01023 end += 12
01024 (_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.track.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01025 start = end
01026 end += 4
01027 (length,) = _struct_I.unpack(str[start:end])
01028 start = end
01029 end += length
01030 self.model.track.header.frame_id = str[start:end]
01031 start = end
01032 end += 4
01033 (self.model.track.id,) = _struct_i.unpack(str[start:end])
01034 start = end
01035 end += 4
01036 (length,) = _struct_I.unpack(str[start:end])
01037 self.model.track.pose = []
01038 for i in xrange(0, length):
01039 val1 = geometry_msgs.msg.Pose()
01040 _v31 = val1.position
01041 _x = _v31
01042 start = end
01043 end += 24
01044 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01045 _v32 = val1.orientation
01046 _x = _v32
01047 start = end
01048 end += 32
01049 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01050 self.model.track.pose.append(val1)
01051 start = end
01052 end += 4
01053 (length,) = _struct_I.unpack(str[start:end])
01054 self.model.track.pose_projected = []
01055 for i in xrange(0, length):
01056 val1 = geometry_msgs.msg.Pose()
01057 _v33 = val1.position
01058 _x = _v33
01059 start = end
01060 end += 24
01061 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01062 _v34 = val1.orientation
01063 _x = _v34
01064 start = end
01065 end += 32
01066 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01067 self.model.track.pose_projected.append(val1)
01068 start = end
01069 end += 4
01070 (length,) = _struct_I.unpack(str[start:end])
01071 self.model.track.pose_resampled = []
01072 for i in xrange(0, length):
01073 val1 = geometry_msgs.msg.Pose()
01074 _v35 = val1.position
01075 _x = _v35
01076 start = end
01077 end += 24
01078 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01079 _v36 = val1.orientation
01080 _x = _v36
01081 start = end
01082 end += 32
01083 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01084 self.model.track.pose_resampled.append(val1)
01085 start = end
01086 end += 4
01087 (length,) = _struct_I.unpack(str[start:end])
01088 pattern = '<%sI'%length
01089 start = end
01090 end += struct.calcsize(pattern)
01091 self.model.track.pose_flags = struct.unpack(pattern, str[start:end])
01092 start = end
01093 end += 4
01094 (length,) = _struct_I.unpack(str[start:end])
01095 self.model.track.channels = []
01096 for i in xrange(0, length):
01097 val1 = sensor_msgs.msg.ChannelFloat32()
01098 start = end
01099 end += 4
01100 (length,) = _struct_I.unpack(str[start:end])
01101 start = end
01102 end += length
01103 val1.name = str[start:end]
01104 start = end
01105 end += 4
01106 (length,) = _struct_I.unpack(str[start:end])
01107 pattern = '<%sf'%length
01108 start = end
01109 end += struct.calcsize(pattern)
01110 val1.values = struct.unpack(pattern, str[start:end])
01111 self.model.track.channels.append(val1)
01112 return self
01113 except struct.error, e:
01114 raise roslib.message.DeserializationError(e) #most likely buffer underfill
01115
01116
01117 def serialize_numpy(self, buff, numpy):
01118 """
01119 serialize message with numpy array types into buffer
01120 @param buff: buffer
01121 @type buff: StringIO
01122 @param numpy: numpy python module
01123 @type numpy module
01124 """
01125 try:
01126 _x = self
01127 buff.write(_struct_3I.pack(_x.model.header.seq, _x.model.header.stamp.secs, _x.model.header.stamp.nsecs))
01128 _x = self.model.header.frame_id
01129 length = len(_x)
01130 buff.write(struct.pack('<I%ss'%length, length, _x))
01131 buff.write(_struct_i.pack(self.model.id))
01132 _x = self.model.name
01133 length = len(_x)
01134 buff.write(struct.pack('<I%ss'%length, length, _x))
01135 length = len(self.model.params)
01136 buff.write(_struct_I.pack(length))
01137 for val1 in self.model.params:
01138 _x = val1.name
01139 length = len(_x)
01140 buff.write(struct.pack('<I%ss'%length, length, _x))
01141 _x = val1
01142 buff.write(_struct_dB.pack(_x.value, _x.type))
01143 _x = self
01144 buff.write(_struct_3I.pack(_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.track.header.stamp.nsecs))
01145 _x = self.model.track.header.frame_id
01146 length = len(_x)
01147 buff.write(struct.pack('<I%ss'%length, length, _x))
01148 buff.write(_struct_i.pack(self.model.track.id))
01149 length = len(self.model.track.pose)
01150 buff.write(_struct_I.pack(length))
01151 for val1 in self.model.track.pose:
01152 _v37 = val1.position
01153 _x = _v37
01154 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01155 _v38 = val1.orientation
01156 _x = _v38
01157 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01158 length = len(self.model.track.pose_projected)
01159 buff.write(_struct_I.pack(length))
01160 for val1 in self.model.track.pose_projected:
01161 _v39 = val1.position
01162 _x = _v39
01163 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01164 _v40 = val1.orientation
01165 _x = _v40
01166 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01167 length = len(self.model.track.pose_resampled)
01168 buff.write(_struct_I.pack(length))
01169 for val1 in self.model.track.pose_resampled:
01170 _v41 = val1.position
01171 _x = _v41
01172 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01173 _v42 = val1.orientation
01174 _x = _v42
01175 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01176 length = len(self.model.track.pose_flags)
01177 buff.write(_struct_I.pack(length))
01178 pattern = '<%sI'%length
01179 buff.write(self.model.track.pose_flags.tostring())
01180 length = len(self.model.track.channels)
01181 buff.write(_struct_I.pack(length))
01182 for val1 in self.model.track.channels:
01183 _x = val1.name
01184 length = len(_x)
01185 buff.write(struct.pack('<I%ss'%length, length, _x))
01186 length = len(val1.values)
01187 buff.write(_struct_I.pack(length))
01188 pattern = '<%sf'%length
01189 buff.write(val1.values.tostring())
01190 except struct.error, se: self._check_types(se)
01191 except TypeError, te: self._check_types(te)
01192
01193 def deserialize_numpy(self, str, numpy):
01194 """
01195 unpack serialized message in str into this message instance using numpy for array types
01196 @param str: byte array of serialized message
01197 @type str: str
01198 @param numpy: numpy python module
01199 @type numpy: module
01200 """
01201 try:
01202 if self.model is None:
01203 self.model = articulation_msgs.msg.ModelMsg()
01204 end = 0
01205 _x = self
01206 start = end
01207 end += 12
01208 (_x.model.header.seq, _x.model.header.stamp.secs, _x.model.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01209 start = end
01210 end += 4
01211 (length,) = _struct_I.unpack(str[start:end])
01212 start = end
01213 end += length
01214 self.model.header.frame_id = str[start:end]
01215 start = end
01216 end += 4
01217 (self.model.id,) = _struct_i.unpack(str[start:end])
01218 start = end
01219 end += 4
01220 (length,) = _struct_I.unpack(str[start:end])
01221 start = end
01222 end += length
01223 self.model.name = str[start:end]
01224 start = end
01225 end += 4
01226 (length,) = _struct_I.unpack(str[start:end])
01227 self.model.params = []
01228 for i in xrange(0, length):
01229 val1 = articulation_msgs.msg.ParamMsg()
01230 start = end
01231 end += 4
01232 (length,) = _struct_I.unpack(str[start:end])
01233 start = end
01234 end += length
01235 val1.name = str[start:end]
01236 _x = val1
01237 start = end
01238 end += 9
01239 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
01240 self.model.params.append(val1)
01241 _x = self
01242 start = end
01243 end += 12
01244 (_x.model.track.header.seq, _x.model.track.header.stamp.secs, _x.model.track.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01245 start = end
01246 end += 4
01247 (length,) = _struct_I.unpack(str[start:end])
01248 start = end
01249 end += length
01250 self.model.track.header.frame_id = str[start:end]
01251 start = end
01252 end += 4
01253 (self.model.track.id,) = _struct_i.unpack(str[start:end])
01254 start = end
01255 end += 4
01256 (length,) = _struct_I.unpack(str[start:end])
01257 self.model.track.pose = []
01258 for i in xrange(0, length):
01259 val1 = geometry_msgs.msg.Pose()
01260 _v43 = val1.position
01261 _x = _v43
01262 start = end
01263 end += 24
01264 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01265 _v44 = val1.orientation
01266 _x = _v44
01267 start = end
01268 end += 32
01269 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01270 self.model.track.pose.append(val1)
01271 start = end
01272 end += 4
01273 (length,) = _struct_I.unpack(str[start:end])
01274 self.model.track.pose_projected = []
01275 for i in xrange(0, length):
01276 val1 = geometry_msgs.msg.Pose()
01277 _v45 = val1.position
01278 _x = _v45
01279 start = end
01280 end += 24
01281 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01282 _v46 = val1.orientation
01283 _x = _v46
01284 start = end
01285 end += 32
01286 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01287 self.model.track.pose_projected.append(val1)
01288 start = end
01289 end += 4
01290 (length,) = _struct_I.unpack(str[start:end])
01291 self.model.track.pose_resampled = []
01292 for i in xrange(0, length):
01293 val1 = geometry_msgs.msg.Pose()
01294 _v47 = val1.position
01295 _x = _v47
01296 start = end
01297 end += 24
01298 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01299 _v48 = val1.orientation
01300 _x = _v48
01301 start = end
01302 end += 32
01303 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01304 self.model.track.pose_resampled.append(val1)
01305 start = end
01306 end += 4
01307 (length,) = _struct_I.unpack(str[start:end])
01308 pattern = '<%sI'%length
01309 start = end
01310 end += struct.calcsize(pattern)
01311 self.model.track.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
01312 start = end
01313 end += 4
01314 (length,) = _struct_I.unpack(str[start:end])
01315 self.model.track.channels = []
01316 for i in xrange(0, length):
01317 val1 = sensor_msgs.msg.ChannelFloat32()
01318 start = end
01319 end += 4
01320 (length,) = _struct_I.unpack(str[start:end])
01321 start = end
01322 end += length
01323 val1.name = str[start:end]
01324 start = end
01325 end += 4
01326 (length,) = _struct_I.unpack(str[start:end])
01327 pattern = '<%sf'%length
01328 start = end
01329 end += struct.calcsize(pattern)
01330 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
01331 self.model.track.channels.append(val1)
01332 return self
01333 except struct.error, e:
01334 raise roslib.message.DeserializationError(e) #most likely buffer underfill
01335
01336 _struct_I = roslib.message.struct_I
01337 _struct_i = struct.Struct("<i")
01338 _struct_3I = struct.Struct("<3I")
01339 _struct_dB = struct.Struct("<dB")
01340 _struct_4d = struct.Struct("<4d")
01341 _struct_3d = struct.Struct("<3d")
01342 class TrackModelSrv(roslib.message.ServiceDefinition):
01343 _type = 'articulation_msgs/TrackModelSrv'
01344 _md5sum = 'eba693fb01232c71f70038728ca60d66'
01345 _request_class = TrackModelSrvRequest
01346 _response_class = TrackModelSrvResponse