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