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