00001 """autogenerated by genmsg_py from ArticulatedObjectMsg.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006 import articulation_msgs.msg
00007 import geometry_msgs.msg
00008 import sensor_msgs.msg
00009 import visualization_msgs.msg
00010 import std_msgs.msg
00011
00012 class ArticulatedObjectMsg(roslib.message.Message):
00013 _md5sum = "37c3f54a6cb19e9fc6d71284d290d369"
00014 _type = "articulation_msgs/ArticulatedObjectMsg"
00015 _has_header = True
00016 _full_text = """Header header
00017
00018 articulation_msgs/TrackMsg[] parts # observed trajectories for each object part
00019 articulation_msgs/ParamMsg[] params # global parameters
00020 articulation_msgs/ModelMsg[] models # models, describing relationships between parts
00021 visualization_msgs/MarkerArray markers # marker visualization of models/object
00022 ================================================================================
00023 MSG: std_msgs/Header
00024 # Standard metadata for higher-level stamped data types.
00025 # This is generally used to communicate timestamped data
00026 # in a particular coordinate frame.
00027 #
00028 # sequence ID: consecutively increasing ID
00029 uint32 seq
00030 #Two-integer timestamp that is expressed as:
00031 # * stamp.secs: seconds (stamp_secs) since epoch
00032 # * stamp.nsecs: nanoseconds since stamp_secs
00033 # time-handling sugar is provided by the client library
00034 time stamp
00035 #Frame this data is associated with
00036 # 0: no frame
00037 # 1: global frame
00038 string frame_id
00039
00040 ================================================================================
00041 MSG: articulation_msgs/TrackMsg
00042 # Single kinematic trajectory
00043 #
00044 # This message contains a kinematic trajectory. The trajectory is specified
00045 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00046 # the track is valid, and whether it includes orientation. The track id
00047 # can be used for automatic coloring in the RVIZ track plugin, and can be
00048 # freely chosen by the client.
00049 #
00050 # A model is fitting only from the trajectory stored in the pose[]-vector.
00051 # Additional information may be associated to each pose using the channels
00052 # vector, with arbitrary # fields (e.g., to include applied/measured forces).
00053 #
00054 # After model evaluation,
00055 # also the associated configurations of the object are stored in the channels,
00056 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00057 # Model evaluation also projects the poses in the pose vector onto the model,
00058 # and stores these ideal poses in the vector pose_projected. Further, during model
00059 # evaluation, a new set of (uniform) configurations over the valid configuration
00060 # range is sampled, and the result is stored in pose_resampled.
00061 # The vector pose_flags contains additional display flags for the poses in the
00062 # pose vector, for example, whether a pose is visible and/or
00063 # the end of a trajectory segment. At the moment, this is only used by the
00064 # prior_model_learner.
00065 #
00066
00067 Header header # Timestamp and frame
00068 int32 id # used-specified track id
00069
00070 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory
00071 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model
00072 # (after model evaluation)
00073 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in
00074 # the valid configuration range
00075 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00076
00077 uint32 POSE_VISIBLE=1
00078 uint32 POSE_END_OF_SEGMENT=2
00079
00080 # Each channel should have the same number of elements as pose array,
00081 # and the data in each channel should correspond 1:1 with each pose
00082 # possible channels: "width", "height", "rgb", ...
00083 sensor_msgs/ChannelFloat32[] channels
00084
00085
00086
00087 ================================================================================
00088 MSG: geometry_msgs/Pose
00089 # A representation of pose in free space, composed of postion and orientation.
00090 Point position
00091 Quaternion orientation
00092
00093 ================================================================================
00094 MSG: geometry_msgs/Point
00095 # This contains the position of a point in free space
00096 float64 x
00097 float64 y
00098 float64 z
00099
00100 ================================================================================
00101 MSG: geometry_msgs/Quaternion
00102 # This represents an orientation in free space in quaternion form.
00103
00104 float64 x
00105 float64 y
00106 float64 z
00107 float64 w
00108
00109 ================================================================================
00110 MSG: sensor_msgs/ChannelFloat32
00111 # This message is used by the PointCloud message to hold optional data
00112 # associated with each point in the cloud. The length of the values
00113 # array should be the same as the length of the points array in the
00114 # PointCloud, and each value should be associated with the corresponding
00115 # point.
00116
00117 # Channel names in existing practice include:
00118 # "u", "v" - row and column (respectively) in the left stereo image.
00119 # This is opposite to usual conventions but remains for
00120 # historical reasons. The newer PointCloud2 message has no
00121 # such problem.
00122 # "rgb" - For point clouds produced by color stereo cameras. uint8
00123 # (R,G,B) values packed into the least significant 24 bits,
00124 # in order.
00125 # "intensity" - laser or pixel intensity.
00126 # "distance"
00127
00128 # The channel name should give semantics of the channel (e.g.
00129 # "intensity" instead of "value").
00130 string name
00131
00132 # The values array should be 1-1 with the elements of the associated
00133 # PointCloud.
00134 float32[] values
00135
00136 ================================================================================
00137 MSG: articulation_msgs/ParamMsg
00138 # Single parameter passed to or from model fitting
00139 #
00140 # This mechanism allows to flexibly pass parameters to
00141 # model fitting (and vice versa). Note that these parameters
00142 # are model-specific: A client may supply additional
00143 # parameters to the model estimator, and, similarly, a estimator
00144 # may add the estimated model parameters to the model message.
00145 # When the model is then evaluated, for example to make predictions
00146 # or to compute the likelihood, the model class can then use
00147 # these parameters.
00148 #
00149 # A parameter has a name, a value, and a type. The type globally
00150 # indicates whether it is a prior parameter (prior to model fitting),
00151 # or a model parameter (found during model fitting, using a maximum-
00152 # likelihood estimator), or a cached evaluation (e.g., the likelihood
00153 # or the BIC are a typical "side"-product of model estimation, and
00154 # can therefore already be cached).
00155 #
00156 # For a list of currently used parameters, see the documentation at
00157 # http://www.ros.org/wiki/articulation_models
00158 #
00159
00160 uint8 PRIOR=0 # indicates a prior model parameter
00161 # (e.g., "sigma_position")
00162 uint8 PARAM=1 # indicates a estimated model parameter
00163 # (e.g., "rot_radius", the estimated radius)
00164 uint8 EVAL=2 # indicates a cached evaluation of the model, given
00165 # the current trajectory
00166 # (e.g., "loglikelihood", the log likelihood of the
00167 # data, given the model and its parameters)
00168
00169 string name # name of the parameter
00170 float64 value # value of the parameter
00171 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)
00172
00173
00174 ================================================================================
00175 MSG: articulation_msgs/ModelMsg
00176 # Single kinematic model
00177 #
00178 # A kinematic model is defined by its model class name, and a set of parameters.
00179 # The client may additionally specify a model id, that can be used to colorize the
00180 # model when visualized using the RVIZ model display.
00181 #
00182 # For a list of currently implemented models, see the documetation at
00183 # http://www.ros.org/wiki/articulation_models
00184 #
00185 #
00186
00187 Header header # frame and timestamp
00188
00189 int32 id # user specified model id
00190 string name # name of the model family (e.g. "rotational",
00191 # "prismatic", "pca-gp", "rigid")
00192 articulation_msgs/ParamMsg[] params # model parameters
00193 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or
00194 # that is evaluated using the model
00195
00196 ================================================================================
00197 MSG: visualization_msgs/MarkerArray
00198 Marker[] markers
00199
00200 ================================================================================
00201 MSG: visualization_msgs/Marker
00202 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz
00203
00204 byte ARROW=0
00205 byte CUBE=1
00206 byte SPHERE=2
00207 byte CYLINDER=3
00208 byte LINE_STRIP=4
00209 byte LINE_LIST=5
00210 byte CUBE_LIST=6
00211 byte SPHERE_LIST=7
00212 byte POINTS=8
00213 byte TEXT_VIEW_FACING=9
00214 byte MESH_RESOURCE=10
00215 byte TRIANGLE_LIST=11
00216
00217 byte ADD=0
00218 byte MODIFY=0
00219 byte DELETE=2
00220
00221 Header header # header for time/frame information
00222 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object
00223 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later
00224 int32 type # Type of object
00225 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object
00226 geometry_msgs/Pose pose # Pose of the object
00227 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)
00228 std_msgs/ColorRGBA color # Color [0.0-1.0]
00229 duration lifetime # How long the object should last before being automatically deleted. 0 means forever
00230 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep
00231
00232 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00233 geometry_msgs/Point[] points
00234 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00235 #number of colors must either be 0 or equal to the number of points
00236 #NOTE: alpha is not yet used
00237 std_msgs/ColorRGBA[] colors
00238
00239 # NOTE: only used for text markers
00240 string text
00241
00242 # NOTE: only used for MESH_RESOURCE markers
00243 string mesh_resource
00244 bool mesh_use_embedded_materials
00245
00246 ================================================================================
00247 MSG: geometry_msgs/Vector3
00248 # This represents a vector in free space.
00249
00250 float64 x
00251 float64 y
00252 float64 z
00253 ================================================================================
00254 MSG: std_msgs/ColorRGBA
00255 float32 r
00256 float32 g
00257 float32 b
00258 float32 a
00259
00260 """
00261 __slots__ = ['header','parts','params','models','markers']
00262 _slot_types = ['Header','articulation_msgs/TrackMsg[]','articulation_msgs/ParamMsg[]','articulation_msgs/ModelMsg[]','visualization_msgs/MarkerArray']
00263
00264 def __init__(self, *args, **kwds):
00265 """
00266 Constructor. Any message fields that are implicitly/explicitly
00267 set to None will be assigned a default value. The recommend
00268 use is keyword arguments as this is more robust to future message
00269 changes. You cannot mix in-order arguments and keyword arguments.
00270
00271 The available fields are:
00272 header,parts,params,models,markers
00273
00274 @param args: complete set of field values, in .msg order
00275 @param kwds: use keyword arguments corresponding to message field names
00276 to set specific fields.
00277 """
00278 if args or kwds:
00279 super(ArticulatedObjectMsg, self).__init__(*args, **kwds)
00280 #message fields cannot be None, assign default values for those that are
00281 if self.header is None:
00282 self.header = std_msgs.msg._Header.Header()
00283 if self.parts is None:
00284 self.parts = []
00285 if self.params is None:
00286 self.params = []
00287 if self.models is None:
00288 self.models = []
00289 if self.markers is None:
00290 self.markers = visualization_msgs.msg.MarkerArray()
00291 else:
00292 self.header = std_msgs.msg._Header.Header()
00293 self.parts = []
00294 self.params = []
00295 self.models = []
00296 self.markers = visualization_msgs.msg.MarkerArray()
00297
00298 def _get_types(self):
00299 """
00300 internal API method
00301 """
00302 return self._slot_types
00303
00304 def serialize(self, buff):
00305 """
00306 serialize message into buffer
00307 @param buff: buffer
00308 @type buff: StringIO
00309 """
00310 try:
00311 _x = self
00312 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00313 _x = self.header.frame_id
00314 length = len(_x)
00315 buff.write(struct.pack('<I%ss'%length, length, _x))
00316 length = len(self.parts)
00317 buff.write(_struct_I.pack(length))
00318 for val1 in self.parts:
00319 _v1 = val1.header
00320 buff.write(_struct_I.pack(_v1.seq))
00321 _v2 = _v1.stamp
00322 _x = _v2
00323 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00324 _x = _v1.frame_id
00325 length = len(_x)
00326 buff.write(struct.pack('<I%ss'%length, length, _x))
00327 buff.write(_struct_i.pack(val1.id))
00328 length = len(val1.pose)
00329 buff.write(_struct_I.pack(length))
00330 for val2 in val1.pose:
00331 _v3 = val2.position
00332 _x = _v3
00333 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00334 _v4 = val2.orientation
00335 _x = _v4
00336 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00337 length = len(val1.pose_projected)
00338 buff.write(_struct_I.pack(length))
00339 for val2 in val1.pose_projected:
00340 _v5 = val2.position
00341 _x = _v5
00342 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00343 _v6 = val2.orientation
00344 _x = _v6
00345 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00346 length = len(val1.pose_resampled)
00347 buff.write(_struct_I.pack(length))
00348 for val2 in val1.pose_resampled:
00349 _v7 = val2.position
00350 _x = _v7
00351 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00352 _v8 = val2.orientation
00353 _x = _v8
00354 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00355 length = len(val1.pose_flags)
00356 buff.write(_struct_I.pack(length))
00357 pattern = '<%sI'%length
00358 buff.write(struct.pack(pattern, *val1.pose_flags))
00359 length = len(val1.channels)
00360 buff.write(_struct_I.pack(length))
00361 for val2 in val1.channels:
00362 _x = val2.name
00363 length = len(_x)
00364 buff.write(struct.pack('<I%ss'%length, length, _x))
00365 length = len(val2.values)
00366 buff.write(_struct_I.pack(length))
00367 pattern = '<%sf'%length
00368 buff.write(struct.pack(pattern, *val2.values))
00369 length = len(self.params)
00370 buff.write(_struct_I.pack(length))
00371 for val1 in self.params:
00372 _x = val1.name
00373 length = len(_x)
00374 buff.write(struct.pack('<I%ss'%length, length, _x))
00375 _x = val1
00376 buff.write(_struct_dB.pack(_x.value, _x.type))
00377 length = len(self.models)
00378 buff.write(_struct_I.pack(length))
00379 for val1 in self.models:
00380 _v9 = val1.header
00381 buff.write(_struct_I.pack(_v9.seq))
00382 _v10 = _v9.stamp
00383 _x = _v10
00384 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00385 _x = _v9.frame_id
00386 length = len(_x)
00387 buff.write(struct.pack('<I%ss'%length, length, _x))
00388 buff.write(_struct_i.pack(val1.id))
00389 _x = val1.name
00390 length = len(_x)
00391 buff.write(struct.pack('<I%ss'%length, length, _x))
00392 length = len(val1.params)
00393 buff.write(_struct_I.pack(length))
00394 for val2 in val1.params:
00395 _x = val2.name
00396 length = len(_x)
00397 buff.write(struct.pack('<I%ss'%length, length, _x))
00398 _x = val2
00399 buff.write(_struct_dB.pack(_x.value, _x.type))
00400 _v11 = val1.track
00401 _v12 = _v11.header
00402 buff.write(_struct_I.pack(_v12.seq))
00403 _v13 = _v12.stamp
00404 _x = _v13
00405 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00406 _x = _v12.frame_id
00407 length = len(_x)
00408 buff.write(struct.pack('<I%ss'%length, length, _x))
00409 buff.write(_struct_i.pack(_v11.id))
00410 length = len(_v11.pose)
00411 buff.write(_struct_I.pack(length))
00412 for val3 in _v11.pose:
00413 _v14 = val3.position
00414 _x = _v14
00415 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00416 _v15 = val3.orientation
00417 _x = _v15
00418 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00419 length = len(_v11.pose_projected)
00420 buff.write(_struct_I.pack(length))
00421 for val3 in _v11.pose_projected:
00422 _v16 = val3.position
00423 _x = _v16
00424 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00425 _v17 = val3.orientation
00426 _x = _v17
00427 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00428 length = len(_v11.pose_resampled)
00429 buff.write(_struct_I.pack(length))
00430 for val3 in _v11.pose_resampled:
00431 _v18 = val3.position
00432 _x = _v18
00433 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00434 _v19 = val3.orientation
00435 _x = _v19
00436 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00437 length = len(_v11.pose_flags)
00438 buff.write(_struct_I.pack(length))
00439 pattern = '<%sI'%length
00440 buff.write(struct.pack(pattern, *_v11.pose_flags))
00441 length = len(_v11.channels)
00442 buff.write(_struct_I.pack(length))
00443 for val3 in _v11.channels:
00444 _x = val3.name
00445 length = len(_x)
00446 buff.write(struct.pack('<I%ss'%length, length, _x))
00447 length = len(val3.values)
00448 buff.write(_struct_I.pack(length))
00449 pattern = '<%sf'%length
00450 buff.write(struct.pack(pattern, *val3.values))
00451 length = len(self.markers.markers)
00452 buff.write(_struct_I.pack(length))
00453 for val1 in self.markers.markers:
00454 _v20 = val1.header
00455 buff.write(_struct_I.pack(_v20.seq))
00456 _v21 = _v20.stamp
00457 _x = _v21
00458 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00459 _x = _v20.frame_id
00460 length = len(_x)
00461 buff.write(struct.pack('<I%ss'%length, length, _x))
00462 _x = val1.ns
00463 length = len(_x)
00464 buff.write(struct.pack('<I%ss'%length, length, _x))
00465 _x = val1
00466 buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
00467 _v22 = val1.pose
00468 _v23 = _v22.position
00469 _x = _v23
00470 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00471 _v24 = _v22.orientation
00472 _x = _v24
00473 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00474 _v25 = val1.scale
00475 _x = _v25
00476 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00477 _v26 = val1.color
00478 _x = _v26
00479 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00480 _v27 = val1.lifetime
00481 _x = _v27
00482 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00483 buff.write(_struct_B.pack(val1.frame_locked))
00484 length = len(val1.points)
00485 buff.write(_struct_I.pack(length))
00486 for val2 in val1.points:
00487 _x = val2
00488 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00489 length = len(val1.colors)
00490 buff.write(_struct_I.pack(length))
00491 for val2 in val1.colors:
00492 _x = val2
00493 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00494 _x = val1.text
00495 length = len(_x)
00496 buff.write(struct.pack('<I%ss'%length, length, _x))
00497 _x = val1.mesh_resource
00498 length = len(_x)
00499 buff.write(struct.pack('<I%ss'%length, length, _x))
00500 buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
00501 except struct.error, se: self._check_types(se)
00502 except TypeError, te: self._check_types(te)
00503
00504 def deserialize(self, str):
00505 """
00506 unpack serialized message in str into this message instance
00507 @param str: byte array of serialized message
00508 @type str: str
00509 """
00510 try:
00511 if self.header is None:
00512 self.header = std_msgs.msg._Header.Header()
00513 if self.markers is None:
00514 self.markers = visualization_msgs.msg.MarkerArray()
00515 end = 0
00516 _x = self
00517 start = end
00518 end += 12
00519 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00520 start = end
00521 end += 4
00522 (length,) = _struct_I.unpack(str[start:end])
00523 start = end
00524 end += length
00525 self.header.frame_id = str[start:end]
00526 start = end
00527 end += 4
00528 (length,) = _struct_I.unpack(str[start:end])
00529 self.parts = []
00530 for i in xrange(0, length):
00531 val1 = articulation_msgs.msg.TrackMsg()
00532 _v28 = val1.header
00533 start = end
00534 end += 4
00535 (_v28.seq,) = _struct_I.unpack(str[start:end])
00536 _v29 = _v28.stamp
00537 _x = _v29
00538 start = end
00539 end += 8
00540 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00541 start = end
00542 end += 4
00543 (length,) = _struct_I.unpack(str[start:end])
00544 start = end
00545 end += length
00546 _v28.frame_id = str[start:end]
00547 start = end
00548 end += 4
00549 (val1.id,) = _struct_i.unpack(str[start:end])
00550 start = end
00551 end += 4
00552 (length,) = _struct_I.unpack(str[start:end])
00553 val1.pose = []
00554 for i in xrange(0, length):
00555 val2 = geometry_msgs.msg.Pose()
00556 _v30 = val2.position
00557 _x = _v30
00558 start = end
00559 end += 24
00560 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00561 _v31 = val2.orientation
00562 _x = _v31
00563 start = end
00564 end += 32
00565 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00566 val1.pose.append(val2)
00567 start = end
00568 end += 4
00569 (length,) = _struct_I.unpack(str[start:end])
00570 val1.pose_projected = []
00571 for i in xrange(0, length):
00572 val2 = geometry_msgs.msg.Pose()
00573 _v32 = val2.position
00574 _x = _v32
00575 start = end
00576 end += 24
00577 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00578 _v33 = val2.orientation
00579 _x = _v33
00580 start = end
00581 end += 32
00582 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00583 val1.pose_projected.append(val2)
00584 start = end
00585 end += 4
00586 (length,) = _struct_I.unpack(str[start:end])
00587 val1.pose_resampled = []
00588 for i in xrange(0, length):
00589 val2 = geometry_msgs.msg.Pose()
00590 _v34 = val2.position
00591 _x = _v34
00592 start = end
00593 end += 24
00594 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00595 _v35 = val2.orientation
00596 _x = _v35
00597 start = end
00598 end += 32
00599 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00600 val1.pose_resampled.append(val2)
00601 start = end
00602 end += 4
00603 (length,) = _struct_I.unpack(str[start:end])
00604 pattern = '<%sI'%length
00605 start = end
00606 end += struct.calcsize(pattern)
00607 val1.pose_flags = struct.unpack(pattern, str[start:end])
00608 start = end
00609 end += 4
00610 (length,) = _struct_I.unpack(str[start:end])
00611 val1.channels = []
00612 for i in xrange(0, length):
00613 val2 = sensor_msgs.msg.ChannelFloat32()
00614 start = end
00615 end += 4
00616 (length,) = _struct_I.unpack(str[start:end])
00617 start = end
00618 end += length
00619 val2.name = str[start:end]
00620 start = end
00621 end += 4
00622 (length,) = _struct_I.unpack(str[start:end])
00623 pattern = '<%sf'%length
00624 start = end
00625 end += struct.calcsize(pattern)
00626 val2.values = struct.unpack(pattern, str[start:end])
00627 val1.channels.append(val2)
00628 self.parts.append(val1)
00629 start = end
00630 end += 4
00631 (length,) = _struct_I.unpack(str[start:end])
00632 self.params = []
00633 for i in xrange(0, length):
00634 val1 = articulation_msgs.msg.ParamMsg()
00635 start = end
00636 end += 4
00637 (length,) = _struct_I.unpack(str[start:end])
00638 start = end
00639 end += length
00640 val1.name = str[start:end]
00641 _x = val1
00642 start = end
00643 end += 9
00644 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00645 self.params.append(val1)
00646 start = end
00647 end += 4
00648 (length,) = _struct_I.unpack(str[start:end])
00649 self.models = []
00650 for i in xrange(0, length):
00651 val1 = articulation_msgs.msg.ModelMsg()
00652 _v36 = val1.header
00653 start = end
00654 end += 4
00655 (_v36.seq,) = _struct_I.unpack(str[start:end])
00656 _v37 = _v36.stamp
00657 _x = _v37
00658 start = end
00659 end += 8
00660 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00661 start = end
00662 end += 4
00663 (length,) = _struct_I.unpack(str[start:end])
00664 start = end
00665 end += length
00666 _v36.frame_id = str[start:end]
00667 start = end
00668 end += 4
00669 (val1.id,) = _struct_i.unpack(str[start:end])
00670 start = end
00671 end += 4
00672 (length,) = _struct_I.unpack(str[start:end])
00673 start = end
00674 end += length
00675 val1.name = str[start:end]
00676 start = end
00677 end += 4
00678 (length,) = _struct_I.unpack(str[start:end])
00679 val1.params = []
00680 for i in xrange(0, length):
00681 val2 = articulation_msgs.msg.ParamMsg()
00682 start = end
00683 end += 4
00684 (length,) = _struct_I.unpack(str[start:end])
00685 start = end
00686 end += length
00687 val2.name = str[start:end]
00688 _x = val2
00689 start = end
00690 end += 9
00691 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00692 val1.params.append(val2)
00693 _v38 = val1.track
00694 _v39 = _v38.header
00695 start = end
00696 end += 4
00697 (_v39.seq,) = _struct_I.unpack(str[start:end])
00698 _v40 = _v39.stamp
00699 _x = _v40
00700 start = end
00701 end += 8
00702 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00703 start = end
00704 end += 4
00705 (length,) = _struct_I.unpack(str[start:end])
00706 start = end
00707 end += length
00708 _v39.frame_id = str[start:end]
00709 start = end
00710 end += 4
00711 (_v38.id,) = _struct_i.unpack(str[start:end])
00712 start = end
00713 end += 4
00714 (length,) = _struct_I.unpack(str[start:end])
00715 _v38.pose = []
00716 for i in xrange(0, length):
00717 val3 = geometry_msgs.msg.Pose()
00718 _v41 = val3.position
00719 _x = _v41
00720 start = end
00721 end += 24
00722 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00723 _v42 = val3.orientation
00724 _x = _v42
00725 start = end
00726 end += 32
00727 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00728 _v38.pose.append(val3)
00729 start = end
00730 end += 4
00731 (length,) = _struct_I.unpack(str[start:end])
00732 _v38.pose_projected = []
00733 for i in xrange(0, length):
00734 val3 = geometry_msgs.msg.Pose()
00735 _v43 = val3.position
00736 _x = _v43
00737 start = end
00738 end += 24
00739 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00740 _v44 = val3.orientation
00741 _x = _v44
00742 start = end
00743 end += 32
00744 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00745 _v38.pose_projected.append(val3)
00746 start = end
00747 end += 4
00748 (length,) = _struct_I.unpack(str[start:end])
00749 _v38.pose_resampled = []
00750 for i in xrange(0, length):
00751 val3 = geometry_msgs.msg.Pose()
00752 _v45 = val3.position
00753 _x = _v45
00754 start = end
00755 end += 24
00756 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00757 _v46 = val3.orientation
00758 _x = _v46
00759 start = end
00760 end += 32
00761 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00762 _v38.pose_resampled.append(val3)
00763 start = end
00764 end += 4
00765 (length,) = _struct_I.unpack(str[start:end])
00766 pattern = '<%sI'%length
00767 start = end
00768 end += struct.calcsize(pattern)
00769 _v38.pose_flags = struct.unpack(pattern, str[start:end])
00770 start = end
00771 end += 4
00772 (length,) = _struct_I.unpack(str[start:end])
00773 _v38.channels = []
00774 for i in xrange(0, length):
00775 val3 = sensor_msgs.msg.ChannelFloat32()
00776 start = end
00777 end += 4
00778 (length,) = _struct_I.unpack(str[start:end])
00779 start = end
00780 end += length
00781 val3.name = str[start:end]
00782 start = end
00783 end += 4
00784 (length,) = _struct_I.unpack(str[start:end])
00785 pattern = '<%sf'%length
00786 start = end
00787 end += struct.calcsize(pattern)
00788 val3.values = struct.unpack(pattern, str[start:end])
00789 _v38.channels.append(val3)
00790 self.models.append(val1)
00791 start = end
00792 end += 4
00793 (length,) = _struct_I.unpack(str[start:end])
00794 self.markers.markers = []
00795 for i in xrange(0, length):
00796 val1 = visualization_msgs.msg.Marker()
00797 _v47 = val1.header
00798 start = end
00799 end += 4
00800 (_v47.seq,) = _struct_I.unpack(str[start:end])
00801 _v48 = _v47.stamp
00802 _x = _v48
00803 start = end
00804 end += 8
00805 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00806 start = end
00807 end += 4
00808 (length,) = _struct_I.unpack(str[start:end])
00809 start = end
00810 end += length
00811 _v47.frame_id = str[start:end]
00812 start = end
00813 end += 4
00814 (length,) = _struct_I.unpack(str[start:end])
00815 start = end
00816 end += length
00817 val1.ns = str[start:end]
00818 _x = val1
00819 start = end
00820 end += 12
00821 (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
00822 _v49 = val1.pose
00823 _v50 = _v49.position
00824 _x = _v50
00825 start = end
00826 end += 24
00827 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00828 _v51 = _v49.orientation
00829 _x = _v51
00830 start = end
00831 end += 32
00832 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00833 _v52 = val1.scale
00834 _x = _v52
00835 start = end
00836 end += 24
00837 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00838 _v53 = val1.color
00839 _x = _v53
00840 start = end
00841 end += 16
00842 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00843 _v54 = val1.lifetime
00844 _x = _v54
00845 start = end
00846 end += 8
00847 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00848 start = end
00849 end += 1
00850 (val1.frame_locked,) = _struct_B.unpack(str[start:end])
00851 val1.frame_locked = bool(val1.frame_locked)
00852 start = end
00853 end += 4
00854 (length,) = _struct_I.unpack(str[start:end])
00855 val1.points = []
00856 for i in xrange(0, length):
00857 val2 = geometry_msgs.msg.Point()
00858 _x = val2
00859 start = end
00860 end += 24
00861 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00862 val1.points.append(val2)
00863 start = end
00864 end += 4
00865 (length,) = _struct_I.unpack(str[start:end])
00866 val1.colors = []
00867 for i in xrange(0, length):
00868 val2 = std_msgs.msg.ColorRGBA()
00869 _x = val2
00870 start = end
00871 end += 16
00872 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00873 val1.colors.append(val2)
00874 start = end
00875 end += 4
00876 (length,) = _struct_I.unpack(str[start:end])
00877 start = end
00878 end += length
00879 val1.text = str[start:end]
00880 start = end
00881 end += 4
00882 (length,) = _struct_I.unpack(str[start:end])
00883 start = end
00884 end += length
00885 val1.mesh_resource = str[start:end]
00886 start = end
00887 end += 1
00888 (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
00889 val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
00890 self.markers.markers.append(val1)
00891 return self
00892 except struct.error, e:
00893 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00894
00895
00896 def serialize_numpy(self, buff, numpy):
00897 """
00898 serialize message with numpy array types into buffer
00899 @param buff: buffer
00900 @type buff: StringIO
00901 @param numpy: numpy python module
00902 @type numpy module
00903 """
00904 try:
00905 _x = self
00906 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00907 _x = self.header.frame_id
00908 length = len(_x)
00909 buff.write(struct.pack('<I%ss'%length, length, _x))
00910 length = len(self.parts)
00911 buff.write(_struct_I.pack(length))
00912 for val1 in self.parts:
00913 _v55 = val1.header
00914 buff.write(_struct_I.pack(_v55.seq))
00915 _v56 = _v55.stamp
00916 _x = _v56
00917 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00918 _x = _v55.frame_id
00919 length = len(_x)
00920 buff.write(struct.pack('<I%ss'%length, length, _x))
00921 buff.write(_struct_i.pack(val1.id))
00922 length = len(val1.pose)
00923 buff.write(_struct_I.pack(length))
00924 for val2 in val1.pose:
00925 _v57 = val2.position
00926 _x = _v57
00927 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00928 _v58 = val2.orientation
00929 _x = _v58
00930 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00931 length = len(val1.pose_projected)
00932 buff.write(_struct_I.pack(length))
00933 for val2 in val1.pose_projected:
00934 _v59 = val2.position
00935 _x = _v59
00936 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00937 _v60 = val2.orientation
00938 _x = _v60
00939 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00940 length = len(val1.pose_resampled)
00941 buff.write(_struct_I.pack(length))
00942 for val2 in val1.pose_resampled:
00943 _v61 = val2.position
00944 _x = _v61
00945 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00946 _v62 = val2.orientation
00947 _x = _v62
00948 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00949 length = len(val1.pose_flags)
00950 buff.write(_struct_I.pack(length))
00951 pattern = '<%sI'%length
00952 buff.write(val1.pose_flags.tostring())
00953 length = len(val1.channels)
00954 buff.write(_struct_I.pack(length))
00955 for val2 in val1.channels:
00956 _x = val2.name
00957 length = len(_x)
00958 buff.write(struct.pack('<I%ss'%length, length, _x))
00959 length = len(val2.values)
00960 buff.write(_struct_I.pack(length))
00961 pattern = '<%sf'%length
00962 buff.write(val2.values.tostring())
00963 length = len(self.params)
00964 buff.write(_struct_I.pack(length))
00965 for val1 in self.params:
00966 _x = val1.name
00967 length = len(_x)
00968 buff.write(struct.pack('<I%ss'%length, length, _x))
00969 _x = val1
00970 buff.write(_struct_dB.pack(_x.value, _x.type))
00971 length = len(self.models)
00972 buff.write(_struct_I.pack(length))
00973 for val1 in self.models:
00974 _v63 = val1.header
00975 buff.write(_struct_I.pack(_v63.seq))
00976 _v64 = _v63.stamp
00977 _x = _v64
00978 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00979 _x = _v63.frame_id
00980 length = len(_x)
00981 buff.write(struct.pack('<I%ss'%length, length, _x))
00982 buff.write(_struct_i.pack(val1.id))
00983 _x = val1.name
00984 length = len(_x)
00985 buff.write(struct.pack('<I%ss'%length, length, _x))
00986 length = len(val1.params)
00987 buff.write(_struct_I.pack(length))
00988 for val2 in val1.params:
00989 _x = val2.name
00990 length = len(_x)
00991 buff.write(struct.pack('<I%ss'%length, length, _x))
00992 _x = val2
00993 buff.write(_struct_dB.pack(_x.value, _x.type))
00994 _v65 = val1.track
00995 _v66 = _v65.header
00996 buff.write(_struct_I.pack(_v66.seq))
00997 _v67 = _v66.stamp
00998 _x = _v67
00999 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01000 _x = _v66.frame_id
01001 length = len(_x)
01002 buff.write(struct.pack('<I%ss'%length, length, _x))
01003 buff.write(_struct_i.pack(_v65.id))
01004 length = len(_v65.pose)
01005 buff.write(_struct_I.pack(length))
01006 for val3 in _v65.pose:
01007 _v68 = val3.position
01008 _x = _v68
01009 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01010 _v69 = val3.orientation
01011 _x = _v69
01012 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01013 length = len(_v65.pose_projected)
01014 buff.write(_struct_I.pack(length))
01015 for val3 in _v65.pose_projected:
01016 _v70 = val3.position
01017 _x = _v70
01018 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01019 _v71 = val3.orientation
01020 _x = _v71
01021 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01022 length = len(_v65.pose_resampled)
01023 buff.write(_struct_I.pack(length))
01024 for val3 in _v65.pose_resampled:
01025 _v72 = val3.position
01026 _x = _v72
01027 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01028 _v73 = val3.orientation
01029 _x = _v73
01030 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01031 length = len(_v65.pose_flags)
01032 buff.write(_struct_I.pack(length))
01033 pattern = '<%sI'%length
01034 buff.write(_v65.pose_flags.tostring())
01035 length = len(_v65.channels)
01036 buff.write(_struct_I.pack(length))
01037 for val3 in _v65.channels:
01038 _x = val3.name
01039 length = len(_x)
01040 buff.write(struct.pack('<I%ss'%length, length, _x))
01041 length = len(val3.values)
01042 buff.write(_struct_I.pack(length))
01043 pattern = '<%sf'%length
01044 buff.write(val3.values.tostring())
01045 length = len(self.markers.markers)
01046 buff.write(_struct_I.pack(length))
01047 for val1 in self.markers.markers:
01048 _v74 = val1.header
01049 buff.write(_struct_I.pack(_v74.seq))
01050 _v75 = _v74.stamp
01051 _x = _v75
01052 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01053 _x = _v74.frame_id
01054 length = len(_x)
01055 buff.write(struct.pack('<I%ss'%length, length, _x))
01056 _x = val1.ns
01057 length = len(_x)
01058 buff.write(struct.pack('<I%ss'%length, length, _x))
01059 _x = val1
01060 buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
01061 _v76 = val1.pose
01062 _v77 = _v76.position
01063 _x = _v77
01064 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01065 _v78 = _v76.orientation
01066 _x = _v78
01067 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01068 _v79 = val1.scale
01069 _x = _v79
01070 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01071 _v80 = val1.color
01072 _x = _v80
01073 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
01074 _v81 = val1.lifetime
01075 _x = _v81
01076 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
01077 buff.write(_struct_B.pack(val1.frame_locked))
01078 length = len(val1.points)
01079 buff.write(_struct_I.pack(length))
01080 for val2 in val1.points:
01081 _x = val2
01082 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01083 length = len(val1.colors)
01084 buff.write(_struct_I.pack(length))
01085 for val2 in val1.colors:
01086 _x = val2
01087 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
01088 _x = val1.text
01089 length = len(_x)
01090 buff.write(struct.pack('<I%ss'%length, length, _x))
01091 _x = val1.mesh_resource
01092 length = len(_x)
01093 buff.write(struct.pack('<I%ss'%length, length, _x))
01094 buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
01095 except struct.error, se: self._check_types(se)
01096 except TypeError, te: self._check_types(te)
01097
01098 def deserialize_numpy(self, str, numpy):
01099 """
01100 unpack serialized message in str into this message instance using numpy for array types
01101 @param str: byte array of serialized message
01102 @type str: str
01103 @param numpy: numpy python module
01104 @type numpy: module
01105 """
01106 try:
01107 if self.header is None:
01108 self.header = std_msgs.msg._Header.Header()
01109 if self.markers is None:
01110 self.markers = visualization_msgs.msg.MarkerArray()
01111 end = 0
01112 _x = self
01113 start = end
01114 end += 12
01115 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01116 start = end
01117 end += 4
01118 (length,) = _struct_I.unpack(str[start:end])
01119 start = end
01120 end += length
01121 self.header.frame_id = str[start:end]
01122 start = end
01123 end += 4
01124 (length,) = _struct_I.unpack(str[start:end])
01125 self.parts = []
01126 for i in xrange(0, length):
01127 val1 = articulation_msgs.msg.TrackMsg()
01128 _v82 = val1.header
01129 start = end
01130 end += 4
01131 (_v82.seq,) = _struct_I.unpack(str[start:end])
01132 _v83 = _v82.stamp
01133 _x = _v83
01134 start = end
01135 end += 8
01136 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01137 start = end
01138 end += 4
01139 (length,) = _struct_I.unpack(str[start:end])
01140 start = end
01141 end += length
01142 _v82.frame_id = str[start:end]
01143 start = end
01144 end += 4
01145 (val1.id,) = _struct_i.unpack(str[start:end])
01146 start = end
01147 end += 4
01148 (length,) = _struct_I.unpack(str[start:end])
01149 val1.pose = []
01150 for i in xrange(0, length):
01151 val2 = geometry_msgs.msg.Pose()
01152 _v84 = val2.position
01153 _x = _v84
01154 start = end
01155 end += 24
01156 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01157 _v85 = val2.orientation
01158 _x = _v85
01159 start = end
01160 end += 32
01161 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01162 val1.pose.append(val2)
01163 start = end
01164 end += 4
01165 (length,) = _struct_I.unpack(str[start:end])
01166 val1.pose_projected = []
01167 for i in xrange(0, length):
01168 val2 = geometry_msgs.msg.Pose()
01169 _v86 = val2.position
01170 _x = _v86
01171 start = end
01172 end += 24
01173 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01174 _v87 = val2.orientation
01175 _x = _v87
01176 start = end
01177 end += 32
01178 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01179 val1.pose_projected.append(val2)
01180 start = end
01181 end += 4
01182 (length,) = _struct_I.unpack(str[start:end])
01183 val1.pose_resampled = []
01184 for i in xrange(0, length):
01185 val2 = geometry_msgs.msg.Pose()
01186 _v88 = val2.position
01187 _x = _v88
01188 start = end
01189 end += 24
01190 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01191 _v89 = val2.orientation
01192 _x = _v89
01193 start = end
01194 end += 32
01195 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01196 val1.pose_resampled.append(val2)
01197 start = end
01198 end += 4
01199 (length,) = _struct_I.unpack(str[start:end])
01200 pattern = '<%sI'%length
01201 start = end
01202 end += struct.calcsize(pattern)
01203 val1.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
01204 start = end
01205 end += 4
01206 (length,) = _struct_I.unpack(str[start:end])
01207 val1.channels = []
01208 for i in xrange(0, length):
01209 val2 = sensor_msgs.msg.ChannelFloat32()
01210 start = end
01211 end += 4
01212 (length,) = _struct_I.unpack(str[start:end])
01213 start = end
01214 end += length
01215 val2.name = str[start:end]
01216 start = end
01217 end += 4
01218 (length,) = _struct_I.unpack(str[start:end])
01219 pattern = '<%sf'%length
01220 start = end
01221 end += struct.calcsize(pattern)
01222 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
01223 val1.channels.append(val2)
01224 self.parts.append(val1)
01225 start = end
01226 end += 4
01227 (length,) = _struct_I.unpack(str[start:end])
01228 self.params = []
01229 for i in xrange(0, length):
01230 val1 = articulation_msgs.msg.ParamMsg()
01231 start = end
01232 end += 4
01233 (length,) = _struct_I.unpack(str[start:end])
01234 start = end
01235 end += length
01236 val1.name = str[start:end]
01237 _x = val1
01238 start = end
01239 end += 9
01240 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
01241 self.params.append(val1)
01242 start = end
01243 end += 4
01244 (length,) = _struct_I.unpack(str[start:end])
01245 self.models = []
01246 for i in xrange(0, length):
01247 val1 = articulation_msgs.msg.ModelMsg()
01248 _v90 = val1.header
01249 start = end
01250 end += 4
01251 (_v90.seq,) = _struct_I.unpack(str[start:end])
01252 _v91 = _v90.stamp
01253 _x = _v91
01254 start = end
01255 end += 8
01256 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01257 start = end
01258 end += 4
01259 (length,) = _struct_I.unpack(str[start:end])
01260 start = end
01261 end += length
01262 _v90.frame_id = str[start:end]
01263 start = end
01264 end += 4
01265 (val1.id,) = _struct_i.unpack(str[start:end])
01266 start = end
01267 end += 4
01268 (length,) = _struct_I.unpack(str[start:end])
01269 start = end
01270 end += length
01271 val1.name = str[start:end]
01272 start = end
01273 end += 4
01274 (length,) = _struct_I.unpack(str[start:end])
01275 val1.params = []
01276 for i in xrange(0, length):
01277 val2 = articulation_msgs.msg.ParamMsg()
01278 start = end
01279 end += 4
01280 (length,) = _struct_I.unpack(str[start:end])
01281 start = end
01282 end += length
01283 val2.name = str[start:end]
01284 _x = val2
01285 start = end
01286 end += 9
01287 (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
01288 val1.params.append(val2)
01289 _v92 = val1.track
01290 _v93 = _v92.header
01291 start = end
01292 end += 4
01293 (_v93.seq,) = _struct_I.unpack(str[start:end])
01294 _v94 = _v93.stamp
01295 _x = _v94
01296 start = end
01297 end += 8
01298 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01299 start = end
01300 end += 4
01301 (length,) = _struct_I.unpack(str[start:end])
01302 start = end
01303 end += length
01304 _v93.frame_id = str[start:end]
01305 start = end
01306 end += 4
01307 (_v92.id,) = _struct_i.unpack(str[start:end])
01308 start = end
01309 end += 4
01310 (length,) = _struct_I.unpack(str[start:end])
01311 _v92.pose = []
01312 for i in xrange(0, length):
01313 val3 = geometry_msgs.msg.Pose()
01314 _v95 = val3.position
01315 _x = _v95
01316 start = end
01317 end += 24
01318 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01319 _v96 = val3.orientation
01320 _x = _v96
01321 start = end
01322 end += 32
01323 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01324 _v92.pose.append(val3)
01325 start = end
01326 end += 4
01327 (length,) = _struct_I.unpack(str[start:end])
01328 _v92.pose_projected = []
01329 for i in xrange(0, length):
01330 val3 = geometry_msgs.msg.Pose()
01331 _v97 = val3.position
01332 _x = _v97
01333 start = end
01334 end += 24
01335 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01336 _v98 = val3.orientation
01337 _x = _v98
01338 start = end
01339 end += 32
01340 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01341 _v92.pose_projected.append(val3)
01342 start = end
01343 end += 4
01344 (length,) = _struct_I.unpack(str[start:end])
01345 _v92.pose_resampled = []
01346 for i in xrange(0, length):
01347 val3 = geometry_msgs.msg.Pose()
01348 _v99 = val3.position
01349 _x = _v99
01350 start = end
01351 end += 24
01352 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01353 _v100 = val3.orientation
01354 _x = _v100
01355 start = end
01356 end += 32
01357 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01358 _v92.pose_resampled.append(val3)
01359 start = end
01360 end += 4
01361 (length,) = _struct_I.unpack(str[start:end])
01362 pattern = '<%sI'%length
01363 start = end
01364 end += struct.calcsize(pattern)
01365 _v92.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
01366 start = end
01367 end += 4
01368 (length,) = _struct_I.unpack(str[start:end])
01369 _v92.channels = []
01370 for i in xrange(0, length):
01371 val3 = sensor_msgs.msg.ChannelFloat32()
01372 start = end
01373 end += 4
01374 (length,) = _struct_I.unpack(str[start:end])
01375 start = end
01376 end += length
01377 val3.name = str[start:end]
01378 start = end
01379 end += 4
01380 (length,) = _struct_I.unpack(str[start:end])
01381 pattern = '<%sf'%length
01382 start = end
01383 end += struct.calcsize(pattern)
01384 val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
01385 _v92.channels.append(val3)
01386 self.models.append(val1)
01387 start = end
01388 end += 4
01389 (length,) = _struct_I.unpack(str[start:end])
01390 self.markers.markers = []
01391 for i in xrange(0, length):
01392 val1 = visualization_msgs.msg.Marker()
01393 _v101 = val1.header
01394 start = end
01395 end += 4
01396 (_v101.seq,) = _struct_I.unpack(str[start:end])
01397 _v102 = _v101.stamp
01398 _x = _v102
01399 start = end
01400 end += 8
01401 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01402 start = end
01403 end += 4
01404 (length,) = _struct_I.unpack(str[start:end])
01405 start = end
01406 end += length
01407 _v101.frame_id = str[start:end]
01408 start = end
01409 end += 4
01410 (length,) = _struct_I.unpack(str[start:end])
01411 start = end
01412 end += length
01413 val1.ns = str[start:end]
01414 _x = val1
01415 start = end
01416 end += 12
01417 (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
01418 _v103 = val1.pose
01419 _v104 = _v103.position
01420 _x = _v104
01421 start = end
01422 end += 24
01423 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01424 _v105 = _v103.orientation
01425 _x = _v105
01426 start = end
01427 end += 32
01428 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01429 _v106 = val1.scale
01430 _x = _v106
01431 start = end
01432 end += 24
01433 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01434 _v107 = val1.color
01435 _x = _v107
01436 start = end
01437 end += 16
01438 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
01439 _v108 = val1.lifetime
01440 _x = _v108
01441 start = end
01442 end += 8
01443 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
01444 start = end
01445 end += 1
01446 (val1.frame_locked,) = _struct_B.unpack(str[start:end])
01447 val1.frame_locked = bool(val1.frame_locked)
01448 start = end
01449 end += 4
01450 (length,) = _struct_I.unpack(str[start:end])
01451 val1.points = []
01452 for i in xrange(0, length):
01453 val2 = geometry_msgs.msg.Point()
01454 _x = val2
01455 start = end
01456 end += 24
01457 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01458 val1.points.append(val2)
01459 start = end
01460 end += 4
01461 (length,) = _struct_I.unpack(str[start:end])
01462 val1.colors = []
01463 for i in xrange(0, length):
01464 val2 = std_msgs.msg.ColorRGBA()
01465 _x = val2
01466 start = end
01467 end += 16
01468 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
01469 val1.colors.append(val2)
01470 start = end
01471 end += 4
01472 (length,) = _struct_I.unpack(str[start:end])
01473 start = end
01474 end += length
01475 val1.text = str[start:end]
01476 start = end
01477 end += 4
01478 (length,) = _struct_I.unpack(str[start:end])
01479 start = end
01480 end += length
01481 val1.mesh_resource = str[start:end]
01482 start = end
01483 end += 1
01484 (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
01485 val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
01486 self.markers.markers.append(val1)
01487 return self
01488 except struct.error, e:
01489 raise roslib.message.DeserializationError(e) #most likely buffer underfill
01490
01491 _struct_I = roslib.message.struct_I
01492 _struct_B = struct.Struct("<B")
01493 _struct_dB = struct.Struct("<dB")
01494 _struct_3i = struct.Struct("<3i")
01495 _struct_2i = struct.Struct("<2i")
01496 _struct_i = struct.Struct("<i")
01497 _struct_3I = struct.Struct("<3I")
01498 _struct_4f = struct.Struct("<4f")
01499 _struct_4d = struct.Struct("<4d")
01500 _struct_2I = struct.Struct("<2I")
01501 _struct_3d = struct.Struct("<3d")