00001 """autogenerated by genmsg_py from SyncPlanningSceneActionGoal.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import arm_navigation_msgs.msg
00006 import roslib.rostime
00007 import actionlib_msgs.msg
00008 import geometry_msgs.msg
00009 import sensor_msgs.msg
00010 import std_msgs.msg
00011
00012 class SyncPlanningSceneActionGoal(roslib.message.Message):
00013 _md5sum = "d841beb927266bf620ac574e2b28ec55"
00014 _type = "arm_navigation_msgs/SyncPlanningSceneActionGoal"
00015 _has_header = True
00016 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00017
00018 Header header
00019 actionlib_msgs/GoalID goal_id
00020 SyncPlanningSceneGoal goal
00021
00022 ================================================================================
00023 MSG: std_msgs/Header
00024 # Standard metadata for higher-level stamped data types.
00025 # This is generally used to communicate timestamped data
00026 # in a particular coordinate frame.
00027 #
00028 # sequence ID: consecutively increasing ID
00029 uint32 seq
00030 #Two-integer timestamp that is expressed as:
00031 # * stamp.secs: seconds (stamp_secs) since epoch
00032 # * stamp.nsecs: nanoseconds since stamp_secs
00033 # time-handling sugar is provided by the client library
00034 time stamp
00035 #Frame this data is associated with
00036 # 0: no frame
00037 # 1: global frame
00038 string frame_id
00039
00040 ================================================================================
00041 MSG: actionlib_msgs/GoalID
00042 # The stamp should store the time at which this goal was requested.
00043 # It is used by an action server when it tries to preempt all
00044 # goals that were requested before a certain time
00045 time stamp
00046
00047 # The id provides a way to associate feedback and
00048 # result message with specific goal requests. The id
00049 # specified must be unique.
00050 string id
00051
00052
00053 ================================================================================
00054 MSG: arm_navigation_msgs/SyncPlanningSceneGoal
00055 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00056 # THIS MESSAGE IS FOR INTERNAL COMMUNICATION BETWEEN
00057 # PLANNING ENVIRONMENT COMPONENTS ONLY
00058
00059 #Full planning scene
00060 PlanningScene planning_scene
00061
00062 ================================================================================
00063 MSG: arm_navigation_msgs/PlanningScene
00064 #full robot state
00065 arm_navigation_msgs/RobotState robot_state
00066
00067 #additional frames for duplicating tf
00068 geometry_msgs/TransformStamped[] fixed_frame_transforms
00069
00070 #full allowed collision matrix
00071 AllowedCollisionMatrix allowed_collision_matrix
00072
00073 #allowed contacts
00074 arm_navigation_msgs/AllowedContactSpecification[] allowed_contacts
00075
00076 #all link paddings
00077 arm_navigation_msgs/LinkPadding[] link_padding
00078
00079 #collision objects
00080 arm_navigation_msgs/CollisionObject[] collision_objects
00081 arm_navigation_msgs/AttachedCollisionObject[] attached_collision_objects
00082
00083 #the collision map
00084 arm_navigation_msgs/CollisionMap collision_map
00085
00086 ================================================================================
00087 MSG: arm_navigation_msgs/RobotState
00088 # This message contains information about the robot state, i.e. the positions of its joints and links
00089 sensor_msgs/JointState joint_state
00090 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00091
00092 ================================================================================
00093 MSG: sensor_msgs/JointState
00094 # This is a message that holds data to describe the state of a set of torque controlled joints.
00095 #
00096 # The state of each joint (revolute or prismatic) is defined by:
00097 # * the position of the joint (rad or m),
00098 # * the velocity of the joint (rad/s or m/s) and
00099 # * the effort that is applied in the joint (Nm or N).
00100 #
00101 # Each joint is uniquely identified by its name
00102 # The header specifies the time at which the joint states were recorded. All the joint states
00103 # in one message have to be recorded at the same time.
00104 #
00105 # This message consists of a multiple arrays, one for each part of the joint state.
00106 # The goal is to make each of the fields optional. When e.g. your joints have no
00107 # effort associated with them, you can leave the effort array empty.
00108 #
00109 # All arrays in this message should have the same size, or be empty.
00110 # This is the only way to uniquely associate the joint name with the correct
00111 # states.
00112
00113
00114 Header header
00115
00116 string[] name
00117 float64[] position
00118 float64[] velocity
00119 float64[] effort
00120
00121 ================================================================================
00122 MSG: arm_navigation_msgs/MultiDOFJointState
00123 #A representation of a multi-dof joint state
00124 time stamp
00125 string[] joint_names
00126 string[] frame_ids
00127 string[] child_frame_ids
00128 geometry_msgs/Pose[] poses
00129
00130 ================================================================================
00131 MSG: geometry_msgs/Pose
00132 # A representation of pose in free space, composed of postion and orientation.
00133 Point position
00134 Quaternion orientation
00135
00136 ================================================================================
00137 MSG: geometry_msgs/Point
00138 # This contains the position of a point in free space
00139 float64 x
00140 float64 y
00141 float64 z
00142
00143 ================================================================================
00144 MSG: geometry_msgs/Quaternion
00145 # This represents an orientation in free space in quaternion form.
00146
00147 float64 x
00148 float64 y
00149 float64 z
00150 float64 w
00151
00152 ================================================================================
00153 MSG: geometry_msgs/TransformStamped
00154 # This expresses a transform from coordinate frame header.frame_id
00155 # to the coordinate frame child_frame_id
00156 #
00157 # This message is mostly used by the
00158 # <a href="http://www.ros.org/wiki/tf">tf</a> package.
00159 # See it's documentation for more information.
00160
00161 Header header
00162 string child_frame_id # the frame id of the child frame
00163 Transform transform
00164
00165 ================================================================================
00166 MSG: geometry_msgs/Transform
00167 # This represents the transform between two coordinate frames in free space.
00168
00169 Vector3 translation
00170 Quaternion rotation
00171
00172 ================================================================================
00173 MSG: geometry_msgs/Vector3
00174 # This represents a vector in free space.
00175
00176 float64 x
00177 float64 y
00178 float64 z
00179 ================================================================================
00180 MSG: arm_navigation_msgs/AllowedCollisionMatrix
00181 # the list of link names in the matrix
00182 string[] link_names
00183
00184 # the individual entries in the allowed collision matrix
00185 # symmetric, with same order as link_names
00186 AllowedCollisionEntry[] entries
00187
00188 ================================================================================
00189 MSG: arm_navigation_msgs/AllowedCollisionEntry
00190 # whether or not collision checking is enabled
00191 bool[] enabled
00192
00193 ================================================================================
00194 MSG: arm_navigation_msgs/AllowedContactSpecification
00195 # The names of the regions
00196 string name
00197
00198 # The shape of the region in the environment
00199 arm_navigation_msgs/Shape shape
00200
00201 # The pose of the space defining the region
00202 geometry_msgs/PoseStamped pose_stamped
00203
00204 # The set of links that will be allowed to have penetration contact within this region
00205 string[] link_names
00206
00207 # The maximum penetration depth allowed for every link
00208 float64 penetration_depth
00209
00210 ================================================================================
00211 MSG: arm_navigation_msgs/Shape
00212 byte SPHERE=0
00213 byte BOX=1
00214 byte CYLINDER=2
00215 byte MESH=3
00216
00217 byte type
00218
00219
00220 #### define sphere, box, cylinder ####
00221 # the origin of each shape is considered at the shape's center
00222
00223 # for sphere
00224 # radius := dimensions[0]
00225
00226 # for cylinder
00227 # radius := dimensions[0]
00228 # length := dimensions[1]
00229 # the length is along the Z axis
00230
00231 # for box
00232 # size_x := dimensions[0]
00233 # size_y := dimensions[1]
00234 # size_z := dimensions[2]
00235 float64[] dimensions
00236
00237
00238 #### define mesh ####
00239
00240 # list of triangles; triangle k is defined by tre vertices located
00241 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00242 int32[] triangles
00243 geometry_msgs/Point[] vertices
00244
00245 ================================================================================
00246 MSG: geometry_msgs/PoseStamped
00247 # A Pose with reference coordinate frame and timestamp
00248 Header header
00249 Pose pose
00250
00251 ================================================================================
00252 MSG: arm_navigation_msgs/LinkPadding
00253 #name for the link
00254 string link_name
00255
00256 # padding to apply to the link
00257 float64 padding
00258
00259 ================================================================================
00260 MSG: arm_navigation_msgs/CollisionObject
00261 # a header, used for interpreting the poses
00262 Header header
00263
00264 # the id of the object
00265 string id
00266
00267 # The padding used for filtering points near the object.
00268 # This does not affect collision checking for the object.
00269 # Set to negative to get zero padding.
00270 float32 padding
00271
00272 #This contains what is to be done with the object
00273 CollisionObjectOperation operation
00274
00275 #the shapes associated with the object
00276 arm_navigation_msgs/Shape[] shapes
00277
00278 #the poses associated with the shapes - will be transformed using the header
00279 geometry_msgs/Pose[] poses
00280
00281 ================================================================================
00282 MSG: arm_navigation_msgs/CollisionObjectOperation
00283 #Puts the object into the environment
00284 #or updates the object if already added
00285 byte ADD=0
00286
00287 #Removes the object from the environment entirely
00288 byte REMOVE=1
00289
00290 #Only valid within the context of a CollisionAttachedObject message
00291 #Will be ignored if sent with an CollisionObject message
00292 #Takes an attached object, detaches from the attached link
00293 #But adds back in as regular object
00294 byte DETACH_AND_ADD_AS_OBJECT=2
00295
00296 #Only valid within the context of a CollisionAttachedObject message
00297 #Will be ignored if sent with an CollisionObject message
00298 #Takes current object in the environment and removes it as
00299 #a regular object
00300 byte ATTACH_AND_REMOVE_AS_OBJECT=3
00301
00302 # Byte code for operation
00303 byte operation
00304
00305 ================================================================================
00306 MSG: arm_navigation_msgs/AttachedCollisionObject
00307 # The CollisionObject will be attached with a fixed joint to this link
00308 # If link name is set to REMOVE_ALL_ATTACHED_OBJECTS and object.operation
00309 # is set to REMOVE will remove all attached bodies attached to any object
00310 string link_name
00311
00312 #Reserved for indicating that all attached objects should be removed
00313 string REMOVE_ALL_ATTACHED_OBJECTS = "all"
00314
00315 #This contains the actual shapes and poses for the CollisionObject
00316 #to be attached to the link
00317 #If action is remove and no object.id is set, all objects
00318 #attached to the link indicated by link_name will be removed
00319 CollisionObject object
00320
00321 # The set of links that the attached objects are allowed to touch
00322 # by default - the link_name is included by default
00323 string[] touch_links
00324
00325 ================================================================================
00326 MSG: arm_navigation_msgs/CollisionMap
00327 #header for interpreting box positions
00328 Header header
00329
00330 #boxes for use in collision testing
00331 OrientedBoundingBox[] boxes
00332
00333 ================================================================================
00334 MSG: arm_navigation_msgs/OrientedBoundingBox
00335 #the center of the box
00336 geometry_msgs/Point32 center
00337
00338 #the extents of the box, assuming the center is at the point
00339 geometry_msgs/Point32 extents
00340
00341 #the axis of the box
00342 geometry_msgs/Point32 axis
00343
00344 #the angle of rotation around the axis
00345 float32 angle
00346
00347 ================================================================================
00348 MSG: geometry_msgs/Point32
00349 # This contains the position of a point in free space(with 32 bits of precision).
00350 # It is recommeded to use Point wherever possible instead of Point32.
00351 #
00352 # This recommendation is to promote interoperability.
00353 #
00354 # This message is designed to take up less space when sending
00355 # lots of points at once, as in the case of a PointCloud.
00356
00357 float32 x
00358 float32 y
00359 float32 z
00360 """
00361 __slots__ = ['header','goal_id','goal']
00362 _slot_types = ['Header','actionlib_msgs/GoalID','arm_navigation_msgs/SyncPlanningSceneGoal']
00363
00364 def __init__(self, *args, **kwds):
00365 """
00366 Constructor. Any message fields that are implicitly/explicitly
00367 set to None will be assigned a default value. The recommend
00368 use is keyword arguments as this is more robust to future message
00369 changes. You cannot mix in-order arguments and keyword arguments.
00370
00371 The available fields are:
00372 header,goal_id,goal
00373
00374 @param args: complete set of field values, in .msg order
00375 @param kwds: use keyword arguments corresponding to message field names
00376 to set specific fields.
00377 """
00378 if args or kwds:
00379 super(SyncPlanningSceneActionGoal, self).__init__(*args, **kwds)
00380
00381 if self.header is None:
00382 self.header = std_msgs.msg._Header.Header()
00383 if self.goal_id is None:
00384 self.goal_id = actionlib_msgs.msg.GoalID()
00385 if self.goal is None:
00386 self.goal = arm_navigation_msgs.msg.SyncPlanningSceneGoal()
00387 else:
00388 self.header = std_msgs.msg._Header.Header()
00389 self.goal_id = actionlib_msgs.msg.GoalID()
00390 self.goal = arm_navigation_msgs.msg.SyncPlanningSceneGoal()
00391
00392 def _get_types(self):
00393 """
00394 internal API method
00395 """
00396 return self._slot_types
00397
00398 def serialize(self, buff):
00399 """
00400 serialize message into buffer
00401 @param buff: buffer
00402 @type buff: StringIO
00403 """
00404 try:
00405 _x = self
00406 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00407 _x = self.header.frame_id
00408 length = len(_x)
00409 buff.write(struct.pack('<I%ss'%length, length, _x))
00410 _x = self
00411 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00412 _x = self.goal_id.id
00413 length = len(_x)
00414 buff.write(struct.pack('<I%ss'%length, length, _x))
00415 _x = self
00416 buff.write(_struct_3I.pack(_x.goal.planning_scene.robot_state.joint_state.header.seq, _x.goal.planning_scene.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene.robot_state.joint_state.header.stamp.nsecs))
00417 _x = self.goal.planning_scene.robot_state.joint_state.header.frame_id
00418 length = len(_x)
00419 buff.write(struct.pack('<I%ss'%length, length, _x))
00420 length = len(self.goal.planning_scene.robot_state.joint_state.name)
00421 buff.write(_struct_I.pack(length))
00422 for val1 in self.goal.planning_scene.robot_state.joint_state.name:
00423 length = len(val1)
00424 buff.write(struct.pack('<I%ss'%length, length, val1))
00425 length = len(self.goal.planning_scene.robot_state.joint_state.position)
00426 buff.write(_struct_I.pack(length))
00427 pattern = '<%sd'%length
00428 buff.write(struct.pack(pattern, *self.goal.planning_scene.robot_state.joint_state.position))
00429 length = len(self.goal.planning_scene.robot_state.joint_state.velocity)
00430 buff.write(_struct_I.pack(length))
00431 pattern = '<%sd'%length
00432 buff.write(struct.pack(pattern, *self.goal.planning_scene.robot_state.joint_state.velocity))
00433 length = len(self.goal.planning_scene.robot_state.joint_state.effort)
00434 buff.write(_struct_I.pack(length))
00435 pattern = '<%sd'%length
00436 buff.write(struct.pack(pattern, *self.goal.planning_scene.robot_state.joint_state.effort))
00437 _x = self
00438 buff.write(_struct_2I.pack(_x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs))
00439 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names)
00440 buff.write(_struct_I.pack(length))
00441 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names:
00442 length = len(val1)
00443 buff.write(struct.pack('<I%ss'%length, length, val1))
00444 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids)
00445 buff.write(_struct_I.pack(length))
00446 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids:
00447 length = len(val1)
00448 buff.write(struct.pack('<I%ss'%length, length, val1))
00449 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids)
00450 buff.write(_struct_I.pack(length))
00451 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids:
00452 length = len(val1)
00453 buff.write(struct.pack('<I%ss'%length, length, val1))
00454 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.poses)
00455 buff.write(_struct_I.pack(length))
00456 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.poses:
00457 _v1 = val1.position
00458 _x = _v1
00459 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00460 _v2 = val1.orientation
00461 _x = _v2
00462 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00463 length = len(self.goal.planning_scene.fixed_frame_transforms)
00464 buff.write(_struct_I.pack(length))
00465 for val1 in self.goal.planning_scene.fixed_frame_transforms:
00466 _v3 = val1.header
00467 buff.write(_struct_I.pack(_v3.seq))
00468 _v4 = _v3.stamp
00469 _x = _v4
00470 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00471 _x = _v3.frame_id
00472 length = len(_x)
00473 buff.write(struct.pack('<I%ss'%length, length, _x))
00474 _x = val1.child_frame_id
00475 length = len(_x)
00476 buff.write(struct.pack('<I%ss'%length, length, _x))
00477 _v5 = val1.transform
00478 _v6 = _v5.translation
00479 _x = _v6
00480 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00481 _v7 = _v5.rotation
00482 _x = _v7
00483 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00484 length = len(self.goal.planning_scene.allowed_collision_matrix.link_names)
00485 buff.write(_struct_I.pack(length))
00486 for val1 in self.goal.planning_scene.allowed_collision_matrix.link_names:
00487 length = len(val1)
00488 buff.write(struct.pack('<I%ss'%length, length, val1))
00489 length = len(self.goal.planning_scene.allowed_collision_matrix.entries)
00490 buff.write(_struct_I.pack(length))
00491 for val1 in self.goal.planning_scene.allowed_collision_matrix.entries:
00492 length = len(val1.enabled)
00493 buff.write(_struct_I.pack(length))
00494 pattern = '<%sB'%length
00495 buff.write(struct.pack(pattern, *val1.enabled))
00496 length = len(self.goal.planning_scene.allowed_contacts)
00497 buff.write(_struct_I.pack(length))
00498 for val1 in self.goal.planning_scene.allowed_contacts:
00499 _x = val1.name
00500 length = len(_x)
00501 buff.write(struct.pack('<I%ss'%length, length, _x))
00502 _v8 = val1.shape
00503 buff.write(_struct_b.pack(_v8.type))
00504 length = len(_v8.dimensions)
00505 buff.write(_struct_I.pack(length))
00506 pattern = '<%sd'%length
00507 buff.write(struct.pack(pattern, *_v8.dimensions))
00508 length = len(_v8.triangles)
00509 buff.write(_struct_I.pack(length))
00510 pattern = '<%si'%length
00511 buff.write(struct.pack(pattern, *_v8.triangles))
00512 length = len(_v8.vertices)
00513 buff.write(_struct_I.pack(length))
00514 for val3 in _v8.vertices:
00515 _x = val3
00516 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00517 _v9 = val1.pose_stamped
00518 _v10 = _v9.header
00519 buff.write(_struct_I.pack(_v10.seq))
00520 _v11 = _v10.stamp
00521 _x = _v11
00522 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00523 _x = _v10.frame_id
00524 length = len(_x)
00525 buff.write(struct.pack('<I%ss'%length, length, _x))
00526 _v12 = _v9.pose
00527 _v13 = _v12.position
00528 _x = _v13
00529 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00530 _v14 = _v12.orientation
00531 _x = _v14
00532 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00533 length = len(val1.link_names)
00534 buff.write(_struct_I.pack(length))
00535 for val2 in val1.link_names:
00536 length = len(val2)
00537 buff.write(struct.pack('<I%ss'%length, length, val2))
00538 buff.write(_struct_d.pack(val1.penetration_depth))
00539 length = len(self.goal.planning_scene.link_padding)
00540 buff.write(_struct_I.pack(length))
00541 for val1 in self.goal.planning_scene.link_padding:
00542 _x = val1.link_name
00543 length = len(_x)
00544 buff.write(struct.pack('<I%ss'%length, length, _x))
00545 buff.write(_struct_d.pack(val1.padding))
00546 length = len(self.goal.planning_scene.collision_objects)
00547 buff.write(_struct_I.pack(length))
00548 for val1 in self.goal.planning_scene.collision_objects:
00549 _v15 = val1.header
00550 buff.write(_struct_I.pack(_v15.seq))
00551 _v16 = _v15.stamp
00552 _x = _v16
00553 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00554 _x = _v15.frame_id
00555 length = len(_x)
00556 buff.write(struct.pack('<I%ss'%length, length, _x))
00557 _x = val1.id
00558 length = len(_x)
00559 buff.write(struct.pack('<I%ss'%length, length, _x))
00560 buff.write(_struct_f.pack(val1.padding))
00561 _v17 = val1.operation
00562 buff.write(_struct_b.pack(_v17.operation))
00563 length = len(val1.shapes)
00564 buff.write(_struct_I.pack(length))
00565 for val2 in val1.shapes:
00566 buff.write(_struct_b.pack(val2.type))
00567 length = len(val2.dimensions)
00568 buff.write(_struct_I.pack(length))
00569 pattern = '<%sd'%length
00570 buff.write(struct.pack(pattern, *val2.dimensions))
00571 length = len(val2.triangles)
00572 buff.write(_struct_I.pack(length))
00573 pattern = '<%si'%length
00574 buff.write(struct.pack(pattern, *val2.triangles))
00575 length = len(val2.vertices)
00576 buff.write(_struct_I.pack(length))
00577 for val3 in val2.vertices:
00578 _x = val3
00579 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00580 length = len(val1.poses)
00581 buff.write(_struct_I.pack(length))
00582 for val2 in val1.poses:
00583 _v18 = val2.position
00584 _x = _v18
00585 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00586 _v19 = val2.orientation
00587 _x = _v19
00588 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00589 length = len(self.goal.planning_scene.attached_collision_objects)
00590 buff.write(_struct_I.pack(length))
00591 for val1 in self.goal.planning_scene.attached_collision_objects:
00592 _x = val1.link_name
00593 length = len(_x)
00594 buff.write(struct.pack('<I%ss'%length, length, _x))
00595 _v20 = val1.object
00596 _v21 = _v20.header
00597 buff.write(_struct_I.pack(_v21.seq))
00598 _v22 = _v21.stamp
00599 _x = _v22
00600 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00601 _x = _v21.frame_id
00602 length = len(_x)
00603 buff.write(struct.pack('<I%ss'%length, length, _x))
00604 _x = _v20.id
00605 length = len(_x)
00606 buff.write(struct.pack('<I%ss'%length, length, _x))
00607 buff.write(_struct_f.pack(_v20.padding))
00608 _v23 = _v20.operation
00609 buff.write(_struct_b.pack(_v23.operation))
00610 length = len(_v20.shapes)
00611 buff.write(_struct_I.pack(length))
00612 for val3 in _v20.shapes:
00613 buff.write(_struct_b.pack(val3.type))
00614 length = len(val3.dimensions)
00615 buff.write(_struct_I.pack(length))
00616 pattern = '<%sd'%length
00617 buff.write(struct.pack(pattern, *val3.dimensions))
00618 length = len(val3.triangles)
00619 buff.write(_struct_I.pack(length))
00620 pattern = '<%si'%length
00621 buff.write(struct.pack(pattern, *val3.triangles))
00622 length = len(val3.vertices)
00623 buff.write(_struct_I.pack(length))
00624 for val4 in val3.vertices:
00625 _x = val4
00626 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00627 length = len(_v20.poses)
00628 buff.write(_struct_I.pack(length))
00629 for val3 in _v20.poses:
00630 _v24 = val3.position
00631 _x = _v24
00632 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00633 _v25 = val3.orientation
00634 _x = _v25
00635 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00636 length = len(val1.touch_links)
00637 buff.write(_struct_I.pack(length))
00638 for val2 in val1.touch_links:
00639 length = len(val2)
00640 buff.write(struct.pack('<I%ss'%length, length, val2))
00641 _x = self
00642 buff.write(_struct_3I.pack(_x.goal.planning_scene.collision_map.header.seq, _x.goal.planning_scene.collision_map.header.stamp.secs, _x.goal.planning_scene.collision_map.header.stamp.nsecs))
00643 _x = self.goal.planning_scene.collision_map.header.frame_id
00644 length = len(_x)
00645 buff.write(struct.pack('<I%ss'%length, length, _x))
00646 length = len(self.goal.planning_scene.collision_map.boxes)
00647 buff.write(_struct_I.pack(length))
00648 for val1 in self.goal.planning_scene.collision_map.boxes:
00649 _v26 = val1.center
00650 _x = _v26
00651 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00652 _v27 = val1.extents
00653 _x = _v27
00654 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00655 _v28 = val1.axis
00656 _x = _v28
00657 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00658 buff.write(_struct_f.pack(val1.angle))
00659 except struct.error as se: self._check_types(se)
00660 except TypeError as te: self._check_types(te)
00661
00662 def deserialize(self, str):
00663 """
00664 unpack serialized message in str into this message instance
00665 @param str: byte array of serialized message
00666 @type str: str
00667 """
00668 try:
00669 if self.header is None:
00670 self.header = std_msgs.msg._Header.Header()
00671 if self.goal_id is None:
00672 self.goal_id = actionlib_msgs.msg.GoalID()
00673 if self.goal is None:
00674 self.goal = arm_navigation_msgs.msg.SyncPlanningSceneGoal()
00675 end = 0
00676 _x = self
00677 start = end
00678 end += 12
00679 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00680 start = end
00681 end += 4
00682 (length,) = _struct_I.unpack(str[start:end])
00683 start = end
00684 end += length
00685 self.header.frame_id = str[start:end]
00686 _x = self
00687 start = end
00688 end += 8
00689 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00690 start = end
00691 end += 4
00692 (length,) = _struct_I.unpack(str[start:end])
00693 start = end
00694 end += length
00695 self.goal_id.id = str[start:end]
00696 _x = self
00697 start = end
00698 end += 12
00699 (_x.goal.planning_scene.robot_state.joint_state.header.seq, _x.goal.planning_scene.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00700 start = end
00701 end += 4
00702 (length,) = _struct_I.unpack(str[start:end])
00703 start = end
00704 end += length
00705 self.goal.planning_scene.robot_state.joint_state.header.frame_id = str[start:end]
00706 start = end
00707 end += 4
00708 (length,) = _struct_I.unpack(str[start:end])
00709 self.goal.planning_scene.robot_state.joint_state.name = []
00710 for i in range(0, length):
00711 start = end
00712 end += 4
00713 (length,) = _struct_I.unpack(str[start:end])
00714 start = end
00715 end += length
00716 val1 = str[start:end]
00717 self.goal.planning_scene.robot_state.joint_state.name.append(val1)
00718 start = end
00719 end += 4
00720 (length,) = _struct_I.unpack(str[start:end])
00721 pattern = '<%sd'%length
00722 start = end
00723 end += struct.calcsize(pattern)
00724 self.goal.planning_scene.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
00725 start = end
00726 end += 4
00727 (length,) = _struct_I.unpack(str[start:end])
00728 pattern = '<%sd'%length
00729 start = end
00730 end += struct.calcsize(pattern)
00731 self.goal.planning_scene.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
00732 start = end
00733 end += 4
00734 (length,) = _struct_I.unpack(str[start:end])
00735 pattern = '<%sd'%length
00736 start = end
00737 end += struct.calcsize(pattern)
00738 self.goal.planning_scene.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
00739 _x = self
00740 start = end
00741 end += 8
00742 (_x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00743 start = end
00744 end += 4
00745 (length,) = _struct_I.unpack(str[start:end])
00746 self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names = []
00747 for i in range(0, length):
00748 start = end
00749 end += 4
00750 (length,) = _struct_I.unpack(str[start:end])
00751 start = end
00752 end += length
00753 val1 = str[start:end]
00754 self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names.append(val1)
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids = []
00759 for i in range(0, length):
00760 start = end
00761 end += 4
00762 (length,) = _struct_I.unpack(str[start:end])
00763 start = end
00764 end += length
00765 val1 = str[start:end]
00766 self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids.append(val1)
00767 start = end
00768 end += 4
00769 (length,) = _struct_I.unpack(str[start:end])
00770 self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids = []
00771 for i in range(0, length):
00772 start = end
00773 end += 4
00774 (length,) = _struct_I.unpack(str[start:end])
00775 start = end
00776 end += length
00777 val1 = str[start:end]
00778 self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
00779 start = end
00780 end += 4
00781 (length,) = _struct_I.unpack(str[start:end])
00782 self.goal.planning_scene.robot_state.multi_dof_joint_state.poses = []
00783 for i in range(0, length):
00784 val1 = geometry_msgs.msg.Pose()
00785 _v29 = val1.position
00786 _x = _v29
00787 start = end
00788 end += 24
00789 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00790 _v30 = val1.orientation
00791 _x = _v30
00792 start = end
00793 end += 32
00794 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00795 self.goal.planning_scene.robot_state.multi_dof_joint_state.poses.append(val1)
00796 start = end
00797 end += 4
00798 (length,) = _struct_I.unpack(str[start:end])
00799 self.goal.planning_scene.fixed_frame_transforms = []
00800 for i in range(0, length):
00801 val1 = geometry_msgs.msg.TransformStamped()
00802 _v31 = val1.header
00803 start = end
00804 end += 4
00805 (_v31.seq,) = _struct_I.unpack(str[start:end])
00806 _v32 = _v31.stamp
00807 _x = _v32
00808 start = end
00809 end += 8
00810 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00811 start = end
00812 end += 4
00813 (length,) = _struct_I.unpack(str[start:end])
00814 start = end
00815 end += length
00816 _v31.frame_id = str[start:end]
00817 start = end
00818 end += 4
00819 (length,) = _struct_I.unpack(str[start:end])
00820 start = end
00821 end += length
00822 val1.child_frame_id = str[start:end]
00823 _v33 = val1.transform
00824 _v34 = _v33.translation
00825 _x = _v34
00826 start = end
00827 end += 24
00828 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00829 _v35 = _v33.rotation
00830 _x = _v35
00831 start = end
00832 end += 32
00833 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00834 self.goal.planning_scene.fixed_frame_transforms.append(val1)
00835 start = end
00836 end += 4
00837 (length,) = _struct_I.unpack(str[start:end])
00838 self.goal.planning_scene.allowed_collision_matrix.link_names = []
00839 for i in range(0, length):
00840 start = end
00841 end += 4
00842 (length,) = _struct_I.unpack(str[start:end])
00843 start = end
00844 end += length
00845 val1 = str[start:end]
00846 self.goal.planning_scene.allowed_collision_matrix.link_names.append(val1)
00847 start = end
00848 end += 4
00849 (length,) = _struct_I.unpack(str[start:end])
00850 self.goal.planning_scene.allowed_collision_matrix.entries = []
00851 for i in range(0, length):
00852 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
00853 start = end
00854 end += 4
00855 (length,) = _struct_I.unpack(str[start:end])
00856 pattern = '<%sB'%length
00857 start = end
00858 end += struct.calcsize(pattern)
00859 val1.enabled = struct.unpack(pattern, str[start:end])
00860 val1.enabled = map(bool, val1.enabled)
00861 self.goal.planning_scene.allowed_collision_matrix.entries.append(val1)
00862 start = end
00863 end += 4
00864 (length,) = _struct_I.unpack(str[start:end])
00865 self.goal.planning_scene.allowed_contacts = []
00866 for i in range(0, length):
00867 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
00868 start = end
00869 end += 4
00870 (length,) = _struct_I.unpack(str[start:end])
00871 start = end
00872 end += length
00873 val1.name = str[start:end]
00874 _v36 = val1.shape
00875 start = end
00876 end += 1
00877 (_v36.type,) = _struct_b.unpack(str[start:end])
00878 start = end
00879 end += 4
00880 (length,) = _struct_I.unpack(str[start:end])
00881 pattern = '<%sd'%length
00882 start = end
00883 end += struct.calcsize(pattern)
00884 _v36.dimensions = struct.unpack(pattern, str[start:end])
00885 start = end
00886 end += 4
00887 (length,) = _struct_I.unpack(str[start:end])
00888 pattern = '<%si'%length
00889 start = end
00890 end += struct.calcsize(pattern)
00891 _v36.triangles = struct.unpack(pattern, str[start:end])
00892 start = end
00893 end += 4
00894 (length,) = _struct_I.unpack(str[start:end])
00895 _v36.vertices = []
00896 for i in range(0, length):
00897 val3 = geometry_msgs.msg.Point()
00898 _x = val3
00899 start = end
00900 end += 24
00901 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00902 _v36.vertices.append(val3)
00903 _v37 = val1.pose_stamped
00904 _v38 = _v37.header
00905 start = end
00906 end += 4
00907 (_v38.seq,) = _struct_I.unpack(str[start:end])
00908 _v39 = _v38.stamp
00909 _x = _v39
00910 start = end
00911 end += 8
00912 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00913 start = end
00914 end += 4
00915 (length,) = _struct_I.unpack(str[start:end])
00916 start = end
00917 end += length
00918 _v38.frame_id = str[start:end]
00919 _v40 = _v37.pose
00920 _v41 = _v40.position
00921 _x = _v41
00922 start = end
00923 end += 24
00924 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00925 _v42 = _v40.orientation
00926 _x = _v42
00927 start = end
00928 end += 32
00929 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00930 start = end
00931 end += 4
00932 (length,) = _struct_I.unpack(str[start:end])
00933 val1.link_names = []
00934 for i in range(0, length):
00935 start = end
00936 end += 4
00937 (length,) = _struct_I.unpack(str[start:end])
00938 start = end
00939 end += length
00940 val2 = str[start:end]
00941 val1.link_names.append(val2)
00942 start = end
00943 end += 8
00944 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
00945 self.goal.planning_scene.allowed_contacts.append(val1)
00946 start = end
00947 end += 4
00948 (length,) = _struct_I.unpack(str[start:end])
00949 self.goal.planning_scene.link_padding = []
00950 for i in range(0, length):
00951 val1 = arm_navigation_msgs.msg.LinkPadding()
00952 start = end
00953 end += 4
00954 (length,) = _struct_I.unpack(str[start:end])
00955 start = end
00956 end += length
00957 val1.link_name = str[start:end]
00958 start = end
00959 end += 8
00960 (val1.padding,) = _struct_d.unpack(str[start:end])
00961 self.goal.planning_scene.link_padding.append(val1)
00962 start = end
00963 end += 4
00964 (length,) = _struct_I.unpack(str[start:end])
00965 self.goal.planning_scene.collision_objects = []
00966 for i in range(0, length):
00967 val1 = arm_navigation_msgs.msg.CollisionObject()
00968 _v43 = val1.header
00969 start = end
00970 end += 4
00971 (_v43.seq,) = _struct_I.unpack(str[start:end])
00972 _v44 = _v43.stamp
00973 _x = _v44
00974 start = end
00975 end += 8
00976 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00977 start = end
00978 end += 4
00979 (length,) = _struct_I.unpack(str[start:end])
00980 start = end
00981 end += length
00982 _v43.frame_id = str[start:end]
00983 start = end
00984 end += 4
00985 (length,) = _struct_I.unpack(str[start:end])
00986 start = end
00987 end += length
00988 val1.id = str[start:end]
00989 start = end
00990 end += 4
00991 (val1.padding,) = _struct_f.unpack(str[start:end])
00992 _v45 = val1.operation
00993 start = end
00994 end += 1
00995 (_v45.operation,) = _struct_b.unpack(str[start:end])
00996 start = end
00997 end += 4
00998 (length,) = _struct_I.unpack(str[start:end])
00999 val1.shapes = []
01000 for i in range(0, length):
01001 val2 = arm_navigation_msgs.msg.Shape()
01002 start = end
01003 end += 1
01004 (val2.type,) = _struct_b.unpack(str[start:end])
01005 start = end
01006 end += 4
01007 (length,) = _struct_I.unpack(str[start:end])
01008 pattern = '<%sd'%length
01009 start = end
01010 end += struct.calcsize(pattern)
01011 val2.dimensions = struct.unpack(pattern, str[start:end])
01012 start = end
01013 end += 4
01014 (length,) = _struct_I.unpack(str[start:end])
01015 pattern = '<%si'%length
01016 start = end
01017 end += struct.calcsize(pattern)
01018 val2.triangles = struct.unpack(pattern, str[start:end])
01019 start = end
01020 end += 4
01021 (length,) = _struct_I.unpack(str[start:end])
01022 val2.vertices = []
01023 for i in range(0, length):
01024 val3 = geometry_msgs.msg.Point()
01025 _x = val3
01026 start = end
01027 end += 24
01028 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01029 val2.vertices.append(val3)
01030 val1.shapes.append(val2)
01031 start = end
01032 end += 4
01033 (length,) = _struct_I.unpack(str[start:end])
01034 val1.poses = []
01035 for i in range(0, length):
01036 val2 = geometry_msgs.msg.Pose()
01037 _v46 = val2.position
01038 _x = _v46
01039 start = end
01040 end += 24
01041 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01042 _v47 = val2.orientation
01043 _x = _v47
01044 start = end
01045 end += 32
01046 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01047 val1.poses.append(val2)
01048 self.goal.planning_scene.collision_objects.append(val1)
01049 start = end
01050 end += 4
01051 (length,) = _struct_I.unpack(str[start:end])
01052 self.goal.planning_scene.attached_collision_objects = []
01053 for i in range(0, length):
01054 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
01055 start = end
01056 end += 4
01057 (length,) = _struct_I.unpack(str[start:end])
01058 start = end
01059 end += length
01060 val1.link_name = str[start:end]
01061 _v48 = val1.object
01062 _v49 = _v48.header
01063 start = end
01064 end += 4
01065 (_v49.seq,) = _struct_I.unpack(str[start:end])
01066 _v50 = _v49.stamp
01067 _x = _v50
01068 start = end
01069 end += 8
01070 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01071 start = end
01072 end += 4
01073 (length,) = _struct_I.unpack(str[start:end])
01074 start = end
01075 end += length
01076 _v49.frame_id = str[start:end]
01077 start = end
01078 end += 4
01079 (length,) = _struct_I.unpack(str[start:end])
01080 start = end
01081 end += length
01082 _v48.id = str[start:end]
01083 start = end
01084 end += 4
01085 (_v48.padding,) = _struct_f.unpack(str[start:end])
01086 _v51 = _v48.operation
01087 start = end
01088 end += 1
01089 (_v51.operation,) = _struct_b.unpack(str[start:end])
01090 start = end
01091 end += 4
01092 (length,) = _struct_I.unpack(str[start:end])
01093 _v48.shapes = []
01094 for i in range(0, length):
01095 val3 = arm_navigation_msgs.msg.Shape()
01096 start = end
01097 end += 1
01098 (val3.type,) = _struct_b.unpack(str[start:end])
01099 start = end
01100 end += 4
01101 (length,) = _struct_I.unpack(str[start:end])
01102 pattern = '<%sd'%length
01103 start = end
01104 end += struct.calcsize(pattern)
01105 val3.dimensions = struct.unpack(pattern, str[start:end])
01106 start = end
01107 end += 4
01108 (length,) = _struct_I.unpack(str[start:end])
01109 pattern = '<%si'%length
01110 start = end
01111 end += struct.calcsize(pattern)
01112 val3.triangles = struct.unpack(pattern, str[start:end])
01113 start = end
01114 end += 4
01115 (length,) = _struct_I.unpack(str[start:end])
01116 val3.vertices = []
01117 for i in range(0, length):
01118 val4 = geometry_msgs.msg.Point()
01119 _x = val4
01120 start = end
01121 end += 24
01122 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01123 val3.vertices.append(val4)
01124 _v48.shapes.append(val3)
01125 start = end
01126 end += 4
01127 (length,) = _struct_I.unpack(str[start:end])
01128 _v48.poses = []
01129 for i in range(0, length):
01130 val3 = geometry_msgs.msg.Pose()
01131 _v52 = val3.position
01132 _x = _v52
01133 start = end
01134 end += 24
01135 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01136 _v53 = val3.orientation
01137 _x = _v53
01138 start = end
01139 end += 32
01140 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01141 _v48.poses.append(val3)
01142 start = end
01143 end += 4
01144 (length,) = _struct_I.unpack(str[start:end])
01145 val1.touch_links = []
01146 for i in range(0, length):
01147 start = end
01148 end += 4
01149 (length,) = _struct_I.unpack(str[start:end])
01150 start = end
01151 end += length
01152 val2 = str[start:end]
01153 val1.touch_links.append(val2)
01154 self.goal.planning_scene.attached_collision_objects.append(val1)
01155 _x = self
01156 start = end
01157 end += 12
01158 (_x.goal.planning_scene.collision_map.header.seq, _x.goal.planning_scene.collision_map.header.stamp.secs, _x.goal.planning_scene.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01159 start = end
01160 end += 4
01161 (length,) = _struct_I.unpack(str[start:end])
01162 start = end
01163 end += length
01164 self.goal.planning_scene.collision_map.header.frame_id = str[start:end]
01165 start = end
01166 end += 4
01167 (length,) = _struct_I.unpack(str[start:end])
01168 self.goal.planning_scene.collision_map.boxes = []
01169 for i in range(0, length):
01170 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
01171 _v54 = val1.center
01172 _x = _v54
01173 start = end
01174 end += 12
01175 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01176 _v55 = val1.extents
01177 _x = _v55
01178 start = end
01179 end += 12
01180 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01181 _v56 = val1.axis
01182 _x = _v56
01183 start = end
01184 end += 12
01185 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01186 start = end
01187 end += 4
01188 (val1.angle,) = _struct_f.unpack(str[start:end])
01189 self.goal.planning_scene.collision_map.boxes.append(val1)
01190 return self
01191 except struct.error as e:
01192 raise roslib.message.DeserializationError(e)
01193
01194
01195 def serialize_numpy(self, buff, numpy):
01196 """
01197 serialize message with numpy array types into buffer
01198 @param buff: buffer
01199 @type buff: StringIO
01200 @param numpy: numpy python module
01201 @type numpy module
01202 """
01203 try:
01204 _x = self
01205 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
01206 _x = self.header.frame_id
01207 length = len(_x)
01208 buff.write(struct.pack('<I%ss'%length, length, _x))
01209 _x = self
01210 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
01211 _x = self.goal_id.id
01212 length = len(_x)
01213 buff.write(struct.pack('<I%ss'%length, length, _x))
01214 _x = self
01215 buff.write(_struct_3I.pack(_x.goal.planning_scene.robot_state.joint_state.header.seq, _x.goal.planning_scene.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene.robot_state.joint_state.header.stamp.nsecs))
01216 _x = self.goal.planning_scene.robot_state.joint_state.header.frame_id
01217 length = len(_x)
01218 buff.write(struct.pack('<I%ss'%length, length, _x))
01219 length = len(self.goal.planning_scene.robot_state.joint_state.name)
01220 buff.write(_struct_I.pack(length))
01221 for val1 in self.goal.planning_scene.robot_state.joint_state.name:
01222 length = len(val1)
01223 buff.write(struct.pack('<I%ss'%length, length, val1))
01224 length = len(self.goal.planning_scene.robot_state.joint_state.position)
01225 buff.write(_struct_I.pack(length))
01226 pattern = '<%sd'%length
01227 buff.write(self.goal.planning_scene.robot_state.joint_state.position.tostring())
01228 length = len(self.goal.planning_scene.robot_state.joint_state.velocity)
01229 buff.write(_struct_I.pack(length))
01230 pattern = '<%sd'%length
01231 buff.write(self.goal.planning_scene.robot_state.joint_state.velocity.tostring())
01232 length = len(self.goal.planning_scene.robot_state.joint_state.effort)
01233 buff.write(_struct_I.pack(length))
01234 pattern = '<%sd'%length
01235 buff.write(self.goal.planning_scene.robot_state.joint_state.effort.tostring())
01236 _x = self
01237 buff.write(_struct_2I.pack(_x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs))
01238 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names)
01239 buff.write(_struct_I.pack(length))
01240 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names:
01241 length = len(val1)
01242 buff.write(struct.pack('<I%ss'%length, length, val1))
01243 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids)
01244 buff.write(_struct_I.pack(length))
01245 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids:
01246 length = len(val1)
01247 buff.write(struct.pack('<I%ss'%length, length, val1))
01248 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids)
01249 buff.write(_struct_I.pack(length))
01250 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids:
01251 length = len(val1)
01252 buff.write(struct.pack('<I%ss'%length, length, val1))
01253 length = len(self.goal.planning_scene.robot_state.multi_dof_joint_state.poses)
01254 buff.write(_struct_I.pack(length))
01255 for val1 in self.goal.planning_scene.robot_state.multi_dof_joint_state.poses:
01256 _v57 = val1.position
01257 _x = _v57
01258 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01259 _v58 = val1.orientation
01260 _x = _v58
01261 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01262 length = len(self.goal.planning_scene.fixed_frame_transforms)
01263 buff.write(_struct_I.pack(length))
01264 for val1 in self.goal.planning_scene.fixed_frame_transforms:
01265 _v59 = val1.header
01266 buff.write(_struct_I.pack(_v59.seq))
01267 _v60 = _v59.stamp
01268 _x = _v60
01269 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01270 _x = _v59.frame_id
01271 length = len(_x)
01272 buff.write(struct.pack('<I%ss'%length, length, _x))
01273 _x = val1.child_frame_id
01274 length = len(_x)
01275 buff.write(struct.pack('<I%ss'%length, length, _x))
01276 _v61 = val1.transform
01277 _v62 = _v61.translation
01278 _x = _v62
01279 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01280 _v63 = _v61.rotation
01281 _x = _v63
01282 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01283 length = len(self.goal.planning_scene.allowed_collision_matrix.link_names)
01284 buff.write(_struct_I.pack(length))
01285 for val1 in self.goal.planning_scene.allowed_collision_matrix.link_names:
01286 length = len(val1)
01287 buff.write(struct.pack('<I%ss'%length, length, val1))
01288 length = len(self.goal.planning_scene.allowed_collision_matrix.entries)
01289 buff.write(_struct_I.pack(length))
01290 for val1 in self.goal.planning_scene.allowed_collision_matrix.entries:
01291 length = len(val1.enabled)
01292 buff.write(_struct_I.pack(length))
01293 pattern = '<%sB'%length
01294 buff.write(val1.enabled.tostring())
01295 length = len(self.goal.planning_scene.allowed_contacts)
01296 buff.write(_struct_I.pack(length))
01297 for val1 in self.goal.planning_scene.allowed_contacts:
01298 _x = val1.name
01299 length = len(_x)
01300 buff.write(struct.pack('<I%ss'%length, length, _x))
01301 _v64 = val1.shape
01302 buff.write(_struct_b.pack(_v64.type))
01303 length = len(_v64.dimensions)
01304 buff.write(_struct_I.pack(length))
01305 pattern = '<%sd'%length
01306 buff.write(_v64.dimensions.tostring())
01307 length = len(_v64.triangles)
01308 buff.write(_struct_I.pack(length))
01309 pattern = '<%si'%length
01310 buff.write(_v64.triangles.tostring())
01311 length = len(_v64.vertices)
01312 buff.write(_struct_I.pack(length))
01313 for val3 in _v64.vertices:
01314 _x = val3
01315 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01316 _v65 = val1.pose_stamped
01317 _v66 = _v65.header
01318 buff.write(_struct_I.pack(_v66.seq))
01319 _v67 = _v66.stamp
01320 _x = _v67
01321 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01322 _x = _v66.frame_id
01323 length = len(_x)
01324 buff.write(struct.pack('<I%ss'%length, length, _x))
01325 _v68 = _v65.pose
01326 _v69 = _v68.position
01327 _x = _v69
01328 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01329 _v70 = _v68.orientation
01330 _x = _v70
01331 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01332 length = len(val1.link_names)
01333 buff.write(_struct_I.pack(length))
01334 for val2 in val1.link_names:
01335 length = len(val2)
01336 buff.write(struct.pack('<I%ss'%length, length, val2))
01337 buff.write(_struct_d.pack(val1.penetration_depth))
01338 length = len(self.goal.planning_scene.link_padding)
01339 buff.write(_struct_I.pack(length))
01340 for val1 in self.goal.planning_scene.link_padding:
01341 _x = val1.link_name
01342 length = len(_x)
01343 buff.write(struct.pack('<I%ss'%length, length, _x))
01344 buff.write(_struct_d.pack(val1.padding))
01345 length = len(self.goal.planning_scene.collision_objects)
01346 buff.write(_struct_I.pack(length))
01347 for val1 in self.goal.planning_scene.collision_objects:
01348 _v71 = val1.header
01349 buff.write(_struct_I.pack(_v71.seq))
01350 _v72 = _v71.stamp
01351 _x = _v72
01352 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01353 _x = _v71.frame_id
01354 length = len(_x)
01355 buff.write(struct.pack('<I%ss'%length, length, _x))
01356 _x = val1.id
01357 length = len(_x)
01358 buff.write(struct.pack('<I%ss'%length, length, _x))
01359 buff.write(_struct_f.pack(val1.padding))
01360 _v73 = val1.operation
01361 buff.write(_struct_b.pack(_v73.operation))
01362 length = len(val1.shapes)
01363 buff.write(_struct_I.pack(length))
01364 for val2 in val1.shapes:
01365 buff.write(_struct_b.pack(val2.type))
01366 length = len(val2.dimensions)
01367 buff.write(_struct_I.pack(length))
01368 pattern = '<%sd'%length
01369 buff.write(val2.dimensions.tostring())
01370 length = len(val2.triangles)
01371 buff.write(_struct_I.pack(length))
01372 pattern = '<%si'%length
01373 buff.write(val2.triangles.tostring())
01374 length = len(val2.vertices)
01375 buff.write(_struct_I.pack(length))
01376 for val3 in val2.vertices:
01377 _x = val3
01378 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01379 length = len(val1.poses)
01380 buff.write(_struct_I.pack(length))
01381 for val2 in val1.poses:
01382 _v74 = val2.position
01383 _x = _v74
01384 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01385 _v75 = val2.orientation
01386 _x = _v75
01387 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01388 length = len(self.goal.planning_scene.attached_collision_objects)
01389 buff.write(_struct_I.pack(length))
01390 for val1 in self.goal.planning_scene.attached_collision_objects:
01391 _x = val1.link_name
01392 length = len(_x)
01393 buff.write(struct.pack('<I%ss'%length, length, _x))
01394 _v76 = val1.object
01395 _v77 = _v76.header
01396 buff.write(_struct_I.pack(_v77.seq))
01397 _v78 = _v77.stamp
01398 _x = _v78
01399 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01400 _x = _v77.frame_id
01401 length = len(_x)
01402 buff.write(struct.pack('<I%ss'%length, length, _x))
01403 _x = _v76.id
01404 length = len(_x)
01405 buff.write(struct.pack('<I%ss'%length, length, _x))
01406 buff.write(_struct_f.pack(_v76.padding))
01407 _v79 = _v76.operation
01408 buff.write(_struct_b.pack(_v79.operation))
01409 length = len(_v76.shapes)
01410 buff.write(_struct_I.pack(length))
01411 for val3 in _v76.shapes:
01412 buff.write(_struct_b.pack(val3.type))
01413 length = len(val3.dimensions)
01414 buff.write(_struct_I.pack(length))
01415 pattern = '<%sd'%length
01416 buff.write(val3.dimensions.tostring())
01417 length = len(val3.triangles)
01418 buff.write(_struct_I.pack(length))
01419 pattern = '<%si'%length
01420 buff.write(val3.triangles.tostring())
01421 length = len(val3.vertices)
01422 buff.write(_struct_I.pack(length))
01423 for val4 in val3.vertices:
01424 _x = val4
01425 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01426 length = len(_v76.poses)
01427 buff.write(_struct_I.pack(length))
01428 for val3 in _v76.poses:
01429 _v80 = val3.position
01430 _x = _v80
01431 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01432 _v81 = val3.orientation
01433 _x = _v81
01434 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01435 length = len(val1.touch_links)
01436 buff.write(_struct_I.pack(length))
01437 for val2 in val1.touch_links:
01438 length = len(val2)
01439 buff.write(struct.pack('<I%ss'%length, length, val2))
01440 _x = self
01441 buff.write(_struct_3I.pack(_x.goal.planning_scene.collision_map.header.seq, _x.goal.planning_scene.collision_map.header.stamp.secs, _x.goal.planning_scene.collision_map.header.stamp.nsecs))
01442 _x = self.goal.planning_scene.collision_map.header.frame_id
01443 length = len(_x)
01444 buff.write(struct.pack('<I%ss'%length, length, _x))
01445 length = len(self.goal.planning_scene.collision_map.boxes)
01446 buff.write(_struct_I.pack(length))
01447 for val1 in self.goal.planning_scene.collision_map.boxes:
01448 _v82 = val1.center
01449 _x = _v82
01450 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01451 _v83 = val1.extents
01452 _x = _v83
01453 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01454 _v84 = val1.axis
01455 _x = _v84
01456 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
01457 buff.write(_struct_f.pack(val1.angle))
01458 except struct.error as se: self._check_types(se)
01459 except TypeError as te: self._check_types(te)
01460
01461 def deserialize_numpy(self, str, numpy):
01462 """
01463 unpack serialized message in str into this message instance using numpy for array types
01464 @param str: byte array of serialized message
01465 @type str: str
01466 @param numpy: numpy python module
01467 @type numpy: module
01468 """
01469 try:
01470 if self.header is None:
01471 self.header = std_msgs.msg._Header.Header()
01472 if self.goal_id is None:
01473 self.goal_id = actionlib_msgs.msg.GoalID()
01474 if self.goal is None:
01475 self.goal = arm_navigation_msgs.msg.SyncPlanningSceneGoal()
01476 end = 0
01477 _x = self
01478 start = end
01479 end += 12
01480 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01481 start = end
01482 end += 4
01483 (length,) = _struct_I.unpack(str[start:end])
01484 start = end
01485 end += length
01486 self.header.frame_id = str[start:end]
01487 _x = self
01488 start = end
01489 end += 8
01490 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01491 start = end
01492 end += 4
01493 (length,) = _struct_I.unpack(str[start:end])
01494 start = end
01495 end += length
01496 self.goal_id.id = str[start:end]
01497 _x = self
01498 start = end
01499 end += 12
01500 (_x.goal.planning_scene.robot_state.joint_state.header.seq, _x.goal.planning_scene.robot_state.joint_state.header.stamp.secs, _x.goal.planning_scene.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01501 start = end
01502 end += 4
01503 (length,) = _struct_I.unpack(str[start:end])
01504 start = end
01505 end += length
01506 self.goal.planning_scene.robot_state.joint_state.header.frame_id = str[start:end]
01507 start = end
01508 end += 4
01509 (length,) = _struct_I.unpack(str[start:end])
01510 self.goal.planning_scene.robot_state.joint_state.name = []
01511 for i in range(0, length):
01512 start = end
01513 end += 4
01514 (length,) = _struct_I.unpack(str[start:end])
01515 start = end
01516 end += length
01517 val1 = str[start:end]
01518 self.goal.planning_scene.robot_state.joint_state.name.append(val1)
01519 start = end
01520 end += 4
01521 (length,) = _struct_I.unpack(str[start:end])
01522 pattern = '<%sd'%length
01523 start = end
01524 end += struct.calcsize(pattern)
01525 self.goal.planning_scene.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01526 start = end
01527 end += 4
01528 (length,) = _struct_I.unpack(str[start:end])
01529 pattern = '<%sd'%length
01530 start = end
01531 end += struct.calcsize(pattern)
01532 self.goal.planning_scene.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01533 start = end
01534 end += 4
01535 (length,) = _struct_I.unpack(str[start:end])
01536 pattern = '<%sd'%length
01537 start = end
01538 end += struct.calcsize(pattern)
01539 self.goal.planning_scene.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01540 _x = self
01541 start = end
01542 end += 8
01543 (_x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.secs, _x.goal.planning_scene.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01544 start = end
01545 end += 4
01546 (length,) = _struct_I.unpack(str[start:end])
01547 self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names = []
01548 for i in range(0, length):
01549 start = end
01550 end += 4
01551 (length,) = _struct_I.unpack(str[start:end])
01552 start = end
01553 end += length
01554 val1 = str[start:end]
01555 self.goal.planning_scene.robot_state.multi_dof_joint_state.joint_names.append(val1)
01556 start = end
01557 end += 4
01558 (length,) = _struct_I.unpack(str[start:end])
01559 self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids = []
01560 for i in range(0, length):
01561 start = end
01562 end += 4
01563 (length,) = _struct_I.unpack(str[start:end])
01564 start = end
01565 end += length
01566 val1 = str[start:end]
01567 self.goal.planning_scene.robot_state.multi_dof_joint_state.frame_ids.append(val1)
01568 start = end
01569 end += 4
01570 (length,) = _struct_I.unpack(str[start:end])
01571 self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids = []
01572 for i in range(0, length):
01573 start = end
01574 end += 4
01575 (length,) = _struct_I.unpack(str[start:end])
01576 start = end
01577 end += length
01578 val1 = str[start:end]
01579 self.goal.planning_scene.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
01580 start = end
01581 end += 4
01582 (length,) = _struct_I.unpack(str[start:end])
01583 self.goal.planning_scene.robot_state.multi_dof_joint_state.poses = []
01584 for i in range(0, length):
01585 val1 = geometry_msgs.msg.Pose()
01586 _v85 = val1.position
01587 _x = _v85
01588 start = end
01589 end += 24
01590 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01591 _v86 = val1.orientation
01592 _x = _v86
01593 start = end
01594 end += 32
01595 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01596 self.goal.planning_scene.robot_state.multi_dof_joint_state.poses.append(val1)
01597 start = end
01598 end += 4
01599 (length,) = _struct_I.unpack(str[start:end])
01600 self.goal.planning_scene.fixed_frame_transforms = []
01601 for i in range(0, length):
01602 val1 = geometry_msgs.msg.TransformStamped()
01603 _v87 = val1.header
01604 start = end
01605 end += 4
01606 (_v87.seq,) = _struct_I.unpack(str[start:end])
01607 _v88 = _v87.stamp
01608 _x = _v88
01609 start = end
01610 end += 8
01611 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01612 start = end
01613 end += 4
01614 (length,) = _struct_I.unpack(str[start:end])
01615 start = end
01616 end += length
01617 _v87.frame_id = str[start:end]
01618 start = end
01619 end += 4
01620 (length,) = _struct_I.unpack(str[start:end])
01621 start = end
01622 end += length
01623 val1.child_frame_id = str[start:end]
01624 _v89 = val1.transform
01625 _v90 = _v89.translation
01626 _x = _v90
01627 start = end
01628 end += 24
01629 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01630 _v91 = _v89.rotation
01631 _x = _v91
01632 start = end
01633 end += 32
01634 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01635 self.goal.planning_scene.fixed_frame_transforms.append(val1)
01636 start = end
01637 end += 4
01638 (length,) = _struct_I.unpack(str[start:end])
01639 self.goal.planning_scene.allowed_collision_matrix.link_names = []
01640 for i in range(0, length):
01641 start = end
01642 end += 4
01643 (length,) = _struct_I.unpack(str[start:end])
01644 start = end
01645 end += length
01646 val1 = str[start:end]
01647 self.goal.planning_scene.allowed_collision_matrix.link_names.append(val1)
01648 start = end
01649 end += 4
01650 (length,) = _struct_I.unpack(str[start:end])
01651 self.goal.planning_scene.allowed_collision_matrix.entries = []
01652 for i in range(0, length):
01653 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry()
01654 start = end
01655 end += 4
01656 (length,) = _struct_I.unpack(str[start:end])
01657 pattern = '<%sB'%length
01658 start = end
01659 end += struct.calcsize(pattern)
01660 val1.enabled = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=length)
01661 val1.enabled = map(bool, val1.enabled)
01662 self.goal.planning_scene.allowed_collision_matrix.entries.append(val1)
01663 start = end
01664 end += 4
01665 (length,) = _struct_I.unpack(str[start:end])
01666 self.goal.planning_scene.allowed_contacts = []
01667 for i in range(0, length):
01668 val1 = arm_navigation_msgs.msg.AllowedContactSpecification()
01669 start = end
01670 end += 4
01671 (length,) = _struct_I.unpack(str[start:end])
01672 start = end
01673 end += length
01674 val1.name = str[start:end]
01675 _v92 = val1.shape
01676 start = end
01677 end += 1
01678 (_v92.type,) = _struct_b.unpack(str[start:end])
01679 start = end
01680 end += 4
01681 (length,) = _struct_I.unpack(str[start:end])
01682 pattern = '<%sd'%length
01683 start = end
01684 end += struct.calcsize(pattern)
01685 _v92.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01686 start = end
01687 end += 4
01688 (length,) = _struct_I.unpack(str[start:end])
01689 pattern = '<%si'%length
01690 start = end
01691 end += struct.calcsize(pattern)
01692 _v92.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01693 start = end
01694 end += 4
01695 (length,) = _struct_I.unpack(str[start:end])
01696 _v92.vertices = []
01697 for i in range(0, length):
01698 val3 = geometry_msgs.msg.Point()
01699 _x = val3
01700 start = end
01701 end += 24
01702 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01703 _v92.vertices.append(val3)
01704 _v93 = val1.pose_stamped
01705 _v94 = _v93.header
01706 start = end
01707 end += 4
01708 (_v94.seq,) = _struct_I.unpack(str[start:end])
01709 _v95 = _v94.stamp
01710 _x = _v95
01711 start = end
01712 end += 8
01713 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01714 start = end
01715 end += 4
01716 (length,) = _struct_I.unpack(str[start:end])
01717 start = end
01718 end += length
01719 _v94.frame_id = str[start:end]
01720 _v96 = _v93.pose
01721 _v97 = _v96.position
01722 _x = _v97
01723 start = end
01724 end += 24
01725 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01726 _v98 = _v96.orientation
01727 _x = _v98
01728 start = end
01729 end += 32
01730 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01731 start = end
01732 end += 4
01733 (length,) = _struct_I.unpack(str[start:end])
01734 val1.link_names = []
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 val2 = str[start:end]
01742 val1.link_names.append(val2)
01743 start = end
01744 end += 8
01745 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
01746 self.goal.planning_scene.allowed_contacts.append(val1)
01747 start = end
01748 end += 4
01749 (length,) = _struct_I.unpack(str[start:end])
01750 self.goal.planning_scene.link_padding = []
01751 for i in range(0, length):
01752 val1 = arm_navigation_msgs.msg.LinkPadding()
01753 start = end
01754 end += 4
01755 (length,) = _struct_I.unpack(str[start:end])
01756 start = end
01757 end += length
01758 val1.link_name = str[start:end]
01759 start = end
01760 end += 8
01761 (val1.padding,) = _struct_d.unpack(str[start:end])
01762 self.goal.planning_scene.link_padding.append(val1)
01763 start = end
01764 end += 4
01765 (length,) = _struct_I.unpack(str[start:end])
01766 self.goal.planning_scene.collision_objects = []
01767 for i in range(0, length):
01768 val1 = arm_navigation_msgs.msg.CollisionObject()
01769 _v99 = val1.header
01770 start = end
01771 end += 4
01772 (_v99.seq,) = _struct_I.unpack(str[start:end])
01773 _v100 = _v99.stamp
01774 _x = _v100
01775 start = end
01776 end += 8
01777 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01778 start = end
01779 end += 4
01780 (length,) = _struct_I.unpack(str[start:end])
01781 start = end
01782 end += length
01783 _v99.frame_id = str[start:end]
01784 start = end
01785 end += 4
01786 (length,) = _struct_I.unpack(str[start:end])
01787 start = end
01788 end += length
01789 val1.id = str[start:end]
01790 start = end
01791 end += 4
01792 (val1.padding,) = _struct_f.unpack(str[start:end])
01793 _v101 = val1.operation
01794 start = end
01795 end += 1
01796 (_v101.operation,) = _struct_b.unpack(str[start:end])
01797 start = end
01798 end += 4
01799 (length,) = _struct_I.unpack(str[start:end])
01800 val1.shapes = []
01801 for i in range(0, length):
01802 val2 = arm_navigation_msgs.msg.Shape()
01803 start = end
01804 end += 1
01805 (val2.type,) = _struct_b.unpack(str[start:end])
01806 start = end
01807 end += 4
01808 (length,) = _struct_I.unpack(str[start:end])
01809 pattern = '<%sd'%length
01810 start = end
01811 end += struct.calcsize(pattern)
01812 val2.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01813 start = end
01814 end += 4
01815 (length,) = _struct_I.unpack(str[start:end])
01816 pattern = '<%si'%length
01817 start = end
01818 end += struct.calcsize(pattern)
01819 val2.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01820 start = end
01821 end += 4
01822 (length,) = _struct_I.unpack(str[start:end])
01823 val2.vertices = []
01824 for i in range(0, length):
01825 val3 = geometry_msgs.msg.Point()
01826 _x = val3
01827 start = end
01828 end += 24
01829 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01830 val2.vertices.append(val3)
01831 val1.shapes.append(val2)
01832 start = end
01833 end += 4
01834 (length,) = _struct_I.unpack(str[start:end])
01835 val1.poses = []
01836 for i in range(0, length):
01837 val2 = geometry_msgs.msg.Pose()
01838 _v102 = val2.position
01839 _x = _v102
01840 start = end
01841 end += 24
01842 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01843 _v103 = val2.orientation
01844 _x = _v103
01845 start = end
01846 end += 32
01847 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01848 val1.poses.append(val2)
01849 self.goal.planning_scene.collision_objects.append(val1)
01850 start = end
01851 end += 4
01852 (length,) = _struct_I.unpack(str[start:end])
01853 self.goal.planning_scene.attached_collision_objects = []
01854 for i in range(0, length):
01855 val1 = arm_navigation_msgs.msg.AttachedCollisionObject()
01856 start = end
01857 end += 4
01858 (length,) = _struct_I.unpack(str[start:end])
01859 start = end
01860 end += length
01861 val1.link_name = str[start:end]
01862 _v104 = val1.object
01863 _v105 = _v104.header
01864 start = end
01865 end += 4
01866 (_v105.seq,) = _struct_I.unpack(str[start:end])
01867 _v106 = _v105.stamp
01868 _x = _v106
01869 start = end
01870 end += 8
01871 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01872 start = end
01873 end += 4
01874 (length,) = _struct_I.unpack(str[start:end])
01875 start = end
01876 end += length
01877 _v105.frame_id = str[start:end]
01878 start = end
01879 end += 4
01880 (length,) = _struct_I.unpack(str[start:end])
01881 start = end
01882 end += length
01883 _v104.id = str[start:end]
01884 start = end
01885 end += 4
01886 (_v104.padding,) = _struct_f.unpack(str[start:end])
01887 _v107 = _v104.operation
01888 start = end
01889 end += 1
01890 (_v107.operation,) = _struct_b.unpack(str[start:end])
01891 start = end
01892 end += 4
01893 (length,) = _struct_I.unpack(str[start:end])
01894 _v104.shapes = []
01895 for i in range(0, length):
01896 val3 = arm_navigation_msgs.msg.Shape()
01897 start = end
01898 end += 1
01899 (val3.type,) = _struct_b.unpack(str[start:end])
01900 start = end
01901 end += 4
01902 (length,) = _struct_I.unpack(str[start:end])
01903 pattern = '<%sd'%length
01904 start = end
01905 end += struct.calcsize(pattern)
01906 val3.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01907 start = end
01908 end += 4
01909 (length,) = _struct_I.unpack(str[start:end])
01910 pattern = '<%si'%length
01911 start = end
01912 end += struct.calcsize(pattern)
01913 val3.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01914 start = end
01915 end += 4
01916 (length,) = _struct_I.unpack(str[start:end])
01917 val3.vertices = []
01918 for i in range(0, length):
01919 val4 = geometry_msgs.msg.Point()
01920 _x = val4
01921 start = end
01922 end += 24
01923 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01924 val3.vertices.append(val4)
01925 _v104.shapes.append(val3)
01926 start = end
01927 end += 4
01928 (length,) = _struct_I.unpack(str[start:end])
01929 _v104.poses = []
01930 for i in range(0, length):
01931 val3 = geometry_msgs.msg.Pose()
01932 _v108 = val3.position
01933 _x = _v108
01934 start = end
01935 end += 24
01936 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01937 _v109 = val3.orientation
01938 _x = _v109
01939 start = end
01940 end += 32
01941 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01942 _v104.poses.append(val3)
01943 start = end
01944 end += 4
01945 (length,) = _struct_I.unpack(str[start:end])
01946 val1.touch_links = []
01947 for i in range(0, length):
01948 start = end
01949 end += 4
01950 (length,) = _struct_I.unpack(str[start:end])
01951 start = end
01952 end += length
01953 val2 = str[start:end]
01954 val1.touch_links.append(val2)
01955 self.goal.planning_scene.attached_collision_objects.append(val1)
01956 _x = self
01957 start = end
01958 end += 12
01959 (_x.goal.planning_scene.collision_map.header.seq, _x.goal.planning_scene.collision_map.header.stamp.secs, _x.goal.planning_scene.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01960 start = end
01961 end += 4
01962 (length,) = _struct_I.unpack(str[start:end])
01963 start = end
01964 end += length
01965 self.goal.planning_scene.collision_map.header.frame_id = str[start:end]
01966 start = end
01967 end += 4
01968 (length,) = _struct_I.unpack(str[start:end])
01969 self.goal.planning_scene.collision_map.boxes = []
01970 for i in range(0, length):
01971 val1 = arm_navigation_msgs.msg.OrientedBoundingBox()
01972 _v110 = val1.center
01973 _x = _v110
01974 start = end
01975 end += 12
01976 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01977 _v111 = val1.extents
01978 _x = _v111
01979 start = end
01980 end += 12
01981 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01982 _v112 = val1.axis
01983 _x = _v112
01984 start = end
01985 end += 12
01986 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
01987 start = end
01988 end += 4
01989 (val1.angle,) = _struct_f.unpack(str[start:end])
01990 self.goal.planning_scene.collision_map.boxes.append(val1)
01991 return self
01992 except struct.error as e:
01993 raise roslib.message.DeserializationError(e)
01994
01995 _struct_I = roslib.message.struct_I
01996 _struct_b = struct.Struct("<b")
01997 _struct_d = struct.Struct("<d")
01998 _struct_f = struct.Struct("<f")
01999 _struct_3f = struct.Struct("<3f")
02000 _struct_3I = struct.Struct("<3I")
02001 _struct_4d = struct.Struct("<4d")
02002 _struct_2I = struct.Struct("<2I")
02003 _struct_3d = struct.Struct("<3d")