00001 """autogenerated by genpy from arm_navigation_msgs/GetPlanningSceneRequest.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 arm_navigation_msgs.msg
00008 import geometry_msgs.msg
00009 import std_msgs.msg
00010 import genpy
00011 import sensor_msgs.msg
00012
00013 class GetPlanningSceneRequest(genpy.Message):
00014 _md5sum = "67ad55e9bed9c8f21dfb4b9b1ca8df7d"
00015 _type = "arm_navigation_msgs/GetPlanningSceneRequest"
00016 _has_header = False
00017 _full_text = """
00018
00019
00020 PlanningScene planning_scene_diff
00021
00022
00023 arm_navigation_msgs/OrderedCollisionOperations operations
00024
00025 ================================================================================
00026 MSG: arm_navigation_msgs/PlanningScene
00027 #full robot state
00028 arm_navigation_msgs/RobotState robot_state
00029
00030 #additional frames for duplicating tf
00031 geometry_msgs/TransformStamped[] fixed_frame_transforms
00032
00033 #full allowed collision matrix
00034 AllowedCollisionMatrix allowed_collision_matrix
00035
00036 #allowed contacts
00037 arm_navigation_msgs/AllowedContactSpecification[] allowed_contacts
00038
00039 #all link paddings
00040 arm_navigation_msgs/LinkPadding[] link_padding
00041
00042 #collision objects
00043 arm_navigation_msgs/CollisionObject[] collision_objects
00044 arm_navigation_msgs/AttachedCollisionObject[] attached_collision_objects
00045
00046 #the collision map
00047 arm_navigation_msgs/CollisionMap collision_map
00048
00049 ================================================================================
00050 MSG: arm_navigation_msgs/RobotState
00051 # This message contains information about the robot state, i.e. the positions of its joints and links
00052 sensor_msgs/JointState joint_state
00053 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00054
00055 ================================================================================
00056 MSG: sensor_msgs/JointState
00057 # This is a message that holds data to describe the state of a set of torque controlled joints.
00058 #
00059 # The state of each joint (revolute or prismatic) is defined by:
00060 # * the position of the joint (rad or m),
00061 # * the velocity of the joint (rad/s or m/s) and
00062 # * the effort that is applied in the joint (Nm or N).
00063 #
00064 # Each joint is uniquely identified by its name
00065 # The header specifies the time at which the joint states were recorded. All the joint states
00066 # in one message have to be recorded at the same time.
00067 #
00068 # This message consists of a multiple arrays, one for each part of the joint state.
00069 # The goal is to make each of the fields optional. When e.g. your joints have no
00070 # effort associated with them, you can leave the effort array empty.
00071 #
00072 # All arrays in this message should have the same size, or be empty.
00073 # This is the only way to uniquely associate the joint name with the correct
00074 # states.
00075
00076
00077 Header header
00078
00079 string[] name
00080 float64[] position
00081 float64[] velocity
00082 float64[] effort
00083
00084 ================================================================================
00085 MSG: std_msgs/Header
00086 # Standard metadata for higher-level stamped data types.
00087 # This is generally used to communicate timestamped data
00088 # in a particular coordinate frame.
00089 #
00090 # sequence ID: consecutively increasing ID
00091 uint32 seq
00092 #Two-integer timestamp that is expressed as:
00093 # * stamp.secs: seconds (stamp_secs) since epoch
00094 # * stamp.nsecs: nanoseconds since stamp_secs
00095 # time-handling sugar is provided by the client library
00096 time stamp
00097 #Frame this data is associated with
00098 # 0: no frame
00099 # 1: global frame
00100 string frame_id
00101
00102 ================================================================================
00103 MSG: arm_navigation_msgs/MultiDOFJointState
00104 #A representation of a multi-dof joint state
00105 time stamp
00106 string[] joint_names
00107 string[] frame_ids
00108 string[] child_frame_ids
00109 geometry_msgs/Pose[] poses
00110
00111 ================================================================================
00112 MSG: geometry_msgs/Pose
00113 # A representation of pose in free space, composed of postion and orientation.
00114 Point position
00115 Quaternion orientation
00116
00117 ================================================================================
00118 MSG: geometry_msgs/Point
00119 # This contains the position of a point in free space
00120 float64 x
00121 float64 y
00122 float64 z
00123
00124 ================================================================================
00125 MSG: geometry_msgs/Quaternion
00126 # This represents an orientation in free space in quaternion form.
00127
00128 float64 x
00129 float64 y
00130 float64 z
00131 float64 w
00132
00133 ================================================================================
00134 MSG: geometry_msgs/TransformStamped
00135 # This expresses a transform from coordinate frame header.frame_id
00136 # to the coordinate frame child_frame_id
00137 #
00138 # This message is mostly used by the
00139 # <a href="http://www.ros.org/wiki/tf">tf</a> package.
00140 # See it's documentation for more information.
00141
00142 Header header
00143 string child_frame_id # the frame id of the child frame
00144 Transform transform
00145
00146 ================================================================================
00147 MSG: geometry_msgs/Transform
00148 # This represents the transform between two coordinate frames in free space.
00149
00150 Vector3 translation
00151 Quaternion rotation
00152
00153 ================================================================================
00154 MSG: geometry_msgs/Vector3
00155 # This represents a vector in free space.
00156
00157 float64 x
00158 float64 y
00159 float64 z
00160 ================================================================================
00161 MSG: arm_navigation_msgs/AllowedCollisionMatrix
00162 # the list of link names in the matrix
00163 string[] link_names
00164
00165 # the individual entries in the allowed collision matrix
00166 # symmetric, with same order as link_names
00167 AllowedCollisionEntry[] entries
00168
00169 ================================================================================
00170 MSG: arm_navigation_msgs/AllowedCollisionEntry
00171 # whether or not collision checking is enabled
00172 bool[] enabled
00173
00174 ================================================================================
00175 MSG: arm_navigation_msgs/AllowedContactSpecification
00176 # The names of the regions
00177 string name
00178
00179 # The shape of the region in the environment
00180 arm_navigation_msgs/Shape shape
00181
00182 # The pose of the space defining the region
00183 geometry_msgs/PoseStamped pose_stamped
00184
00185 # The set of links that will be allowed to have penetration contact within this region
00186 string[] link_names
00187
00188 # The maximum penetration depth allowed for every link
00189 float64 penetration_depth
00190
00191 ================================================================================
00192 MSG: arm_navigation_msgs/Shape
00193 byte SPHERE=0
00194 byte BOX=1
00195 byte CYLINDER=2
00196 byte MESH=3
00197
00198 byte type
00199
00200
00201 #### define sphere, box, cylinder ####
00202 # the origin of each shape is considered at the shape's center
00203
00204 # for sphere
00205 # radius := dimensions[0]
00206
00207 # for cylinder
00208 # radius := dimensions[0]
00209 # length := dimensions[1]
00210 # the length is along the Z axis
00211
00212 # for box
00213 # size_x := dimensions[0]
00214 # size_y := dimensions[1]
00215 # size_z := dimensions[2]
00216 float64[] dimensions
00217
00218
00219 #### define mesh ####
00220
00221 # list of triangles; triangle k is defined by tre vertices located
00222 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00223 int32[] triangles
00224 geometry_msgs/Point[] vertices
00225
00226 ================================================================================
00227 MSG: geometry_msgs/PoseStamped
00228 # A Pose with reference coordinate frame and timestamp
00229 Header header
00230 Pose pose
00231
00232 ================================================================================
00233 MSG: arm_navigation_msgs/LinkPadding
00234 #name for the link
00235 string link_name
00236
00237 # padding to apply to the link
00238 float64 padding
00239
00240 ================================================================================
00241 MSG: arm_navigation_msgs/CollisionObject
00242 # a header, used for interpreting the poses
00243 Header header
00244
00245 # the id of the object
00246 string id
00247
00248 # The padding used for filtering points near the object.
00249 # This does not affect collision checking for the object.
00250 # Set to negative to get zero padding.
00251 float32 padding
00252
00253 #This contains what is to be done with the object
00254 CollisionObjectOperation operation
00255
00256 #the shapes associated with the object
00257 arm_navigation_msgs/Shape[] shapes
00258
00259 #the poses associated with the shapes - will be transformed using the header
00260 geometry_msgs/Pose[] poses
00261
00262 ================================================================================
00263 MSG: arm_navigation_msgs/CollisionObjectOperation
00264 #Puts the object into the environment
00265 #or updates the object if already added
00266 byte ADD=0
00267
00268 #Removes the object from the environment entirely
00269 byte REMOVE=1
00270
00271 #Only valid within the context of a CollisionAttachedObject message
00272 #Will be ignored if sent with an CollisionObject message
00273 #Takes an attached object, detaches from the attached link
00274 #But adds back in as regular object
00275 byte DETACH_AND_ADD_AS_OBJECT=2
00276
00277 #Only valid within the context of a CollisionAttachedObject message
00278 #Will be ignored if sent with an CollisionObject message
00279 #Takes current object in the environment and removes it as
00280 #a regular object
00281 byte ATTACH_AND_REMOVE_AS_OBJECT=3
00282
00283 # Byte code for operation
00284 byte operation
00285
00286 ================================================================================
00287 MSG: arm_navigation_msgs/AttachedCollisionObject
00288 # The CollisionObject will be attached with a fixed joint to this link
00289 # If link name is set to REMOVE_ALL_ATTACHED_OBJECTS and object.operation
00290 # is set to REMOVE will remove all attached bodies attached to any object
00291 string link_name
00292
00293 #Reserved for indicating that all attached objects should be removed
00294 string REMOVE_ALL_ATTACHED_OBJECTS = "all"
00295
00296 #This contains the actual shapes and poses for the CollisionObject
00297 #to be attached to the link
00298 #If action is remove and no object.id is set, all objects
00299 #attached to the link indicated by link_name will be removed
00300 CollisionObject object
00301
00302 # The set of links that the attached objects are allowed to touch
00303 # by default - the link_name is included by default
00304 string[] touch_links
00305
00306 ================================================================================
00307 MSG: arm_navigation_msgs/CollisionMap
00308 #header for interpreting box positions
00309 Header header
00310
00311 #boxes for use in collision testing
00312 OrientedBoundingBox[] boxes
00313
00314 ================================================================================
00315 MSG: arm_navigation_msgs/OrientedBoundingBox
00316 #the center of the box
00317 geometry_msgs/Point32 center
00318
00319 #the extents of the box, assuming the center is at the point
00320 geometry_msgs/Point32 extents
00321
00322 #the axis of the box
00323 geometry_msgs/Point32 axis
00324
00325 #the angle of rotation around the axis
00326 float32 angle
00327
00328 ================================================================================
00329 MSG: geometry_msgs/Point32
00330 # This contains the position of a point in free space(with 32 bits of precision).
00331 # It is recommeded to use Point wherever possible instead of Point32.
00332 #
00333 # This recommendation is to promote interoperability.
00334 #
00335 # This message is designed to take up less space when sending
00336 # lots of points at once, as in the case of a PointCloud.
00337
00338 float32 x
00339 float32 y
00340 float32 z
00341 ================================================================================
00342 MSG: arm_navigation_msgs/OrderedCollisionOperations
00343 # A set of collision operations that will be performed in the order they are specified
00344 CollisionOperation[] collision_operations
00345 ================================================================================
00346 MSG: arm_navigation_msgs/CollisionOperation
00347 # A definition of a collision operation
00348 # E.g. ("gripper",COLLISION_SET_ALL,ENABLE) will enable collisions
00349 # between the gripper and all objects in the collision space
00350
00351 string object1
00352 string object2
00353 string COLLISION_SET_ALL="all"
00354 string COLLISION_SET_OBJECTS="objects"
00355 string COLLISION_SET_ATTACHED_OBJECTS="attached"
00356
00357 # The penetration distance to which collisions are allowed. This is 0.0 by default.
00358 float64 penetration_distance
00359
00360 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above
00361 int32 operation
00362 int32 DISABLE=0
00363 int32 ENABLE=1
00364
00365 """
00366 __slots__ = ['planning_scene_diff','operations']
00367 _slot_types = ['arm_navigation_msgs/PlanningScene','arm_navigation_msgs/OrderedCollisionOperations']
00368
00369 def __init__(self, *args, **kwds):
00370 """
00371 Constructor. Any message fields that are implicitly/explicitly
00372 set to None will be assigned a default value. The recommend
00373 use is keyword arguments as this is more robust to future message
00374 changes. You cannot mix in-order arguments and keyword arguments.
00375
00376 The available fields are:
00377 planning_scene_diff,operations
00378
00379 :param args: complete set of field values, in .msg order
00380 :param kwds: use keyword arguments corresponding to message field names
00381 to set specific fields.
00382 """
00383 if args or kwds:
00384 super(GetPlanningSceneRequest, self).__init__(*args, **kwds)
00385
00386 if self.planning_scene_diff is None:
00387 self.planning_scene_diff = arm_navigation_msgs.msg.PlanningScene()
00388 if self.operations is None:
00389 self.operations = arm_navigation_msgs.msg.OrderedCollisionOperations()
00390 else:
00391 self.planning_scene_diff = arm_navigation_msgs.msg.PlanningScene()
00392 self.operations = arm_navigation_msgs.msg.OrderedCollisionOperations()
00393
00394 def _get_types(self):
00395 """
00396 internal API method
00397 """
00398 return self._slot_types
00399
00400 def serialize(self, buff):
00401 """
00402 serialize message into buffer
00403 :param buff: buffer, ``StringIO``
00404 """
00405 try:
00406 _x = self
00407 buff.write(_struct_3I.pack(_x.planning_scene_diff.robot_state.joint_state.header.seq, _x.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs))
00408 _x = self.planning_scene_diff.robot_state.joint_state.header.frame_id
00409 length = len(_x)
00410 if python3 or type(_x) == unicode:
00411 _x = _x.encode('utf-8')
00412 length = len(_x)
00413 buff.write(struct.pack('<I%ss'%length, length, _x))
00414 length = len(self.planning_scene_diff.robot_state.joint_state.name)
00415 buff.write(_struct_I.pack(length))
00416 for val1 in self.planning_scene_diff.robot_state.joint_state.name:
00417 length = len(val1)
00418 if python3 or type(val1) == unicode:
00419 val1 = val1.encode('utf-8')
00420 length = len(val1)
00421 buff.write(struct.pack('<I%ss'%length, length, val1))
00422 length = len(self.planning_scene_diff.robot_state.joint_state.position)
00423 buff.write(_struct_I.pack(length))
00424 pattern = '<%sd'%length
00425 buff.write(struct.pack(pattern, *self.planning_scene_diff.robot_state.joint_state.position))
00426 length = len(self.planning_scene_diff.robot_state.joint_state.velocity)
00427 buff.write(_struct_I.pack(length))
00428 pattern = '<%sd'%length
00429 buff.write(struct.pack(pattern, *self.planning_scene_diff.robot_state.joint_state.velocity))
00430 length = len(self.planning_scene_diff.robot_state.joint_state.effort)
00431 buff.write(_struct_I.pack(length))
00432 pattern = '<%sd'%length
00433 buff.write(struct.pack(pattern, *self.planning_scene_diff.robot_state.joint_state.effort))
00434 _x = self
00435 buff.write(_struct_2I.pack(_x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs))
00436 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names)
00437 buff.write(_struct_I.pack(length))
00438 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names:
00439 length = len(val1)
00440 if python3 or type(val1) == unicode:
00441 val1 = val1.encode('utf-8')
00442 length = len(val1)
00443 buff.write(struct.pack('<I%ss'%length, length, val1))
00444 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids)
00445 buff.write(_struct_I.pack(length))
00446 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids:
00447 length = len(val1)
00448 if python3 or type(val1) == unicode:
00449 val1 = val1.encode('utf-8')
00450 length = len(val1)
00451 buff.write(struct.pack('<I%ss'%length, length, val1))
00452 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids)
00453 buff.write(_struct_I.pack(length))
00454 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids:
00455 length = len(val1)
00456 if python3 or type(val1) == unicode:
00457 val1 = val1.encode('utf-8')
00458 length = len(val1)
00459 buff.write(struct.pack('<I%ss'%length, length, val1))
00460 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.poses)
00461 buff.write(_struct_I.pack(length))
00462 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.poses:
00463 _v1 = val1.position
00464 _x = _v1
00465 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00466 _v2 = val1.orientation
00467 _x = _v2
00468 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00469 length = len(self.planning_scene_diff.fixed_frame_transforms)
00470 buff.write(_struct_I.pack(length))
00471 for val1 in self.planning_scene_diff.fixed_frame_transforms:
00472 _v3 = val1.header
00473 buff.write(_struct_I.pack(_v3.seq))
00474 _v4 = _v3.stamp
00475 _x = _v4
00476 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00477 _x = _v3.frame_id
00478 length = len(_x)
00479 if python3 or type(_x) == unicode:
00480 _x = _x.encode('utf-8')
00481 length = len(_x)
00482 buff.write(struct.pack('<I%ss'%length, length, _x))
00483 _x = val1.child_frame_id
00484 length = len(_x)
00485 if python3 or type(_x) == unicode:
00486 _x = _x.encode('utf-8')
00487 length = len(_x)
00488 buff.write(struct.pack('<I%ss'%length, length, _x))
00489 _v5 = val1.transform
00490 _v6 = _v5.translation
00491 _x = _v6
00492 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00493 _v7 = _v5.rotation
00494 _x = _v7
00495 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00496 length = len(self.planning_scene_diff.allowed_collision_matrix.link_names)
00497 buff.write(_struct_I.pack(length))
00498 for val1 in self.planning_scene_diff.allowed_collision_matrix.link_names:
00499 length = len(val1)
00500 if python3 or type(val1) == unicode:
00501 val1 = val1.encode('utf-8')
00502 length = len(val1)
00503 buff.write(struct.pack('<I%ss'%length, length, val1))
00504 length = len(self.planning_scene_diff.allowed_collision_matrix.entries)
00505 buff.write(_struct_I.pack(length))
00506 for val1 in self.planning_scene_diff.allowed_collision_matrix.entries:
00507 length = len(val1.enabled)
00508 buff.write(_struct_I.pack(length))
00509 pattern = '<%sB'%length
00510 buff.write(struct.pack(pattern, *val1.enabled))
00511 length = len(self.planning_scene_diff.allowed_contacts)
00512 buff.write(_struct_I.pack(length))
00513 for val1 in self.planning_scene_diff.allowed_contacts:
00514 _x = val1.name
00515 length = len(_x)
00516 if python3 or type(_x) == unicode:
00517 _x = _x.encode('utf-8')
00518 length = len(_x)
00519 buff.write(struct.pack('<I%ss'%length, length, _x))
00520 _v8 = val1.shape
00521 buff.write(_struct_b.pack(_v8.type))
00522 length = len(_v8.dimensions)
00523 buff.write(_struct_I.pack(length))
00524 pattern = '<%sd'%length
00525 buff.write(struct.pack(pattern, *_v8.dimensions))
00526 length = len(_v8.triangles)
00527 buff.write(_struct_I.pack(length))
00528 pattern = '<%si'%length
00529 buff.write(struct.pack(pattern, *_v8.triangles))
00530 length = len(_v8.vertices)
00531 buff.write(_struct_I.pack(length))
00532 for val3 in _v8.vertices:
00533 _x = val3
00534 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00535 _v9 = val1.pose_stamped
00536 _v10 = _v9.header
00537 buff.write(_struct_I.pack(_v10.seq))
00538 _v11 = _v10.stamp
00539 _x = _v11
00540 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00541 _x = _v10.frame_id
00542 length = len(_x)
00543 if python3 or type(_x) == unicode:
00544 _x = _x.encode('utf-8')
00545 length = len(_x)
00546 buff.write(struct.pack('<I%ss'%length, length, _x))
00547 _v12 = _v9.pose
00548 _v13 = _v12.position
00549 _x = _v13
00550 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00551 _v14 = _v12.orientation
00552 _x = _v14
00553 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00554 length = len(val1.link_names)
00555 buff.write(_struct_I.pack(length))
00556 for val2 in val1.link_names:
00557 length = len(val2)
00558 if python3 or type(val2) == unicode:
00559 val2 = val2.encode('utf-8')
00560 length = len(val2)
00561 buff.write(struct.pack('<I%ss'%length, length, val2))
00562 buff.write(_struct_d.pack(val1.penetration_depth))
00563 length = len(self.planning_scene_diff.link_padding)
00564 buff.write(_struct_I.pack(length))
00565 for val1 in self.planning_scene_diff.link_padding:
00566 _x = val1.link_name
00567 length = len(_x)
00568 if python3 or type(_x) == unicode:
00569 _x = _x.encode('utf-8')
00570 length = len(_x)
00571 buff.write(struct.pack('<I%ss'%length, length, _x))
00572 buff.write(_struct_d.pack(val1.padding))
00573 length = len(self.planning_scene_diff.collision_objects)
00574 buff.write(_struct_I.pack(length))
00575 for val1 in self.planning_scene_diff.collision_objects:
00576 _v15 = val1.header
00577 buff.write(_struct_I.pack(_v15.seq))
00578 _v16 = _v15.stamp
00579 _x = _v16
00580 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00581 _x = _v15.frame_id
00582 length = len(_x)
00583 if python3 or type(_x) == unicode:
00584 _x = _x.encode('utf-8')
00585 length = len(_x)
00586 buff.write(struct.pack('<I%ss'%length, length, _x))
00587 _x = val1.id
00588 length = len(_x)
00589 if python3 or type(_x) == unicode:
00590 _x = _x.encode('utf-8')
00591 length = len(_x)
00592 buff.write(struct.pack('<I%ss'%length, length, _x))
00593 buff.write(_struct_f.pack(val1.padding))
00594 _v17 = val1.operation
00595 buff.write(_struct_b.pack(_v17.operation))
00596 length = len(val1.shapes)
00597 buff.write(_struct_I.pack(length))
00598 for val2 in val1.shapes:
00599 buff.write(_struct_b.pack(val2.type))
00600 length = len(val2.dimensions)
00601 buff.write(_struct_I.pack(length))
00602 pattern = '<%sd'%length
00603 buff.write(struct.pack(pattern, *val2.dimensions))
00604 length = len(val2.triangles)
00605 buff.write(_struct_I.pack(length))
00606 pattern = '<%si'%length
00607 buff.write(struct.pack(pattern, *val2.triangles))
00608 length = len(val2.vertices)
00609 buff.write(_struct_I.pack(length))
00610 for val3 in val2.vertices:
00611 _x = val3
00612 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00613 length = len(val1.poses)
00614 buff.write(_struct_I.pack(length))
00615 for val2 in val1.poses:
00616 _v18 = val2.position
00617 _x = _v18
00618 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00619 _v19 = val2.orientation
00620 _x = _v19
00621 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00622 length = len(self.planning_scene_diff.attached_collision_objects)
00623 buff.write(_struct_I.pack(length))
00624 for val1 in self.planning_scene_diff.attached_collision_objects:
00625 _x = val1.link_name
00626 length = len(_x)
00627 if python3 or type(_x) == unicode:
00628 _x = _x.encode('utf-8')
00629 length = len(_x)
00630 buff.write(struct.pack('<I%ss'%length, length, _x))
00631 _v20 = val1.object
00632 _v21 = _v20.header
00633 buff.write(_struct_I.pack(_v21.seq))
00634 _v22 = _v21.stamp
00635 _x = _v22
00636 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00637 _x = _v21.frame_id
00638 length = len(_x)
00639 if python3 or type(_x) == unicode:
00640 _x = _x.encode('utf-8')
00641 length = len(_x)
00642 buff.write(struct.pack('<I%ss'%length, length, _x))
00643 _x = _v20.id
00644 length = len(_x)
00645 if python3 or type(_x) == unicode:
00646 _x = _x.encode('utf-8')
00647 length = len(_x)
00648 buff.write(struct.pack('<I%ss'%length, length, _x))
00649 buff.write(_struct_f.pack(_v20.padding))
00650 _v23 = _v20.operation
00651 buff.write(_struct_b.pack(_v23.operation))
00652 length = len(_v20.shapes)
00653 buff.write(_struct_I.pack(length))
00654 for val3 in _v20.shapes:
00655 buff.write(_struct_b.pack(val3.type))
00656 length = len(val3.dimensions)
00657 buff.write(_struct_I.pack(length))
00658 pattern = '<%sd'%length
00659 buff.write(struct.pack(pattern, *val3.dimensions))
00660 length = len(val3.triangles)
00661 buff.write(_struct_I.pack(length))
00662 pattern = '<%si'%length
00663 buff.write(struct.pack(pattern, *val3.triangles))
00664 length = len(val3.vertices)
00665 buff.write(_struct_I.pack(length))
00666 for val4 in val3.vertices:
00667 _x = val4
00668 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00669 length = len(_v20.poses)
00670 buff.write(_struct_I.pack(length))
00671 for val3 in _v20.poses:
00672 _v24 = val3.position
00673 _x = _v24
00674 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00675 _v25 = val3.orientation
00676 _x = _v25
00677 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00678 length = len(val1.touch_links)
00679 buff.write(_struct_I.pack(length))
00680 for val2 in val1.touch_links:
00681 length = len(val2)
00682 if python3 or type(val2) == unicode:
00683 val2 = val2.encode('utf-8')
00684 length = len(val2)
00685 buff.write(struct.pack('<I%ss'%length, length, val2))
00686 _x = self
00687 buff.write(_struct_3I.pack(_x.planning_scene_diff.collision_map.header.seq, _x.planning_scene_diff.collision_map.header.stamp.secs, _x.planning_scene_diff.collision_map.header.stamp.nsecs))
00688 _x = self.planning_scene_diff.collision_map.header.frame_id
00689 length = len(_x)
00690 if python3 or type(_x) == unicode:
00691 _x = _x.encode('utf-8')
00692 length = len(_x)
00693 buff.write(struct.pack('<I%ss'%length, length, _x))
00694 length = len(self.planning_scene_diff.collision_map.boxes)
00695 buff.write(_struct_I.pack(length))
00696 for val1 in self.planning_scene_diff.collision_map.boxes:
00697 _v26 = val1.center
00698 _x = _v26
00699 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00700 _v27 = val1.extents
00701 _x = _v27
00702 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00703 _v28 = val1.axis
00704 _x = _v28
00705 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00706 buff.write(_struct_f.pack(val1.angle))
00707 length = len(self.operations.collision_operations)
00708 buff.write(_struct_I.pack(length))
00709 for val1 in self.operations.collision_operations:
00710 _x = val1.object1
00711 length = len(_x)
00712 if python3 or type(_x) == unicode:
00713 _x = _x.encode('utf-8')
00714 length = len(_x)
00715 buff.write(struct.pack('<I%ss'%length, length, _x))
00716 _x = val1.object2
00717 length = len(_x)
00718 if python3 or type(_x) == unicode:
00719 _x = _x.encode('utf-8')
00720 length = len(_x)
00721 buff.write(struct.pack('<I%ss'%length, length, _x))
00722 _x = val1
00723 buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
00724 except struct.error as se: self._check_types(se)
00725 except TypeError as te: self._check_types(te)
00726
00727 def deserialize(self, str):
00728 """
00729 unpack serialized message in str into this message instance
00730 :param str: byte array of serialized message, ``str``
00731 """
00732 try:
00733 if self.planning_scene_diff is None:
00734 self.planning_scene_diff = arm_navigation_msgs.msg.PlanningScene()
00735 if self.operations is None:
00736 self.operations = arm_navigation_msgs.msg.OrderedCollisionOperations()
00737 end = 0
00738 _x = self
00739 start = end
00740 end += 12
00741 (_x.planning_scene_diff.robot_state.joint_state.header.seq, _x.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00742 start = end
00743 end += 4
00744 (length,) = _struct_I.unpack(str[start:end])
00745 start = end
00746 end += length
00747 if python3:
00748 self.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
00749 else:
00750 self.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end]
00751 start = end
00752 end += 4
00753 (length,) = _struct_I.unpack(str[start:end])
00754 self.planning_scene_diff.robot_state.joint_state.name = []
00755 for i in range(0, length):
00756 start = end
00757 end += 4
00758 (length,) = _struct_I.unpack(str[start:end])
00759 start = end
00760 end += length
00761 if python3:
00762 val1 = str[start:end].decode('utf-8')
00763 else:
00764 val1 = str[start:end]
00765 self.planning_scene_diff.robot_state.joint_state.name.append(val1)
00766 start = end
00767 end += 4
00768 (length,) = _struct_I.unpack(str[start:end])
00769 pattern = '<%sd'%length
00770 start = end
00771 end += struct.calcsize(pattern)
00772 self.planning_scene_diff.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
00773 start = end
00774 end += 4
00775 (length,) = _struct_I.unpack(str[start:end])
00776 pattern = '<%sd'%length
00777 start = end
00778 end += struct.calcsize(pattern)
00779 self.planning_scene_diff.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
00780 start = end
00781 end += 4
00782 (length,) = _struct_I.unpack(str[start:end])
00783 pattern = '<%sd'%length
00784 start = end
00785 end += struct.calcsize(pattern)
00786 self.planning_scene_diff.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
00787 _x = self
00788 start = end
00789 end += 8
00790 (_x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00791 start = end
00792 end += 4
00793 (length,) = _struct_I.unpack(str[start:end])
00794 self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names = []
00795 for i in range(0, length):
00796 start = end
00797 end += 4
00798 (length,) = _struct_I.unpack(str[start:end])
00799 start = end
00800 end += length
00801 if python3:
00802 val1 = str[start:end].decode('utf-8')
00803 else:
00804 val1 = str[start:end]
00805 self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names.append(val1)
00806 start = end
00807 end += 4
00808 (length,) = _struct_I.unpack(str[start:end])
00809 self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids = []
00810 for i in range(0, length):
00811 start = end
00812 end += 4
00813 (length,) = _struct_I.unpack(str[start:end])
00814 start = end
00815 end += length
00816 if python3:
00817 val1 = str[start:end].decode('utf-8')
00818 else:
00819 val1 = str[start:end]
00820 self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids.append(val1)
00821 start = end
00822 end += 4
00823 (length,) = _struct_I.unpack(str[start:end])
00824 self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids = []
00825 for i in range(0, length):
00826 start = end
00827 end += 4
00828 (length,) = _struct_I.unpack(str[start:end])
00829 start = end
00830 end += length
00831 if python3:
00832 val1 = str[start:end].decode('utf-8')
00833 else:
00834 val1 = str[start:end]
00835 self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
00836 start = end
00837 end += 4
00838 (length,) = _struct_I.unpack(str[start:end])
00839 self.planning_scene_diff.robot_state.multi_dof_joint_state.poses = []
00840 for i in range(0, length):
00841 val1 = geometry_msgs.msg.Pose()
00842 _v29 = val1.position
00843 _x = _v29
00844 start = end
00845 end += 24
00846 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00847 _v30 = val1.orientation
00848 _x = _v30
00849 start = end
00850 end += 32
00851 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00852 self.planning_scene_diff.robot_state.multi_dof_joint_state.poses.append(val1)
00853 start = end
00854 end += 4
00855 (length,) = _struct_I.unpack(str[start:end])
00856 self.planning_scene_diff.fixed_frame_transforms = []
00857 for i in range(0, length):
00858 val1 = geometry_msgs.msg.TransformStamped()
00859 _v31 = val1.header
00860 start = end
00861 end += 4
00862 (_v31.seq,) = _struct_I.unpack(str[start:end])
00863 _v32 = _v31.stamp
00864 _x = _v32
00865 start = end
00866 end += 8
00867 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00868 start = end
00869 end += 4
00870 (length,) = _struct_I.unpack(str[start:end])
00871 start = end
00872 end += length
00873 if python3:
00874 _v31.frame_id = str[start:end].decode('utf-8')
00875 else:
00876 _v31.frame_id = str[start:end]
00877 start = end
00878 end += 4
00879 (length,) = _struct_I.unpack(str[start:end])
00880 start = end
00881 end += length
00882 if python3:
00883 val1.child_frame_id = str[start:end].decode('utf-8')
00884 else:
00885 val1.child_frame_id = str[start:end]
00886 _v33 = val1.transform
00887 _v34 = _v33.translation
00888 _x = _v34
00889 start = end
00890 end += 24
00891 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00892 _v35 = _v33.rotation
00893 _x = _v35
00894 start = end
00895 end += 32
00896 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00897 self.planning_scene_diff.fixed_frame_transforms.append(val1)
00898 start = end
00899 end += 4
00900 (length,) = _struct_I.unpack(str[start:end])
00901 self.planning_scene_diff.allowed_collision_matrix.link_names = []
00902 for i in range(0, length):
00903 start = end
00904 end += 4
00905 (length,) = _struct_I.unpack(str[start:end])
00906 start = end
00907 end += length
00908 if python3:
00909 val1 = str[start:end].decode('utf-8')
00910 else:
00911 val1 = str[start:end]
00912 self.planning_scene_diff.allowed_collision_matrix.link_names.append(val1)
00913 start = end
00914 end += 4
00915 (length,) = _struct_I.unpack(str[start:end])
00916 self.planning_scene_diff.allowed_collision_matrix.entries = []
00917 for i in range(0, length):
00918 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
00919 start = end
00920 end += 4
00921 (length,) = _struct_I.unpack(str[start:end])
00922 pattern = '<%sB'%length
00923 start = end
00924 end += struct.calcsize(pattern)
00925 val1.enabled = struct.unpack(pattern, str[start:end])
00926 val1.enabled = map(bool, val1.enabled)
00927 self.planning_scene_diff.allowed_collision_matrix.entries.append(val1)
00928 start = end
00929 end += 4
00930 (length,) = _struct_I.unpack(str[start:end])
00931 self.planning_scene_diff.allowed_contacts = []
00932 for i in range(0, length):
00933 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
00934 start = end
00935 end += 4
00936 (length,) = _struct_I.unpack(str[start:end])
00937 start = end
00938 end += length
00939 if python3:
00940 val1.name = str[start:end].decode('utf-8')
00941 else:
00942 val1.name = str[start:end]
00943 _v36 = val1.shape
00944 start = end
00945 end += 1
00946 (_v36.type,) = _struct_b.unpack(str[start:end])
00947 start = end
00948 end += 4
00949 (length,) = _struct_I.unpack(str[start:end])
00950 pattern = '<%sd'%length
00951 start = end
00952 end += struct.calcsize(pattern)
00953 _v36.dimensions = struct.unpack(pattern, str[start:end])
00954 start = end
00955 end += 4
00956 (length,) = _struct_I.unpack(str[start:end])
00957 pattern = '<%si'%length
00958 start = end
00959 end += struct.calcsize(pattern)
00960 _v36.triangles = struct.unpack(pattern, str[start:end])
00961 start = end
00962 end += 4
00963 (length,) = _struct_I.unpack(str[start:end])
00964 _v36.vertices = []
00965 for i in range(0, length):
00966 val3 = geometry_msgs.msg.Point()
00967 _x = val3
00968 start = end
00969 end += 24
00970 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00971 _v36.vertices.append(val3)
00972 _v37 = val1.pose_stamped
00973 _v38 = _v37.header
00974 start = end
00975 end += 4
00976 (_v38.seq,) = _struct_I.unpack(str[start:end])
00977 _v39 = _v38.stamp
00978 _x = _v39
00979 start = end
00980 end += 8
00981 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00982 start = end
00983 end += 4
00984 (length,) = _struct_I.unpack(str[start:end])
00985 start = end
00986 end += length
00987 if python3:
00988 _v38.frame_id = str[start:end].decode('utf-8')
00989 else:
00990 _v38.frame_id = str[start:end]
00991 _v40 = _v37.pose
00992 _v41 = _v40.position
00993 _x = _v41
00994 start = end
00995 end += 24
00996 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00997 _v42 = _v40.orientation
00998 _x = _v42
00999 start = end
01000 end += 32
01001 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01002 start = end
01003 end += 4
01004 (length,) = _struct_I.unpack(str[start:end])
01005 val1.link_names = []
01006 for i in range(0, length):
01007 start = end
01008 end += 4
01009 (length,) = _struct_I.unpack(str[start:end])
01010 start = end
01011 end += length
01012 if python3:
01013 val2 = str[start:end].decode('utf-8')
01014 else:
01015 val2 = str[start:end]
01016 val1.link_names.append(val2)
01017 start = end
01018 end += 8
01019 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
01020 self.planning_scene_diff.allowed_contacts.append(val1)
01021 start = end
01022 end += 4
01023 (length,) = _struct_I.unpack(str[start:end])
01024 self.planning_scene_diff.link_padding = []
01025 for i in range(0, length):
01026 val1 = arm_navigation_msgs.msg.LinkPadding()
01027 start = end
01028 end += 4
01029 (length,) = _struct_I.unpack(str[start:end])
01030 start = end
01031 end += length
01032 if python3:
01033 val1.link_name = str[start:end].decode('utf-8')
01034 else:
01035 val1.link_name = str[start:end]
01036 start = end
01037 end += 8
01038 (val1.padding,) = _struct_d.unpack(str[start:end])
01039 self.planning_scene_diff.link_padding.append(val1)
01040 start = end
01041 end += 4
01042 (length,) = _struct_I.unpack(str[start:end])
01043 self.planning_scene_diff.collision_objects = []
01044 for i in range(0, length):
01045 val1 = arm_navigation_msgs.msg.CollisionObject()
01046 _v43 = val1.header
01047 start = end
01048 end += 4
01049 (_v43.seq,) = _struct_I.unpack(str[start:end])
01050 _v44 = _v43.stamp
01051 _x = _v44
01052 start = end
01053 end += 8
01054 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01055 start = end
01056 end += 4
01057 (length,) = _struct_I.unpack(str[start:end])
01058 start = end
01059 end += length
01060 if python3:
01061 _v43.frame_id = str[start:end].decode('utf-8')
01062 else:
01063 _v43.frame_id = str[start:end]
01064 start = end
01065 end += 4
01066 (length,) = _struct_I.unpack(str[start:end])
01067 start = end
01068 end += length
01069 if python3:
01070 val1.id = str[start:end].decode('utf-8')
01071 else:
01072 val1.id = str[start:end]
01073 start = end
01074 end += 4
01075 (val1.padding,) = _struct_f.unpack(str[start:end])
01076 _v45 = val1.operation
01077 start = end
01078 end += 1
01079 (_v45.operation,) = _struct_b.unpack(str[start:end])
01080 start = end
01081 end += 4
01082 (length,) = _struct_I.unpack(str[start:end])
01083 val1.shapes = []
01084 for i in range(0, length):
01085 val2 = arm_navigation_msgs.msg.Shape()
01086 start = end
01087 end += 1
01088 (val2.type,) = _struct_b.unpack(str[start:end])
01089 start = end
01090 end += 4
01091 (length,) = _struct_I.unpack(str[start:end])
01092 pattern = '<%sd'%length
01093 start = end
01094 end += struct.calcsize(pattern)
01095 val2.dimensions = struct.unpack(pattern, str[start:end])
01096 start = end
01097 end += 4
01098 (length,) = _struct_I.unpack(str[start:end])
01099 pattern = '<%si'%length
01100 start = end
01101 end += struct.calcsize(pattern)
01102 val2.triangles = struct.unpack(pattern, str[start:end])
01103 start = end
01104 end += 4
01105 (length,) = _struct_I.unpack(str[start:end])
01106 val2.vertices = []
01107 for i in range(0, length):
01108 val3 = geometry_msgs.msg.Point()
01109 _x = val3
01110 start = end
01111 end += 24
01112 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01113 val2.vertices.append(val3)
01114 val1.shapes.append(val2)
01115 start = end
01116 end += 4
01117 (length,) = _struct_I.unpack(str[start:end])
01118 val1.poses = []
01119 for i in range(0, length):
01120 val2 = geometry_msgs.msg.Pose()
01121 _v46 = val2.position
01122 _x = _v46
01123 start = end
01124 end += 24
01125 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01126 _v47 = val2.orientation
01127 _x = _v47
01128 start = end
01129 end += 32
01130 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01131 val1.poses.append(val2)
01132 self.planning_scene_diff.collision_objects.append(val1)
01133 start = end
01134 end += 4
01135 (length,) = _struct_I.unpack(str[start:end])
01136 self.planning_scene_diff.attached_collision_objects = []
01137 for i in range(0, length):
01138 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
01139 start = end
01140 end += 4
01141 (length,) = _struct_I.unpack(str[start:end])
01142 start = end
01143 end += length
01144 if python3:
01145 val1.link_name = str[start:end].decode('utf-8')
01146 else:
01147 val1.link_name = str[start:end]
01148 _v48 = val1.object
01149 _v49 = _v48.header
01150 start = end
01151 end += 4
01152 (_v49.seq,) = _struct_I.unpack(str[start:end])
01153 _v50 = _v49.stamp
01154 _x = _v50
01155 start = end
01156 end += 8
01157 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01158 start = end
01159 end += 4
01160 (length,) = _struct_I.unpack(str[start:end])
01161 start = end
01162 end += length
01163 if python3:
01164 _v49.frame_id = str[start:end].decode('utf-8')
01165 else:
01166 _v49.frame_id = str[start:end]
01167 start = end
01168 end += 4
01169 (length,) = _struct_I.unpack(str[start:end])
01170 start = end
01171 end += length
01172 if python3:
01173 _v48.id = str[start:end].decode('utf-8')
01174 else:
01175 _v48.id = str[start:end]
01176 start = end
01177 end += 4
01178 (_v48.padding,) = _struct_f.unpack(str[start:end])
01179 _v51 = _v48.operation
01180 start = end
01181 end += 1
01182 (_v51.operation,) = _struct_b.unpack(str[start:end])
01183 start = end
01184 end += 4
01185 (length,) = _struct_I.unpack(str[start:end])
01186 _v48.shapes = []
01187 for i in range(0, length):
01188 val3 = arm_navigation_msgs.msg.Shape()
01189 start = end
01190 end += 1
01191 (val3.type,) = _struct_b.unpack(str[start:end])
01192 start = end
01193 end += 4
01194 (length,) = _struct_I.unpack(str[start:end])
01195 pattern = '<%sd'%length
01196 start = end
01197 end += struct.calcsize(pattern)
01198 val3.dimensions = struct.unpack(pattern, str[start:end])
01199 start = end
01200 end += 4
01201 (length,) = _struct_I.unpack(str[start:end])
01202 pattern = '<%si'%length
01203 start = end
01204 end += struct.calcsize(pattern)
01205 val3.triangles = struct.unpack(pattern, str[start:end])
01206 start = end
01207 end += 4
01208 (length,) = _struct_I.unpack(str[start:end])
01209 val3.vertices = []
01210 for i in range(0, length):
01211 val4 = geometry_msgs.msg.Point()
01212 _x = val4
01213 start = end
01214 end += 24
01215 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01216 val3.vertices.append(val4)
01217 _v48.shapes.append(val3)
01218 start = end
01219 end += 4
01220 (length,) = _struct_I.unpack(str[start:end])
01221 _v48.poses = []
01222 for i in range(0, length):
01223 val3 = geometry_msgs.msg.Pose()
01224 _v52 = val3.position
01225 _x = _v52
01226 start = end
01227 end += 24
01228 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01229 _v53 = val3.orientation
01230 _x = _v53
01231 start = end
01232 end += 32
01233 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01234 _v48.poses.append(val3)
01235 start = end
01236 end += 4
01237 (length,) = _struct_I.unpack(str[start:end])
01238 val1.touch_links = []
01239 for i in range(0, length):
01240 start = end
01241 end += 4
01242 (length,) = _struct_I.unpack(str[start:end])
01243 start = end
01244 end += length
01245 if python3:
01246 val2 = str[start:end].decode('utf-8')
01247 else:
01248 val2 = str[start:end]
01249 val1.touch_links.append(val2)
01250 self.planning_scene_diff.attached_collision_objects.append(val1)
01251 _x = self
01252 start = end
01253 end += 12
01254 (_x.planning_scene_diff.collision_map.header.seq, _x.planning_scene_diff.collision_map.header.stamp.secs, _x.planning_scene_diff.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01255 start = end
01256 end += 4
01257 (length,) = _struct_I.unpack(str[start:end])
01258 start = end
01259 end += length
01260 if python3:
01261 self.planning_scene_diff.collision_map.header.frame_id = str[start:end].decode('utf-8')
01262 else:
01263 self.planning_scene_diff.collision_map.header.frame_id = str[start:end]
01264 start = end
01265 end += 4
01266 (length,) = _struct_I.unpack(str[start:end])
01267 self.planning_scene_diff.collision_map.boxes = []
01268 for i in range(0, length):
01269 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
01270 _v54 = val1.center
01271 _x = _v54
01272 start = end
01273 end += 12
01274 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01275 _v55 = val1.extents
01276 _x = _v55
01277 start = end
01278 end += 12
01279 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01280 _v56 = val1.axis
01281 _x = _v56
01282 start = end
01283 end += 12
01284 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01285 start = end
01286 end += 4
01287 (val1.angle,) = _struct_f.unpack(str[start:end])
01288 self.planning_scene_diff.collision_map.boxes.append(val1)
01289 start = end
01290 end += 4
01291 (length,) = _struct_I.unpack(str[start:end])
01292 self.operations.collision_operations = []
01293 for i in range(0, length):
01294 val1 = arm_navigation_msgs.msg.CollisionOperation()
01295 start = end
01296 end += 4
01297 (length,) = _struct_I.unpack(str[start:end])
01298 start = end
01299 end += length
01300 if python3:
01301 val1.object1 = str[start:end].decode('utf-8')
01302 else:
01303 val1.object1 = str[start:end]
01304 start = end
01305 end += 4
01306 (length,) = _struct_I.unpack(str[start:end])
01307 start = end
01308 end += length
01309 if python3:
01310 val1.object2 = str[start:end].decode('utf-8')
01311 else:
01312 val1.object2 = str[start:end]
01313 _x = val1
01314 start = end
01315 end += 12
01316 (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
01317 self.operations.collision_operations.append(val1)
01318 return self
01319 except struct.error as e:
01320 raise genpy.DeserializationError(e)
01321
01322
01323 def serialize_numpy(self, buff, numpy):
01324 """
01325 serialize message with numpy array types into buffer
01326 :param buff: buffer, ``StringIO``
01327 :param numpy: numpy python module
01328 """
01329 try:
01330 _x = self
01331 buff.write(_struct_3I.pack(_x.planning_scene_diff.robot_state.joint_state.header.seq, _x.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs))
01332 _x = self.planning_scene_diff.robot_state.joint_state.header.frame_id
01333 length = len(_x)
01334 if python3 or type(_x) == unicode:
01335 _x = _x.encode('utf-8')
01336 length = len(_x)
01337 buff.write(struct.pack('<I%ss'%length, length, _x))
01338 length = len(self.planning_scene_diff.robot_state.joint_state.name)
01339 buff.write(_struct_I.pack(length))
01340 for val1 in self.planning_scene_diff.robot_state.joint_state.name:
01341 length = len(val1)
01342 if python3 or type(val1) == unicode:
01343 val1 = val1.encode('utf-8')
01344 length = len(val1)
01345 buff.write(struct.pack('<I%ss'%length, length, val1))
01346 length = len(self.planning_scene_diff.robot_state.joint_state.position)
01347 buff.write(_struct_I.pack(length))
01348 pattern = '<%sd'%length
01349 buff.write(self.planning_scene_diff.robot_state.joint_state.position.tostring())
01350 length = len(self.planning_scene_diff.robot_state.joint_state.velocity)
01351 buff.write(_struct_I.pack(length))
01352 pattern = '<%sd'%length
01353 buff.write(self.planning_scene_diff.robot_state.joint_state.velocity.tostring())
01354 length = len(self.planning_scene_diff.robot_state.joint_state.effort)
01355 buff.write(_struct_I.pack(length))
01356 pattern = '<%sd'%length
01357 buff.write(self.planning_scene_diff.robot_state.joint_state.effort.tostring())
01358 _x = self
01359 buff.write(_struct_2I.pack(_x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs))
01360 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names)
01361 buff.write(_struct_I.pack(length))
01362 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names:
01363 length = len(val1)
01364 if python3 or type(val1) == unicode:
01365 val1 = val1.encode('utf-8')
01366 length = len(val1)
01367 buff.write(struct.pack('<I%ss'%length, length, val1))
01368 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids)
01369 buff.write(_struct_I.pack(length))
01370 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids:
01371 length = len(val1)
01372 if python3 or type(val1) == unicode:
01373 val1 = val1.encode('utf-8')
01374 length = len(val1)
01375 buff.write(struct.pack('<I%ss'%length, length, val1))
01376 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids)
01377 buff.write(_struct_I.pack(length))
01378 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids:
01379 length = len(val1)
01380 if python3 or type(val1) == unicode:
01381 val1 = val1.encode('utf-8')
01382 length = len(val1)
01383 buff.write(struct.pack('<I%ss'%length, length, val1))
01384 length = len(self.planning_scene_diff.robot_state.multi_dof_joint_state.poses)
01385 buff.write(_struct_I.pack(length))
01386 for val1 in self.planning_scene_diff.robot_state.multi_dof_joint_state.poses:
01387 _v57 = val1.position
01388 _x = _v57
01389 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01390 _v58 = val1.orientation
01391 _x = _v58
01392 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01393 length = len(self.planning_scene_diff.fixed_frame_transforms)
01394 buff.write(_struct_I.pack(length))
01395 for val1 in self.planning_scene_diff.fixed_frame_transforms:
01396 _v59 = val1.header
01397 buff.write(_struct_I.pack(_v59.seq))
01398 _v60 = _v59.stamp
01399 _x = _v60
01400 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01401 _x = _v59.frame_id
01402 length = len(_x)
01403 if python3 or type(_x) == unicode:
01404 _x = _x.encode('utf-8')
01405 length = len(_x)
01406 buff.write(struct.pack('<I%ss'%length, length, _x))
01407 _x = val1.child_frame_id
01408 length = len(_x)
01409 if python3 or type(_x) == unicode:
01410 _x = _x.encode('utf-8')
01411 length = len(_x)
01412 buff.write(struct.pack('<I%ss'%length, length, _x))
01413 _v61 = val1.transform
01414 _v62 = _v61.translation
01415 _x = _v62
01416 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01417 _v63 = _v61.rotation
01418 _x = _v63
01419 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01420 length = len(self.planning_scene_diff.allowed_collision_matrix.link_names)
01421 buff.write(_struct_I.pack(length))
01422 for val1 in self.planning_scene_diff.allowed_collision_matrix.link_names:
01423 length = len(val1)
01424 if python3 or type(val1) == unicode:
01425 val1 = val1.encode('utf-8')
01426 length = len(val1)
01427 buff.write(struct.pack('<I%ss'%length, length, val1))
01428 length = len(self.planning_scene_diff.allowed_collision_matrix.entries)
01429 buff.write(_struct_I.pack(length))
01430 for val1 in self.planning_scene_diff.allowed_collision_matrix.entries:
01431 length = len(val1.enabled)
01432 buff.write(_struct_I.pack(length))
01433 pattern = '<%sB'%length
01434 buff.write(val1.enabled.tostring())
01435 length = len(self.planning_scene_diff.allowed_contacts)
01436 buff.write(_struct_I.pack(length))
01437 for val1 in self.planning_scene_diff.allowed_contacts:
01438 _x = val1.name
01439 length = len(_x)
01440 if python3 or type(_x) == unicode:
01441 _x = _x.encode('utf-8')
01442 length = len(_x)
01443 buff.write(struct.pack('<I%ss'%length, length, _x))
01444 _v64 = val1.shape
01445 buff.write(_struct_b.pack(_v64.type))
01446 length = len(_v64.dimensions)
01447 buff.write(_struct_I.pack(length))
01448 pattern = '<%sd'%length
01449 buff.write(_v64.dimensions.tostring())
01450 length = len(_v64.triangles)
01451 buff.write(_struct_I.pack(length))
01452 pattern = '<%si'%length
01453 buff.write(_v64.triangles.tostring())
01454 length = len(_v64.vertices)
01455 buff.write(_struct_I.pack(length))
01456 for val3 in _v64.vertices:
01457 _x = val3
01458 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01459 _v65 = val1.pose_stamped
01460 _v66 = _v65.header
01461 buff.write(_struct_I.pack(_v66.seq))
01462 _v67 = _v66.stamp
01463 _x = _v67
01464 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01465 _x = _v66.frame_id
01466 length = len(_x)
01467 if python3 or type(_x) == unicode:
01468 _x = _x.encode('utf-8')
01469 length = len(_x)
01470 buff.write(struct.pack('<I%ss'%length, length, _x))
01471 _v68 = _v65.pose
01472 _v69 = _v68.position
01473 _x = _v69
01474 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01475 _v70 = _v68.orientation
01476 _x = _v70
01477 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01478 length = len(val1.link_names)
01479 buff.write(_struct_I.pack(length))
01480 for val2 in val1.link_names:
01481 length = len(val2)
01482 if python3 or type(val2) == unicode:
01483 val2 = val2.encode('utf-8')
01484 length = len(val2)
01485 buff.write(struct.pack('<I%ss'%length, length, val2))
01486 buff.write(_struct_d.pack(val1.penetration_depth))
01487 length = len(self.planning_scene_diff.link_padding)
01488 buff.write(_struct_I.pack(length))
01489 for val1 in self.planning_scene_diff.link_padding:
01490 _x = val1.link_name
01491 length = len(_x)
01492 if python3 or type(_x) == unicode:
01493 _x = _x.encode('utf-8')
01494 length = len(_x)
01495 buff.write(struct.pack('<I%ss'%length, length, _x))
01496 buff.write(_struct_d.pack(val1.padding))
01497 length = len(self.planning_scene_diff.collision_objects)
01498 buff.write(_struct_I.pack(length))
01499 for val1 in self.planning_scene_diff.collision_objects:
01500 _v71 = val1.header
01501 buff.write(_struct_I.pack(_v71.seq))
01502 _v72 = _v71.stamp
01503 _x = _v72
01504 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01505 _x = _v71.frame_id
01506 length = len(_x)
01507 if python3 or type(_x) == unicode:
01508 _x = _x.encode('utf-8')
01509 length = len(_x)
01510 buff.write(struct.pack('<I%ss'%length, length, _x))
01511 _x = val1.id
01512 length = len(_x)
01513 if python3 or type(_x) == unicode:
01514 _x = _x.encode('utf-8')
01515 length = len(_x)
01516 buff.write(struct.pack('<I%ss'%length, length, _x))
01517 buff.write(_struct_f.pack(val1.padding))
01518 _v73 = val1.operation
01519 buff.write(_struct_b.pack(_v73.operation))
01520 length = len(val1.shapes)
01521 buff.write(_struct_I.pack(length))
01522 for val2 in val1.shapes:
01523 buff.write(_struct_b.pack(val2.type))
01524 length = len(val2.dimensions)
01525 buff.write(_struct_I.pack(length))
01526 pattern = '<%sd'%length
01527 buff.write(val2.dimensions.tostring())
01528 length = len(val2.triangles)
01529 buff.write(_struct_I.pack(length))
01530 pattern = '<%si'%length
01531 buff.write(val2.triangles.tostring())
01532 length = len(val2.vertices)
01533 buff.write(_struct_I.pack(length))
01534 for val3 in val2.vertices:
01535 _x = val3
01536 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01537 length = len(val1.poses)
01538 buff.write(_struct_I.pack(length))
01539 for val2 in val1.poses:
01540 _v74 = val2.position
01541 _x = _v74
01542 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01543 _v75 = val2.orientation
01544 _x = _v75
01545 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01546 length = len(self.planning_scene_diff.attached_collision_objects)
01547 buff.write(_struct_I.pack(length))
01548 for val1 in self.planning_scene_diff.attached_collision_objects:
01549 _x = val1.link_name
01550 length = len(_x)
01551 if python3 or type(_x) == unicode:
01552 _x = _x.encode('utf-8')
01553 length = len(_x)
01554 buff.write(struct.pack('<I%ss'%length, length, _x))
01555 _v76 = val1.object
01556 _v77 = _v76.header
01557 buff.write(_struct_I.pack(_v77.seq))
01558 _v78 = _v77.stamp
01559 _x = _v78
01560 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01561 _x = _v77.frame_id
01562 length = len(_x)
01563 if python3 or type(_x) == unicode:
01564 _x = _x.encode('utf-8')
01565 length = len(_x)
01566 buff.write(struct.pack('<I%ss'%length, length, _x))
01567 _x = _v76.id
01568 length = len(_x)
01569 if python3 or type(_x) == unicode:
01570 _x = _x.encode('utf-8')
01571 length = len(_x)
01572 buff.write(struct.pack('<I%ss'%length, length, _x))
01573 buff.write(_struct_f.pack(_v76.padding))
01574 _v79 = _v76.operation
01575 buff.write(_struct_b.pack(_v79.operation))
01576 length = len(_v76.shapes)
01577 buff.write(_struct_I.pack(length))
01578 for val3 in _v76.shapes:
01579 buff.write(_struct_b.pack(val3.type))
01580 length = len(val3.dimensions)
01581 buff.write(_struct_I.pack(length))
01582 pattern = '<%sd'%length
01583 buff.write(val3.dimensions.tostring())
01584 length = len(val3.triangles)
01585 buff.write(_struct_I.pack(length))
01586 pattern = '<%si'%length
01587 buff.write(val3.triangles.tostring())
01588 length = len(val3.vertices)
01589 buff.write(_struct_I.pack(length))
01590 for val4 in val3.vertices:
01591 _x = val4
01592 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01593 length = len(_v76.poses)
01594 buff.write(_struct_I.pack(length))
01595 for val3 in _v76.poses:
01596 _v80 = val3.position
01597 _x = _v80
01598 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01599 _v81 = val3.orientation
01600 _x = _v81
01601 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01602 length = len(val1.touch_links)
01603 buff.write(_struct_I.pack(length))
01604 for val2 in val1.touch_links:
01605 length = len(val2)
01606 if python3 or type(val2) == unicode:
01607 val2 = val2.encode('utf-8')
01608 length = len(val2)
01609 buff.write(struct.pack('<I%ss'%length, length, val2))
01610 _x = self
01611 buff.write(_struct_3I.pack(_x.planning_scene_diff.collision_map.header.seq, _x.planning_scene_diff.collision_map.header.stamp.secs, _x.planning_scene_diff.collision_map.header.stamp.nsecs))
01612 _x = self.planning_scene_diff.collision_map.header.frame_id
01613 length = len(_x)
01614 if python3 or type(_x) == unicode:
01615 _x = _x.encode('utf-8')
01616 length = len(_x)
01617 buff.write(struct.pack('<I%ss'%length, length, _x))
01618 length = len(self.planning_scene_diff.collision_map.boxes)
01619 buff.write(_struct_I.pack(length))
01620 for val1 in self.planning_scene_diff.collision_map.boxes:
01621 _v82 = val1.center
01622 _x = _v82
01623 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01624 _v83 = val1.extents
01625 _x = _v83
01626 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01627 _v84 = val1.axis
01628 _x = _v84
01629 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01630 buff.write(_struct_f.pack(val1.angle))
01631 length = len(self.operations.collision_operations)
01632 buff.write(_struct_I.pack(length))
01633 for val1 in self.operations.collision_operations:
01634 _x = val1.object1
01635 length = len(_x)
01636 if python3 or type(_x) == unicode:
01637 _x = _x.encode('utf-8')
01638 length = len(_x)
01639 buff.write(struct.pack('<I%ss'%length, length, _x))
01640 _x = val1.object2
01641 length = len(_x)
01642 if python3 or type(_x) == unicode:
01643 _x = _x.encode('utf-8')
01644 length = len(_x)
01645 buff.write(struct.pack('<I%ss'%length, length, _x))
01646 _x = val1
01647 buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
01648 except struct.error as se: self._check_types(se)
01649 except TypeError as te: self._check_types(te)
01650
01651 def deserialize_numpy(self, str, numpy):
01652 """
01653 unpack serialized message in str into this message instance using numpy for array types
01654 :param str: byte array of serialized message, ``str``
01655 :param numpy: numpy python module
01656 """
01657 try:
01658 if self.planning_scene_diff is None:
01659 self.planning_scene_diff = arm_navigation_msgs.msg.PlanningScene()
01660 if self.operations is None:
01661 self.operations = arm_navigation_msgs.msg.OrderedCollisionOperations()
01662 end = 0
01663 _x = self
01664 start = end
01665 end += 12
01666 (_x.planning_scene_diff.robot_state.joint_state.header.seq, _x.planning_scene_diff.robot_state.joint_state.header.stamp.secs, _x.planning_scene_diff.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01667 start = end
01668 end += 4
01669 (length,) = _struct_I.unpack(str[start:end])
01670 start = end
01671 end += length
01672 if python3:
01673 self.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
01674 else:
01675 self.planning_scene_diff.robot_state.joint_state.header.frame_id = str[start:end]
01676 start = end
01677 end += 4
01678 (length,) = _struct_I.unpack(str[start:end])
01679 self.planning_scene_diff.robot_state.joint_state.name = []
01680 for i in range(0, length):
01681 start = end
01682 end += 4
01683 (length,) = _struct_I.unpack(str[start:end])
01684 start = end
01685 end += length
01686 if python3:
01687 val1 = str[start:end].decode('utf-8')
01688 else:
01689 val1 = str[start:end]
01690 self.planning_scene_diff.robot_state.joint_state.name.append(val1)
01691 start = end
01692 end += 4
01693 (length,) = _struct_I.unpack(str[start:end])
01694 pattern = '<%sd'%length
01695 start = end
01696 end += struct.calcsize(pattern)
01697 self.planning_scene_diff.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01698 start = end
01699 end += 4
01700 (length,) = _struct_I.unpack(str[start:end])
01701 pattern = '<%sd'%length
01702 start = end
01703 end += struct.calcsize(pattern)
01704 self.planning_scene_diff.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01705 start = end
01706 end += 4
01707 (length,) = _struct_I.unpack(str[start:end])
01708 pattern = '<%sd'%length
01709 start = end
01710 end += struct.calcsize(pattern)
01711 self.planning_scene_diff.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01712 _x = self
01713 start = end
01714 end += 8
01715 (_x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene_diff.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01716 start = end
01717 end += 4
01718 (length,) = _struct_I.unpack(str[start:end])
01719 self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names = []
01720 for i in range(0, length):
01721 start = end
01722 end += 4
01723 (length,) = _struct_I.unpack(str[start:end])
01724 start = end
01725 end += length
01726 if python3:
01727 val1 = str[start:end].decode('utf-8')
01728 else:
01729 val1 = str[start:end]
01730 self.planning_scene_diff.robot_state.multi_dof_joint_state.joint_names.append(val1)
01731 start = end
01732 end += 4
01733 (length,) = _struct_I.unpack(str[start:end])
01734 self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids = []
01735 for i in range(0, length):
01736 start = end
01737 end += 4
01738 (length,) = _struct_I.unpack(str[start:end])
01739 start = end
01740 end += length
01741 if python3:
01742 val1 = str[start:end].decode('utf-8')
01743 else:
01744 val1 = str[start:end]
01745 self.planning_scene_diff.robot_state.multi_dof_joint_state.frame_ids.append(val1)
01746 start = end
01747 end += 4
01748 (length,) = _struct_I.unpack(str[start:end])
01749 self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids = []
01750 for i in range(0, length):
01751 start = end
01752 end += 4
01753 (length,) = _struct_I.unpack(str[start:end])
01754 start = end
01755 end += length
01756 if python3:
01757 val1 = str[start:end].decode('utf-8')
01758 else:
01759 val1 = str[start:end]
01760 self.planning_scene_diff.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
01761 start = end
01762 end += 4
01763 (length,) = _struct_I.unpack(str[start:end])
01764 self.planning_scene_diff.robot_state.multi_dof_joint_state.poses = []
01765 for i in range(0, length):
01766 val1 = geometry_msgs.msg.Pose()
01767 _v85 = val1.position
01768 _x = _v85
01769 start = end
01770 end += 24
01771 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01772 _v86 = val1.orientation
01773 _x = _v86
01774 start = end
01775 end += 32
01776 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01777 self.planning_scene_diff.robot_state.multi_dof_joint_state.poses.append(val1)
01778 start = end
01779 end += 4
01780 (length,) = _struct_I.unpack(str[start:end])
01781 self.planning_scene_diff.fixed_frame_transforms = []
01782 for i in range(0, length):
01783 val1 = geometry_msgs.msg.TransformStamped()
01784 _v87 = val1.header
01785 start = end
01786 end += 4
01787 (_v87.seq,) = _struct_I.unpack(str[start:end])
01788 _v88 = _v87.stamp
01789 _x = _v88
01790 start = end
01791 end += 8
01792 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01793 start = end
01794 end += 4
01795 (length,) = _struct_I.unpack(str[start:end])
01796 start = end
01797 end += length
01798 if python3:
01799 _v87.frame_id = str[start:end].decode('utf-8')
01800 else:
01801 _v87.frame_id = str[start:end]
01802 start = end
01803 end += 4
01804 (length,) = _struct_I.unpack(str[start:end])
01805 start = end
01806 end += length
01807 if python3:
01808 val1.child_frame_id = str[start:end].decode('utf-8')
01809 else:
01810 val1.child_frame_id = str[start:end]
01811 _v89 = val1.transform
01812 _v90 = _v89.translation
01813 _x = _v90
01814 start = end
01815 end += 24
01816 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01817 _v91 = _v89.rotation
01818 _x = _v91
01819 start = end
01820 end += 32
01821 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01822 self.planning_scene_diff.fixed_frame_transforms.append(val1)
01823 start = end
01824 end += 4
01825 (length,) = _struct_I.unpack(str[start:end])
01826 self.planning_scene_diff.allowed_collision_matrix.link_names = []
01827 for i in range(0, length):
01828 start = end
01829 end += 4
01830 (length,) = _struct_I.unpack(str[start:end])
01831 start = end
01832 end += length
01833 if python3:
01834 val1 = str[start:end].decode('utf-8')
01835 else:
01836 val1 = str[start:end]
01837 self.planning_scene_diff.allowed_collision_matrix.link_names.append(val1)
01838 start = end
01839 end += 4
01840 (length,) = _struct_I.unpack(str[start:end])
01841 self.planning_scene_diff.allowed_collision_matrix.entries = []
01842 for i in range(0, length):
01843 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
01844 start = end
01845 end += 4
01846 (length,) = _struct_I.unpack(str[start:end])
01847 pattern = '<%sB'%length
01848 start = end
01849 end += struct.calcsize(pattern)
01850 val1.enabled = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=length)
01851 val1.enabled = map(bool, val1.enabled)
01852 self.planning_scene_diff.allowed_collision_matrix.entries.append(val1)
01853 start = end
01854 end += 4
01855 (length,) = _struct_I.unpack(str[start:end])
01856 self.planning_scene_diff.allowed_contacts = []
01857 for i in range(0, length):
01858 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
01859 start = end
01860 end += 4
01861 (length,) = _struct_I.unpack(str[start:end])
01862 start = end
01863 end += length
01864 if python3:
01865 val1.name = str[start:end].decode('utf-8')
01866 else:
01867 val1.name = str[start:end]
01868 _v92 = val1.shape
01869 start = end
01870 end += 1
01871 (_v92.type,) = _struct_b.unpack(str[start:end])
01872 start = end
01873 end += 4
01874 (length,) = _struct_I.unpack(str[start:end])
01875 pattern = '<%sd'%length
01876 start = end
01877 end += struct.calcsize(pattern)
01878 _v92.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01879 start = end
01880 end += 4
01881 (length,) = _struct_I.unpack(str[start:end])
01882 pattern = '<%si'%length
01883 start = end
01884 end += struct.calcsize(pattern)
01885 _v92.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01886 start = end
01887 end += 4
01888 (length,) = _struct_I.unpack(str[start:end])
01889 _v92.vertices = []
01890 for i in range(0, length):
01891 val3 = geometry_msgs.msg.Point()
01892 _x = val3
01893 start = end
01894 end += 24
01895 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01896 _v92.vertices.append(val3)
01897 _v93 = val1.pose_stamped
01898 _v94 = _v93.header
01899 start = end
01900 end += 4
01901 (_v94.seq,) = _struct_I.unpack(str[start:end])
01902 _v95 = _v94.stamp
01903 _x = _v95
01904 start = end
01905 end += 8
01906 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01907 start = end
01908 end += 4
01909 (length,) = _struct_I.unpack(str[start:end])
01910 start = end
01911 end += length
01912 if python3:
01913 _v94.frame_id = str[start:end].decode('utf-8')
01914 else:
01915 _v94.frame_id = str[start:end]
01916 _v96 = _v93.pose
01917 _v97 = _v96.position
01918 _x = _v97
01919 start = end
01920 end += 24
01921 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01922 _v98 = _v96.orientation
01923 _x = _v98
01924 start = end
01925 end += 32
01926 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01927 start = end
01928 end += 4
01929 (length,) = _struct_I.unpack(str[start:end])
01930 val1.link_names = []
01931 for i in range(0, length):
01932 start = end
01933 end += 4
01934 (length,) = _struct_I.unpack(str[start:end])
01935 start = end
01936 end += length
01937 if python3:
01938 val2 = str[start:end].decode('utf-8')
01939 else:
01940 val2 = str[start:end]
01941 val1.link_names.append(val2)
01942 start = end
01943 end += 8
01944 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
01945 self.planning_scene_diff.allowed_contacts.append(val1)
01946 start = end
01947 end += 4
01948 (length,) = _struct_I.unpack(str[start:end])
01949 self.planning_scene_diff.link_padding = []
01950 for i in range(0, length):
01951 val1 = arm_navigation_msgs.msg.LinkPadding()
01952 start = end
01953 end += 4
01954 (length,) = _struct_I.unpack(str[start:end])
01955 start = end
01956 end += length
01957 if python3:
01958 val1.link_name = str[start:end].decode('utf-8')
01959 else:
01960 val1.link_name = str[start:end]
01961 start = end
01962 end += 8
01963 (val1.padding,) = _struct_d.unpack(str[start:end])
01964 self.planning_scene_diff.link_padding.append(val1)
01965 start = end
01966 end += 4
01967 (length,) = _struct_I.unpack(str[start:end])
01968 self.planning_scene_diff.collision_objects = []
01969 for i in range(0, length):
01970 val1 = arm_navigation_msgs.msg.CollisionObject()
01971 _v99 = val1.header
01972 start = end
01973 end += 4
01974 (_v99.seq,) = _struct_I.unpack(str[start:end])
01975 _v100 = _v99.stamp
01976 _x = _v100
01977 start = end
01978 end += 8
01979 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01980 start = end
01981 end += 4
01982 (length,) = _struct_I.unpack(str[start:end])
01983 start = end
01984 end += length
01985 if python3:
01986 _v99.frame_id = str[start:end].decode('utf-8')
01987 else:
01988 _v99.frame_id = str[start:end]
01989 start = end
01990 end += 4
01991 (length,) = _struct_I.unpack(str[start:end])
01992 start = end
01993 end += length
01994 if python3:
01995 val1.id = str[start:end].decode('utf-8')
01996 else:
01997 val1.id = str[start:end]
01998 start = end
01999 end += 4
02000 (val1.padding,) = _struct_f.unpack(str[start:end])
02001 _v101 = val1.operation
02002 start = end
02003 end += 1
02004 (_v101.operation,) = _struct_b.unpack(str[start:end])
02005 start = end
02006 end += 4
02007 (length,) = _struct_I.unpack(str[start:end])
02008 val1.shapes = []
02009 for i in range(0, length):
02010 val2 = arm_navigation_msgs.msg.Shape()
02011 start = end
02012 end += 1
02013 (val2.type,) = _struct_b.unpack(str[start:end])
02014 start = end
02015 end += 4
02016 (length,) = _struct_I.unpack(str[start:end])
02017 pattern = '<%sd'%length
02018 start = end
02019 end += struct.calcsize(pattern)
02020 val2.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02021 start = end
02022 end += 4
02023 (length,) = _struct_I.unpack(str[start:end])
02024 pattern = '<%si'%length
02025 start = end
02026 end += struct.calcsize(pattern)
02027 val2.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02028 start = end
02029 end += 4
02030 (length,) = _struct_I.unpack(str[start:end])
02031 val2.vertices = []
02032 for i in range(0, length):
02033 val3 = geometry_msgs.msg.Point()
02034 _x = val3
02035 start = end
02036 end += 24
02037 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02038 val2.vertices.append(val3)
02039 val1.shapes.append(val2)
02040 start = end
02041 end += 4
02042 (length,) = _struct_I.unpack(str[start:end])
02043 val1.poses = []
02044 for i in range(0, length):
02045 val2 = geometry_msgs.msg.Pose()
02046 _v102 = val2.position
02047 _x = _v102
02048 start = end
02049 end += 24
02050 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02051 _v103 = val2.orientation
02052 _x = _v103
02053 start = end
02054 end += 32
02055 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02056 val1.poses.append(val2)
02057 self.planning_scene_diff.collision_objects.append(val1)
02058 start = end
02059 end += 4
02060 (length,) = _struct_I.unpack(str[start:end])
02061 self.planning_scene_diff.attached_collision_objects = []
02062 for i in range(0, length):
02063 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
02064 start = end
02065 end += 4
02066 (length,) = _struct_I.unpack(str[start:end])
02067 start = end
02068 end += length
02069 if python3:
02070 val1.link_name = str[start:end].decode('utf-8')
02071 else:
02072 val1.link_name = str[start:end]
02073 _v104 = val1.object
02074 _v105 = _v104.header
02075 start = end
02076 end += 4
02077 (_v105.seq,) = _struct_I.unpack(str[start:end])
02078 _v106 = _v105.stamp
02079 _x = _v106
02080 start = end
02081 end += 8
02082 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02083 start = end
02084 end += 4
02085 (length,) = _struct_I.unpack(str[start:end])
02086 start = end
02087 end += length
02088 if python3:
02089 _v105.frame_id = str[start:end].decode('utf-8')
02090 else:
02091 _v105.frame_id = str[start:end]
02092 start = end
02093 end += 4
02094 (length,) = _struct_I.unpack(str[start:end])
02095 start = end
02096 end += length
02097 if python3:
02098 _v104.id = str[start:end].decode('utf-8')
02099 else:
02100 _v104.id = str[start:end]
02101 start = end
02102 end += 4
02103 (_v104.padding,) = _struct_f.unpack(str[start:end])
02104 _v107 = _v104.operation
02105 start = end
02106 end += 1
02107 (_v107.operation,) = _struct_b.unpack(str[start:end])
02108 start = end
02109 end += 4
02110 (length,) = _struct_I.unpack(str[start:end])
02111 _v104.shapes = []
02112 for i in range(0, length):
02113 val3 = arm_navigation_msgs.msg.Shape()
02114 start = end
02115 end += 1
02116 (val3.type,) = _struct_b.unpack(str[start:end])
02117 start = end
02118 end += 4
02119 (length,) = _struct_I.unpack(str[start:end])
02120 pattern = '<%sd'%length
02121 start = end
02122 end += struct.calcsize(pattern)
02123 val3.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02124 start = end
02125 end += 4
02126 (length,) = _struct_I.unpack(str[start:end])
02127 pattern = '<%si'%length
02128 start = end
02129 end += struct.calcsize(pattern)
02130 val3.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02131 start = end
02132 end += 4
02133 (length,) = _struct_I.unpack(str[start:end])
02134 val3.vertices = []
02135 for i in range(0, length):
02136 val4 = geometry_msgs.msg.Point()
02137 _x = val4
02138 start = end
02139 end += 24
02140 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02141 val3.vertices.append(val4)
02142 _v104.shapes.append(val3)
02143 start = end
02144 end += 4
02145 (length,) = _struct_I.unpack(str[start:end])
02146 _v104.poses = []
02147 for i in range(0, length):
02148 val3 = geometry_msgs.msg.Pose()
02149 _v108 = val3.position
02150 _x = _v108
02151 start = end
02152 end += 24
02153 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02154 _v109 = val3.orientation
02155 _x = _v109
02156 start = end
02157 end += 32
02158 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02159 _v104.poses.append(val3)
02160 start = end
02161 end += 4
02162 (length,) = _struct_I.unpack(str[start:end])
02163 val1.touch_links = []
02164 for i in range(0, length):
02165 start = end
02166 end += 4
02167 (length,) = _struct_I.unpack(str[start:end])
02168 start = end
02169 end += length
02170 if python3:
02171 val2 = str[start:end].decode('utf-8')
02172 else:
02173 val2 = str[start:end]
02174 val1.touch_links.append(val2)
02175 self.planning_scene_diff.attached_collision_objects.append(val1)
02176 _x = self
02177 start = end
02178 end += 12
02179 (_x.planning_scene_diff.collision_map.header.seq, _x.planning_scene_diff.collision_map.header.stamp.secs, _x.planning_scene_diff.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02180 start = end
02181 end += 4
02182 (length,) = _struct_I.unpack(str[start:end])
02183 start = end
02184 end += length
02185 if python3:
02186 self.planning_scene_diff.collision_map.header.frame_id = str[start:end].decode('utf-8')
02187 else:
02188 self.planning_scene_diff.collision_map.header.frame_id = str[start:end]
02189 start = end
02190 end += 4
02191 (length,) = _struct_I.unpack(str[start:end])
02192 self.planning_scene_diff.collision_map.boxes = []
02193 for i in range(0, length):
02194 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
02195 _v110 = val1.center
02196 _x = _v110
02197 start = end
02198 end += 12
02199 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02200 _v111 = val1.extents
02201 _x = _v111
02202 start = end
02203 end += 12
02204 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02205 _v112 = val1.axis
02206 _x = _v112
02207 start = end
02208 end += 12
02209 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
02210 start = end
02211 end += 4
02212 (val1.angle,) = _struct_f.unpack(str[start:end])
02213 self.planning_scene_diff.collision_map.boxes.append(val1)
02214 start = end
02215 end += 4
02216 (length,) = _struct_I.unpack(str[start:end])
02217 self.operations.collision_operations = []
02218 for i in range(0, length):
02219 val1 = arm_navigation_msgs.msg.CollisionOperation()
02220 start = end
02221 end += 4
02222 (length,) = _struct_I.unpack(str[start:end])
02223 start = end
02224 end += length
02225 if python3:
02226 val1.object1 = str[start:end].decode('utf-8')
02227 else:
02228 val1.object1 = str[start:end]
02229 start = end
02230 end += 4
02231 (length,) = _struct_I.unpack(str[start:end])
02232 start = end
02233 end += length
02234 if python3:
02235 val1.object2 = str[start:end].decode('utf-8')
02236 else:
02237 val1.object2 = str[start:end]
02238 _x = val1
02239 start = end
02240 end += 12
02241 (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
02242 self.operations.collision_operations.append(val1)
02243 return self
02244 except struct.error as e:
02245 raise genpy.DeserializationError(e)
02246
02247 _struct_I = genpy.struct_I
02248 _struct_b = struct.Struct("<b")
02249 _struct_d = struct.Struct("<d")
02250 _struct_f = struct.Struct("<f")
02251 _struct_di = struct.Struct("<di")
02252 _struct_3f = struct.Struct("<3f")
02253 _struct_3I = struct.Struct("<3I")
02254 _struct_4d = struct.Struct("<4d")
02255 _struct_2I = struct.Struct("<2I")
02256 _struct_3d = struct.Struct("<3d")
02257 """autogenerated by genpy from arm_navigation_msgs/GetPlanningSceneResponse.msg. Do not edit."""
02258 import sys
02259 python3 = True if sys.hexversion > 0x03000000 else False
02260 import genpy
02261 import struct
02262
02263 import arm_navigation_msgs.msg
02264 import geometry_msgs.msg
02265 import std_msgs.msg
02266 import genpy
02267 import sensor_msgs.msg
02268
02269 class GetPlanningSceneResponse(genpy.Message):
02270 _md5sum = "285525c9abe002fbafa99af84a14b4cb"
02271 _type = "arm_navigation_msgs/GetPlanningSceneResponse"
02272 _has_header = False
02273 _full_text = """
02274
02275 PlanningScene planning_scene
02276
02277
02278
02279
02280
02281 ================================================================================
02282 MSG: arm_navigation_msgs/PlanningScene
02283 #full robot state
02284 arm_navigation_msgs/RobotState robot_state
02285
02286 #additional frames for duplicating tf
02287 geometry_msgs/TransformStamped[] fixed_frame_transforms
02288
02289 #full allowed collision matrix
02290 AllowedCollisionMatrix allowed_collision_matrix
02291
02292 #allowed contacts
02293 arm_navigation_msgs/AllowedContactSpecification[] allowed_contacts
02294
02295 #all link paddings
02296 arm_navigation_msgs/LinkPadding[] link_padding
02297
02298 #collision objects
02299 arm_navigation_msgs/CollisionObject[] collision_objects
02300 arm_navigation_msgs/AttachedCollisionObject[] attached_collision_objects
02301
02302 #the collision map
02303 arm_navigation_msgs/CollisionMap collision_map
02304
02305 ================================================================================
02306 MSG: arm_navigation_msgs/RobotState
02307 # This message contains information about the robot state, i.e. the positions of its joints and links
02308 sensor_msgs/JointState joint_state
02309 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
02310
02311 ================================================================================
02312 MSG: sensor_msgs/JointState
02313 # This is a message that holds data to describe the state of a set of torque controlled joints.
02314 #
02315 # The state of each joint (revolute or prismatic) is defined by:
02316 # * the position of the joint (rad or m),
02317 # * the velocity of the joint (rad/s or m/s) and
02318 # * the effort that is applied in the joint (Nm or N).
02319 #
02320 # Each joint is uniquely identified by its name
02321 # The header specifies the time at which the joint states were recorded. All the joint states
02322 # in one message have to be recorded at the same time.
02323 #
02324 # This message consists of a multiple arrays, one for each part of the joint state.
02325 # The goal is to make each of the fields optional. When e.g. your joints have no
02326 # effort associated with them, you can leave the effort array empty.
02327 #
02328 # All arrays in this message should have the same size, or be empty.
02329 # This is the only way to uniquely associate the joint name with the correct
02330 # states.
02331
02332
02333 Header header
02334
02335 string[] name
02336 float64[] position
02337 float64[] velocity
02338 float64[] effort
02339
02340 ================================================================================
02341 MSG: std_msgs/Header
02342 # Standard metadata for higher-level stamped data types.
02343 # This is generally used to communicate timestamped data
02344 # in a particular coordinate frame.
02345 #
02346 # sequence ID: consecutively increasing ID
02347 uint32 seq
02348 #Two-integer timestamp that is expressed as:
02349 # * stamp.secs: seconds (stamp_secs) since epoch
02350 # * stamp.nsecs: nanoseconds since stamp_secs
02351 # time-handling sugar is provided by the client library
02352 time stamp
02353 #Frame this data is associated with
02354 # 0: no frame
02355 # 1: global frame
02356 string frame_id
02357
02358 ================================================================================
02359 MSG: arm_navigation_msgs/MultiDOFJointState
02360 #A representation of a multi-dof joint state
02361 time stamp
02362 string[] joint_names
02363 string[] frame_ids
02364 string[] child_frame_ids
02365 geometry_msgs/Pose[] poses
02366
02367 ================================================================================
02368 MSG: geometry_msgs/Pose
02369 # A representation of pose in free space, composed of postion and orientation.
02370 Point position
02371 Quaternion orientation
02372
02373 ================================================================================
02374 MSG: geometry_msgs/Point
02375 # This contains the position of a point in free space
02376 float64 x
02377 float64 y
02378 float64 z
02379
02380 ================================================================================
02381 MSG: geometry_msgs/Quaternion
02382 # This represents an orientation in free space in quaternion form.
02383
02384 float64 x
02385 float64 y
02386 float64 z
02387 float64 w
02388
02389 ================================================================================
02390 MSG: geometry_msgs/TransformStamped
02391 # This expresses a transform from coordinate frame header.frame_id
02392 # to the coordinate frame child_frame_id
02393 #
02394 # This message is mostly used by the
02395 # <a href="http://www.ros.org/wiki/tf">tf</a> package.
02396 # See it's documentation for more information.
02397
02398 Header header
02399 string child_frame_id # the frame id of the child frame
02400 Transform transform
02401
02402 ================================================================================
02403 MSG: geometry_msgs/Transform
02404 # This represents the transform between two coordinate frames in free space.
02405
02406 Vector3 translation
02407 Quaternion rotation
02408
02409 ================================================================================
02410 MSG: geometry_msgs/Vector3
02411 # This represents a vector in free space.
02412
02413 float64 x
02414 float64 y
02415 float64 z
02416 ================================================================================
02417 MSG: arm_navigation_msgs/AllowedCollisionMatrix
02418 # the list of link names in the matrix
02419 string[] link_names
02420
02421 # the individual entries in the allowed collision matrix
02422 # symmetric, with same order as link_names
02423 AllowedCollisionEntry[] entries
02424
02425 ================================================================================
02426 MSG: arm_navigation_msgs/AllowedCollisionEntry
02427 # whether or not collision checking is enabled
02428 bool[] enabled
02429
02430 ================================================================================
02431 MSG: arm_navigation_msgs/AllowedContactSpecification
02432 # The names of the regions
02433 string name
02434
02435 # The shape of the region in the environment
02436 arm_navigation_msgs/Shape shape
02437
02438 # The pose of the space defining the region
02439 geometry_msgs/PoseStamped pose_stamped
02440
02441 # The set of links that will be allowed to have penetration contact within this region
02442 string[] link_names
02443
02444 # The maximum penetration depth allowed for every link
02445 float64 penetration_depth
02446
02447 ================================================================================
02448 MSG: arm_navigation_msgs/Shape
02449 byte SPHERE=0
02450 byte BOX=1
02451 byte CYLINDER=2
02452 byte MESH=3
02453
02454 byte type
02455
02456
02457 #### define sphere, box, cylinder ####
02458 # the origin of each shape is considered at the shape's center
02459
02460 # for sphere
02461 # radius := dimensions[0]
02462
02463 # for cylinder
02464 # radius := dimensions[0]
02465 # length := dimensions[1]
02466 # the length is along the Z axis
02467
02468 # for box
02469 # size_x := dimensions[0]
02470 # size_y := dimensions[1]
02471 # size_z := dimensions[2]
02472 float64[] dimensions
02473
02474
02475 #### define mesh ####
02476
02477 # list of triangles; triangle k is defined by tre vertices located
02478 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
02479 int32[] triangles
02480 geometry_msgs/Point[] vertices
02481
02482 ================================================================================
02483 MSG: geometry_msgs/PoseStamped
02484 # A Pose with reference coordinate frame and timestamp
02485 Header header
02486 Pose pose
02487
02488 ================================================================================
02489 MSG: arm_navigation_msgs/LinkPadding
02490 #name for the link
02491 string link_name
02492
02493 # padding to apply to the link
02494 float64 padding
02495
02496 ================================================================================
02497 MSG: arm_navigation_msgs/CollisionObject
02498 # a header, used for interpreting the poses
02499 Header header
02500
02501 # the id of the object
02502 string id
02503
02504 # The padding used for filtering points near the object.
02505 # This does not affect collision checking for the object.
02506 # Set to negative to get zero padding.
02507 float32 padding
02508
02509 #This contains what is to be done with the object
02510 CollisionObjectOperation operation
02511
02512 #the shapes associated with the object
02513 arm_navigation_msgs/Shape[] shapes
02514
02515 #the poses associated with the shapes - will be transformed using the header
02516 geometry_msgs/Pose[] poses
02517
02518 ================================================================================
02519 MSG: arm_navigation_msgs/CollisionObjectOperation
02520 #Puts the object into the environment
02521 #or updates the object if already added
02522 byte ADD=0
02523
02524 #Removes the object from the environment entirely
02525 byte REMOVE=1
02526
02527 #Only valid within the context of a CollisionAttachedObject message
02528 #Will be ignored if sent with an CollisionObject message
02529 #Takes an attached object, detaches from the attached link
02530 #But adds back in as regular object
02531 byte DETACH_AND_ADD_AS_OBJECT=2
02532
02533 #Only valid within the context of a CollisionAttachedObject message
02534 #Will be ignored if sent with an CollisionObject message
02535 #Takes current object in the environment and removes it as
02536 #a regular object
02537 byte ATTACH_AND_REMOVE_AS_OBJECT=3
02538
02539 # Byte code for operation
02540 byte operation
02541
02542 ================================================================================
02543 MSG: arm_navigation_msgs/AttachedCollisionObject
02544 # The CollisionObject will be attached with a fixed joint to this link
02545 # If link name is set to REMOVE_ALL_ATTACHED_OBJECTS and object.operation
02546 # is set to REMOVE will remove all attached bodies attached to any object
02547 string link_name
02548
02549 #Reserved for indicating that all attached objects should be removed
02550 string REMOVE_ALL_ATTACHED_OBJECTS = "all"
02551
02552 #This contains the actual shapes and poses for the CollisionObject
02553 #to be attached to the link
02554 #If action is remove and no object.id is set, all objects
02555 #attached to the link indicated by link_name will be removed
02556 CollisionObject object
02557
02558 # The set of links that the attached objects are allowed to touch
02559 # by default - the link_name is included by default
02560 string[] touch_links
02561
02562 ================================================================================
02563 MSG: arm_navigation_msgs/CollisionMap
02564 #header for interpreting box positions
02565 Header header
02566
02567 #boxes for use in collision testing
02568 OrientedBoundingBox[] boxes
02569
02570 ================================================================================
02571 MSG: arm_navigation_msgs/OrientedBoundingBox
02572 #the center of the box
02573 geometry_msgs/Point32 center
02574
02575 #the extents of the box, assuming the center is at the point
02576 geometry_msgs/Point32 extents
02577
02578 #the axis of the box
02579 geometry_msgs/Point32 axis
02580
02581 #the angle of rotation around the axis
02582 float32 angle
02583
02584 ================================================================================
02585 MSG: geometry_msgs/Point32
02586 # This contains the position of a point in free space(with 32 bits of precision).
02587 # It is recommeded to use Point wherever possible instead of Point32.
02588 #
02589 # This recommendation is to promote interoperability.
02590 #
02591 # This message is designed to take up less space when sending
02592 # lots of points at once, as in the case of a PointCloud.
02593
02594 float32 x
02595 float32 y
02596 float32 z
02597 """
02598 __slots__ = ['planning_scene']
02599 _slot_types = ['arm_navigation_msgs/PlanningScene']
02600
02601 def __init__(self, *args, **kwds):
02602 """
02603 Constructor. Any message fields that are implicitly/explicitly
02604 set to None will be assigned a default value. The recommend
02605 use is keyword arguments as this is more robust to future message
02606 changes. You cannot mix in-order arguments and keyword arguments.
02607
02608 The available fields are:
02609 planning_scene
02610
02611 :param args: complete set of field values, in .msg order
02612 :param kwds: use keyword arguments corresponding to message field names
02613 to set specific fields.
02614 """
02615 if args or kwds:
02616 super(GetPlanningSceneResponse, self).__init__(*args, **kwds)
02617
02618 if self.planning_scene is None:
02619 self.planning_scene = arm_navigation_msgs.msg.PlanningScene()
02620 else:
02621 self.planning_scene = arm_navigation_msgs.msg.PlanningScene()
02622
02623 def _get_types(self):
02624 """
02625 internal API method
02626 """
02627 return self._slot_types
02628
02629 def serialize(self, buff):
02630 """
02631 serialize message into buffer
02632 :param buff: buffer, ``StringIO``
02633 """
02634 try:
02635 _x = self
02636 buff.write(_struct_3I.pack(_x.planning_scene.robot_state.joint_state.header.seq, _x.planning_scene.robot_state.joint_state.header.stamp.secs, _x.planning_scene.robot_state.joint_state.header.stamp.nsecs))
02637 _x = self.planning_scene.robot_state.joint_state.header.frame_id
02638 length = len(_x)
02639 if python3 or type(_x) == unicode:
02640 _x = _x.encode('utf-8')
02641 length = len(_x)
02642 buff.write(struct.pack('<I%ss'%length, length, _x))
02643 length = len(self.planning_scene.robot_state.joint_state.name)
02644 buff.write(_struct_I.pack(length))
02645 for val1 in self.planning_scene.robot_state.joint_state.name:
02646 length = len(val1)
02647 if python3 or type(val1) == unicode:
02648 val1 = val1.encode('utf-8')
02649 length = len(val1)
02650 buff.write(struct.pack('<I%ss'%length, length, val1))
02651 length = len(self.planning_scene.robot_state.joint_state.position)
02652 buff.write(_struct_I.pack(length))
02653 pattern = '<%sd'%length
02654 buff.write(struct.pack(pattern, *self.planning_scene.robot_state.joint_state.position))
02655 length = len(self.planning_scene.robot_state.joint_state.velocity)
02656 buff.write(_struct_I.pack(length))
02657 pattern = '<%sd'%length
02658 buff.write(struct.pack(pattern, *self.planning_scene.robot_state.joint_state.velocity))
02659 length = len(self.planning_scene.robot_state.joint_state.effort)
02660 buff.write(_struct_I.pack(length))
02661 pattern = '<%sd'%length
02662 buff.write(struct.pack(pattern, *self.planning_scene.robot_state.joint_state.effort))
02663 _x = self
02664 buff.write(_struct_2I.pack(_x.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs))
02665 length = len(self.planning_scene.robot_state.multi_dof_joint_state.joint_names)
02666 buff.write(_struct_I.pack(length))
02667 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.joint_names:
02668 length = len(val1)
02669 if python3 or type(val1) == unicode:
02670 val1 = val1.encode('utf-8')
02671 length = len(val1)
02672 buff.write(struct.pack('<I%ss'%length, length, val1))
02673 length = len(self.planning_scene.robot_state.multi_dof_joint_state.frame_ids)
02674 buff.write(_struct_I.pack(length))
02675 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.frame_ids:
02676 length = len(val1)
02677 if python3 or type(val1) == unicode:
02678 val1 = val1.encode('utf-8')
02679 length = len(val1)
02680 buff.write(struct.pack('<I%ss'%length, length, val1))
02681 length = len(self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids)
02682 buff.write(_struct_I.pack(length))
02683 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids:
02684 length = len(val1)
02685 if python3 or type(val1) == unicode:
02686 val1 = val1.encode('utf-8')
02687 length = len(val1)
02688 buff.write(struct.pack('<I%ss'%length, length, val1))
02689 length = len(self.planning_scene.robot_state.multi_dof_joint_state.poses)
02690 buff.write(_struct_I.pack(length))
02691 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.poses:
02692 _v113 = val1.position
02693 _x = _v113
02694 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02695 _v114 = val1.orientation
02696 _x = _v114
02697 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02698 length = len(self.planning_scene.fixed_frame_transforms)
02699 buff.write(_struct_I.pack(length))
02700 for val1 in self.planning_scene.fixed_frame_transforms:
02701 _v115 = val1.header
02702 buff.write(_struct_I.pack(_v115.seq))
02703 _v116 = _v115.stamp
02704 _x = _v116
02705 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02706 _x = _v115.frame_id
02707 length = len(_x)
02708 if python3 or type(_x) == unicode:
02709 _x = _x.encode('utf-8')
02710 length = len(_x)
02711 buff.write(struct.pack('<I%ss'%length, length, _x))
02712 _x = val1.child_frame_id
02713 length = len(_x)
02714 if python3 or type(_x) == unicode:
02715 _x = _x.encode('utf-8')
02716 length = len(_x)
02717 buff.write(struct.pack('<I%ss'%length, length, _x))
02718 _v117 = val1.transform
02719 _v118 = _v117.translation
02720 _x = _v118
02721 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02722 _v119 = _v117.rotation
02723 _x = _v119
02724 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02725 length = len(self.planning_scene.allowed_collision_matrix.link_names)
02726 buff.write(_struct_I.pack(length))
02727 for val1 in self.planning_scene.allowed_collision_matrix.link_names:
02728 length = len(val1)
02729 if python3 or type(val1) == unicode:
02730 val1 = val1.encode('utf-8')
02731 length = len(val1)
02732 buff.write(struct.pack('<I%ss'%length, length, val1))
02733 length = len(self.planning_scene.allowed_collision_matrix.entries)
02734 buff.write(_struct_I.pack(length))
02735 for val1 in self.planning_scene.allowed_collision_matrix.entries:
02736 length = len(val1.enabled)
02737 buff.write(_struct_I.pack(length))
02738 pattern = '<%sB'%length
02739 buff.write(struct.pack(pattern, *val1.enabled))
02740 length = len(self.planning_scene.allowed_contacts)
02741 buff.write(_struct_I.pack(length))
02742 for val1 in self.planning_scene.allowed_contacts:
02743 _x = val1.name
02744 length = len(_x)
02745 if python3 or type(_x) == unicode:
02746 _x = _x.encode('utf-8')
02747 length = len(_x)
02748 buff.write(struct.pack('<I%ss'%length, length, _x))
02749 _v120 = val1.shape
02750 buff.write(_struct_b.pack(_v120.type))
02751 length = len(_v120.dimensions)
02752 buff.write(_struct_I.pack(length))
02753 pattern = '<%sd'%length
02754 buff.write(struct.pack(pattern, *_v120.dimensions))
02755 length = len(_v120.triangles)
02756 buff.write(_struct_I.pack(length))
02757 pattern = '<%si'%length
02758 buff.write(struct.pack(pattern, *_v120.triangles))
02759 length = len(_v120.vertices)
02760 buff.write(_struct_I.pack(length))
02761 for val3 in _v120.vertices:
02762 _x = val3
02763 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02764 _v121 = val1.pose_stamped
02765 _v122 = _v121.header
02766 buff.write(_struct_I.pack(_v122.seq))
02767 _v123 = _v122.stamp
02768 _x = _v123
02769 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02770 _x = _v122.frame_id
02771 length = len(_x)
02772 if python3 or type(_x) == unicode:
02773 _x = _x.encode('utf-8')
02774 length = len(_x)
02775 buff.write(struct.pack('<I%ss'%length, length, _x))
02776 _v124 = _v121.pose
02777 _v125 = _v124.position
02778 _x = _v125
02779 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02780 _v126 = _v124.orientation
02781 _x = _v126
02782 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02783 length = len(val1.link_names)
02784 buff.write(_struct_I.pack(length))
02785 for val2 in val1.link_names:
02786 length = len(val2)
02787 if python3 or type(val2) == unicode:
02788 val2 = val2.encode('utf-8')
02789 length = len(val2)
02790 buff.write(struct.pack('<I%ss'%length, length, val2))
02791 buff.write(_struct_d.pack(val1.penetration_depth))
02792 length = len(self.planning_scene.link_padding)
02793 buff.write(_struct_I.pack(length))
02794 for val1 in self.planning_scene.link_padding:
02795 _x = val1.link_name
02796 length = len(_x)
02797 if python3 or type(_x) == unicode:
02798 _x = _x.encode('utf-8')
02799 length = len(_x)
02800 buff.write(struct.pack('<I%ss'%length, length, _x))
02801 buff.write(_struct_d.pack(val1.padding))
02802 length = len(self.planning_scene.collision_objects)
02803 buff.write(_struct_I.pack(length))
02804 for val1 in self.planning_scene.collision_objects:
02805 _v127 = val1.header
02806 buff.write(_struct_I.pack(_v127.seq))
02807 _v128 = _v127.stamp
02808 _x = _v128
02809 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02810 _x = _v127.frame_id
02811 length = len(_x)
02812 if python3 or type(_x) == unicode:
02813 _x = _x.encode('utf-8')
02814 length = len(_x)
02815 buff.write(struct.pack('<I%ss'%length, length, _x))
02816 _x = val1.id
02817 length = len(_x)
02818 if python3 or type(_x) == unicode:
02819 _x = _x.encode('utf-8')
02820 length = len(_x)
02821 buff.write(struct.pack('<I%ss'%length, length, _x))
02822 buff.write(_struct_f.pack(val1.padding))
02823 _v129 = val1.operation
02824 buff.write(_struct_b.pack(_v129.operation))
02825 length = len(val1.shapes)
02826 buff.write(_struct_I.pack(length))
02827 for val2 in val1.shapes:
02828 buff.write(_struct_b.pack(val2.type))
02829 length = len(val2.dimensions)
02830 buff.write(_struct_I.pack(length))
02831 pattern = '<%sd'%length
02832 buff.write(struct.pack(pattern, *val2.dimensions))
02833 length = len(val2.triangles)
02834 buff.write(_struct_I.pack(length))
02835 pattern = '<%si'%length
02836 buff.write(struct.pack(pattern, *val2.triangles))
02837 length = len(val2.vertices)
02838 buff.write(_struct_I.pack(length))
02839 for val3 in val2.vertices:
02840 _x = val3
02841 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02842 length = len(val1.poses)
02843 buff.write(_struct_I.pack(length))
02844 for val2 in val1.poses:
02845 _v130 = val2.position
02846 _x = _v130
02847 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02848 _v131 = val2.orientation
02849 _x = _v131
02850 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02851 length = len(self.planning_scene.attached_collision_objects)
02852 buff.write(_struct_I.pack(length))
02853 for val1 in self.planning_scene.attached_collision_objects:
02854 _x = val1.link_name
02855 length = len(_x)
02856 if python3 or type(_x) == unicode:
02857 _x = _x.encode('utf-8')
02858 length = len(_x)
02859 buff.write(struct.pack('<I%ss'%length, length, _x))
02860 _v132 = val1.object
02861 _v133 = _v132.header
02862 buff.write(_struct_I.pack(_v133.seq))
02863 _v134 = _v133.stamp
02864 _x = _v134
02865 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02866 _x = _v133.frame_id
02867 length = len(_x)
02868 if python3 or type(_x) == unicode:
02869 _x = _x.encode('utf-8')
02870 length = len(_x)
02871 buff.write(struct.pack('<I%ss'%length, length, _x))
02872 _x = _v132.id
02873 length = len(_x)
02874 if python3 or type(_x) == unicode:
02875 _x = _x.encode('utf-8')
02876 length = len(_x)
02877 buff.write(struct.pack('<I%ss'%length, length, _x))
02878 buff.write(_struct_f.pack(_v132.padding))
02879 _v135 = _v132.operation
02880 buff.write(_struct_b.pack(_v135.operation))
02881 length = len(_v132.shapes)
02882 buff.write(_struct_I.pack(length))
02883 for val3 in _v132.shapes:
02884 buff.write(_struct_b.pack(val3.type))
02885 length = len(val3.dimensions)
02886 buff.write(_struct_I.pack(length))
02887 pattern = '<%sd'%length
02888 buff.write(struct.pack(pattern, *val3.dimensions))
02889 length = len(val3.triangles)
02890 buff.write(_struct_I.pack(length))
02891 pattern = '<%si'%length
02892 buff.write(struct.pack(pattern, *val3.triangles))
02893 length = len(val3.vertices)
02894 buff.write(_struct_I.pack(length))
02895 for val4 in val3.vertices:
02896 _x = val4
02897 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02898 length = len(_v132.poses)
02899 buff.write(_struct_I.pack(length))
02900 for val3 in _v132.poses:
02901 _v136 = val3.position
02902 _x = _v136
02903 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02904 _v137 = val3.orientation
02905 _x = _v137
02906 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02907 length = len(val1.touch_links)
02908 buff.write(_struct_I.pack(length))
02909 for val2 in val1.touch_links:
02910 length = len(val2)
02911 if python3 or type(val2) == unicode:
02912 val2 = val2.encode('utf-8')
02913 length = len(val2)
02914 buff.write(struct.pack('<I%ss'%length, length, val2))
02915 _x = self
02916 buff.write(_struct_3I.pack(_x.planning_scene.collision_map.header.seq, _x.planning_scene.collision_map.header.stamp.secs, _x.planning_scene.collision_map.header.stamp.nsecs))
02917 _x = self.planning_scene.collision_map.header.frame_id
02918 length = len(_x)
02919 if python3 or type(_x) == unicode:
02920 _x = _x.encode('utf-8')
02921 length = len(_x)
02922 buff.write(struct.pack('<I%ss'%length, length, _x))
02923 length = len(self.planning_scene.collision_map.boxes)
02924 buff.write(_struct_I.pack(length))
02925 for val1 in self.planning_scene.collision_map.boxes:
02926 _v138 = val1.center
02927 _x = _v138
02928 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02929 _v139 = val1.extents
02930 _x = _v139
02931 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02932 _v140 = val1.axis
02933 _x = _v140
02934 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
02935 buff.write(_struct_f.pack(val1.angle))
02936 except struct.error as se: self._check_types(se)
02937 except TypeError as te: self._check_types(te)
02938
02939 def deserialize(self, str):
02940 """
02941 unpack serialized message in str into this message instance
02942 :param str: byte array of serialized message, ``str``
02943 """
02944 try:
02945 if self.planning_scene is None:
02946 self.planning_scene = arm_navigation_msgs.msg.PlanningScene()
02947 end = 0
02948 _x = self
02949 start = end
02950 end += 12
02951 (_x.planning_scene.robot_state.joint_state.header.seq, _x.planning_scene.robot_state.joint_state.header.stamp.secs, _x.planning_scene.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02952 start = end
02953 end += 4
02954 (length,) = _struct_I.unpack(str[start:end])
02955 start = end
02956 end += length
02957 if python3:
02958 self.planning_scene.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
02959 else:
02960 self.planning_scene.robot_state.joint_state.header.frame_id = str[start:end]
02961 start = end
02962 end += 4
02963 (length,) = _struct_I.unpack(str[start:end])
02964 self.planning_scene.robot_state.joint_state.name = []
02965 for i in range(0, length):
02966 start = end
02967 end += 4
02968 (length,) = _struct_I.unpack(str[start:end])
02969 start = end
02970 end += length
02971 if python3:
02972 val1 = str[start:end].decode('utf-8')
02973 else:
02974 val1 = str[start:end]
02975 self.planning_scene.robot_state.joint_state.name.append(val1)
02976 start = end
02977 end += 4
02978 (length,) = _struct_I.unpack(str[start:end])
02979 pattern = '<%sd'%length
02980 start = end
02981 end += struct.calcsize(pattern)
02982 self.planning_scene.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
02983 start = end
02984 end += 4
02985 (length,) = _struct_I.unpack(str[start:end])
02986 pattern = '<%sd'%length
02987 start = end
02988 end += struct.calcsize(pattern)
02989 self.planning_scene.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
02990 start = end
02991 end += 4
02992 (length,) = _struct_I.unpack(str[start:end])
02993 pattern = '<%sd'%length
02994 start = end
02995 end += struct.calcsize(pattern)
02996 self.planning_scene.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
02997 _x = self
02998 start = end
02999 end += 8
03000 (_x.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03001 start = end
03002 end += 4
03003 (length,) = _struct_I.unpack(str[start:end])
03004 self.planning_scene.robot_state.multi_dof_joint_state.joint_names = []
03005 for i in range(0, length):
03006 start = end
03007 end += 4
03008 (length,) = _struct_I.unpack(str[start:end])
03009 start = end
03010 end += length
03011 if python3:
03012 val1 = str[start:end].decode('utf-8')
03013 else:
03014 val1 = str[start:end]
03015 self.planning_scene.robot_state.multi_dof_joint_state.joint_names.append(val1)
03016 start = end
03017 end += 4
03018 (length,) = _struct_I.unpack(str[start:end])
03019 self.planning_scene.robot_state.multi_dof_joint_state.frame_ids = []
03020 for i in range(0, length):
03021 start = end
03022 end += 4
03023 (length,) = _struct_I.unpack(str[start:end])
03024 start = end
03025 end += length
03026 if python3:
03027 val1 = str[start:end].decode('utf-8')
03028 else:
03029 val1 = str[start:end]
03030 self.planning_scene.robot_state.multi_dof_joint_state.frame_ids.append(val1)
03031 start = end
03032 end += 4
03033 (length,) = _struct_I.unpack(str[start:end])
03034 self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids = []
03035 for i in range(0, length):
03036 start = end
03037 end += 4
03038 (length,) = _struct_I.unpack(str[start:end])
03039 start = end
03040 end += length
03041 if python3:
03042 val1 = str[start:end].decode('utf-8')
03043 else:
03044 val1 = str[start:end]
03045 self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
03046 start = end
03047 end += 4
03048 (length,) = _struct_I.unpack(str[start:end])
03049 self.planning_scene.robot_state.multi_dof_joint_state.poses = []
03050 for i in range(0, length):
03051 val1 = geometry_msgs.msg.Pose()
03052 _v141 = val1.position
03053 _x = _v141
03054 start = end
03055 end += 24
03056 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03057 _v142 = val1.orientation
03058 _x = _v142
03059 start = end
03060 end += 32
03061 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03062 self.planning_scene.robot_state.multi_dof_joint_state.poses.append(val1)
03063 start = end
03064 end += 4
03065 (length,) = _struct_I.unpack(str[start:end])
03066 self.planning_scene.fixed_frame_transforms = []
03067 for i in range(0, length):
03068 val1 = geometry_msgs.msg.TransformStamped()
03069 _v143 = val1.header
03070 start = end
03071 end += 4
03072 (_v143.seq,) = _struct_I.unpack(str[start:end])
03073 _v144 = _v143.stamp
03074 _x = _v144
03075 start = end
03076 end += 8
03077 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03078 start = end
03079 end += 4
03080 (length,) = _struct_I.unpack(str[start:end])
03081 start = end
03082 end += length
03083 if python3:
03084 _v143.frame_id = str[start:end].decode('utf-8')
03085 else:
03086 _v143.frame_id = str[start:end]
03087 start = end
03088 end += 4
03089 (length,) = _struct_I.unpack(str[start:end])
03090 start = end
03091 end += length
03092 if python3:
03093 val1.child_frame_id = str[start:end].decode('utf-8')
03094 else:
03095 val1.child_frame_id = str[start:end]
03096 _v145 = val1.transform
03097 _v146 = _v145.translation
03098 _x = _v146
03099 start = end
03100 end += 24
03101 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03102 _v147 = _v145.rotation
03103 _x = _v147
03104 start = end
03105 end += 32
03106 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03107 self.planning_scene.fixed_frame_transforms.append(val1)
03108 start = end
03109 end += 4
03110 (length,) = _struct_I.unpack(str[start:end])
03111 self.planning_scene.allowed_collision_matrix.link_names = []
03112 for i in range(0, length):
03113 start = end
03114 end += 4
03115 (length,) = _struct_I.unpack(str[start:end])
03116 start = end
03117 end += length
03118 if python3:
03119 val1 = str[start:end].decode('utf-8')
03120 else:
03121 val1 = str[start:end]
03122 self.planning_scene.allowed_collision_matrix.link_names.append(val1)
03123 start = end
03124 end += 4
03125 (length,) = _struct_I.unpack(str[start:end])
03126 self.planning_scene.allowed_collision_matrix.entries = []
03127 for i in range(0, length):
03128 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
03129 start = end
03130 end += 4
03131 (length,) = _struct_I.unpack(str[start:end])
03132 pattern = '<%sB'%length
03133 start = end
03134 end += struct.calcsize(pattern)
03135 val1.enabled = struct.unpack(pattern, str[start:end])
03136 val1.enabled = map(bool, val1.enabled)
03137 self.planning_scene.allowed_collision_matrix.entries.append(val1)
03138 start = end
03139 end += 4
03140 (length,) = _struct_I.unpack(str[start:end])
03141 self.planning_scene.allowed_contacts = []
03142 for i in range(0, length):
03143 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
03144 start = end
03145 end += 4
03146 (length,) = _struct_I.unpack(str[start:end])
03147 start = end
03148 end += length
03149 if python3:
03150 val1.name = str[start:end].decode('utf-8')
03151 else:
03152 val1.name = str[start:end]
03153 _v148 = val1.shape
03154 start = end
03155 end += 1
03156 (_v148.type,) = _struct_b.unpack(str[start:end])
03157 start = end
03158 end += 4
03159 (length,) = _struct_I.unpack(str[start:end])
03160 pattern = '<%sd'%length
03161 start = end
03162 end += struct.calcsize(pattern)
03163 _v148.dimensions = struct.unpack(pattern, str[start:end])
03164 start = end
03165 end += 4
03166 (length,) = _struct_I.unpack(str[start:end])
03167 pattern = '<%si'%length
03168 start = end
03169 end += struct.calcsize(pattern)
03170 _v148.triangles = struct.unpack(pattern, str[start:end])
03171 start = end
03172 end += 4
03173 (length,) = _struct_I.unpack(str[start:end])
03174 _v148.vertices = []
03175 for i in range(0, length):
03176 val3 = geometry_msgs.msg.Point()
03177 _x = val3
03178 start = end
03179 end += 24
03180 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03181 _v148.vertices.append(val3)
03182 _v149 = val1.pose_stamped
03183 _v150 = _v149.header
03184 start = end
03185 end += 4
03186 (_v150.seq,) = _struct_I.unpack(str[start:end])
03187 _v151 = _v150.stamp
03188 _x = _v151
03189 start = end
03190 end += 8
03191 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03192 start = end
03193 end += 4
03194 (length,) = _struct_I.unpack(str[start:end])
03195 start = end
03196 end += length
03197 if python3:
03198 _v150.frame_id = str[start:end].decode('utf-8')
03199 else:
03200 _v150.frame_id = str[start:end]
03201 _v152 = _v149.pose
03202 _v153 = _v152.position
03203 _x = _v153
03204 start = end
03205 end += 24
03206 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03207 _v154 = _v152.orientation
03208 _x = _v154
03209 start = end
03210 end += 32
03211 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03212 start = end
03213 end += 4
03214 (length,) = _struct_I.unpack(str[start:end])
03215 val1.link_names = []
03216 for i in range(0, length):
03217 start = end
03218 end += 4
03219 (length,) = _struct_I.unpack(str[start:end])
03220 start = end
03221 end += length
03222 if python3:
03223 val2 = str[start:end].decode('utf-8')
03224 else:
03225 val2 = str[start:end]
03226 val1.link_names.append(val2)
03227 start = end
03228 end += 8
03229 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
03230 self.planning_scene.allowed_contacts.append(val1)
03231 start = end
03232 end += 4
03233 (length,) = _struct_I.unpack(str[start:end])
03234 self.planning_scene.link_padding = []
03235 for i in range(0, length):
03236 val1 = arm_navigation_msgs.msg.LinkPadding()
03237 start = end
03238 end += 4
03239 (length,) = _struct_I.unpack(str[start:end])
03240 start = end
03241 end += length
03242 if python3:
03243 val1.link_name = str[start:end].decode('utf-8')
03244 else:
03245 val1.link_name = str[start:end]
03246 start = end
03247 end += 8
03248 (val1.padding,) = _struct_d.unpack(str[start:end])
03249 self.planning_scene.link_padding.append(val1)
03250 start = end
03251 end += 4
03252 (length,) = _struct_I.unpack(str[start:end])
03253 self.planning_scene.collision_objects = []
03254 for i in range(0, length):
03255 val1 = arm_navigation_msgs.msg.CollisionObject()
03256 _v155 = val1.header
03257 start = end
03258 end += 4
03259 (_v155.seq,) = _struct_I.unpack(str[start:end])
03260 _v156 = _v155.stamp
03261 _x = _v156
03262 start = end
03263 end += 8
03264 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03265 start = end
03266 end += 4
03267 (length,) = _struct_I.unpack(str[start:end])
03268 start = end
03269 end += length
03270 if python3:
03271 _v155.frame_id = str[start:end].decode('utf-8')
03272 else:
03273 _v155.frame_id = str[start:end]
03274 start = end
03275 end += 4
03276 (length,) = _struct_I.unpack(str[start:end])
03277 start = end
03278 end += length
03279 if python3:
03280 val1.id = str[start:end].decode('utf-8')
03281 else:
03282 val1.id = str[start:end]
03283 start = end
03284 end += 4
03285 (val1.padding,) = _struct_f.unpack(str[start:end])
03286 _v157 = val1.operation
03287 start = end
03288 end += 1
03289 (_v157.operation,) = _struct_b.unpack(str[start:end])
03290 start = end
03291 end += 4
03292 (length,) = _struct_I.unpack(str[start:end])
03293 val1.shapes = []
03294 for i in range(0, length):
03295 val2 = arm_navigation_msgs.msg.Shape()
03296 start = end
03297 end += 1
03298 (val2.type,) = _struct_b.unpack(str[start:end])
03299 start = end
03300 end += 4
03301 (length,) = _struct_I.unpack(str[start:end])
03302 pattern = '<%sd'%length
03303 start = end
03304 end += struct.calcsize(pattern)
03305 val2.dimensions = struct.unpack(pattern, str[start:end])
03306 start = end
03307 end += 4
03308 (length,) = _struct_I.unpack(str[start:end])
03309 pattern = '<%si'%length
03310 start = end
03311 end += struct.calcsize(pattern)
03312 val2.triangles = struct.unpack(pattern, str[start:end])
03313 start = end
03314 end += 4
03315 (length,) = _struct_I.unpack(str[start:end])
03316 val2.vertices = []
03317 for i in range(0, length):
03318 val3 = geometry_msgs.msg.Point()
03319 _x = val3
03320 start = end
03321 end += 24
03322 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03323 val2.vertices.append(val3)
03324 val1.shapes.append(val2)
03325 start = end
03326 end += 4
03327 (length,) = _struct_I.unpack(str[start:end])
03328 val1.poses = []
03329 for i in range(0, length):
03330 val2 = geometry_msgs.msg.Pose()
03331 _v158 = val2.position
03332 _x = _v158
03333 start = end
03334 end += 24
03335 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03336 _v159 = val2.orientation
03337 _x = _v159
03338 start = end
03339 end += 32
03340 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03341 val1.poses.append(val2)
03342 self.planning_scene.collision_objects.append(val1)
03343 start = end
03344 end += 4
03345 (length,) = _struct_I.unpack(str[start:end])
03346 self.planning_scene.attached_collision_objects = []
03347 for i in range(0, length):
03348 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
03349 start = end
03350 end += 4
03351 (length,) = _struct_I.unpack(str[start:end])
03352 start = end
03353 end += length
03354 if python3:
03355 val1.link_name = str[start:end].decode('utf-8')
03356 else:
03357 val1.link_name = str[start:end]
03358 _v160 = val1.object
03359 _v161 = _v160.header
03360 start = end
03361 end += 4
03362 (_v161.seq,) = _struct_I.unpack(str[start:end])
03363 _v162 = _v161.stamp
03364 _x = _v162
03365 start = end
03366 end += 8
03367 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03368 start = end
03369 end += 4
03370 (length,) = _struct_I.unpack(str[start:end])
03371 start = end
03372 end += length
03373 if python3:
03374 _v161.frame_id = str[start:end].decode('utf-8')
03375 else:
03376 _v161.frame_id = str[start:end]
03377 start = end
03378 end += 4
03379 (length,) = _struct_I.unpack(str[start:end])
03380 start = end
03381 end += length
03382 if python3:
03383 _v160.id = str[start:end].decode('utf-8')
03384 else:
03385 _v160.id = str[start:end]
03386 start = end
03387 end += 4
03388 (_v160.padding,) = _struct_f.unpack(str[start:end])
03389 _v163 = _v160.operation
03390 start = end
03391 end += 1
03392 (_v163.operation,) = _struct_b.unpack(str[start:end])
03393 start = end
03394 end += 4
03395 (length,) = _struct_I.unpack(str[start:end])
03396 _v160.shapes = []
03397 for i in range(0, length):
03398 val3 = arm_navigation_msgs.msg.Shape()
03399 start = end
03400 end += 1
03401 (val3.type,) = _struct_b.unpack(str[start:end])
03402 start = end
03403 end += 4
03404 (length,) = _struct_I.unpack(str[start:end])
03405 pattern = '<%sd'%length
03406 start = end
03407 end += struct.calcsize(pattern)
03408 val3.dimensions = struct.unpack(pattern, str[start:end])
03409 start = end
03410 end += 4
03411 (length,) = _struct_I.unpack(str[start:end])
03412 pattern = '<%si'%length
03413 start = end
03414 end += struct.calcsize(pattern)
03415 val3.triangles = struct.unpack(pattern, str[start:end])
03416 start = end
03417 end += 4
03418 (length,) = _struct_I.unpack(str[start:end])
03419 val3.vertices = []
03420 for i in range(0, length):
03421 val4 = geometry_msgs.msg.Point()
03422 _x = val4
03423 start = end
03424 end += 24
03425 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03426 val3.vertices.append(val4)
03427 _v160.shapes.append(val3)
03428 start = end
03429 end += 4
03430 (length,) = _struct_I.unpack(str[start:end])
03431 _v160.poses = []
03432 for i in range(0, length):
03433 val3 = geometry_msgs.msg.Pose()
03434 _v164 = val3.position
03435 _x = _v164
03436 start = end
03437 end += 24
03438 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03439 _v165 = val3.orientation
03440 _x = _v165
03441 start = end
03442 end += 32
03443 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03444 _v160.poses.append(val3)
03445 start = end
03446 end += 4
03447 (length,) = _struct_I.unpack(str[start:end])
03448 val1.touch_links = []
03449 for i in range(0, length):
03450 start = end
03451 end += 4
03452 (length,) = _struct_I.unpack(str[start:end])
03453 start = end
03454 end += length
03455 if python3:
03456 val2 = str[start:end].decode('utf-8')
03457 else:
03458 val2 = str[start:end]
03459 val1.touch_links.append(val2)
03460 self.planning_scene.attached_collision_objects.append(val1)
03461 _x = self
03462 start = end
03463 end += 12
03464 (_x.planning_scene.collision_map.header.seq, _x.planning_scene.collision_map.header.stamp.secs, _x.planning_scene.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03465 start = end
03466 end += 4
03467 (length,) = _struct_I.unpack(str[start:end])
03468 start = end
03469 end += length
03470 if python3:
03471 self.planning_scene.collision_map.header.frame_id = str[start:end].decode('utf-8')
03472 else:
03473 self.planning_scene.collision_map.header.frame_id = str[start:end]
03474 start = end
03475 end += 4
03476 (length,) = _struct_I.unpack(str[start:end])
03477 self.planning_scene.collision_map.boxes = []
03478 for i in range(0, length):
03479 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
03480 _v166 = val1.center
03481 _x = _v166
03482 start = end
03483 end += 12
03484 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03485 _v167 = val1.extents
03486 _x = _v167
03487 start = end
03488 end += 12
03489 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03490 _v168 = val1.axis
03491 _x = _v168
03492 start = end
03493 end += 12
03494 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
03495 start = end
03496 end += 4
03497 (val1.angle,) = _struct_f.unpack(str[start:end])
03498 self.planning_scene.collision_map.boxes.append(val1)
03499 return self
03500 except struct.error as e:
03501 raise genpy.DeserializationError(e)
03502
03503
03504 def serialize_numpy(self, buff, numpy):
03505 """
03506 serialize message with numpy array types into buffer
03507 :param buff: buffer, ``StringIO``
03508 :param numpy: numpy python module
03509 """
03510 try:
03511 _x = self
03512 buff.write(_struct_3I.pack(_x.planning_scene.robot_state.joint_state.header.seq, _x.planning_scene.robot_state.joint_state.header.stamp.secs, _x.planning_scene.robot_state.joint_state.header.stamp.nsecs))
03513 _x = self.planning_scene.robot_state.joint_state.header.frame_id
03514 length = len(_x)
03515 if python3 or type(_x) == unicode:
03516 _x = _x.encode('utf-8')
03517 length = len(_x)
03518 buff.write(struct.pack('<I%ss'%length, length, _x))
03519 length = len(self.planning_scene.robot_state.joint_state.name)
03520 buff.write(_struct_I.pack(length))
03521 for val1 in self.planning_scene.robot_state.joint_state.name:
03522 length = len(val1)
03523 if python3 or type(val1) == unicode:
03524 val1 = val1.encode('utf-8')
03525 length = len(val1)
03526 buff.write(struct.pack('<I%ss'%length, length, val1))
03527 length = len(self.planning_scene.robot_state.joint_state.position)
03528 buff.write(_struct_I.pack(length))
03529 pattern = '<%sd'%length
03530 buff.write(self.planning_scene.robot_state.joint_state.position.tostring())
03531 length = len(self.planning_scene.robot_state.joint_state.velocity)
03532 buff.write(_struct_I.pack(length))
03533 pattern = '<%sd'%length
03534 buff.write(self.planning_scene.robot_state.joint_state.velocity.tostring())
03535 length = len(self.planning_scene.robot_state.joint_state.effort)
03536 buff.write(_struct_I.pack(length))
03537 pattern = '<%sd'%length
03538 buff.write(self.planning_scene.robot_state.joint_state.effort.tostring())
03539 _x = self
03540 buff.write(_struct_2I.pack(_x.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs))
03541 length = len(self.planning_scene.robot_state.multi_dof_joint_state.joint_names)
03542 buff.write(_struct_I.pack(length))
03543 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.joint_names:
03544 length = len(val1)
03545 if python3 or type(val1) == unicode:
03546 val1 = val1.encode('utf-8')
03547 length = len(val1)
03548 buff.write(struct.pack('<I%ss'%length, length, val1))
03549 length = len(self.planning_scene.robot_state.multi_dof_joint_state.frame_ids)
03550 buff.write(_struct_I.pack(length))
03551 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.frame_ids:
03552 length = len(val1)
03553 if python3 or type(val1) == unicode:
03554 val1 = val1.encode('utf-8')
03555 length = len(val1)
03556 buff.write(struct.pack('<I%ss'%length, length, val1))
03557 length = len(self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids)
03558 buff.write(_struct_I.pack(length))
03559 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids:
03560 length = len(val1)
03561 if python3 or type(val1) == unicode:
03562 val1 = val1.encode('utf-8')
03563 length = len(val1)
03564 buff.write(struct.pack('<I%ss'%length, length, val1))
03565 length = len(self.planning_scene.robot_state.multi_dof_joint_state.poses)
03566 buff.write(_struct_I.pack(length))
03567 for val1 in self.planning_scene.robot_state.multi_dof_joint_state.poses:
03568 _v169 = val1.position
03569 _x = _v169
03570 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03571 _v170 = val1.orientation
03572 _x = _v170
03573 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03574 length = len(self.planning_scene.fixed_frame_transforms)
03575 buff.write(_struct_I.pack(length))
03576 for val1 in self.planning_scene.fixed_frame_transforms:
03577 _v171 = val1.header
03578 buff.write(_struct_I.pack(_v171.seq))
03579 _v172 = _v171.stamp
03580 _x = _v172
03581 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03582 _x = _v171.frame_id
03583 length = len(_x)
03584 if python3 or type(_x) == unicode:
03585 _x = _x.encode('utf-8')
03586 length = len(_x)
03587 buff.write(struct.pack('<I%ss'%length, length, _x))
03588 _x = val1.child_frame_id
03589 length = len(_x)
03590 if python3 or type(_x) == unicode:
03591 _x = _x.encode('utf-8')
03592 length = len(_x)
03593 buff.write(struct.pack('<I%ss'%length, length, _x))
03594 _v173 = val1.transform
03595 _v174 = _v173.translation
03596 _x = _v174
03597 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03598 _v175 = _v173.rotation
03599 _x = _v175
03600 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03601 length = len(self.planning_scene.allowed_collision_matrix.link_names)
03602 buff.write(_struct_I.pack(length))
03603 for val1 in self.planning_scene.allowed_collision_matrix.link_names:
03604 length = len(val1)
03605 if python3 or type(val1) == unicode:
03606 val1 = val1.encode('utf-8')
03607 length = len(val1)
03608 buff.write(struct.pack('<I%ss'%length, length, val1))
03609 length = len(self.planning_scene.allowed_collision_matrix.entries)
03610 buff.write(_struct_I.pack(length))
03611 for val1 in self.planning_scene.allowed_collision_matrix.entries:
03612 length = len(val1.enabled)
03613 buff.write(_struct_I.pack(length))
03614 pattern = '<%sB'%length
03615 buff.write(val1.enabled.tostring())
03616 length = len(self.planning_scene.allowed_contacts)
03617 buff.write(_struct_I.pack(length))
03618 for val1 in self.planning_scene.allowed_contacts:
03619 _x = val1.name
03620 length = len(_x)
03621 if python3 or type(_x) == unicode:
03622 _x = _x.encode('utf-8')
03623 length = len(_x)
03624 buff.write(struct.pack('<I%ss'%length, length, _x))
03625 _v176 = val1.shape
03626 buff.write(_struct_b.pack(_v176.type))
03627 length = len(_v176.dimensions)
03628 buff.write(_struct_I.pack(length))
03629 pattern = '<%sd'%length
03630 buff.write(_v176.dimensions.tostring())
03631 length = len(_v176.triangles)
03632 buff.write(_struct_I.pack(length))
03633 pattern = '<%si'%length
03634 buff.write(_v176.triangles.tostring())
03635 length = len(_v176.vertices)
03636 buff.write(_struct_I.pack(length))
03637 for val3 in _v176.vertices:
03638 _x = val3
03639 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03640 _v177 = val1.pose_stamped
03641 _v178 = _v177.header
03642 buff.write(_struct_I.pack(_v178.seq))
03643 _v179 = _v178.stamp
03644 _x = _v179
03645 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03646 _x = _v178.frame_id
03647 length = len(_x)
03648 if python3 or type(_x) == unicode:
03649 _x = _x.encode('utf-8')
03650 length = len(_x)
03651 buff.write(struct.pack('<I%ss'%length, length, _x))
03652 _v180 = _v177.pose
03653 _v181 = _v180.position
03654 _x = _v181
03655 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03656 _v182 = _v180.orientation
03657 _x = _v182
03658 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03659 length = len(val1.link_names)
03660 buff.write(_struct_I.pack(length))
03661 for val2 in val1.link_names:
03662 length = len(val2)
03663 if python3 or type(val2) == unicode:
03664 val2 = val2.encode('utf-8')
03665 length = len(val2)
03666 buff.write(struct.pack('<I%ss'%length, length, val2))
03667 buff.write(_struct_d.pack(val1.penetration_depth))
03668 length = len(self.planning_scene.link_padding)
03669 buff.write(_struct_I.pack(length))
03670 for val1 in self.planning_scene.link_padding:
03671 _x = val1.link_name
03672 length = len(_x)
03673 if python3 or type(_x) == unicode:
03674 _x = _x.encode('utf-8')
03675 length = len(_x)
03676 buff.write(struct.pack('<I%ss'%length, length, _x))
03677 buff.write(_struct_d.pack(val1.padding))
03678 length = len(self.planning_scene.collision_objects)
03679 buff.write(_struct_I.pack(length))
03680 for val1 in self.planning_scene.collision_objects:
03681 _v183 = val1.header
03682 buff.write(_struct_I.pack(_v183.seq))
03683 _v184 = _v183.stamp
03684 _x = _v184
03685 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03686 _x = _v183.frame_id
03687 length = len(_x)
03688 if python3 or type(_x) == unicode:
03689 _x = _x.encode('utf-8')
03690 length = len(_x)
03691 buff.write(struct.pack('<I%ss'%length, length, _x))
03692 _x = val1.id
03693 length = len(_x)
03694 if python3 or type(_x) == unicode:
03695 _x = _x.encode('utf-8')
03696 length = len(_x)
03697 buff.write(struct.pack('<I%ss'%length, length, _x))
03698 buff.write(_struct_f.pack(val1.padding))
03699 _v185 = val1.operation
03700 buff.write(_struct_b.pack(_v185.operation))
03701 length = len(val1.shapes)
03702 buff.write(_struct_I.pack(length))
03703 for val2 in val1.shapes:
03704 buff.write(_struct_b.pack(val2.type))
03705 length = len(val2.dimensions)
03706 buff.write(_struct_I.pack(length))
03707 pattern = '<%sd'%length
03708 buff.write(val2.dimensions.tostring())
03709 length = len(val2.triangles)
03710 buff.write(_struct_I.pack(length))
03711 pattern = '<%si'%length
03712 buff.write(val2.triangles.tostring())
03713 length = len(val2.vertices)
03714 buff.write(_struct_I.pack(length))
03715 for val3 in val2.vertices:
03716 _x = val3
03717 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03718 length = len(val1.poses)
03719 buff.write(_struct_I.pack(length))
03720 for val2 in val1.poses:
03721 _v186 = val2.position
03722 _x = _v186
03723 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03724 _v187 = val2.orientation
03725 _x = _v187
03726 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03727 length = len(self.planning_scene.attached_collision_objects)
03728 buff.write(_struct_I.pack(length))
03729 for val1 in self.planning_scene.attached_collision_objects:
03730 _x = val1.link_name
03731 length = len(_x)
03732 if python3 or type(_x) == unicode:
03733 _x = _x.encode('utf-8')
03734 length = len(_x)
03735 buff.write(struct.pack('<I%ss'%length, length, _x))
03736 _v188 = val1.object
03737 _v189 = _v188.header
03738 buff.write(_struct_I.pack(_v189.seq))
03739 _v190 = _v189.stamp
03740 _x = _v190
03741 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03742 _x = _v189.frame_id
03743 length = len(_x)
03744 if python3 or type(_x) == unicode:
03745 _x = _x.encode('utf-8')
03746 length = len(_x)
03747 buff.write(struct.pack('<I%ss'%length, length, _x))
03748 _x = _v188.id
03749 length = len(_x)
03750 if python3 or type(_x) == unicode:
03751 _x = _x.encode('utf-8')
03752 length = len(_x)
03753 buff.write(struct.pack('<I%ss'%length, length, _x))
03754 buff.write(_struct_f.pack(_v188.padding))
03755 _v191 = _v188.operation
03756 buff.write(_struct_b.pack(_v191.operation))
03757 length = len(_v188.shapes)
03758 buff.write(_struct_I.pack(length))
03759 for val3 in _v188.shapes:
03760 buff.write(_struct_b.pack(val3.type))
03761 length = len(val3.dimensions)
03762 buff.write(_struct_I.pack(length))
03763 pattern = '<%sd'%length
03764 buff.write(val3.dimensions.tostring())
03765 length = len(val3.triangles)
03766 buff.write(_struct_I.pack(length))
03767 pattern = '<%si'%length
03768 buff.write(val3.triangles.tostring())
03769 length = len(val3.vertices)
03770 buff.write(_struct_I.pack(length))
03771 for val4 in val3.vertices:
03772 _x = val4
03773 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03774 length = len(_v188.poses)
03775 buff.write(_struct_I.pack(length))
03776 for val3 in _v188.poses:
03777 _v192 = val3.position
03778 _x = _v192
03779 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03780 _v193 = val3.orientation
03781 _x = _v193
03782 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03783 length = len(val1.touch_links)
03784 buff.write(_struct_I.pack(length))
03785 for val2 in val1.touch_links:
03786 length = len(val2)
03787 if python3 or type(val2) == unicode:
03788 val2 = val2.encode('utf-8')
03789 length = len(val2)
03790 buff.write(struct.pack('<I%ss'%length, length, val2))
03791 _x = self
03792 buff.write(_struct_3I.pack(_x.planning_scene.collision_map.header.seq, _x.planning_scene.collision_map.header.stamp.secs, _x.planning_scene.collision_map.header.stamp.nsecs))
03793 _x = self.planning_scene.collision_map.header.frame_id
03794 length = len(_x)
03795 if python3 or type(_x) == unicode:
03796 _x = _x.encode('utf-8')
03797 length = len(_x)
03798 buff.write(struct.pack('<I%ss'%length, length, _x))
03799 length = len(self.planning_scene.collision_map.boxes)
03800 buff.write(_struct_I.pack(length))
03801 for val1 in self.planning_scene.collision_map.boxes:
03802 _v194 = val1.center
03803 _x = _v194
03804 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
03805 _v195 = val1.extents
03806 _x = _v195
03807 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
03808 _v196 = val1.axis
03809 _x = _v196
03810 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
03811 buff.write(_struct_f.pack(val1.angle))
03812 except struct.error as se: self._check_types(se)
03813 except TypeError as te: self._check_types(te)
03814
03815 def deserialize_numpy(self, str, numpy):
03816 """
03817 unpack serialized message in str into this message instance using numpy for array types
03818 :param str: byte array of serialized message, ``str``
03819 :param numpy: numpy python module
03820 """
03821 try:
03822 if self.planning_scene is None:
03823 self.planning_scene = arm_navigation_msgs.msg.PlanningScene()
03824 end = 0
03825 _x = self
03826 start = end
03827 end += 12
03828 (_x.planning_scene.robot_state.joint_state.header.seq, _x.planning_scene.robot_state.joint_state.header.stamp.secs, _x.planning_scene.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03829 start = end
03830 end += 4
03831 (length,) = _struct_I.unpack(str[start:end])
03832 start = end
03833 end += length
03834 if python3:
03835 self.planning_scene.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
03836 else:
03837 self.planning_scene.robot_state.joint_state.header.frame_id = str[start:end]
03838 start = end
03839 end += 4
03840 (length,) = _struct_I.unpack(str[start:end])
03841 self.planning_scene.robot_state.joint_state.name = []
03842 for i in range(0, length):
03843 start = end
03844 end += 4
03845 (length,) = _struct_I.unpack(str[start:end])
03846 start = end
03847 end += length
03848 if python3:
03849 val1 = str[start:end].decode('utf-8')
03850 else:
03851 val1 = str[start:end]
03852 self.planning_scene.robot_state.joint_state.name.append(val1)
03853 start = end
03854 end += 4
03855 (length,) = _struct_I.unpack(str[start:end])
03856 pattern = '<%sd'%length
03857 start = end
03858 end += struct.calcsize(pattern)
03859 self.planning_scene.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03860 start = end
03861 end += 4
03862 (length,) = _struct_I.unpack(str[start:end])
03863 pattern = '<%sd'%length
03864 start = end
03865 end += struct.calcsize(pattern)
03866 self.planning_scene.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03867 start = end
03868 end += 4
03869 (length,) = _struct_I.unpack(str[start:end])
03870 pattern = '<%sd'%length
03871 start = end
03872 end += struct.calcsize(pattern)
03873 self.planning_scene.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03874 _x = self
03875 start = end
03876 end += 8
03877 (_x.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03878 start = end
03879 end += 4
03880 (length,) = _struct_I.unpack(str[start:end])
03881 self.planning_scene.robot_state.multi_dof_joint_state.joint_names = []
03882 for i in range(0, length):
03883 start = end
03884 end += 4
03885 (length,) = _struct_I.unpack(str[start:end])
03886 start = end
03887 end += length
03888 if python3:
03889 val1 = str[start:end].decode('utf-8')
03890 else:
03891 val1 = str[start:end]
03892 self.planning_scene.robot_state.multi_dof_joint_state.joint_names.append(val1)
03893 start = end
03894 end += 4
03895 (length,) = _struct_I.unpack(str[start:end])
03896 self.planning_scene.robot_state.multi_dof_joint_state.frame_ids = []
03897 for i in range(0, length):
03898 start = end
03899 end += 4
03900 (length,) = _struct_I.unpack(str[start:end])
03901 start = end
03902 end += length
03903 if python3:
03904 val1 = str[start:end].decode('utf-8')
03905 else:
03906 val1 = str[start:end]
03907 self.planning_scene.robot_state.multi_dof_joint_state.frame_ids.append(val1)
03908 start = end
03909 end += 4
03910 (length,) = _struct_I.unpack(str[start:end])
03911 self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids = []
03912 for i in range(0, length):
03913 start = end
03914 end += 4
03915 (length,) = _struct_I.unpack(str[start:end])
03916 start = end
03917 end += length
03918 if python3:
03919 val1 = str[start:end].decode('utf-8')
03920 else:
03921 val1 = str[start:end]
03922 self.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
03923 start = end
03924 end += 4
03925 (length,) = _struct_I.unpack(str[start:end])
03926 self.planning_scene.robot_state.multi_dof_joint_state.poses = []
03927 for i in range(0, length):
03928 val1 = geometry_msgs.msg.Pose()
03929 _v197 = val1.position
03930 _x = _v197
03931 start = end
03932 end += 24
03933 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03934 _v198 = val1.orientation
03935 _x = _v198
03936 start = end
03937 end += 32
03938 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03939 self.planning_scene.robot_state.multi_dof_joint_state.poses.append(val1)
03940 start = end
03941 end += 4
03942 (length,) = _struct_I.unpack(str[start:end])
03943 self.planning_scene.fixed_frame_transforms = []
03944 for i in range(0, length):
03945 val1 = geometry_msgs.msg.TransformStamped()
03946 _v199 = val1.header
03947 start = end
03948 end += 4
03949 (_v199.seq,) = _struct_I.unpack(str[start:end])
03950 _v200 = _v199.stamp
03951 _x = _v200
03952 start = end
03953 end += 8
03954 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03955 start = end
03956 end += 4
03957 (length,) = _struct_I.unpack(str[start:end])
03958 start = end
03959 end += length
03960 if python3:
03961 _v199.frame_id = str[start:end].decode('utf-8')
03962 else:
03963 _v199.frame_id = str[start:end]
03964 start = end
03965 end += 4
03966 (length,) = _struct_I.unpack(str[start:end])
03967 start = end
03968 end += length
03969 if python3:
03970 val1.child_frame_id = str[start:end].decode('utf-8')
03971 else:
03972 val1.child_frame_id = str[start:end]
03973 _v201 = val1.transform
03974 _v202 = _v201.translation
03975 _x = _v202
03976 start = end
03977 end += 24
03978 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03979 _v203 = _v201.rotation
03980 _x = _v203
03981 start = end
03982 end += 32
03983 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03984 self.planning_scene.fixed_frame_transforms.append(val1)
03985 start = end
03986 end += 4
03987 (length,) = _struct_I.unpack(str[start:end])
03988 self.planning_scene.allowed_collision_matrix.link_names = []
03989 for i in range(0, length):
03990 start = end
03991 end += 4
03992 (length,) = _struct_I.unpack(str[start:end])
03993 start = end
03994 end += length
03995 if python3:
03996 val1 = str[start:end].decode('utf-8')
03997 else:
03998 val1 = str[start:end]
03999 self.planning_scene.allowed_collision_matrix.link_names.append(val1)
04000 start = end
04001 end += 4
04002 (length,) = _struct_I.unpack(str[start:end])
04003 self.planning_scene.allowed_collision_matrix.entries = []
04004 for i in range(0, length):
04005 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
04006 start = end
04007 end += 4
04008 (length,) = _struct_I.unpack(str[start:end])
04009 pattern = '<%sB'%length
04010 start = end
04011 end += struct.calcsize(pattern)
04012 val1.enabled = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=length)
04013 val1.enabled = map(bool, val1.enabled)
04014 self.planning_scene.allowed_collision_matrix.entries.append(val1)
04015 start = end
04016 end += 4
04017 (length,) = _struct_I.unpack(str[start:end])
04018 self.planning_scene.allowed_contacts = []
04019 for i in range(0, length):
04020 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
04021 start = end
04022 end += 4
04023 (length,) = _struct_I.unpack(str[start:end])
04024 start = end
04025 end += length
04026 if python3:
04027 val1.name = str[start:end].decode('utf-8')
04028 else:
04029 val1.name = str[start:end]
04030 _v204 = val1.shape
04031 start = end
04032 end += 1
04033 (_v204.type,) = _struct_b.unpack(str[start:end])
04034 start = end
04035 end += 4
04036 (length,) = _struct_I.unpack(str[start:end])
04037 pattern = '<%sd'%length
04038 start = end
04039 end += struct.calcsize(pattern)
04040 _v204.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04041 start = end
04042 end += 4
04043 (length,) = _struct_I.unpack(str[start:end])
04044 pattern = '<%si'%length
04045 start = end
04046 end += struct.calcsize(pattern)
04047 _v204.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
04048 start = end
04049 end += 4
04050 (length,) = _struct_I.unpack(str[start:end])
04051 _v204.vertices = []
04052 for i in range(0, length):
04053 val3 = geometry_msgs.msg.Point()
04054 _x = val3
04055 start = end
04056 end += 24
04057 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04058 _v204.vertices.append(val3)
04059 _v205 = val1.pose_stamped
04060 _v206 = _v205.header
04061 start = end
04062 end += 4
04063 (_v206.seq,) = _struct_I.unpack(str[start:end])
04064 _v207 = _v206.stamp
04065 _x = _v207
04066 start = end
04067 end += 8
04068 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04069 start = end
04070 end += 4
04071 (length,) = _struct_I.unpack(str[start:end])
04072 start = end
04073 end += length
04074 if python3:
04075 _v206.frame_id = str[start:end].decode('utf-8')
04076 else:
04077 _v206.frame_id = str[start:end]
04078 _v208 = _v205.pose
04079 _v209 = _v208.position
04080 _x = _v209
04081 start = end
04082 end += 24
04083 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04084 _v210 = _v208.orientation
04085 _x = _v210
04086 start = end
04087 end += 32
04088 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04089 start = end
04090 end += 4
04091 (length,) = _struct_I.unpack(str[start:end])
04092 val1.link_names = []
04093 for i in range(0, length):
04094 start = end
04095 end += 4
04096 (length,) = _struct_I.unpack(str[start:end])
04097 start = end
04098 end += length
04099 if python3:
04100 val2 = str[start:end].decode('utf-8')
04101 else:
04102 val2 = str[start:end]
04103 val1.link_names.append(val2)
04104 start = end
04105 end += 8
04106 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
04107 self.planning_scene.allowed_contacts.append(val1)
04108 start = end
04109 end += 4
04110 (length,) = _struct_I.unpack(str[start:end])
04111 self.planning_scene.link_padding = []
04112 for i in range(0, length):
04113 val1 = arm_navigation_msgs.msg.LinkPadding()
04114 start = end
04115 end += 4
04116 (length,) = _struct_I.unpack(str[start:end])
04117 start = end
04118 end += length
04119 if python3:
04120 val1.link_name = str[start:end].decode('utf-8')
04121 else:
04122 val1.link_name = str[start:end]
04123 start = end
04124 end += 8
04125 (val1.padding,) = _struct_d.unpack(str[start:end])
04126 self.planning_scene.link_padding.append(val1)
04127 start = end
04128 end += 4
04129 (length,) = _struct_I.unpack(str[start:end])
04130 self.planning_scene.collision_objects = []
04131 for i in range(0, length):
04132 val1 = arm_navigation_msgs.msg.CollisionObject()
04133 _v211 = val1.header
04134 start = end
04135 end += 4
04136 (_v211.seq,) = _struct_I.unpack(str[start:end])
04137 _v212 = _v211.stamp
04138 _x = _v212
04139 start = end
04140 end += 8
04141 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04142 start = end
04143 end += 4
04144 (length,) = _struct_I.unpack(str[start:end])
04145 start = end
04146 end += length
04147 if python3:
04148 _v211.frame_id = str[start:end].decode('utf-8')
04149 else:
04150 _v211.frame_id = str[start:end]
04151 start = end
04152 end += 4
04153 (length,) = _struct_I.unpack(str[start:end])
04154 start = end
04155 end += length
04156 if python3:
04157 val1.id = str[start:end].decode('utf-8')
04158 else:
04159 val1.id = str[start:end]
04160 start = end
04161 end += 4
04162 (val1.padding,) = _struct_f.unpack(str[start:end])
04163 _v213 = val1.operation
04164 start = end
04165 end += 1
04166 (_v213.operation,) = _struct_b.unpack(str[start:end])
04167 start = end
04168 end += 4
04169 (length,) = _struct_I.unpack(str[start:end])
04170 val1.shapes = []
04171 for i in range(0, length):
04172 val2 = arm_navigation_msgs.msg.Shape()
04173 start = end
04174 end += 1
04175 (val2.type,) = _struct_b.unpack(str[start:end])
04176 start = end
04177 end += 4
04178 (length,) = _struct_I.unpack(str[start:end])
04179 pattern = '<%sd'%length
04180 start = end
04181 end += struct.calcsize(pattern)
04182 val2.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04183 start = end
04184 end += 4
04185 (length,) = _struct_I.unpack(str[start:end])
04186 pattern = '<%si'%length
04187 start = end
04188 end += struct.calcsize(pattern)
04189 val2.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
04190 start = end
04191 end += 4
04192 (length,) = _struct_I.unpack(str[start:end])
04193 val2.vertices = []
04194 for i in range(0, length):
04195 val3 = geometry_msgs.msg.Point()
04196 _x = val3
04197 start = end
04198 end += 24
04199 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04200 val2.vertices.append(val3)
04201 val1.shapes.append(val2)
04202 start = end
04203 end += 4
04204 (length,) = _struct_I.unpack(str[start:end])
04205 val1.poses = []
04206 for i in range(0, length):
04207 val2 = geometry_msgs.msg.Pose()
04208 _v214 = val2.position
04209 _x = _v214
04210 start = end
04211 end += 24
04212 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04213 _v215 = val2.orientation
04214 _x = _v215
04215 start = end
04216 end += 32
04217 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04218 val1.poses.append(val2)
04219 self.planning_scene.collision_objects.append(val1)
04220 start = end
04221 end += 4
04222 (length,) = _struct_I.unpack(str[start:end])
04223 self.planning_scene.attached_collision_objects = []
04224 for i in range(0, length):
04225 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
04226 start = end
04227 end += 4
04228 (length,) = _struct_I.unpack(str[start:end])
04229 start = end
04230 end += length
04231 if python3:
04232 val1.link_name = str[start:end].decode('utf-8')
04233 else:
04234 val1.link_name = str[start:end]
04235 _v216 = val1.object
04236 _v217 = _v216.header
04237 start = end
04238 end += 4
04239 (_v217.seq,) = _struct_I.unpack(str[start:end])
04240 _v218 = _v217.stamp
04241 _x = _v218
04242 start = end
04243 end += 8
04244 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
04245 start = end
04246 end += 4
04247 (length,) = _struct_I.unpack(str[start:end])
04248 start = end
04249 end += length
04250 if python3:
04251 _v217.frame_id = str[start:end].decode('utf-8')
04252 else:
04253 _v217.frame_id = str[start:end]
04254 start = end
04255 end += 4
04256 (length,) = _struct_I.unpack(str[start:end])
04257 start = end
04258 end += length
04259 if python3:
04260 _v216.id = str[start:end].decode('utf-8')
04261 else:
04262 _v216.id = str[start:end]
04263 start = end
04264 end += 4
04265 (_v216.padding,) = _struct_f.unpack(str[start:end])
04266 _v219 = _v216.operation
04267 start = end
04268 end += 1
04269 (_v219.operation,) = _struct_b.unpack(str[start:end])
04270 start = end
04271 end += 4
04272 (length,) = _struct_I.unpack(str[start:end])
04273 _v216.shapes = []
04274 for i in range(0, length):
04275 val3 = arm_navigation_msgs.msg.Shape()
04276 start = end
04277 end += 1
04278 (val3.type,) = _struct_b.unpack(str[start:end])
04279 start = end
04280 end += 4
04281 (length,) = _struct_I.unpack(str[start:end])
04282 pattern = '<%sd'%length
04283 start = end
04284 end += struct.calcsize(pattern)
04285 val3.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
04286 start = end
04287 end += 4
04288 (length,) = _struct_I.unpack(str[start:end])
04289 pattern = '<%si'%length
04290 start = end
04291 end += struct.calcsize(pattern)
04292 val3.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
04293 start = end
04294 end += 4
04295 (length,) = _struct_I.unpack(str[start:end])
04296 val3.vertices = []
04297 for i in range(0, length):
04298 val4 = geometry_msgs.msg.Point()
04299 _x = val4
04300 start = end
04301 end += 24
04302 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04303 val3.vertices.append(val4)
04304 _v216.shapes.append(val3)
04305 start = end
04306 end += 4
04307 (length,) = _struct_I.unpack(str[start:end])
04308 _v216.poses = []
04309 for i in range(0, length):
04310 val3 = geometry_msgs.msg.Pose()
04311 _v220 = val3.position
04312 _x = _v220
04313 start = end
04314 end += 24
04315 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
04316 _v221 = val3.orientation
04317 _x = _v221
04318 start = end
04319 end += 32
04320 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
04321 _v216.poses.append(val3)
04322 start = end
04323 end += 4
04324 (length,) = _struct_I.unpack(str[start:end])
04325 val1.touch_links = []
04326 for i in range(0, length):
04327 start = end
04328 end += 4
04329 (length,) = _struct_I.unpack(str[start:end])
04330 start = end
04331 end += length
04332 if python3:
04333 val2 = str[start:end].decode('utf-8')
04334 else:
04335 val2 = str[start:end]
04336 val1.touch_links.append(val2)
04337 self.planning_scene.attached_collision_objects.append(val1)
04338 _x = self
04339 start = end
04340 end += 12
04341 (_x.planning_scene.collision_map.header.seq, _x.planning_scene.collision_map.header.stamp.secs, _x.planning_scene.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
04342 start = end
04343 end += 4
04344 (length,) = _struct_I.unpack(str[start:end])
04345 start = end
04346 end += length
04347 if python3:
04348 self.planning_scene.collision_map.header.frame_id = str[start:end].decode('utf-8')
04349 else:
04350 self.planning_scene.collision_map.header.frame_id = str[start:end]
04351 start = end
04352 end += 4
04353 (length,) = _struct_I.unpack(str[start:end])
04354 self.planning_scene.collision_map.boxes = []
04355 for i in range(0, length):
04356 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
04357 _v222 = val1.center
04358 _x = _v222
04359 start = end
04360 end += 12
04361 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
04362 _v223 = val1.extents
04363 _x = _v223
04364 start = end
04365 end += 12
04366 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
04367 _v224 = val1.axis
04368 _x = _v224
04369 start = end
04370 end += 12
04371 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
04372 start = end
04373 end += 4
04374 (val1.angle,) = _struct_f.unpack(str[start:end])
04375 self.planning_scene.collision_map.boxes.append(val1)
04376 return self
04377 except struct.error as e:
04378 raise genpy.DeserializationError(e)
04379
04380 _struct_I = genpy.struct_I
04381 _struct_b = struct.Struct("<b")
04382 _struct_d = struct.Struct("<d")
04383 _struct_f = struct.Struct("<f")
04384 _struct_3f = struct.Struct("<3f")
04385 _struct_3I = struct.Struct("<3I")
04386 _struct_4d = struct.Struct("<4d")
04387 _struct_2I = struct.Struct("<2I")
04388 _struct_3d = struct.Struct("<3d")
04389 class GetPlanningScene(object):
04390 _type = 'arm_navigation_msgs/GetPlanningScene'
04391 _md5sum = '0a7b07718e4e5c5d35740c730509a151'
04392 _request_class = GetPlanningSceneRequest
04393 _response_class = GetPlanningSceneResponse