00001 """autogenerated by genmsg_py from GetMotionPlanRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import motion_planning_msgs.msg
00006 import geometric_shapes_msgs.msg
00007 import geometry_msgs.msg
00008 import sensor_msgs.msg
00009 import roslib.rostime
00010 import std_msgs.msg
00011
00012 class GetMotionPlanRequest(roslib.message.Message):
00013 _md5sum = "e019cf7ddef76622c851e221d4cf164d"
00014 _type = "motion_planning_msgs/GetMotionPlanRequest"
00015 _has_header = False
00016 _full_text = """
00017
00018
00019 MotionPlanRequest motion_plan_request
00020
00021
00022 ================================================================================
00023 MSG: motion_planning_msgs/MotionPlanRequest
00024 # This service contains the definition for a request to the motion
00025 # planner and the output it provides
00026
00027 # Parameters for the workspace that the planner should work inside
00028 motion_planning_msgs/WorkspaceParameters workspace_parameters
00029
00030 # Starting state updates. If certain joints should be considered
00031 # at positions other than the current ones, these positions should
00032 # be set here
00033 motion_planning_msgs/RobotState start_state
00034
00035 # The goal state for the model to plan for. The goal is achieved
00036 # if all constraints are satisfied
00037 motion_planning_msgs/Constraints goal_constraints
00038
00039 # No state at any point along the path in the produced motion plan will violate these constraints
00040 motion_planning_msgs/Constraints path_constraints
00041
00042 # A specification for regions where contact is
00043 # allowed up to a certain depth
00044 # Any collision within this set of regions with a link
00045 # specified in the message will be allowed if
00046 # it is less than the penetration depth specified in the message
00047 AllowedContactSpecification[] allowed_contacts
00048
00049 # A set of ordered collision operations,
00050 # these are applied to all links, objects,
00051 # namespaces in the collision space
00052 OrderedCollisionOperations ordered_collision_operations
00053
00054 # Specifies a set of links and paddings to change from the default
00055 # specified in the yaml file
00056 motion_planning_msgs/LinkPadding[] link_padding
00057
00058 # The name of the motion planner to use. If no name is specified,
00059 # a default motion planner will be used
00060 string planner_id
00061
00062 # The name of the group of joints on which this planner is operating
00063 string group_name
00064
00065 # The number of times this plan is to be computed. Shortest solution
00066 # will be reported.
00067 int32 num_planning_attempts
00068
00069 # The maximum amount of time the motion planner is allowed to plan for
00070 duration allowed_planning_time
00071
00072 # An expected path duration (in seconds) along with an expected discretization of the path allows the planner to determine the discretization of the trajectory that it returns
00073 duration expected_path_duration
00074 duration expected_path_dt
00075
00076 ================================================================================
00077 MSG: motion_planning_msgs/WorkspaceParameters
00078 # This message contains a set of parameters useful in
00079 # setting up the workspace for planning
00080 geometric_shapes_msgs/Shape workspace_region_shape
00081 geometry_msgs/PoseStamped workspace_region_pose
00082
00083
00084 ================================================================================
00085 MSG: geometric_shapes_msgs/Shape
00086 byte SPHERE=0
00087 byte BOX=1
00088 byte CYLINDER=2
00089 byte MESH=3
00090
00091 byte type
00092
00093
00094 #### define sphere, box, cylinder ####
00095 # the origin of each shape is considered at the shape's center
00096
00097 # for sphere
00098 # radius := dimensions[0]
00099
00100 # for cylinder
00101 # radius := dimensions[0]
00102 # length := dimensions[1]
00103 # the length is along the Z axis
00104
00105 # for box
00106 # size_x := dimensions[0]
00107 # size_y := dimensions[1]
00108 # size_z := dimensions[2]
00109 float64[] dimensions
00110
00111
00112 #### define mesh ####
00113
00114 # list of triangles; triangle k is defined by tre vertices located
00115 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00116 int32[] triangles
00117 geometry_msgs/Point[] vertices
00118
00119 ================================================================================
00120 MSG: geometry_msgs/Point
00121 # This contains the position of a point in free space
00122 float64 x
00123 float64 y
00124 float64 z
00125
00126 ================================================================================
00127 MSG: geometry_msgs/PoseStamped
00128 # A Pose with reference coordinate frame and timestamp
00129 Header header
00130 Pose pose
00131
00132 ================================================================================
00133 MSG: std_msgs/Header
00134 # Standard metadata for higher-level stamped data types.
00135 # This is generally used to communicate timestamped data
00136 # in a particular coordinate frame.
00137 #
00138 # sequence ID: consecutively increasing ID
00139 uint32 seq
00140 #Two-integer timestamp that is expressed as:
00141 # * stamp.secs: seconds (stamp_secs) since epoch
00142 # * stamp.nsecs: nanoseconds since stamp_secs
00143 # time-handling sugar is provided by the client library
00144 time stamp
00145 #Frame this data is associated with
00146 # 0: no frame
00147 # 1: global frame
00148 string frame_id
00149
00150 ================================================================================
00151 MSG: geometry_msgs/Pose
00152 # A representation of pose in free space, composed of postion and orientation.
00153 Point position
00154 Quaternion orientation
00155
00156 ================================================================================
00157 MSG: geometry_msgs/Quaternion
00158 # This represents an orientation in free space in quaternion form.
00159
00160 float64 x
00161 float64 y
00162 float64 z
00163 float64 w
00164
00165 ================================================================================
00166 MSG: motion_planning_msgs/RobotState
00167 # This message contains information about the robot state, i.e. the positions of its joints and links
00168 sensor_msgs/JointState joint_state
00169 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state
00170 ================================================================================
00171 MSG: sensor_msgs/JointState
00172 # This is a message that holds data to describe the state of a set of torque controlled joints.
00173 #
00174 # The state of each joint (revolute or prismatic) is defined by:
00175 # * the position of the joint (rad or m),
00176 # * the velocity of the joint (rad/s or m/s) and
00177 # * the effort that is applied in the joint (Nm or N).
00178 #
00179 # Each joint is uniquely identified by its name
00180 # The header specifies the time at which the joint states were recorded. All the joint states
00181 # in one message have to be recorded at the same time.
00182 #
00183 # This message consists of a multiple arrays, one for each part of the joint state.
00184 # The goal is to make each of the fields optional. When e.g. your joints have no
00185 # effort associated with them, you can leave the effort array empty.
00186 #
00187 # All arrays in this message should have the same size, or be empty.
00188 # This is the only way to uniquely associate the joint name with the correct
00189 # states.
00190
00191
00192 Header header
00193
00194 string[] name
00195 float64[] position
00196 float64[] velocity
00197 float64[] effort
00198
00199 ================================================================================
00200 MSG: motion_planning_msgs/MultiDOFJointState
00201 #A representation of a multi-dof joint state
00202 time stamp
00203 string[] joint_names
00204 string[] frame_ids
00205 string[] child_frame_ids
00206 geometry_msgs/Pose[] poses
00207
00208 ================================================================================
00209 MSG: motion_planning_msgs/Constraints
00210 # This message contains a list of motion planning constraints.
00211
00212 motion_planning_msgs/JointConstraint[] joint_constraints
00213 motion_planning_msgs/PositionConstraint[] position_constraints
00214 motion_planning_msgs/OrientationConstraint[] orientation_constraints
00215 motion_planning_msgs/VisibilityConstraint[] visibility_constraints
00216
00217 ================================================================================
00218 MSG: motion_planning_msgs/JointConstraint
00219 # Constrain the position of a joint to be within a certain bound
00220 string joint_name
00221
00222 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]
00223 float64 position
00224 float64 tolerance_above
00225 float64 tolerance_below
00226
00227 # A weighting factor for this constraint
00228 float64 weight
00229 ================================================================================
00230 MSG: motion_planning_msgs/PositionConstraint
00231 # This message contains the definition of a position constraint.
00232 Header header
00233
00234 # The robot link this constraint refers to
00235 string link_name
00236
00237 # The offset (in the link frame) for the target point on the link we are planning for
00238 geometry_msgs/Point target_point_offset
00239
00240 # The nominal/target position for the point we are planning for
00241 geometry_msgs/Point position
00242
00243 # The shape of the bounded region that constrains the position of the end-effector
00244 # This region is always centered at the position defined above
00245 geometric_shapes_msgs/Shape constraint_region_shape
00246
00247 # The orientation of the bounded region that constrains the position of the end-effector.
00248 # This allows the specification of non-axis aligned constraints
00249 geometry_msgs/Quaternion constraint_region_orientation
00250
00251 # Constraint weighting factor - a weight for this constraint
00252 float64 weight
00253 ================================================================================
00254 MSG: motion_planning_msgs/OrientationConstraint
00255 # This message contains the definition of an orientation constraint.
00256 Header header
00257
00258 # The robot link this constraint refers to
00259 string link_name
00260
00261 # The type of the constraint
00262 int32 type
00263 int32 LINK_FRAME=0
00264 int32 HEADER_FRAME=1
00265
00266 # The desired orientation of the robot link specified as a quaternion
00267 geometry_msgs/Quaternion orientation
00268
00269 # optional RPY error tolerances specified if
00270 float64 absolute_roll_tolerance
00271 float64 absolute_pitch_tolerance
00272 float64 absolute_yaw_tolerance
00273
00274 # Constraint weighting factor - a weight for this constraint
00275 float64 weight
00276
00277 ================================================================================
00278 MSG: motion_planning_msgs/VisibilityConstraint
00279 # This message contains the definition of a visibility constraint.
00280 Header header
00281
00282 # The point stamped target that needs to be kept within view of the sensor
00283 geometry_msgs/PointStamped target
00284
00285 # The local pose of the frame in which visibility is to be maintained
00286 # The frame id should represent the robot link to which the sensor is attached
00287 # The visual axis of the sensor is assumed to be along the X axis of this frame
00288 geometry_msgs/PoseStamped sensor_pose
00289
00290 # The deviation (in radians) that will be tolerated
00291 # Constraint error will be measured as the solid angle between the
00292 # X axis of the frame defined above and the vector between the origin
00293 # of the frame defined above and the target location
00294 float64 absolute_tolerance
00295
00296
00297 ================================================================================
00298 MSG: geometry_msgs/PointStamped
00299 # This represents a Point with reference coordinate frame and timestamp
00300 Header header
00301 Point point
00302
00303 ================================================================================
00304 MSG: motion_planning_msgs/AllowedContactSpecification
00305 # The names of the regions
00306 string name
00307
00308 # The shape of the region in the environment
00309 geometric_shapes_msgs/Shape shape
00310
00311 # The pose of the space defining the region
00312 geometry_msgs/PoseStamped pose_stamped
00313
00314 # The set of links that will be allowed to have penetration contact within this region
00315 string[] link_names
00316
00317 # The maximum penetration depth allowed for every link
00318 float64 penetration_depth
00319 ================================================================================
00320 MSG: motion_planning_msgs/OrderedCollisionOperations
00321 # A set of collision operations that will be performed in the order they are specified
00322 CollisionOperation[] collision_operations
00323 ================================================================================
00324 MSG: motion_planning_msgs/CollisionOperation
00325 # A definition of a collision operation
00326 # E.g. ("gripper",COLLISION_SET_ALL,ENABLE) will enable collisions
00327 # between the gripper and all objects in the collision space
00328
00329 string object1
00330 string object2
00331 string COLLISION_SET_ALL="all"
00332 string COLLISION_SET_OBJECTS="objects"
00333 string COLLISION_SET_ATTACHED_OBJECTS="attached"
00334
00335 # The penetration distance to which collisions are allowed. This is 0.0 by default.
00336 float64 penetration_distance
00337
00338 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above
00339 int32 operation
00340 int32 DISABLE=0
00341 int32 ENABLE=1
00342
00343 ================================================================================
00344 MSG: motion_planning_msgs/LinkPadding
00345 #name for the link
00346 string link_name
00347
00348 # padding to apply to the link
00349 float64 padding
00350
00351 """
00352 __slots__ = ['motion_plan_request']
00353 _slot_types = ['motion_planning_msgs/MotionPlanRequest']
00354
00355 def __init__(self, *args, **kwds):
00356 """
00357 Constructor. Any message fields that are implicitly/explicitly
00358 set to None will be assigned a default value. The recommend
00359 use is keyword arguments as this is more robust to future message
00360 changes. You cannot mix in-order arguments and keyword arguments.
00361
00362 The available fields are:
00363 motion_plan_request
00364
00365 @param args: complete set of field values, in .msg order
00366 @param kwds: use keyword arguments corresponding to message field names
00367 to set specific fields.
00368 """
00369 if args or kwds:
00370 super(GetMotionPlanRequest, self).__init__(*args, **kwds)
00371
00372 if self.motion_plan_request is None:
00373 self.motion_plan_request = motion_planning_msgs.msg.MotionPlanRequest()
00374 else:
00375 self.motion_plan_request = motion_planning_msgs.msg.MotionPlanRequest()
00376
00377 def _get_types(self):
00378 """
00379 internal API method
00380 """
00381 return self._slot_types
00382
00383 def serialize(self, buff):
00384 """
00385 serialize message into buffer
00386 @param buff: buffer
00387 @type buff: StringIO
00388 """
00389 try:
00390 buff.write(_struct_b.pack(self.motion_plan_request.workspace_parameters.workspace_region_shape.type))
00391 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions)
00392 buff.write(_struct_I.pack(length))
00393 pattern = '<%sd'%length
00394 buff.write(struct.pack(pattern, *self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions))
00395 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles)
00396 buff.write(_struct_I.pack(length))
00397 pattern = '<%si'%length
00398 buff.write(struct.pack(pattern, *self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles))
00399 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices)
00400 buff.write(_struct_I.pack(length))
00401 for val1 in self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices:
00402 _x = val1
00403 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00404 _x = self
00405 buff.write(_struct_3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
00406 _x = self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id
00407 length = len(_x)
00408 buff.write(struct.pack('<I%ss'%length, length, _x))
00409 _x = self
00410 buff.write(_struct_7d3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs))
00411 _x = self.motion_plan_request.start_state.joint_state.header.frame_id
00412 length = len(_x)
00413 buff.write(struct.pack('<I%ss'%length, length, _x))
00414 length = len(self.motion_plan_request.start_state.joint_state.name)
00415 buff.write(_struct_I.pack(length))
00416 for val1 in self.motion_plan_request.start_state.joint_state.name:
00417 length = len(val1)
00418 buff.write(struct.pack('<I%ss'%length, length, val1))
00419 length = len(self.motion_plan_request.start_state.joint_state.position)
00420 buff.write(_struct_I.pack(length))
00421 pattern = '<%sd'%length
00422 buff.write(struct.pack(pattern, *self.motion_plan_request.start_state.joint_state.position))
00423 length = len(self.motion_plan_request.start_state.joint_state.velocity)
00424 buff.write(_struct_I.pack(length))
00425 pattern = '<%sd'%length
00426 buff.write(struct.pack(pattern, *self.motion_plan_request.start_state.joint_state.velocity))
00427 length = len(self.motion_plan_request.start_state.joint_state.effort)
00428 buff.write(_struct_I.pack(length))
00429 pattern = '<%sd'%length
00430 buff.write(struct.pack(pattern, *self.motion_plan_request.start_state.joint_state.effort))
00431 _x = self
00432 buff.write(_struct_2I.pack(_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs))
00433 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.joint_names)
00434 buff.write(_struct_I.pack(length))
00435 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.joint_names:
00436 length = len(val1)
00437 buff.write(struct.pack('<I%ss'%length, length, val1))
00438 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids)
00439 buff.write(_struct_I.pack(length))
00440 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids:
00441 length = len(val1)
00442 buff.write(struct.pack('<I%ss'%length, length, val1))
00443 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids)
00444 buff.write(_struct_I.pack(length))
00445 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids:
00446 length = len(val1)
00447 buff.write(struct.pack('<I%ss'%length, length, val1))
00448 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.poses)
00449 buff.write(_struct_I.pack(length))
00450 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.poses:
00451 _v1 = val1.position
00452 _x = _v1
00453 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00454 _v2 = val1.orientation
00455 _x = _v2
00456 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00457 length = len(self.motion_plan_request.goal_constraints.joint_constraints)
00458 buff.write(_struct_I.pack(length))
00459 for val1 in self.motion_plan_request.goal_constraints.joint_constraints:
00460 _x = val1.joint_name
00461 length = len(_x)
00462 buff.write(struct.pack('<I%ss'%length, length, _x))
00463 _x = val1
00464 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00465 length = len(self.motion_plan_request.goal_constraints.position_constraints)
00466 buff.write(_struct_I.pack(length))
00467 for val1 in self.motion_plan_request.goal_constraints.position_constraints:
00468 _v3 = val1.header
00469 buff.write(_struct_I.pack(_v3.seq))
00470 _v4 = _v3.stamp
00471 _x = _v4
00472 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00473 _x = _v3.frame_id
00474 length = len(_x)
00475 buff.write(struct.pack('<I%ss'%length, length, _x))
00476 _x = val1.link_name
00477 length = len(_x)
00478 buff.write(struct.pack('<I%ss'%length, length, _x))
00479 _v5 = val1.target_point_offset
00480 _x = _v5
00481 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00482 _v6 = val1.position
00483 _x = _v6
00484 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00485 _v7 = val1.constraint_region_shape
00486 buff.write(_struct_b.pack(_v7.type))
00487 length = len(_v7.dimensions)
00488 buff.write(_struct_I.pack(length))
00489 pattern = '<%sd'%length
00490 buff.write(struct.pack(pattern, *_v7.dimensions))
00491 length = len(_v7.triangles)
00492 buff.write(_struct_I.pack(length))
00493 pattern = '<%si'%length
00494 buff.write(struct.pack(pattern, *_v7.triangles))
00495 length = len(_v7.vertices)
00496 buff.write(_struct_I.pack(length))
00497 for val3 in _v7.vertices:
00498 _x = val3
00499 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00500 _v8 = val1.constraint_region_orientation
00501 _x = _v8
00502 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00503 buff.write(_struct_d.pack(val1.weight))
00504 length = len(self.motion_plan_request.goal_constraints.orientation_constraints)
00505 buff.write(_struct_I.pack(length))
00506 for val1 in self.motion_plan_request.goal_constraints.orientation_constraints:
00507 _v9 = val1.header
00508 buff.write(_struct_I.pack(_v9.seq))
00509 _v10 = _v9.stamp
00510 _x = _v10
00511 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00512 _x = _v9.frame_id
00513 length = len(_x)
00514 buff.write(struct.pack('<I%ss'%length, length, _x))
00515 _x = val1.link_name
00516 length = len(_x)
00517 buff.write(struct.pack('<I%ss'%length, length, _x))
00518 buff.write(_struct_i.pack(val1.type))
00519 _v11 = val1.orientation
00520 _x = _v11
00521 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00522 _x = val1
00523 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00524 length = len(self.motion_plan_request.goal_constraints.visibility_constraints)
00525 buff.write(_struct_I.pack(length))
00526 for val1 in self.motion_plan_request.goal_constraints.visibility_constraints:
00527 _v12 = val1.header
00528 buff.write(_struct_I.pack(_v12.seq))
00529 _v13 = _v12.stamp
00530 _x = _v13
00531 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00532 _x = _v12.frame_id
00533 length = len(_x)
00534 buff.write(struct.pack('<I%ss'%length, length, _x))
00535 _v14 = val1.target
00536 _v15 = _v14.header
00537 buff.write(_struct_I.pack(_v15.seq))
00538 _v16 = _v15.stamp
00539 _x = _v16
00540 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00541 _x = _v15.frame_id
00542 length = len(_x)
00543 buff.write(struct.pack('<I%ss'%length, length, _x))
00544 _v17 = _v14.point
00545 _x = _v17
00546 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00547 _v18 = val1.sensor_pose
00548 _v19 = _v18.header
00549 buff.write(_struct_I.pack(_v19.seq))
00550 _v20 = _v19.stamp
00551 _x = _v20
00552 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00553 _x = _v19.frame_id
00554 length = len(_x)
00555 buff.write(struct.pack('<I%ss'%length, length, _x))
00556 _v21 = _v18.pose
00557 _v22 = _v21.position
00558 _x = _v22
00559 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00560 _v23 = _v21.orientation
00561 _x = _v23
00562 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00563 buff.write(_struct_d.pack(val1.absolute_tolerance))
00564 length = len(self.motion_plan_request.path_constraints.joint_constraints)
00565 buff.write(_struct_I.pack(length))
00566 for val1 in self.motion_plan_request.path_constraints.joint_constraints:
00567 _x = val1.joint_name
00568 length = len(_x)
00569 buff.write(struct.pack('<I%ss'%length, length, _x))
00570 _x = val1
00571 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00572 length = len(self.motion_plan_request.path_constraints.position_constraints)
00573 buff.write(_struct_I.pack(length))
00574 for val1 in self.motion_plan_request.path_constraints.position_constraints:
00575 _v24 = val1.header
00576 buff.write(_struct_I.pack(_v24.seq))
00577 _v25 = _v24.stamp
00578 _x = _v25
00579 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00580 _x = _v24.frame_id
00581 length = len(_x)
00582 buff.write(struct.pack('<I%ss'%length, length, _x))
00583 _x = val1.link_name
00584 length = len(_x)
00585 buff.write(struct.pack('<I%ss'%length, length, _x))
00586 _v26 = val1.target_point_offset
00587 _x = _v26
00588 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00589 _v27 = val1.position
00590 _x = _v27
00591 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00592 _v28 = val1.constraint_region_shape
00593 buff.write(_struct_b.pack(_v28.type))
00594 length = len(_v28.dimensions)
00595 buff.write(_struct_I.pack(length))
00596 pattern = '<%sd'%length
00597 buff.write(struct.pack(pattern, *_v28.dimensions))
00598 length = len(_v28.triangles)
00599 buff.write(_struct_I.pack(length))
00600 pattern = '<%si'%length
00601 buff.write(struct.pack(pattern, *_v28.triangles))
00602 length = len(_v28.vertices)
00603 buff.write(_struct_I.pack(length))
00604 for val3 in _v28.vertices:
00605 _x = val3
00606 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00607 _v29 = val1.constraint_region_orientation
00608 _x = _v29
00609 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00610 buff.write(_struct_d.pack(val1.weight))
00611 length = len(self.motion_plan_request.path_constraints.orientation_constraints)
00612 buff.write(_struct_I.pack(length))
00613 for val1 in self.motion_plan_request.path_constraints.orientation_constraints:
00614 _v30 = val1.header
00615 buff.write(_struct_I.pack(_v30.seq))
00616 _v31 = _v30.stamp
00617 _x = _v31
00618 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00619 _x = _v30.frame_id
00620 length = len(_x)
00621 buff.write(struct.pack('<I%ss'%length, length, _x))
00622 _x = val1.link_name
00623 length = len(_x)
00624 buff.write(struct.pack('<I%ss'%length, length, _x))
00625 buff.write(_struct_i.pack(val1.type))
00626 _v32 = val1.orientation
00627 _x = _v32
00628 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00629 _x = val1
00630 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00631 length = len(self.motion_plan_request.path_constraints.visibility_constraints)
00632 buff.write(_struct_I.pack(length))
00633 for val1 in self.motion_plan_request.path_constraints.visibility_constraints:
00634 _v33 = val1.header
00635 buff.write(_struct_I.pack(_v33.seq))
00636 _v34 = _v33.stamp
00637 _x = _v34
00638 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00639 _x = _v33.frame_id
00640 length = len(_x)
00641 buff.write(struct.pack('<I%ss'%length, length, _x))
00642 _v35 = val1.target
00643 _v36 = _v35.header
00644 buff.write(_struct_I.pack(_v36.seq))
00645 _v37 = _v36.stamp
00646 _x = _v37
00647 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00648 _x = _v36.frame_id
00649 length = len(_x)
00650 buff.write(struct.pack('<I%ss'%length, length, _x))
00651 _v38 = _v35.point
00652 _x = _v38
00653 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00654 _v39 = val1.sensor_pose
00655 _v40 = _v39.header
00656 buff.write(_struct_I.pack(_v40.seq))
00657 _v41 = _v40.stamp
00658 _x = _v41
00659 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00660 _x = _v40.frame_id
00661 length = len(_x)
00662 buff.write(struct.pack('<I%ss'%length, length, _x))
00663 _v42 = _v39.pose
00664 _v43 = _v42.position
00665 _x = _v43
00666 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00667 _v44 = _v42.orientation
00668 _x = _v44
00669 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00670 buff.write(_struct_d.pack(val1.absolute_tolerance))
00671 length = len(self.motion_plan_request.allowed_contacts)
00672 buff.write(_struct_I.pack(length))
00673 for val1 in self.motion_plan_request.allowed_contacts:
00674 _x = val1.name
00675 length = len(_x)
00676 buff.write(struct.pack('<I%ss'%length, length, _x))
00677 _v45 = val1.shape
00678 buff.write(_struct_b.pack(_v45.type))
00679 length = len(_v45.dimensions)
00680 buff.write(_struct_I.pack(length))
00681 pattern = '<%sd'%length
00682 buff.write(struct.pack(pattern, *_v45.dimensions))
00683 length = len(_v45.triangles)
00684 buff.write(_struct_I.pack(length))
00685 pattern = '<%si'%length
00686 buff.write(struct.pack(pattern, *_v45.triangles))
00687 length = len(_v45.vertices)
00688 buff.write(_struct_I.pack(length))
00689 for val3 in _v45.vertices:
00690 _x = val3
00691 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00692 _v46 = val1.pose_stamped
00693 _v47 = _v46.header
00694 buff.write(_struct_I.pack(_v47.seq))
00695 _v48 = _v47.stamp
00696 _x = _v48
00697 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00698 _x = _v47.frame_id
00699 length = len(_x)
00700 buff.write(struct.pack('<I%ss'%length, length, _x))
00701 _v49 = _v46.pose
00702 _v50 = _v49.position
00703 _x = _v50
00704 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00705 _v51 = _v49.orientation
00706 _x = _v51
00707 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00708 length = len(val1.link_names)
00709 buff.write(_struct_I.pack(length))
00710 for val2 in val1.link_names:
00711 length = len(val2)
00712 buff.write(struct.pack('<I%ss'%length, length, val2))
00713 buff.write(_struct_d.pack(val1.penetration_depth))
00714 length = len(self.motion_plan_request.ordered_collision_operations.collision_operations)
00715 buff.write(_struct_I.pack(length))
00716 for val1 in self.motion_plan_request.ordered_collision_operations.collision_operations:
00717 _x = val1.object1
00718 length = len(_x)
00719 buff.write(struct.pack('<I%ss'%length, length, _x))
00720 _x = val1.object2
00721 length = len(_x)
00722 buff.write(struct.pack('<I%ss'%length, length, _x))
00723 _x = val1
00724 buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
00725 length = len(self.motion_plan_request.link_padding)
00726 buff.write(_struct_I.pack(length))
00727 for val1 in self.motion_plan_request.link_padding:
00728 _x = val1.link_name
00729 length = len(_x)
00730 buff.write(struct.pack('<I%ss'%length, length, _x))
00731 buff.write(_struct_d.pack(val1.padding))
00732 _x = self.motion_plan_request.planner_id
00733 length = len(_x)
00734 buff.write(struct.pack('<I%ss'%length, length, _x))
00735 _x = self.motion_plan_request.group_name
00736 length = len(_x)
00737 buff.write(struct.pack('<I%ss'%length, length, _x))
00738 _x = self
00739 buff.write(_struct_7i.pack(_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs))
00740 except struct.error, se: self._check_types(se)
00741 except TypeError, te: self._check_types(te)
00742
00743 def deserialize(self, str):
00744 """
00745 unpack serialized message in str into this message instance
00746 @param str: byte array of serialized message
00747 @type str: str
00748 """
00749 try:
00750 if self.motion_plan_request is None:
00751 self.motion_plan_request = motion_planning_msgs.msg.MotionPlanRequest()
00752 end = 0
00753 start = end
00754 end += 1
00755 (self.motion_plan_request.workspace_parameters.workspace_region_shape.type,) = _struct_b.unpack(str[start:end])
00756 start = end
00757 end += 4
00758 (length,) = _struct_I.unpack(str[start:end])
00759 pattern = '<%sd'%length
00760 start = end
00761 end += struct.calcsize(pattern)
00762 self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions = struct.unpack(pattern, str[start:end])
00763 start = end
00764 end += 4
00765 (length,) = _struct_I.unpack(str[start:end])
00766 pattern = '<%si'%length
00767 start = end
00768 end += struct.calcsize(pattern)
00769 self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles = struct.unpack(pattern, str[start:end])
00770 start = end
00771 end += 4
00772 (length,) = _struct_I.unpack(str[start:end])
00773 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices = []
00774 for i in xrange(0, length):
00775 val1 = geometry_msgs.msg.Point()
00776 _x = val1
00777 start = end
00778 end += 24
00779 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00780 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices.append(val1)
00781 _x = self
00782 start = end
00783 end += 12
00784 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00785 start = end
00786 end += 4
00787 (length,) = _struct_I.unpack(str[start:end])
00788 start = end
00789 end += length
00790 self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
00791 _x = self
00792 start = end
00793 end += 68
00794 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00795 start = end
00796 end += 4
00797 (length,) = _struct_I.unpack(str[start:end])
00798 start = end
00799 end += length
00800 self.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end]
00801 start = end
00802 end += 4
00803 (length,) = _struct_I.unpack(str[start:end])
00804 self.motion_plan_request.start_state.joint_state.name = []
00805 for i in xrange(0, length):
00806 start = end
00807 end += 4
00808 (length,) = _struct_I.unpack(str[start:end])
00809 start = end
00810 end += length
00811 val1 = str[start:end]
00812 self.motion_plan_request.start_state.joint_state.name.append(val1)
00813 start = end
00814 end += 4
00815 (length,) = _struct_I.unpack(str[start:end])
00816 pattern = '<%sd'%length
00817 start = end
00818 end += struct.calcsize(pattern)
00819 self.motion_plan_request.start_state.joint_state.position = struct.unpack(pattern, str[start:end])
00820 start = end
00821 end += 4
00822 (length,) = _struct_I.unpack(str[start:end])
00823 pattern = '<%sd'%length
00824 start = end
00825 end += struct.calcsize(pattern)
00826 self.motion_plan_request.start_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
00827 start = end
00828 end += 4
00829 (length,) = _struct_I.unpack(str[start:end])
00830 pattern = '<%sd'%length
00831 start = end
00832 end += struct.calcsize(pattern)
00833 self.motion_plan_request.start_state.joint_state.effort = struct.unpack(pattern, str[start:end])
00834 _x = self
00835 start = end
00836 end += 8
00837 (_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00838 start = end
00839 end += 4
00840 (length,) = _struct_I.unpack(str[start:end])
00841 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names = []
00842 for i in xrange(0, length):
00843 start = end
00844 end += 4
00845 (length,) = _struct_I.unpack(str[start:end])
00846 start = end
00847 end += length
00848 val1 = str[start:end]
00849 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names.append(val1)
00850 start = end
00851 end += 4
00852 (length,) = _struct_I.unpack(str[start:end])
00853 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids = []
00854 for i in xrange(0, length):
00855 start = end
00856 end += 4
00857 (length,) = _struct_I.unpack(str[start:end])
00858 start = end
00859 end += length
00860 val1 = str[start:end]
00861 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids.append(val1)
00862 start = end
00863 end += 4
00864 (length,) = _struct_I.unpack(str[start:end])
00865 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids = []
00866 for i in xrange(0, length):
00867 start = end
00868 end += 4
00869 (length,) = _struct_I.unpack(str[start:end])
00870 start = end
00871 end += length
00872 val1 = str[start:end]
00873 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
00874 start = end
00875 end += 4
00876 (length,) = _struct_I.unpack(str[start:end])
00877 self.motion_plan_request.start_state.multi_dof_joint_state.poses = []
00878 for i in xrange(0, length):
00879 val1 = geometry_msgs.msg.Pose()
00880 _v52 = val1.position
00881 _x = _v52
00882 start = end
00883 end += 24
00884 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00885 _v53 = val1.orientation
00886 _x = _v53
00887 start = end
00888 end += 32
00889 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00890 self.motion_plan_request.start_state.multi_dof_joint_state.poses.append(val1)
00891 start = end
00892 end += 4
00893 (length,) = _struct_I.unpack(str[start:end])
00894 self.motion_plan_request.goal_constraints.joint_constraints = []
00895 for i in xrange(0, length):
00896 val1 = motion_planning_msgs.msg.JointConstraint()
00897 start = end
00898 end += 4
00899 (length,) = _struct_I.unpack(str[start:end])
00900 start = end
00901 end += length
00902 val1.joint_name = str[start:end]
00903 _x = val1
00904 start = end
00905 end += 32
00906 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
00907 self.motion_plan_request.goal_constraints.joint_constraints.append(val1)
00908 start = end
00909 end += 4
00910 (length,) = _struct_I.unpack(str[start:end])
00911 self.motion_plan_request.goal_constraints.position_constraints = []
00912 for i in xrange(0, length):
00913 val1 = motion_planning_msgs.msg.PositionConstraint()
00914 _v54 = val1.header
00915 start = end
00916 end += 4
00917 (_v54.seq,) = _struct_I.unpack(str[start:end])
00918 _v55 = _v54.stamp
00919 _x = _v55
00920 start = end
00921 end += 8
00922 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00923 start = end
00924 end += 4
00925 (length,) = _struct_I.unpack(str[start:end])
00926 start = end
00927 end += length
00928 _v54.frame_id = str[start:end]
00929 start = end
00930 end += 4
00931 (length,) = _struct_I.unpack(str[start:end])
00932 start = end
00933 end += length
00934 val1.link_name = str[start:end]
00935 _v56 = val1.target_point_offset
00936 _x = _v56
00937 start = end
00938 end += 24
00939 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00940 _v57 = val1.position
00941 _x = _v57
00942 start = end
00943 end += 24
00944 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00945 _v58 = val1.constraint_region_shape
00946 start = end
00947 end += 1
00948 (_v58.type,) = _struct_b.unpack(str[start:end])
00949 start = end
00950 end += 4
00951 (length,) = _struct_I.unpack(str[start:end])
00952 pattern = '<%sd'%length
00953 start = end
00954 end += struct.calcsize(pattern)
00955 _v58.dimensions = struct.unpack(pattern, str[start:end])
00956 start = end
00957 end += 4
00958 (length,) = _struct_I.unpack(str[start:end])
00959 pattern = '<%si'%length
00960 start = end
00961 end += struct.calcsize(pattern)
00962 _v58.triangles = struct.unpack(pattern, str[start:end])
00963 start = end
00964 end += 4
00965 (length,) = _struct_I.unpack(str[start:end])
00966 _v58.vertices = []
00967 for i in xrange(0, length):
00968 val3 = geometry_msgs.msg.Point()
00969 _x = val3
00970 start = end
00971 end += 24
00972 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00973 _v58.vertices.append(val3)
00974 _v59 = val1.constraint_region_orientation
00975 _x = _v59
00976 start = end
00977 end += 32
00978 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00979 start = end
00980 end += 8
00981 (val1.weight,) = _struct_d.unpack(str[start:end])
00982 self.motion_plan_request.goal_constraints.position_constraints.append(val1)
00983 start = end
00984 end += 4
00985 (length,) = _struct_I.unpack(str[start:end])
00986 self.motion_plan_request.goal_constraints.orientation_constraints = []
00987 for i in xrange(0, length):
00988 val1 = motion_planning_msgs.msg.OrientationConstraint()
00989 _v60 = val1.header
00990 start = end
00991 end += 4
00992 (_v60.seq,) = _struct_I.unpack(str[start:end])
00993 _v61 = _v60.stamp
00994 _x = _v61
00995 start = end
00996 end += 8
00997 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00998 start = end
00999 end += 4
01000 (length,) = _struct_I.unpack(str[start:end])
01001 start = end
01002 end += length
01003 _v60.frame_id = str[start:end]
01004 start = end
01005 end += 4
01006 (length,) = _struct_I.unpack(str[start:end])
01007 start = end
01008 end += length
01009 val1.link_name = str[start:end]
01010 start = end
01011 end += 4
01012 (val1.type,) = _struct_i.unpack(str[start:end])
01013 _v62 = val1.orientation
01014 _x = _v62
01015 start = end
01016 end += 32
01017 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01018 _x = val1
01019 start = end
01020 end += 32
01021 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01022 self.motion_plan_request.goal_constraints.orientation_constraints.append(val1)
01023 start = end
01024 end += 4
01025 (length,) = _struct_I.unpack(str[start:end])
01026 self.motion_plan_request.goal_constraints.visibility_constraints = []
01027 for i in xrange(0, length):
01028 val1 = motion_planning_msgs.msg.VisibilityConstraint()
01029 _v63 = val1.header
01030 start = end
01031 end += 4
01032 (_v63.seq,) = _struct_I.unpack(str[start:end])
01033 _v64 = _v63.stamp
01034 _x = _v64
01035 start = end
01036 end += 8
01037 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01038 start = end
01039 end += 4
01040 (length,) = _struct_I.unpack(str[start:end])
01041 start = end
01042 end += length
01043 _v63.frame_id = str[start:end]
01044 _v65 = val1.target
01045 _v66 = _v65.header
01046 start = end
01047 end += 4
01048 (_v66.seq,) = _struct_I.unpack(str[start:end])
01049 _v67 = _v66.stamp
01050 _x = _v67
01051 start = end
01052 end += 8
01053 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01054 start = end
01055 end += 4
01056 (length,) = _struct_I.unpack(str[start:end])
01057 start = end
01058 end += length
01059 _v66.frame_id = str[start:end]
01060 _v68 = _v65.point
01061 _x = _v68
01062 start = end
01063 end += 24
01064 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01065 _v69 = val1.sensor_pose
01066 _v70 = _v69.header
01067 start = end
01068 end += 4
01069 (_v70.seq,) = _struct_I.unpack(str[start:end])
01070 _v71 = _v70.stamp
01071 _x = _v71
01072 start = end
01073 end += 8
01074 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01075 start = end
01076 end += 4
01077 (length,) = _struct_I.unpack(str[start:end])
01078 start = end
01079 end += length
01080 _v70.frame_id = str[start:end]
01081 _v72 = _v69.pose
01082 _v73 = _v72.position
01083 _x = _v73
01084 start = end
01085 end += 24
01086 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01087 _v74 = _v72.orientation
01088 _x = _v74
01089 start = end
01090 end += 32
01091 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01092 start = end
01093 end += 8
01094 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01095 self.motion_plan_request.goal_constraints.visibility_constraints.append(val1)
01096 start = end
01097 end += 4
01098 (length,) = _struct_I.unpack(str[start:end])
01099 self.motion_plan_request.path_constraints.joint_constraints = []
01100 for i in xrange(0, length):
01101 val1 = motion_planning_msgs.msg.JointConstraint()
01102 start = end
01103 end += 4
01104 (length,) = _struct_I.unpack(str[start:end])
01105 start = end
01106 end += length
01107 val1.joint_name = str[start:end]
01108 _x = val1
01109 start = end
01110 end += 32
01111 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01112 self.motion_plan_request.path_constraints.joint_constraints.append(val1)
01113 start = end
01114 end += 4
01115 (length,) = _struct_I.unpack(str[start:end])
01116 self.motion_plan_request.path_constraints.position_constraints = []
01117 for i in xrange(0, length):
01118 val1 = motion_planning_msgs.msg.PositionConstraint()
01119 _v75 = val1.header
01120 start = end
01121 end += 4
01122 (_v75.seq,) = _struct_I.unpack(str[start:end])
01123 _v76 = _v75.stamp
01124 _x = _v76
01125 start = end
01126 end += 8
01127 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01128 start = end
01129 end += 4
01130 (length,) = _struct_I.unpack(str[start:end])
01131 start = end
01132 end += length
01133 _v75.frame_id = str[start:end]
01134 start = end
01135 end += 4
01136 (length,) = _struct_I.unpack(str[start:end])
01137 start = end
01138 end += length
01139 val1.link_name = str[start:end]
01140 _v77 = val1.target_point_offset
01141 _x = _v77
01142 start = end
01143 end += 24
01144 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01145 _v78 = val1.position
01146 _x = _v78
01147 start = end
01148 end += 24
01149 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01150 _v79 = val1.constraint_region_shape
01151 start = end
01152 end += 1
01153 (_v79.type,) = _struct_b.unpack(str[start:end])
01154 start = end
01155 end += 4
01156 (length,) = _struct_I.unpack(str[start:end])
01157 pattern = '<%sd'%length
01158 start = end
01159 end += struct.calcsize(pattern)
01160 _v79.dimensions = struct.unpack(pattern, str[start:end])
01161 start = end
01162 end += 4
01163 (length,) = _struct_I.unpack(str[start:end])
01164 pattern = '<%si'%length
01165 start = end
01166 end += struct.calcsize(pattern)
01167 _v79.triangles = struct.unpack(pattern, str[start:end])
01168 start = end
01169 end += 4
01170 (length,) = _struct_I.unpack(str[start:end])
01171 _v79.vertices = []
01172 for i in xrange(0, length):
01173 val3 = geometry_msgs.msg.Point()
01174 _x = val3
01175 start = end
01176 end += 24
01177 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01178 _v79.vertices.append(val3)
01179 _v80 = val1.constraint_region_orientation
01180 _x = _v80
01181 start = end
01182 end += 32
01183 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01184 start = end
01185 end += 8
01186 (val1.weight,) = _struct_d.unpack(str[start:end])
01187 self.motion_plan_request.path_constraints.position_constraints.append(val1)
01188 start = end
01189 end += 4
01190 (length,) = _struct_I.unpack(str[start:end])
01191 self.motion_plan_request.path_constraints.orientation_constraints = []
01192 for i in xrange(0, length):
01193 val1 = motion_planning_msgs.msg.OrientationConstraint()
01194 _v81 = val1.header
01195 start = end
01196 end += 4
01197 (_v81.seq,) = _struct_I.unpack(str[start:end])
01198 _v82 = _v81.stamp
01199 _x = _v82
01200 start = end
01201 end += 8
01202 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01203 start = end
01204 end += 4
01205 (length,) = _struct_I.unpack(str[start:end])
01206 start = end
01207 end += length
01208 _v81.frame_id = str[start:end]
01209 start = end
01210 end += 4
01211 (length,) = _struct_I.unpack(str[start:end])
01212 start = end
01213 end += length
01214 val1.link_name = str[start:end]
01215 start = end
01216 end += 4
01217 (val1.type,) = _struct_i.unpack(str[start:end])
01218 _v83 = val1.orientation
01219 _x = _v83
01220 start = end
01221 end += 32
01222 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01223 _x = val1
01224 start = end
01225 end += 32
01226 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01227 self.motion_plan_request.path_constraints.orientation_constraints.append(val1)
01228 start = end
01229 end += 4
01230 (length,) = _struct_I.unpack(str[start:end])
01231 self.motion_plan_request.path_constraints.visibility_constraints = []
01232 for i in xrange(0, length):
01233 val1 = motion_planning_msgs.msg.VisibilityConstraint()
01234 _v84 = val1.header
01235 start = end
01236 end += 4
01237 (_v84.seq,) = _struct_I.unpack(str[start:end])
01238 _v85 = _v84.stamp
01239 _x = _v85
01240 start = end
01241 end += 8
01242 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01243 start = end
01244 end += 4
01245 (length,) = _struct_I.unpack(str[start:end])
01246 start = end
01247 end += length
01248 _v84.frame_id = str[start:end]
01249 _v86 = val1.target
01250 _v87 = _v86.header
01251 start = end
01252 end += 4
01253 (_v87.seq,) = _struct_I.unpack(str[start:end])
01254 _v88 = _v87.stamp
01255 _x = _v88
01256 start = end
01257 end += 8
01258 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01259 start = end
01260 end += 4
01261 (length,) = _struct_I.unpack(str[start:end])
01262 start = end
01263 end += length
01264 _v87.frame_id = str[start:end]
01265 _v89 = _v86.point
01266 _x = _v89
01267 start = end
01268 end += 24
01269 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01270 _v90 = val1.sensor_pose
01271 _v91 = _v90.header
01272 start = end
01273 end += 4
01274 (_v91.seq,) = _struct_I.unpack(str[start:end])
01275 _v92 = _v91.stamp
01276 _x = _v92
01277 start = end
01278 end += 8
01279 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01280 start = end
01281 end += 4
01282 (length,) = _struct_I.unpack(str[start:end])
01283 start = end
01284 end += length
01285 _v91.frame_id = str[start:end]
01286 _v93 = _v90.pose
01287 _v94 = _v93.position
01288 _x = _v94
01289 start = end
01290 end += 24
01291 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01292 _v95 = _v93.orientation
01293 _x = _v95
01294 start = end
01295 end += 32
01296 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01297 start = end
01298 end += 8
01299 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01300 self.motion_plan_request.path_constraints.visibility_constraints.append(val1)
01301 start = end
01302 end += 4
01303 (length,) = _struct_I.unpack(str[start:end])
01304 self.motion_plan_request.allowed_contacts = []
01305 for i in xrange(0, length):
01306 val1 = motion_planning_msgs.msg.AllowedContactSpecification()
01307 start = end
01308 end += 4
01309 (length,) = _struct_I.unpack(str[start:end])
01310 start = end
01311 end += length
01312 val1.name = str[start:end]
01313 _v96 = val1.shape
01314 start = end
01315 end += 1
01316 (_v96.type,) = _struct_b.unpack(str[start:end])
01317 start = end
01318 end += 4
01319 (length,) = _struct_I.unpack(str[start:end])
01320 pattern = '<%sd'%length
01321 start = end
01322 end += struct.calcsize(pattern)
01323 _v96.dimensions = struct.unpack(pattern, str[start:end])
01324 start = end
01325 end += 4
01326 (length,) = _struct_I.unpack(str[start:end])
01327 pattern = '<%si'%length
01328 start = end
01329 end += struct.calcsize(pattern)
01330 _v96.triangles = struct.unpack(pattern, str[start:end])
01331 start = end
01332 end += 4
01333 (length,) = _struct_I.unpack(str[start:end])
01334 _v96.vertices = []
01335 for i in xrange(0, length):
01336 val3 = geometry_msgs.msg.Point()
01337 _x = val3
01338 start = end
01339 end += 24
01340 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01341 _v96.vertices.append(val3)
01342 _v97 = val1.pose_stamped
01343 _v98 = _v97.header
01344 start = end
01345 end += 4
01346 (_v98.seq,) = _struct_I.unpack(str[start:end])
01347 _v99 = _v98.stamp
01348 _x = _v99
01349 start = end
01350 end += 8
01351 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01352 start = end
01353 end += 4
01354 (length,) = _struct_I.unpack(str[start:end])
01355 start = end
01356 end += length
01357 _v98.frame_id = str[start:end]
01358 _v100 = _v97.pose
01359 _v101 = _v100.position
01360 _x = _v101
01361 start = end
01362 end += 24
01363 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01364 _v102 = _v100.orientation
01365 _x = _v102
01366 start = end
01367 end += 32
01368 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01369 start = end
01370 end += 4
01371 (length,) = _struct_I.unpack(str[start:end])
01372 val1.link_names = []
01373 for i in xrange(0, length):
01374 start = end
01375 end += 4
01376 (length,) = _struct_I.unpack(str[start:end])
01377 start = end
01378 end += length
01379 val2 = str[start:end]
01380 val1.link_names.append(val2)
01381 start = end
01382 end += 8
01383 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
01384 self.motion_plan_request.allowed_contacts.append(val1)
01385 start = end
01386 end += 4
01387 (length,) = _struct_I.unpack(str[start:end])
01388 self.motion_plan_request.ordered_collision_operations.collision_operations = []
01389 for i in xrange(0, length):
01390 val1 = motion_planning_msgs.msg.CollisionOperation()
01391 start = end
01392 end += 4
01393 (length,) = _struct_I.unpack(str[start:end])
01394 start = end
01395 end += length
01396 val1.object1 = str[start:end]
01397 start = end
01398 end += 4
01399 (length,) = _struct_I.unpack(str[start:end])
01400 start = end
01401 end += length
01402 val1.object2 = str[start:end]
01403 _x = val1
01404 start = end
01405 end += 12
01406 (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
01407 self.motion_plan_request.ordered_collision_operations.collision_operations.append(val1)
01408 start = end
01409 end += 4
01410 (length,) = _struct_I.unpack(str[start:end])
01411 self.motion_plan_request.link_padding = []
01412 for i in xrange(0, length):
01413 val1 = motion_planning_msgs.msg.LinkPadding()
01414 start = end
01415 end += 4
01416 (length,) = _struct_I.unpack(str[start:end])
01417 start = end
01418 end += length
01419 val1.link_name = str[start:end]
01420 start = end
01421 end += 8
01422 (val1.padding,) = _struct_d.unpack(str[start:end])
01423 self.motion_plan_request.link_padding.append(val1)
01424 start = end
01425 end += 4
01426 (length,) = _struct_I.unpack(str[start:end])
01427 start = end
01428 end += length
01429 self.motion_plan_request.planner_id = str[start:end]
01430 start = end
01431 end += 4
01432 (length,) = _struct_I.unpack(str[start:end])
01433 start = end
01434 end += length
01435 self.motion_plan_request.group_name = str[start:end]
01436 _x = self
01437 start = end
01438 end += 28
01439 (_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
01440 return self
01441 except struct.error, e:
01442 raise roslib.message.DeserializationError(e)
01443
01444
01445 def serialize_numpy(self, buff, numpy):
01446 """
01447 serialize message with numpy array types into buffer
01448 @param buff: buffer
01449 @type buff: StringIO
01450 @param numpy: numpy python module
01451 @type numpy module
01452 """
01453 try:
01454 buff.write(_struct_b.pack(self.motion_plan_request.workspace_parameters.workspace_region_shape.type))
01455 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions)
01456 buff.write(_struct_I.pack(length))
01457 pattern = '<%sd'%length
01458 buff.write(self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions.tostring())
01459 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles)
01460 buff.write(_struct_I.pack(length))
01461 pattern = '<%si'%length
01462 buff.write(self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles.tostring())
01463 length = len(self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices)
01464 buff.write(_struct_I.pack(length))
01465 for val1 in self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices:
01466 _x = val1
01467 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01468 _x = self
01469 buff.write(_struct_3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
01470 _x = self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id
01471 length = len(_x)
01472 buff.write(struct.pack('<I%ss'%length, length, _x))
01473 _x = self
01474 buff.write(_struct_7d3I.pack(_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs))
01475 _x = self.motion_plan_request.start_state.joint_state.header.frame_id
01476 length = len(_x)
01477 buff.write(struct.pack('<I%ss'%length, length, _x))
01478 length = len(self.motion_plan_request.start_state.joint_state.name)
01479 buff.write(_struct_I.pack(length))
01480 for val1 in self.motion_plan_request.start_state.joint_state.name:
01481 length = len(val1)
01482 buff.write(struct.pack('<I%ss'%length, length, val1))
01483 length = len(self.motion_plan_request.start_state.joint_state.position)
01484 buff.write(_struct_I.pack(length))
01485 pattern = '<%sd'%length
01486 buff.write(self.motion_plan_request.start_state.joint_state.position.tostring())
01487 length = len(self.motion_plan_request.start_state.joint_state.velocity)
01488 buff.write(_struct_I.pack(length))
01489 pattern = '<%sd'%length
01490 buff.write(self.motion_plan_request.start_state.joint_state.velocity.tostring())
01491 length = len(self.motion_plan_request.start_state.joint_state.effort)
01492 buff.write(_struct_I.pack(length))
01493 pattern = '<%sd'%length
01494 buff.write(self.motion_plan_request.start_state.joint_state.effort.tostring())
01495 _x = self
01496 buff.write(_struct_2I.pack(_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs))
01497 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.joint_names)
01498 buff.write(_struct_I.pack(length))
01499 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.joint_names:
01500 length = len(val1)
01501 buff.write(struct.pack('<I%ss'%length, length, val1))
01502 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids)
01503 buff.write(_struct_I.pack(length))
01504 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids:
01505 length = len(val1)
01506 buff.write(struct.pack('<I%ss'%length, length, val1))
01507 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids)
01508 buff.write(_struct_I.pack(length))
01509 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids:
01510 length = len(val1)
01511 buff.write(struct.pack('<I%ss'%length, length, val1))
01512 length = len(self.motion_plan_request.start_state.multi_dof_joint_state.poses)
01513 buff.write(_struct_I.pack(length))
01514 for val1 in self.motion_plan_request.start_state.multi_dof_joint_state.poses:
01515 _v103 = val1.position
01516 _x = _v103
01517 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01518 _v104 = val1.orientation
01519 _x = _v104
01520 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01521 length = len(self.motion_plan_request.goal_constraints.joint_constraints)
01522 buff.write(_struct_I.pack(length))
01523 for val1 in self.motion_plan_request.goal_constraints.joint_constraints:
01524 _x = val1.joint_name
01525 length = len(_x)
01526 buff.write(struct.pack('<I%ss'%length, length, _x))
01527 _x = val1
01528 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01529 length = len(self.motion_plan_request.goal_constraints.position_constraints)
01530 buff.write(_struct_I.pack(length))
01531 for val1 in self.motion_plan_request.goal_constraints.position_constraints:
01532 _v105 = val1.header
01533 buff.write(_struct_I.pack(_v105.seq))
01534 _v106 = _v105.stamp
01535 _x = _v106
01536 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01537 _x = _v105.frame_id
01538 length = len(_x)
01539 buff.write(struct.pack('<I%ss'%length, length, _x))
01540 _x = val1.link_name
01541 length = len(_x)
01542 buff.write(struct.pack('<I%ss'%length, length, _x))
01543 _v107 = val1.target_point_offset
01544 _x = _v107
01545 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01546 _v108 = val1.position
01547 _x = _v108
01548 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01549 _v109 = val1.constraint_region_shape
01550 buff.write(_struct_b.pack(_v109.type))
01551 length = len(_v109.dimensions)
01552 buff.write(_struct_I.pack(length))
01553 pattern = '<%sd'%length
01554 buff.write(_v109.dimensions.tostring())
01555 length = len(_v109.triangles)
01556 buff.write(_struct_I.pack(length))
01557 pattern = '<%si'%length
01558 buff.write(_v109.triangles.tostring())
01559 length = len(_v109.vertices)
01560 buff.write(_struct_I.pack(length))
01561 for val3 in _v109.vertices:
01562 _x = val3
01563 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01564 _v110 = val1.constraint_region_orientation
01565 _x = _v110
01566 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01567 buff.write(_struct_d.pack(val1.weight))
01568 length = len(self.motion_plan_request.goal_constraints.orientation_constraints)
01569 buff.write(_struct_I.pack(length))
01570 for val1 in self.motion_plan_request.goal_constraints.orientation_constraints:
01571 _v111 = val1.header
01572 buff.write(_struct_I.pack(_v111.seq))
01573 _v112 = _v111.stamp
01574 _x = _v112
01575 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01576 _x = _v111.frame_id
01577 length = len(_x)
01578 buff.write(struct.pack('<I%ss'%length, length, _x))
01579 _x = val1.link_name
01580 length = len(_x)
01581 buff.write(struct.pack('<I%ss'%length, length, _x))
01582 buff.write(_struct_i.pack(val1.type))
01583 _v113 = val1.orientation
01584 _x = _v113
01585 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01586 _x = val1
01587 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01588 length = len(self.motion_plan_request.goal_constraints.visibility_constraints)
01589 buff.write(_struct_I.pack(length))
01590 for val1 in self.motion_plan_request.goal_constraints.visibility_constraints:
01591 _v114 = val1.header
01592 buff.write(_struct_I.pack(_v114.seq))
01593 _v115 = _v114.stamp
01594 _x = _v115
01595 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01596 _x = _v114.frame_id
01597 length = len(_x)
01598 buff.write(struct.pack('<I%ss'%length, length, _x))
01599 _v116 = val1.target
01600 _v117 = _v116.header
01601 buff.write(_struct_I.pack(_v117.seq))
01602 _v118 = _v117.stamp
01603 _x = _v118
01604 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01605 _x = _v117.frame_id
01606 length = len(_x)
01607 buff.write(struct.pack('<I%ss'%length, length, _x))
01608 _v119 = _v116.point
01609 _x = _v119
01610 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01611 _v120 = val1.sensor_pose
01612 _v121 = _v120.header
01613 buff.write(_struct_I.pack(_v121.seq))
01614 _v122 = _v121.stamp
01615 _x = _v122
01616 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01617 _x = _v121.frame_id
01618 length = len(_x)
01619 buff.write(struct.pack('<I%ss'%length, length, _x))
01620 _v123 = _v120.pose
01621 _v124 = _v123.position
01622 _x = _v124
01623 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01624 _v125 = _v123.orientation
01625 _x = _v125
01626 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01627 buff.write(_struct_d.pack(val1.absolute_tolerance))
01628 length = len(self.motion_plan_request.path_constraints.joint_constraints)
01629 buff.write(_struct_I.pack(length))
01630 for val1 in self.motion_plan_request.path_constraints.joint_constraints:
01631 _x = val1.joint_name
01632 length = len(_x)
01633 buff.write(struct.pack('<I%ss'%length, length, _x))
01634 _x = val1
01635 buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01636 length = len(self.motion_plan_request.path_constraints.position_constraints)
01637 buff.write(_struct_I.pack(length))
01638 for val1 in self.motion_plan_request.path_constraints.position_constraints:
01639 _v126 = val1.header
01640 buff.write(_struct_I.pack(_v126.seq))
01641 _v127 = _v126.stamp
01642 _x = _v127
01643 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01644 _x = _v126.frame_id
01645 length = len(_x)
01646 buff.write(struct.pack('<I%ss'%length, length, _x))
01647 _x = val1.link_name
01648 length = len(_x)
01649 buff.write(struct.pack('<I%ss'%length, length, _x))
01650 _v128 = val1.target_point_offset
01651 _x = _v128
01652 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01653 _v129 = val1.position
01654 _x = _v129
01655 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01656 _v130 = val1.constraint_region_shape
01657 buff.write(_struct_b.pack(_v130.type))
01658 length = len(_v130.dimensions)
01659 buff.write(_struct_I.pack(length))
01660 pattern = '<%sd'%length
01661 buff.write(_v130.dimensions.tostring())
01662 length = len(_v130.triangles)
01663 buff.write(_struct_I.pack(length))
01664 pattern = '<%si'%length
01665 buff.write(_v130.triangles.tostring())
01666 length = len(_v130.vertices)
01667 buff.write(_struct_I.pack(length))
01668 for val3 in _v130.vertices:
01669 _x = val3
01670 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01671 _v131 = val1.constraint_region_orientation
01672 _x = _v131
01673 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01674 buff.write(_struct_d.pack(val1.weight))
01675 length = len(self.motion_plan_request.path_constraints.orientation_constraints)
01676 buff.write(_struct_I.pack(length))
01677 for val1 in self.motion_plan_request.path_constraints.orientation_constraints:
01678 _v132 = val1.header
01679 buff.write(_struct_I.pack(_v132.seq))
01680 _v133 = _v132.stamp
01681 _x = _v133
01682 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01683 _x = _v132.frame_id
01684 length = len(_x)
01685 buff.write(struct.pack('<I%ss'%length, length, _x))
01686 _x = val1.link_name
01687 length = len(_x)
01688 buff.write(struct.pack('<I%ss'%length, length, _x))
01689 buff.write(_struct_i.pack(val1.type))
01690 _v134 = val1.orientation
01691 _x = _v134
01692 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01693 _x = val1
01694 buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01695 length = len(self.motion_plan_request.path_constraints.visibility_constraints)
01696 buff.write(_struct_I.pack(length))
01697 for val1 in self.motion_plan_request.path_constraints.visibility_constraints:
01698 _v135 = val1.header
01699 buff.write(_struct_I.pack(_v135.seq))
01700 _v136 = _v135.stamp
01701 _x = _v136
01702 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01703 _x = _v135.frame_id
01704 length = len(_x)
01705 buff.write(struct.pack('<I%ss'%length, length, _x))
01706 _v137 = val1.target
01707 _v138 = _v137.header
01708 buff.write(_struct_I.pack(_v138.seq))
01709 _v139 = _v138.stamp
01710 _x = _v139
01711 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01712 _x = _v138.frame_id
01713 length = len(_x)
01714 buff.write(struct.pack('<I%ss'%length, length, _x))
01715 _v140 = _v137.point
01716 _x = _v140
01717 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01718 _v141 = val1.sensor_pose
01719 _v142 = _v141.header
01720 buff.write(_struct_I.pack(_v142.seq))
01721 _v143 = _v142.stamp
01722 _x = _v143
01723 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01724 _x = _v142.frame_id
01725 length = len(_x)
01726 buff.write(struct.pack('<I%ss'%length, length, _x))
01727 _v144 = _v141.pose
01728 _v145 = _v144.position
01729 _x = _v145
01730 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01731 _v146 = _v144.orientation
01732 _x = _v146
01733 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01734 buff.write(_struct_d.pack(val1.absolute_tolerance))
01735 length = len(self.motion_plan_request.allowed_contacts)
01736 buff.write(_struct_I.pack(length))
01737 for val1 in self.motion_plan_request.allowed_contacts:
01738 _x = val1.name
01739 length = len(_x)
01740 buff.write(struct.pack('<I%ss'%length, length, _x))
01741 _v147 = val1.shape
01742 buff.write(_struct_b.pack(_v147.type))
01743 length = len(_v147.dimensions)
01744 buff.write(_struct_I.pack(length))
01745 pattern = '<%sd'%length
01746 buff.write(_v147.dimensions.tostring())
01747 length = len(_v147.triangles)
01748 buff.write(_struct_I.pack(length))
01749 pattern = '<%si'%length
01750 buff.write(_v147.triangles.tostring())
01751 length = len(_v147.vertices)
01752 buff.write(_struct_I.pack(length))
01753 for val3 in _v147.vertices:
01754 _x = val3
01755 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01756 _v148 = val1.pose_stamped
01757 _v149 = _v148.header
01758 buff.write(_struct_I.pack(_v149.seq))
01759 _v150 = _v149.stamp
01760 _x = _v150
01761 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01762 _x = _v149.frame_id
01763 length = len(_x)
01764 buff.write(struct.pack('<I%ss'%length, length, _x))
01765 _v151 = _v148.pose
01766 _v152 = _v151.position
01767 _x = _v152
01768 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01769 _v153 = _v151.orientation
01770 _x = _v153
01771 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01772 length = len(val1.link_names)
01773 buff.write(_struct_I.pack(length))
01774 for val2 in val1.link_names:
01775 length = len(val2)
01776 buff.write(struct.pack('<I%ss'%length, length, val2))
01777 buff.write(_struct_d.pack(val1.penetration_depth))
01778 length = len(self.motion_plan_request.ordered_collision_operations.collision_operations)
01779 buff.write(_struct_I.pack(length))
01780 for val1 in self.motion_plan_request.ordered_collision_operations.collision_operations:
01781 _x = val1.object1
01782 length = len(_x)
01783 buff.write(struct.pack('<I%ss'%length, length, _x))
01784 _x = val1.object2
01785 length = len(_x)
01786 buff.write(struct.pack('<I%ss'%length, length, _x))
01787 _x = val1
01788 buff.write(_struct_di.pack(_x.penetration_distance, _x.operation))
01789 length = len(self.motion_plan_request.link_padding)
01790 buff.write(_struct_I.pack(length))
01791 for val1 in self.motion_plan_request.link_padding:
01792 _x = val1.link_name
01793 length = len(_x)
01794 buff.write(struct.pack('<I%ss'%length, length, _x))
01795 buff.write(_struct_d.pack(val1.padding))
01796 _x = self.motion_plan_request.planner_id
01797 length = len(_x)
01798 buff.write(struct.pack('<I%ss'%length, length, _x))
01799 _x = self.motion_plan_request.group_name
01800 length = len(_x)
01801 buff.write(struct.pack('<I%ss'%length, length, _x))
01802 _x = self
01803 buff.write(_struct_7i.pack(_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs))
01804 except struct.error, se: self._check_types(se)
01805 except TypeError, te: self._check_types(te)
01806
01807 def deserialize_numpy(self, str, numpy):
01808 """
01809 unpack serialized message in str into this message instance using numpy for array types
01810 @param str: byte array of serialized message
01811 @type str: str
01812 @param numpy: numpy python module
01813 @type numpy: module
01814 """
01815 try:
01816 if self.motion_plan_request is None:
01817 self.motion_plan_request = motion_planning_msgs.msg.MotionPlanRequest()
01818 end = 0
01819 start = end
01820 end += 1
01821 (self.motion_plan_request.workspace_parameters.workspace_region_shape.type,) = _struct_b.unpack(str[start:end])
01822 start = end
01823 end += 4
01824 (length,) = _struct_I.unpack(str[start:end])
01825 pattern = '<%sd'%length
01826 start = end
01827 end += struct.calcsize(pattern)
01828 self.motion_plan_request.workspace_parameters.workspace_region_shape.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01829 start = end
01830 end += 4
01831 (length,) = _struct_I.unpack(str[start:end])
01832 pattern = '<%si'%length
01833 start = end
01834 end += struct.calcsize(pattern)
01835 self.motion_plan_request.workspace_parameters.workspace_region_shape.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
01836 start = end
01837 end += 4
01838 (length,) = _struct_I.unpack(str[start:end])
01839 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices = []
01840 for i in xrange(0, length):
01841 val1 = geometry_msgs.msg.Point()
01842 _x = val1
01843 start = end
01844 end += 24
01845 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01846 self.motion_plan_request.workspace_parameters.workspace_region_shape.vertices.append(val1)
01847 _x = self
01848 start = end
01849 end += 12
01850 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.header.seq, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.motion_plan_request.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01851 start = end
01852 end += 4
01853 (length,) = _struct_I.unpack(str[start:end])
01854 start = end
01855 end += length
01856 self.motion_plan_request.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
01857 _x = self
01858 start = end
01859 end += 68
01860 (_x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.position.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.motion_plan_request.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.motion_plan_request.start_state.joint_state.header.seq, _x.motion_plan_request.start_state.joint_state.header.stamp.secs, _x.motion_plan_request.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
01861 start = end
01862 end += 4
01863 (length,) = _struct_I.unpack(str[start:end])
01864 start = end
01865 end += length
01866 self.motion_plan_request.start_state.joint_state.header.frame_id = str[start:end]
01867 start = end
01868 end += 4
01869 (length,) = _struct_I.unpack(str[start:end])
01870 self.motion_plan_request.start_state.joint_state.name = []
01871 for i in xrange(0, length):
01872 start = end
01873 end += 4
01874 (length,) = _struct_I.unpack(str[start:end])
01875 start = end
01876 end += length
01877 val1 = str[start:end]
01878 self.motion_plan_request.start_state.joint_state.name.append(val1)
01879 start = end
01880 end += 4
01881 (length,) = _struct_I.unpack(str[start:end])
01882 pattern = '<%sd'%length
01883 start = end
01884 end += struct.calcsize(pattern)
01885 self.motion_plan_request.start_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01886 start = end
01887 end += 4
01888 (length,) = _struct_I.unpack(str[start:end])
01889 pattern = '<%sd'%length
01890 start = end
01891 end += struct.calcsize(pattern)
01892 self.motion_plan_request.start_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01893 start = end
01894 end += 4
01895 (length,) = _struct_I.unpack(str[start:end])
01896 pattern = '<%sd'%length
01897 start = end
01898 end += struct.calcsize(pattern)
01899 self.motion_plan_request.start_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01900 _x = self
01901 start = end
01902 end += 8
01903 (_x.motion_plan_request.start_state.multi_dof_joint_state.stamp.secs, _x.motion_plan_request.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01904 start = end
01905 end += 4
01906 (length,) = _struct_I.unpack(str[start:end])
01907 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names = []
01908 for i in xrange(0, length):
01909 start = end
01910 end += 4
01911 (length,) = _struct_I.unpack(str[start:end])
01912 start = end
01913 end += length
01914 val1 = str[start:end]
01915 self.motion_plan_request.start_state.multi_dof_joint_state.joint_names.append(val1)
01916 start = end
01917 end += 4
01918 (length,) = _struct_I.unpack(str[start:end])
01919 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids = []
01920 for i in xrange(0, length):
01921 start = end
01922 end += 4
01923 (length,) = _struct_I.unpack(str[start:end])
01924 start = end
01925 end += length
01926 val1 = str[start:end]
01927 self.motion_plan_request.start_state.multi_dof_joint_state.frame_ids.append(val1)
01928 start = end
01929 end += 4
01930 (length,) = _struct_I.unpack(str[start:end])
01931 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids = []
01932 for i in xrange(0, length):
01933 start = end
01934 end += 4
01935 (length,) = _struct_I.unpack(str[start:end])
01936 start = end
01937 end += length
01938 val1 = str[start:end]
01939 self.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
01940 start = end
01941 end += 4
01942 (length,) = _struct_I.unpack(str[start:end])
01943 self.motion_plan_request.start_state.multi_dof_joint_state.poses = []
01944 for i in xrange(0, length):
01945 val1 = geometry_msgs.msg.Pose()
01946 _v154 = val1.position
01947 _x = _v154
01948 start = end
01949 end += 24
01950 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01951 _v155 = val1.orientation
01952 _x = _v155
01953 start = end
01954 end += 32
01955 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01956 self.motion_plan_request.start_state.multi_dof_joint_state.poses.append(val1)
01957 start = end
01958 end += 4
01959 (length,) = _struct_I.unpack(str[start:end])
01960 self.motion_plan_request.goal_constraints.joint_constraints = []
01961 for i in xrange(0, length):
01962 val1 = motion_planning_msgs.msg.JointConstraint()
01963 start = end
01964 end += 4
01965 (length,) = _struct_I.unpack(str[start:end])
01966 start = end
01967 end += length
01968 val1.joint_name = str[start:end]
01969 _x = val1
01970 start = end
01971 end += 32
01972 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01973 self.motion_plan_request.goal_constraints.joint_constraints.append(val1)
01974 start = end
01975 end += 4
01976 (length,) = _struct_I.unpack(str[start:end])
01977 self.motion_plan_request.goal_constraints.position_constraints = []
01978 for i in xrange(0, length):
01979 val1 = motion_planning_msgs.msg.PositionConstraint()
01980 _v156 = val1.header
01981 start = end
01982 end += 4
01983 (_v156.seq,) = _struct_I.unpack(str[start:end])
01984 _v157 = _v156.stamp
01985 _x = _v157
01986 start = end
01987 end += 8
01988 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01989 start = end
01990 end += 4
01991 (length,) = _struct_I.unpack(str[start:end])
01992 start = end
01993 end += length
01994 _v156.frame_id = str[start:end]
01995 start = end
01996 end += 4
01997 (length,) = _struct_I.unpack(str[start:end])
01998 start = end
01999 end += length
02000 val1.link_name = str[start:end]
02001 _v158 = val1.target_point_offset
02002 _x = _v158
02003 start = end
02004 end += 24
02005 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02006 _v159 = val1.position
02007 _x = _v159
02008 start = end
02009 end += 24
02010 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02011 _v160 = val1.constraint_region_shape
02012 start = end
02013 end += 1
02014 (_v160.type,) = _struct_b.unpack(str[start:end])
02015 start = end
02016 end += 4
02017 (length,) = _struct_I.unpack(str[start:end])
02018 pattern = '<%sd'%length
02019 start = end
02020 end += struct.calcsize(pattern)
02021 _v160.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02022 start = end
02023 end += 4
02024 (length,) = _struct_I.unpack(str[start:end])
02025 pattern = '<%si'%length
02026 start = end
02027 end += struct.calcsize(pattern)
02028 _v160.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02029 start = end
02030 end += 4
02031 (length,) = _struct_I.unpack(str[start:end])
02032 _v160.vertices = []
02033 for i in xrange(0, length):
02034 val3 = geometry_msgs.msg.Point()
02035 _x = val3
02036 start = end
02037 end += 24
02038 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02039 _v160.vertices.append(val3)
02040 _v161 = val1.constraint_region_orientation
02041 _x = _v161
02042 start = end
02043 end += 32
02044 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02045 start = end
02046 end += 8
02047 (val1.weight,) = _struct_d.unpack(str[start:end])
02048 self.motion_plan_request.goal_constraints.position_constraints.append(val1)
02049 start = end
02050 end += 4
02051 (length,) = _struct_I.unpack(str[start:end])
02052 self.motion_plan_request.goal_constraints.orientation_constraints = []
02053 for i in xrange(0, length):
02054 val1 = motion_planning_msgs.msg.OrientationConstraint()
02055 _v162 = val1.header
02056 start = end
02057 end += 4
02058 (_v162.seq,) = _struct_I.unpack(str[start:end])
02059 _v163 = _v162.stamp
02060 _x = _v163
02061 start = end
02062 end += 8
02063 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02064 start = end
02065 end += 4
02066 (length,) = _struct_I.unpack(str[start:end])
02067 start = end
02068 end += length
02069 _v162.frame_id = str[start:end]
02070 start = end
02071 end += 4
02072 (length,) = _struct_I.unpack(str[start:end])
02073 start = end
02074 end += length
02075 val1.link_name = str[start:end]
02076 start = end
02077 end += 4
02078 (val1.type,) = _struct_i.unpack(str[start:end])
02079 _v164 = val1.orientation
02080 _x = _v164
02081 start = end
02082 end += 32
02083 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02084 _x = val1
02085 start = end
02086 end += 32
02087 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02088 self.motion_plan_request.goal_constraints.orientation_constraints.append(val1)
02089 start = end
02090 end += 4
02091 (length,) = _struct_I.unpack(str[start:end])
02092 self.motion_plan_request.goal_constraints.visibility_constraints = []
02093 for i in xrange(0, length):
02094 val1 = motion_planning_msgs.msg.VisibilityConstraint()
02095 _v165 = val1.header
02096 start = end
02097 end += 4
02098 (_v165.seq,) = _struct_I.unpack(str[start:end])
02099 _v166 = _v165.stamp
02100 _x = _v166
02101 start = end
02102 end += 8
02103 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02104 start = end
02105 end += 4
02106 (length,) = _struct_I.unpack(str[start:end])
02107 start = end
02108 end += length
02109 _v165.frame_id = str[start:end]
02110 _v167 = val1.target
02111 _v168 = _v167.header
02112 start = end
02113 end += 4
02114 (_v168.seq,) = _struct_I.unpack(str[start:end])
02115 _v169 = _v168.stamp
02116 _x = _v169
02117 start = end
02118 end += 8
02119 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02120 start = end
02121 end += 4
02122 (length,) = _struct_I.unpack(str[start:end])
02123 start = end
02124 end += length
02125 _v168.frame_id = str[start:end]
02126 _v170 = _v167.point
02127 _x = _v170
02128 start = end
02129 end += 24
02130 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02131 _v171 = val1.sensor_pose
02132 _v172 = _v171.header
02133 start = end
02134 end += 4
02135 (_v172.seq,) = _struct_I.unpack(str[start:end])
02136 _v173 = _v172.stamp
02137 _x = _v173
02138 start = end
02139 end += 8
02140 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02141 start = end
02142 end += 4
02143 (length,) = _struct_I.unpack(str[start:end])
02144 start = end
02145 end += length
02146 _v172.frame_id = str[start:end]
02147 _v174 = _v171.pose
02148 _v175 = _v174.position
02149 _x = _v175
02150 start = end
02151 end += 24
02152 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02153 _v176 = _v174.orientation
02154 _x = _v176
02155 start = end
02156 end += 32
02157 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02158 start = end
02159 end += 8
02160 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02161 self.motion_plan_request.goal_constraints.visibility_constraints.append(val1)
02162 start = end
02163 end += 4
02164 (length,) = _struct_I.unpack(str[start:end])
02165 self.motion_plan_request.path_constraints.joint_constraints = []
02166 for i in xrange(0, length):
02167 val1 = motion_planning_msgs.msg.JointConstraint()
02168 start = end
02169 end += 4
02170 (length,) = _struct_I.unpack(str[start:end])
02171 start = end
02172 end += length
02173 val1.joint_name = str[start:end]
02174 _x = val1
02175 start = end
02176 end += 32
02177 (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02178 self.motion_plan_request.path_constraints.joint_constraints.append(val1)
02179 start = end
02180 end += 4
02181 (length,) = _struct_I.unpack(str[start:end])
02182 self.motion_plan_request.path_constraints.position_constraints = []
02183 for i in xrange(0, length):
02184 val1 = motion_planning_msgs.msg.PositionConstraint()
02185 _v177 = val1.header
02186 start = end
02187 end += 4
02188 (_v177.seq,) = _struct_I.unpack(str[start:end])
02189 _v178 = _v177.stamp
02190 _x = _v178
02191 start = end
02192 end += 8
02193 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02194 start = end
02195 end += 4
02196 (length,) = _struct_I.unpack(str[start:end])
02197 start = end
02198 end += length
02199 _v177.frame_id = str[start:end]
02200 start = end
02201 end += 4
02202 (length,) = _struct_I.unpack(str[start:end])
02203 start = end
02204 end += length
02205 val1.link_name = str[start:end]
02206 _v179 = val1.target_point_offset
02207 _x = _v179
02208 start = end
02209 end += 24
02210 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02211 _v180 = val1.position
02212 _x = _v180
02213 start = end
02214 end += 24
02215 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02216 _v181 = val1.constraint_region_shape
02217 start = end
02218 end += 1
02219 (_v181.type,) = _struct_b.unpack(str[start:end])
02220 start = end
02221 end += 4
02222 (length,) = _struct_I.unpack(str[start:end])
02223 pattern = '<%sd'%length
02224 start = end
02225 end += struct.calcsize(pattern)
02226 _v181.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02227 start = end
02228 end += 4
02229 (length,) = _struct_I.unpack(str[start:end])
02230 pattern = '<%si'%length
02231 start = end
02232 end += struct.calcsize(pattern)
02233 _v181.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02234 start = end
02235 end += 4
02236 (length,) = _struct_I.unpack(str[start:end])
02237 _v181.vertices = []
02238 for i in xrange(0, length):
02239 val3 = geometry_msgs.msg.Point()
02240 _x = val3
02241 start = end
02242 end += 24
02243 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02244 _v181.vertices.append(val3)
02245 _v182 = val1.constraint_region_orientation
02246 _x = _v182
02247 start = end
02248 end += 32
02249 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02250 start = end
02251 end += 8
02252 (val1.weight,) = _struct_d.unpack(str[start:end])
02253 self.motion_plan_request.path_constraints.position_constraints.append(val1)
02254 start = end
02255 end += 4
02256 (length,) = _struct_I.unpack(str[start:end])
02257 self.motion_plan_request.path_constraints.orientation_constraints = []
02258 for i in xrange(0, length):
02259 val1 = motion_planning_msgs.msg.OrientationConstraint()
02260 _v183 = val1.header
02261 start = end
02262 end += 4
02263 (_v183.seq,) = _struct_I.unpack(str[start:end])
02264 _v184 = _v183.stamp
02265 _x = _v184
02266 start = end
02267 end += 8
02268 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02269 start = end
02270 end += 4
02271 (length,) = _struct_I.unpack(str[start:end])
02272 start = end
02273 end += length
02274 _v183.frame_id = str[start:end]
02275 start = end
02276 end += 4
02277 (length,) = _struct_I.unpack(str[start:end])
02278 start = end
02279 end += length
02280 val1.link_name = str[start:end]
02281 start = end
02282 end += 4
02283 (val1.type,) = _struct_i.unpack(str[start:end])
02284 _v185 = val1.orientation
02285 _x = _v185
02286 start = end
02287 end += 32
02288 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02289 _x = val1
02290 start = end
02291 end += 32
02292 (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02293 self.motion_plan_request.path_constraints.orientation_constraints.append(val1)
02294 start = end
02295 end += 4
02296 (length,) = _struct_I.unpack(str[start:end])
02297 self.motion_plan_request.path_constraints.visibility_constraints = []
02298 for i in xrange(0, length):
02299 val1 = motion_planning_msgs.msg.VisibilityConstraint()
02300 _v186 = val1.header
02301 start = end
02302 end += 4
02303 (_v186.seq,) = _struct_I.unpack(str[start:end])
02304 _v187 = _v186.stamp
02305 _x = _v187
02306 start = end
02307 end += 8
02308 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02309 start = end
02310 end += 4
02311 (length,) = _struct_I.unpack(str[start:end])
02312 start = end
02313 end += length
02314 _v186.frame_id = str[start:end]
02315 _v188 = val1.target
02316 _v189 = _v188.header
02317 start = end
02318 end += 4
02319 (_v189.seq,) = _struct_I.unpack(str[start:end])
02320 _v190 = _v189.stamp
02321 _x = _v190
02322 start = end
02323 end += 8
02324 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02325 start = end
02326 end += 4
02327 (length,) = _struct_I.unpack(str[start:end])
02328 start = end
02329 end += length
02330 _v189.frame_id = str[start:end]
02331 _v191 = _v188.point
02332 _x = _v191
02333 start = end
02334 end += 24
02335 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02336 _v192 = val1.sensor_pose
02337 _v193 = _v192.header
02338 start = end
02339 end += 4
02340 (_v193.seq,) = _struct_I.unpack(str[start:end])
02341 _v194 = _v193.stamp
02342 _x = _v194
02343 start = end
02344 end += 8
02345 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02346 start = end
02347 end += 4
02348 (length,) = _struct_I.unpack(str[start:end])
02349 start = end
02350 end += length
02351 _v193.frame_id = str[start:end]
02352 _v195 = _v192.pose
02353 _v196 = _v195.position
02354 _x = _v196
02355 start = end
02356 end += 24
02357 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02358 _v197 = _v195.orientation
02359 _x = _v197
02360 start = end
02361 end += 32
02362 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02363 start = end
02364 end += 8
02365 (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02366 self.motion_plan_request.path_constraints.visibility_constraints.append(val1)
02367 start = end
02368 end += 4
02369 (length,) = _struct_I.unpack(str[start:end])
02370 self.motion_plan_request.allowed_contacts = []
02371 for i in xrange(0, length):
02372 val1 = motion_planning_msgs.msg.AllowedContactSpecification()
02373 start = end
02374 end += 4
02375 (length,) = _struct_I.unpack(str[start:end])
02376 start = end
02377 end += length
02378 val1.name = str[start:end]
02379 _v198 = val1.shape
02380 start = end
02381 end += 1
02382 (_v198.type,) = _struct_b.unpack(str[start:end])
02383 start = end
02384 end += 4
02385 (length,) = _struct_I.unpack(str[start:end])
02386 pattern = '<%sd'%length
02387 start = end
02388 end += struct.calcsize(pattern)
02389 _v198.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02390 start = end
02391 end += 4
02392 (length,) = _struct_I.unpack(str[start:end])
02393 pattern = '<%si'%length
02394 start = end
02395 end += struct.calcsize(pattern)
02396 _v198.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02397 start = end
02398 end += 4
02399 (length,) = _struct_I.unpack(str[start:end])
02400 _v198.vertices = []
02401 for i in xrange(0, length):
02402 val3 = geometry_msgs.msg.Point()
02403 _x = val3
02404 start = end
02405 end += 24
02406 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02407 _v198.vertices.append(val3)
02408 _v199 = val1.pose_stamped
02409 _v200 = _v199.header
02410 start = end
02411 end += 4
02412 (_v200.seq,) = _struct_I.unpack(str[start:end])
02413 _v201 = _v200.stamp
02414 _x = _v201
02415 start = end
02416 end += 8
02417 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02418 start = end
02419 end += 4
02420 (length,) = _struct_I.unpack(str[start:end])
02421 start = end
02422 end += length
02423 _v200.frame_id = str[start:end]
02424 _v202 = _v199.pose
02425 _v203 = _v202.position
02426 _x = _v203
02427 start = end
02428 end += 24
02429 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02430 _v204 = _v202.orientation
02431 _x = _v204
02432 start = end
02433 end += 32
02434 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02435 start = end
02436 end += 4
02437 (length,) = _struct_I.unpack(str[start:end])
02438 val1.link_names = []
02439 for i in xrange(0, length):
02440 start = end
02441 end += 4
02442 (length,) = _struct_I.unpack(str[start:end])
02443 start = end
02444 end += length
02445 val2 = str[start:end]
02446 val1.link_names.append(val2)
02447 start = end
02448 end += 8
02449 (val1.penetration_depth,) = _struct_d.unpack(str[start:end])
02450 self.motion_plan_request.allowed_contacts.append(val1)
02451 start = end
02452 end += 4
02453 (length,) = _struct_I.unpack(str[start:end])
02454 self.motion_plan_request.ordered_collision_operations.collision_operations = []
02455 for i in xrange(0, length):
02456 val1 = motion_planning_msgs.msg.CollisionOperation()
02457 start = end
02458 end += 4
02459 (length,) = _struct_I.unpack(str[start:end])
02460 start = end
02461 end += length
02462 val1.object1 = str[start:end]
02463 start = end
02464 end += 4
02465 (length,) = _struct_I.unpack(str[start:end])
02466 start = end
02467 end += length
02468 val1.object2 = str[start:end]
02469 _x = val1
02470 start = end
02471 end += 12
02472 (_x.penetration_distance, _x.operation,) = _struct_di.unpack(str[start:end])
02473 self.motion_plan_request.ordered_collision_operations.collision_operations.append(val1)
02474 start = end
02475 end += 4
02476 (length,) = _struct_I.unpack(str[start:end])
02477 self.motion_plan_request.link_padding = []
02478 for i in xrange(0, length):
02479 val1 = motion_planning_msgs.msg.LinkPadding()
02480 start = end
02481 end += 4
02482 (length,) = _struct_I.unpack(str[start:end])
02483 start = end
02484 end += length
02485 val1.link_name = str[start:end]
02486 start = end
02487 end += 8
02488 (val1.padding,) = _struct_d.unpack(str[start:end])
02489 self.motion_plan_request.link_padding.append(val1)
02490 start = end
02491 end += 4
02492 (length,) = _struct_I.unpack(str[start:end])
02493 start = end
02494 end += length
02495 self.motion_plan_request.planner_id = str[start:end]
02496 start = end
02497 end += 4
02498 (length,) = _struct_I.unpack(str[start:end])
02499 start = end
02500 end += length
02501 self.motion_plan_request.group_name = str[start:end]
02502 _x = self
02503 start = end
02504 end += 28
02505 (_x.motion_plan_request.num_planning_attempts, _x.motion_plan_request.allowed_planning_time.secs, _x.motion_plan_request.allowed_planning_time.nsecs, _x.motion_plan_request.expected_path_duration.secs, _x.motion_plan_request.expected_path_duration.nsecs, _x.motion_plan_request.expected_path_dt.secs, _x.motion_plan_request.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
02506 return self
02507 except struct.error, e:
02508 raise roslib.message.DeserializationError(e)
02509
02510 _struct_I = roslib.message.struct_I
02511 _struct_b = struct.Struct("<b")
02512 _struct_d = struct.Struct("<d")
02513 _struct_di = struct.Struct("<di")
02514 _struct_7i = struct.Struct("<7i")
02515 _struct_2I = struct.Struct("<2I")
02516 _struct_i = struct.Struct("<i")
02517 _struct_3I = struct.Struct("<3I")
02518 _struct_4d = struct.Struct("<4d")
02519 _struct_7d3I = struct.Struct("<7d3I")
02520 _struct_3d = struct.Struct("<3d")
02521 """autogenerated by genmsg_py from GetMotionPlanResponse.msg. Do not edit."""
02522 import roslib.message
02523 import struct
02524
02525 import trajectory_msgs.msg
02526 import roslib.rostime
02527 import geometry_msgs.msg
02528 import sensor_msgs.msg
02529 import motion_planning_msgs.msg
02530 import std_msgs.msg
02531
02532 class GetMotionPlanResponse(roslib.message.Message):
02533 _md5sum = "644f3b4cf5b71b614298ce1d1a472b61"
02534 _type = "motion_planning_msgs/GetMotionPlanResponse"
02535 _has_header = False
02536 _full_text = """
02537
02538 motion_planning_msgs/RobotTrajectory trajectory
02539
02540
02541 motion_planning_msgs/RobotState robot_state
02542
02543
02544 duration planning_time
02545
02546
02547 motion_planning_msgs/ArmNavigationErrorCodes error_code
02548
02549
02550 motion_planning_msgs/ArmNavigationErrorCodes[] trajectory_error_codes
02551
02552
02553 ================================================================================
02554 MSG: motion_planning_msgs/RobotTrajectory
02555 trajectory_msgs/JointTrajectory joint_trajectory
02556 motion_planning_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory
02557 ================================================================================
02558 MSG: trajectory_msgs/JointTrajectory
02559 Header header
02560 string[] joint_names
02561 JointTrajectoryPoint[] points
02562 ================================================================================
02563 MSG: std_msgs/Header
02564 # Standard metadata for higher-level stamped data types.
02565 # This is generally used to communicate timestamped data
02566 # in a particular coordinate frame.
02567 #
02568 # sequence ID: consecutively increasing ID
02569 uint32 seq
02570 #Two-integer timestamp that is expressed as:
02571 # * stamp.secs: seconds (stamp_secs) since epoch
02572 # * stamp.nsecs: nanoseconds since stamp_secs
02573 # time-handling sugar is provided by the client library
02574 time stamp
02575 #Frame this data is associated with
02576 # 0: no frame
02577 # 1: global frame
02578 string frame_id
02579
02580 ================================================================================
02581 MSG: trajectory_msgs/JointTrajectoryPoint
02582 float64[] positions
02583 float64[] velocities
02584 float64[] accelerations
02585 duration time_from_start
02586 ================================================================================
02587 MSG: motion_planning_msgs/MultiDOFJointTrajectory
02588 #A representation of a multi-dof joint trajectory
02589 duration stamp
02590 string[] joint_names
02591 string[] frame_ids
02592 string[] child_frame_ids
02593 MultiDOFJointTrajectoryPoint[] points
02594
02595 ================================================================================
02596 MSG: motion_planning_msgs/MultiDOFJointTrajectoryPoint
02597 geometry_msgs/Pose[] poses
02598 duration time_from_start
02599 ================================================================================
02600 MSG: geometry_msgs/Pose
02601 # A representation of pose in free space, composed of postion and orientation.
02602 Point position
02603 Quaternion orientation
02604
02605 ================================================================================
02606 MSG: geometry_msgs/Point
02607 # This contains the position of a point in free space
02608 float64 x
02609 float64 y
02610 float64 z
02611
02612 ================================================================================
02613 MSG: geometry_msgs/Quaternion
02614 # This represents an orientation in free space in quaternion form.
02615
02616 float64 x
02617 float64 y
02618 float64 z
02619 float64 w
02620
02621 ================================================================================
02622 MSG: motion_planning_msgs/RobotState
02623 # This message contains information about the robot state, i.e. the positions of its joints and links
02624 sensor_msgs/JointState joint_state
02625 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state
02626 ================================================================================
02627 MSG: sensor_msgs/JointState
02628 # This is a message that holds data to describe the state of a set of torque controlled joints.
02629 #
02630 # The state of each joint (revolute or prismatic) is defined by:
02631 # * the position of the joint (rad or m),
02632 # * the velocity of the joint (rad/s or m/s) and
02633 # * the effort that is applied in the joint (Nm or N).
02634 #
02635 # Each joint is uniquely identified by its name
02636 # The header specifies the time at which the joint states were recorded. All the joint states
02637 # in one message have to be recorded at the same time.
02638 #
02639 # This message consists of a multiple arrays, one for each part of the joint state.
02640 # The goal is to make each of the fields optional. When e.g. your joints have no
02641 # effort associated with them, you can leave the effort array empty.
02642 #
02643 # All arrays in this message should have the same size, or be empty.
02644 # This is the only way to uniquely associate the joint name with the correct
02645 # states.
02646
02647
02648 Header header
02649
02650 string[] name
02651 float64[] position
02652 float64[] velocity
02653 float64[] effort
02654
02655 ================================================================================
02656 MSG: motion_planning_msgs/MultiDOFJointState
02657 #A representation of a multi-dof joint state
02658 time stamp
02659 string[] joint_names
02660 string[] frame_ids
02661 string[] child_frame_ids
02662 geometry_msgs/Pose[] poses
02663
02664 ================================================================================
02665 MSG: motion_planning_msgs/ArmNavigationErrorCodes
02666 int32 val
02667
02668 # overall behavior
02669 int32 PLANNING_FAILED=-1
02670 int32 SUCCESS=1
02671 int32 TIMED_OUT=-2
02672
02673 # start state errors
02674 int32 START_STATE_IN_COLLISION=-3
02675 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
02676
02677 # goal errors
02678 int32 GOAL_IN_COLLISION=-5
02679 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
02680
02681 # robot state
02682 int32 INVALID_ROBOT_STATE=-7
02683 int32 INCOMPLETE_ROBOT_STATE=-8
02684
02685 # planning request errors
02686 int32 INVALID_PLANNER_ID=-9
02687 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
02688 int32 INVALID_ALLOWED_PLANNING_TIME=-11
02689 int32 INVALID_GROUP_NAME=-12
02690 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
02691 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
02692 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
02693 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
02694 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
02695 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
02696
02697 # state/trajectory monitor errors
02698 int32 INVALID_TRAJECTORY=-19
02699 int32 INVALID_INDEX=-20
02700 int32 JOINT_LIMITS_VIOLATED=-21
02701 int32 PATH_CONSTRAINTS_VIOLATED=-22
02702 int32 COLLISION_CONSTRAINTS_VIOLATED=-23
02703 int32 GOAL_CONSTRAINTS_VIOLATED=-24
02704 int32 JOINTS_NOT_MOVING=-25
02705 int32 TRAJECTORY_CONTROLLER_FAILED=-26
02706
02707 # system errors
02708 int32 FRAME_TRANSFORM_FAILURE=-27
02709 int32 COLLISION_CHECKING_UNAVAILABLE=-28
02710 int32 ROBOT_STATE_STALE=-29
02711 int32 SENSOR_INFO_STALE=-30
02712
02713 # kinematics errors
02714 int32 NO_IK_SOLUTION=-31
02715 int32 INVALID_LINK_NAME=-32
02716 int32 IK_LINK_IN_COLLISION=-33
02717 int32 NO_FK_SOLUTION=-34
02718 int32 KINEMATICS_STATE_IN_COLLISION=-35
02719
02720 # general errors
02721 int32 INVALID_TIMEOUT=-36
02722
02723
02724 """
02725 __slots__ = ['trajectory','robot_state','planning_time','error_code','trajectory_error_codes']
02726 _slot_types = ['motion_planning_msgs/RobotTrajectory','motion_planning_msgs/RobotState','duration','motion_planning_msgs/ArmNavigationErrorCodes','motion_planning_msgs/ArmNavigationErrorCodes[]']
02727
02728 def __init__(self, *args, **kwds):
02729 """
02730 Constructor. Any message fields that are implicitly/explicitly
02731 set to None will be assigned a default value. The recommend
02732 use is keyword arguments as this is more robust to future message
02733 changes. You cannot mix in-order arguments and keyword arguments.
02734
02735 The available fields are:
02736 trajectory,robot_state,planning_time,error_code,trajectory_error_codes
02737
02738 @param args: complete set of field values, in .msg order
02739 @param kwds: use keyword arguments corresponding to message field names
02740 to set specific fields.
02741 """
02742 if args or kwds:
02743 super(GetMotionPlanResponse, self).__init__(*args, **kwds)
02744
02745 if self.trajectory is None:
02746 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
02747 if self.robot_state is None:
02748 self.robot_state = motion_planning_msgs.msg.RobotState()
02749 if self.planning_time is None:
02750 self.planning_time = roslib.rostime.Duration()
02751 if self.error_code is None:
02752 self.error_code = motion_planning_msgs.msg.ArmNavigationErrorCodes()
02753 if self.trajectory_error_codes is None:
02754 self.trajectory_error_codes = []
02755 else:
02756 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
02757 self.robot_state = motion_planning_msgs.msg.RobotState()
02758 self.planning_time = roslib.rostime.Duration()
02759 self.error_code = motion_planning_msgs.msg.ArmNavigationErrorCodes()
02760 self.trajectory_error_codes = []
02761
02762 def _get_types(self):
02763 """
02764 internal API method
02765 """
02766 return self._slot_types
02767
02768 def serialize(self, buff):
02769 """
02770 serialize message into buffer
02771 @param buff: buffer
02772 @type buff: StringIO
02773 """
02774 try:
02775 _x = self
02776 buff.write(_struct_3I.pack(_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs))
02777 _x = self.trajectory.joint_trajectory.header.frame_id
02778 length = len(_x)
02779 buff.write(struct.pack('<I%ss'%length, length, _x))
02780 length = len(self.trajectory.joint_trajectory.joint_names)
02781 buff.write(_struct_I.pack(length))
02782 for val1 in self.trajectory.joint_trajectory.joint_names:
02783 length = len(val1)
02784 buff.write(struct.pack('<I%ss'%length, length, val1))
02785 length = len(self.trajectory.joint_trajectory.points)
02786 buff.write(_struct_I.pack(length))
02787 for val1 in self.trajectory.joint_trajectory.points:
02788 length = len(val1.positions)
02789 buff.write(_struct_I.pack(length))
02790 pattern = '<%sd'%length
02791 buff.write(struct.pack(pattern, *val1.positions))
02792 length = len(val1.velocities)
02793 buff.write(_struct_I.pack(length))
02794 pattern = '<%sd'%length
02795 buff.write(struct.pack(pattern, *val1.velocities))
02796 length = len(val1.accelerations)
02797 buff.write(_struct_I.pack(length))
02798 pattern = '<%sd'%length
02799 buff.write(struct.pack(pattern, *val1.accelerations))
02800 _v205 = val1.time_from_start
02801 _x = _v205
02802 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
02803 _x = self
02804 buff.write(_struct_2i.pack(_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs))
02805 length = len(self.trajectory.multi_dof_joint_trajectory.joint_names)
02806 buff.write(_struct_I.pack(length))
02807 for val1 in self.trajectory.multi_dof_joint_trajectory.joint_names:
02808 length = len(val1)
02809 buff.write(struct.pack('<I%ss'%length, length, val1))
02810 length = len(self.trajectory.multi_dof_joint_trajectory.frame_ids)
02811 buff.write(_struct_I.pack(length))
02812 for val1 in self.trajectory.multi_dof_joint_trajectory.frame_ids:
02813 length = len(val1)
02814 buff.write(struct.pack('<I%ss'%length, length, val1))
02815 length = len(self.trajectory.multi_dof_joint_trajectory.child_frame_ids)
02816 buff.write(_struct_I.pack(length))
02817 for val1 in self.trajectory.multi_dof_joint_trajectory.child_frame_ids:
02818 length = len(val1)
02819 buff.write(struct.pack('<I%ss'%length, length, val1))
02820 length = len(self.trajectory.multi_dof_joint_trajectory.points)
02821 buff.write(_struct_I.pack(length))
02822 for val1 in self.trajectory.multi_dof_joint_trajectory.points:
02823 length = len(val1.poses)
02824 buff.write(_struct_I.pack(length))
02825 for val2 in val1.poses:
02826 _v206 = val2.position
02827 _x = _v206
02828 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02829 _v207 = val2.orientation
02830 _x = _v207
02831 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02832 _v208 = val1.time_from_start
02833 _x = _v208
02834 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
02835 _x = self
02836 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
02837 _x = self.robot_state.joint_state.header.frame_id
02838 length = len(_x)
02839 buff.write(struct.pack('<I%ss'%length, length, _x))
02840 length = len(self.robot_state.joint_state.name)
02841 buff.write(_struct_I.pack(length))
02842 for val1 in self.robot_state.joint_state.name:
02843 length = len(val1)
02844 buff.write(struct.pack('<I%ss'%length, length, val1))
02845 length = len(self.robot_state.joint_state.position)
02846 buff.write(_struct_I.pack(length))
02847 pattern = '<%sd'%length
02848 buff.write(struct.pack(pattern, *self.robot_state.joint_state.position))
02849 length = len(self.robot_state.joint_state.velocity)
02850 buff.write(_struct_I.pack(length))
02851 pattern = '<%sd'%length
02852 buff.write(struct.pack(pattern, *self.robot_state.joint_state.velocity))
02853 length = len(self.robot_state.joint_state.effort)
02854 buff.write(_struct_I.pack(length))
02855 pattern = '<%sd'%length
02856 buff.write(struct.pack(pattern, *self.robot_state.joint_state.effort))
02857 _x = self
02858 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
02859 length = len(self.robot_state.multi_dof_joint_state.joint_names)
02860 buff.write(_struct_I.pack(length))
02861 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
02862 length = len(val1)
02863 buff.write(struct.pack('<I%ss'%length, length, val1))
02864 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
02865 buff.write(_struct_I.pack(length))
02866 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
02867 length = len(val1)
02868 buff.write(struct.pack('<I%ss'%length, length, val1))
02869 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
02870 buff.write(_struct_I.pack(length))
02871 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
02872 length = len(val1)
02873 buff.write(struct.pack('<I%ss'%length, length, val1))
02874 length = len(self.robot_state.multi_dof_joint_state.poses)
02875 buff.write(_struct_I.pack(length))
02876 for val1 in self.robot_state.multi_dof_joint_state.poses:
02877 _v209 = val1.position
02878 _x = _v209
02879 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02880 _v210 = val1.orientation
02881 _x = _v210
02882 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02883 _x = self
02884 buff.write(_struct_3i.pack(_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val))
02885 length = len(self.trajectory_error_codes)
02886 buff.write(_struct_I.pack(length))
02887 for val1 in self.trajectory_error_codes:
02888 buff.write(_struct_i.pack(val1.val))
02889 except struct.error, se: self._check_types(se)
02890 except TypeError, te: self._check_types(te)
02891
02892 def deserialize(self, str):
02893 """
02894 unpack serialized message in str into this message instance
02895 @param str: byte array of serialized message
02896 @type str: str
02897 """
02898 try:
02899 if self.trajectory is None:
02900 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
02901 if self.robot_state is None:
02902 self.robot_state = motion_planning_msgs.msg.RobotState()
02903 if self.planning_time is None:
02904 self.planning_time = roslib.rostime.Duration()
02905 if self.error_code is None:
02906 self.error_code = motion_planning_msgs.msg.ArmNavigationErrorCodes()
02907 end = 0
02908 _x = self
02909 start = end
02910 end += 12
02911 (_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02912 start = end
02913 end += 4
02914 (length,) = _struct_I.unpack(str[start:end])
02915 start = end
02916 end += length
02917 self.trajectory.joint_trajectory.header.frame_id = str[start:end]
02918 start = end
02919 end += 4
02920 (length,) = _struct_I.unpack(str[start:end])
02921 self.trajectory.joint_trajectory.joint_names = []
02922 for i in xrange(0, length):
02923 start = end
02924 end += 4
02925 (length,) = _struct_I.unpack(str[start:end])
02926 start = end
02927 end += length
02928 val1 = str[start:end]
02929 self.trajectory.joint_trajectory.joint_names.append(val1)
02930 start = end
02931 end += 4
02932 (length,) = _struct_I.unpack(str[start:end])
02933 self.trajectory.joint_trajectory.points = []
02934 for i in xrange(0, length):
02935 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
02936 start = end
02937 end += 4
02938 (length,) = _struct_I.unpack(str[start:end])
02939 pattern = '<%sd'%length
02940 start = end
02941 end += struct.calcsize(pattern)
02942 val1.positions = struct.unpack(pattern, str[start:end])
02943 start = end
02944 end += 4
02945 (length,) = _struct_I.unpack(str[start:end])
02946 pattern = '<%sd'%length
02947 start = end
02948 end += struct.calcsize(pattern)
02949 val1.velocities = struct.unpack(pattern, str[start:end])
02950 start = end
02951 end += 4
02952 (length,) = _struct_I.unpack(str[start:end])
02953 pattern = '<%sd'%length
02954 start = end
02955 end += struct.calcsize(pattern)
02956 val1.accelerations = struct.unpack(pattern, str[start:end])
02957 _v211 = val1.time_from_start
02958 _x = _v211
02959 start = end
02960 end += 8
02961 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
02962 self.trajectory.joint_trajectory.points.append(val1)
02963 _x = self
02964 start = end
02965 end += 8
02966 (_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end])
02967 start = end
02968 end += 4
02969 (length,) = _struct_I.unpack(str[start:end])
02970 self.trajectory.multi_dof_joint_trajectory.joint_names = []
02971 for i in xrange(0, length):
02972 start = end
02973 end += 4
02974 (length,) = _struct_I.unpack(str[start:end])
02975 start = end
02976 end += length
02977 val1 = str[start:end]
02978 self.trajectory.multi_dof_joint_trajectory.joint_names.append(val1)
02979 start = end
02980 end += 4
02981 (length,) = _struct_I.unpack(str[start:end])
02982 self.trajectory.multi_dof_joint_trajectory.frame_ids = []
02983 for i in xrange(0, length):
02984 start = end
02985 end += 4
02986 (length,) = _struct_I.unpack(str[start:end])
02987 start = end
02988 end += length
02989 val1 = str[start:end]
02990 self.trajectory.multi_dof_joint_trajectory.frame_ids.append(val1)
02991 start = end
02992 end += 4
02993 (length,) = _struct_I.unpack(str[start:end])
02994 self.trajectory.multi_dof_joint_trajectory.child_frame_ids = []
02995 for i in xrange(0, length):
02996 start = end
02997 end += 4
02998 (length,) = _struct_I.unpack(str[start:end])
02999 start = end
03000 end += length
03001 val1 = str[start:end]
03002 self.trajectory.multi_dof_joint_trajectory.child_frame_ids.append(val1)
03003 start = end
03004 end += 4
03005 (length,) = _struct_I.unpack(str[start:end])
03006 self.trajectory.multi_dof_joint_trajectory.points = []
03007 for i in xrange(0, length):
03008 val1 = motion_planning_msgs.msg.MultiDOFJointTrajectoryPoint()
03009 start = end
03010 end += 4
03011 (length,) = _struct_I.unpack(str[start:end])
03012 val1.poses = []
03013 for i in xrange(0, length):
03014 val2 = geometry_msgs.msg.Pose()
03015 _v212 = val2.position
03016 _x = _v212
03017 start = end
03018 end += 24
03019 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03020 _v213 = val2.orientation
03021 _x = _v213
03022 start = end
03023 end += 32
03024 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03025 val1.poses.append(val2)
03026 _v214 = val1.time_from_start
03027 _x = _v214
03028 start = end
03029 end += 8
03030 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
03031 self.trajectory.multi_dof_joint_trajectory.points.append(val1)
03032 _x = self
03033 start = end
03034 end += 12
03035 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03036 start = end
03037 end += 4
03038 (length,) = _struct_I.unpack(str[start:end])
03039 start = end
03040 end += length
03041 self.robot_state.joint_state.header.frame_id = str[start:end]
03042 start = end
03043 end += 4
03044 (length,) = _struct_I.unpack(str[start:end])
03045 self.robot_state.joint_state.name = []
03046 for i in xrange(0, length):
03047 start = end
03048 end += 4
03049 (length,) = _struct_I.unpack(str[start:end])
03050 start = end
03051 end += length
03052 val1 = str[start:end]
03053 self.robot_state.joint_state.name.append(val1)
03054 start = end
03055 end += 4
03056 (length,) = _struct_I.unpack(str[start:end])
03057 pattern = '<%sd'%length
03058 start = end
03059 end += struct.calcsize(pattern)
03060 self.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
03061 start = end
03062 end += 4
03063 (length,) = _struct_I.unpack(str[start:end])
03064 pattern = '<%sd'%length
03065 start = end
03066 end += struct.calcsize(pattern)
03067 self.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
03068 start = end
03069 end += 4
03070 (length,) = _struct_I.unpack(str[start:end])
03071 pattern = '<%sd'%length
03072 start = end
03073 end += struct.calcsize(pattern)
03074 self.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
03075 _x = self
03076 start = end
03077 end += 8
03078 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03079 start = end
03080 end += 4
03081 (length,) = _struct_I.unpack(str[start:end])
03082 self.robot_state.multi_dof_joint_state.joint_names = []
03083 for i in xrange(0, length):
03084 start = end
03085 end += 4
03086 (length,) = _struct_I.unpack(str[start:end])
03087 start = end
03088 end += length
03089 val1 = str[start:end]
03090 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
03091 start = end
03092 end += 4
03093 (length,) = _struct_I.unpack(str[start:end])
03094 self.robot_state.multi_dof_joint_state.frame_ids = []
03095 for i in xrange(0, length):
03096 start = end
03097 end += 4
03098 (length,) = _struct_I.unpack(str[start:end])
03099 start = end
03100 end += length
03101 val1 = str[start:end]
03102 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
03103 start = end
03104 end += 4
03105 (length,) = _struct_I.unpack(str[start:end])
03106 self.robot_state.multi_dof_joint_state.child_frame_ids = []
03107 for i in xrange(0, length):
03108 start = end
03109 end += 4
03110 (length,) = _struct_I.unpack(str[start:end])
03111 start = end
03112 end += length
03113 val1 = str[start:end]
03114 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
03115 start = end
03116 end += 4
03117 (length,) = _struct_I.unpack(str[start:end])
03118 self.robot_state.multi_dof_joint_state.poses = []
03119 for i in xrange(0, length):
03120 val1 = geometry_msgs.msg.Pose()
03121 _v215 = val1.position
03122 _x = _v215
03123 start = end
03124 end += 24
03125 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03126 _v216 = val1.orientation
03127 _x = _v216
03128 start = end
03129 end += 32
03130 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03131 self.robot_state.multi_dof_joint_state.poses.append(val1)
03132 _x = self
03133 start = end
03134 end += 12
03135 (_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val,) = _struct_3i.unpack(str[start:end])
03136 start = end
03137 end += 4
03138 (length,) = _struct_I.unpack(str[start:end])
03139 self.trajectory_error_codes = []
03140 for i in xrange(0, length):
03141 val1 = motion_planning_msgs.msg.ArmNavigationErrorCodes()
03142 start = end
03143 end += 4
03144 (val1.val,) = _struct_i.unpack(str[start:end])
03145 self.trajectory_error_codes.append(val1)
03146 self.planning_time.canon()
03147 return self
03148 except struct.error, e:
03149 raise roslib.message.DeserializationError(e)
03150
03151
03152 def serialize_numpy(self, buff, numpy):
03153 """
03154 serialize message with numpy array types into buffer
03155 @param buff: buffer
03156 @type buff: StringIO
03157 @param numpy: numpy python module
03158 @type numpy module
03159 """
03160 try:
03161 _x = self
03162 buff.write(_struct_3I.pack(_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs))
03163 _x = self.trajectory.joint_trajectory.header.frame_id
03164 length = len(_x)
03165 buff.write(struct.pack('<I%ss'%length, length, _x))
03166 length = len(self.trajectory.joint_trajectory.joint_names)
03167 buff.write(_struct_I.pack(length))
03168 for val1 in self.trajectory.joint_trajectory.joint_names:
03169 length = len(val1)
03170 buff.write(struct.pack('<I%ss'%length, length, val1))
03171 length = len(self.trajectory.joint_trajectory.points)
03172 buff.write(_struct_I.pack(length))
03173 for val1 in self.trajectory.joint_trajectory.points:
03174 length = len(val1.positions)
03175 buff.write(_struct_I.pack(length))
03176 pattern = '<%sd'%length
03177 buff.write(val1.positions.tostring())
03178 length = len(val1.velocities)
03179 buff.write(_struct_I.pack(length))
03180 pattern = '<%sd'%length
03181 buff.write(val1.velocities.tostring())
03182 length = len(val1.accelerations)
03183 buff.write(_struct_I.pack(length))
03184 pattern = '<%sd'%length
03185 buff.write(val1.accelerations.tostring())
03186 _v217 = val1.time_from_start
03187 _x = _v217
03188 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
03189 _x = self
03190 buff.write(_struct_2i.pack(_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs))
03191 length = len(self.trajectory.multi_dof_joint_trajectory.joint_names)
03192 buff.write(_struct_I.pack(length))
03193 for val1 in self.trajectory.multi_dof_joint_trajectory.joint_names:
03194 length = len(val1)
03195 buff.write(struct.pack('<I%ss'%length, length, val1))
03196 length = len(self.trajectory.multi_dof_joint_trajectory.frame_ids)
03197 buff.write(_struct_I.pack(length))
03198 for val1 in self.trajectory.multi_dof_joint_trajectory.frame_ids:
03199 length = len(val1)
03200 buff.write(struct.pack('<I%ss'%length, length, val1))
03201 length = len(self.trajectory.multi_dof_joint_trajectory.child_frame_ids)
03202 buff.write(_struct_I.pack(length))
03203 for val1 in self.trajectory.multi_dof_joint_trajectory.child_frame_ids:
03204 length = len(val1)
03205 buff.write(struct.pack('<I%ss'%length, length, val1))
03206 length = len(self.trajectory.multi_dof_joint_trajectory.points)
03207 buff.write(_struct_I.pack(length))
03208 for val1 in self.trajectory.multi_dof_joint_trajectory.points:
03209 length = len(val1.poses)
03210 buff.write(_struct_I.pack(length))
03211 for val2 in val1.poses:
03212 _v218 = val2.position
03213 _x = _v218
03214 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03215 _v219 = val2.orientation
03216 _x = _v219
03217 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03218 _v220 = val1.time_from_start
03219 _x = _v220
03220 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
03221 _x = self
03222 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
03223 _x = self.robot_state.joint_state.header.frame_id
03224 length = len(_x)
03225 buff.write(struct.pack('<I%ss'%length, length, _x))
03226 length = len(self.robot_state.joint_state.name)
03227 buff.write(_struct_I.pack(length))
03228 for val1 in self.robot_state.joint_state.name:
03229 length = len(val1)
03230 buff.write(struct.pack('<I%ss'%length, length, val1))
03231 length = len(self.robot_state.joint_state.position)
03232 buff.write(_struct_I.pack(length))
03233 pattern = '<%sd'%length
03234 buff.write(self.robot_state.joint_state.position.tostring())
03235 length = len(self.robot_state.joint_state.velocity)
03236 buff.write(_struct_I.pack(length))
03237 pattern = '<%sd'%length
03238 buff.write(self.robot_state.joint_state.velocity.tostring())
03239 length = len(self.robot_state.joint_state.effort)
03240 buff.write(_struct_I.pack(length))
03241 pattern = '<%sd'%length
03242 buff.write(self.robot_state.joint_state.effort.tostring())
03243 _x = self
03244 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
03245 length = len(self.robot_state.multi_dof_joint_state.joint_names)
03246 buff.write(_struct_I.pack(length))
03247 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
03248 length = len(val1)
03249 buff.write(struct.pack('<I%ss'%length, length, val1))
03250 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
03251 buff.write(_struct_I.pack(length))
03252 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
03253 length = len(val1)
03254 buff.write(struct.pack('<I%ss'%length, length, val1))
03255 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
03256 buff.write(_struct_I.pack(length))
03257 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
03258 length = len(val1)
03259 buff.write(struct.pack('<I%ss'%length, length, val1))
03260 length = len(self.robot_state.multi_dof_joint_state.poses)
03261 buff.write(_struct_I.pack(length))
03262 for val1 in self.robot_state.multi_dof_joint_state.poses:
03263 _v221 = val1.position
03264 _x = _v221
03265 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03266 _v222 = val1.orientation
03267 _x = _v222
03268 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03269 _x = self
03270 buff.write(_struct_3i.pack(_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val))
03271 length = len(self.trajectory_error_codes)
03272 buff.write(_struct_I.pack(length))
03273 for val1 in self.trajectory_error_codes:
03274 buff.write(_struct_i.pack(val1.val))
03275 except struct.error, se: self._check_types(se)
03276 except TypeError, te: self._check_types(te)
03277
03278 def deserialize_numpy(self, str, numpy):
03279 """
03280 unpack serialized message in str into this message instance using numpy for array types
03281 @param str: byte array of serialized message
03282 @type str: str
03283 @param numpy: numpy python module
03284 @type numpy: module
03285 """
03286 try:
03287 if self.trajectory is None:
03288 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
03289 if self.robot_state is None:
03290 self.robot_state = motion_planning_msgs.msg.RobotState()
03291 if self.planning_time is None:
03292 self.planning_time = roslib.rostime.Duration()
03293 if self.error_code is None:
03294 self.error_code = motion_planning_msgs.msg.ArmNavigationErrorCodes()
03295 end = 0
03296 _x = self
03297 start = end
03298 end += 12
03299 (_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03300 start = end
03301 end += 4
03302 (length,) = _struct_I.unpack(str[start:end])
03303 start = end
03304 end += length
03305 self.trajectory.joint_trajectory.header.frame_id = str[start:end]
03306 start = end
03307 end += 4
03308 (length,) = _struct_I.unpack(str[start:end])
03309 self.trajectory.joint_trajectory.joint_names = []
03310 for i in xrange(0, length):
03311 start = end
03312 end += 4
03313 (length,) = _struct_I.unpack(str[start:end])
03314 start = end
03315 end += length
03316 val1 = str[start:end]
03317 self.trajectory.joint_trajectory.joint_names.append(val1)
03318 start = end
03319 end += 4
03320 (length,) = _struct_I.unpack(str[start:end])
03321 self.trajectory.joint_trajectory.points = []
03322 for i in xrange(0, length):
03323 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
03324 start = end
03325 end += 4
03326 (length,) = _struct_I.unpack(str[start:end])
03327 pattern = '<%sd'%length
03328 start = end
03329 end += struct.calcsize(pattern)
03330 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03331 start = end
03332 end += 4
03333 (length,) = _struct_I.unpack(str[start:end])
03334 pattern = '<%sd'%length
03335 start = end
03336 end += struct.calcsize(pattern)
03337 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03338 start = end
03339 end += 4
03340 (length,) = _struct_I.unpack(str[start:end])
03341 pattern = '<%sd'%length
03342 start = end
03343 end += struct.calcsize(pattern)
03344 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03345 _v223 = val1.time_from_start
03346 _x = _v223
03347 start = end
03348 end += 8
03349 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
03350 self.trajectory.joint_trajectory.points.append(val1)
03351 _x = self
03352 start = end
03353 end += 8
03354 (_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end])
03355 start = end
03356 end += 4
03357 (length,) = _struct_I.unpack(str[start:end])
03358 self.trajectory.multi_dof_joint_trajectory.joint_names = []
03359 for i in xrange(0, length):
03360 start = end
03361 end += 4
03362 (length,) = _struct_I.unpack(str[start:end])
03363 start = end
03364 end += length
03365 val1 = str[start:end]
03366 self.trajectory.multi_dof_joint_trajectory.joint_names.append(val1)
03367 start = end
03368 end += 4
03369 (length,) = _struct_I.unpack(str[start:end])
03370 self.trajectory.multi_dof_joint_trajectory.frame_ids = []
03371 for i in xrange(0, length):
03372 start = end
03373 end += 4
03374 (length,) = _struct_I.unpack(str[start:end])
03375 start = end
03376 end += length
03377 val1 = str[start:end]
03378 self.trajectory.multi_dof_joint_trajectory.frame_ids.append(val1)
03379 start = end
03380 end += 4
03381 (length,) = _struct_I.unpack(str[start:end])
03382 self.trajectory.multi_dof_joint_trajectory.child_frame_ids = []
03383 for i in xrange(0, length):
03384 start = end
03385 end += 4
03386 (length,) = _struct_I.unpack(str[start:end])
03387 start = end
03388 end += length
03389 val1 = str[start:end]
03390 self.trajectory.multi_dof_joint_trajectory.child_frame_ids.append(val1)
03391 start = end
03392 end += 4
03393 (length,) = _struct_I.unpack(str[start:end])
03394 self.trajectory.multi_dof_joint_trajectory.points = []
03395 for i in xrange(0, length):
03396 val1 = motion_planning_msgs.msg.MultiDOFJointTrajectoryPoint()
03397 start = end
03398 end += 4
03399 (length,) = _struct_I.unpack(str[start:end])
03400 val1.poses = []
03401 for i in xrange(0, length):
03402 val2 = geometry_msgs.msg.Pose()
03403 _v224 = val2.position
03404 _x = _v224
03405 start = end
03406 end += 24
03407 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03408 _v225 = val2.orientation
03409 _x = _v225
03410 start = end
03411 end += 32
03412 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03413 val1.poses.append(val2)
03414 _v226 = val1.time_from_start
03415 _x = _v226
03416 start = end
03417 end += 8
03418 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
03419 self.trajectory.multi_dof_joint_trajectory.points.append(val1)
03420 _x = self
03421 start = end
03422 end += 12
03423 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03424 start = end
03425 end += 4
03426 (length,) = _struct_I.unpack(str[start:end])
03427 start = end
03428 end += length
03429 self.robot_state.joint_state.header.frame_id = str[start:end]
03430 start = end
03431 end += 4
03432 (length,) = _struct_I.unpack(str[start:end])
03433 self.robot_state.joint_state.name = []
03434 for i in xrange(0, length):
03435 start = end
03436 end += 4
03437 (length,) = _struct_I.unpack(str[start:end])
03438 start = end
03439 end += length
03440 val1 = str[start:end]
03441 self.robot_state.joint_state.name.append(val1)
03442 start = end
03443 end += 4
03444 (length,) = _struct_I.unpack(str[start:end])
03445 pattern = '<%sd'%length
03446 start = end
03447 end += struct.calcsize(pattern)
03448 self.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03449 start = end
03450 end += 4
03451 (length,) = _struct_I.unpack(str[start:end])
03452 pattern = '<%sd'%length
03453 start = end
03454 end += struct.calcsize(pattern)
03455 self.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03456 start = end
03457 end += 4
03458 (length,) = _struct_I.unpack(str[start:end])
03459 pattern = '<%sd'%length
03460 start = end
03461 end += struct.calcsize(pattern)
03462 self.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
03463 _x = self
03464 start = end
03465 end += 8
03466 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
03467 start = end
03468 end += 4
03469 (length,) = _struct_I.unpack(str[start:end])
03470 self.robot_state.multi_dof_joint_state.joint_names = []
03471 for i in xrange(0, length):
03472 start = end
03473 end += 4
03474 (length,) = _struct_I.unpack(str[start:end])
03475 start = end
03476 end += length
03477 val1 = str[start:end]
03478 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
03479 start = end
03480 end += 4
03481 (length,) = _struct_I.unpack(str[start:end])
03482 self.robot_state.multi_dof_joint_state.frame_ids = []
03483 for i in xrange(0, length):
03484 start = end
03485 end += 4
03486 (length,) = _struct_I.unpack(str[start:end])
03487 start = end
03488 end += length
03489 val1 = str[start:end]
03490 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
03491 start = end
03492 end += 4
03493 (length,) = _struct_I.unpack(str[start:end])
03494 self.robot_state.multi_dof_joint_state.child_frame_ids = []
03495 for i in xrange(0, length):
03496 start = end
03497 end += 4
03498 (length,) = _struct_I.unpack(str[start:end])
03499 start = end
03500 end += length
03501 val1 = str[start:end]
03502 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
03503 start = end
03504 end += 4
03505 (length,) = _struct_I.unpack(str[start:end])
03506 self.robot_state.multi_dof_joint_state.poses = []
03507 for i in xrange(0, length):
03508 val1 = geometry_msgs.msg.Pose()
03509 _v227 = val1.position
03510 _x = _v227
03511 start = end
03512 end += 24
03513 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03514 _v228 = val1.orientation
03515 _x = _v228
03516 start = end
03517 end += 32
03518 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03519 self.robot_state.multi_dof_joint_state.poses.append(val1)
03520 _x = self
03521 start = end
03522 end += 12
03523 (_x.planning_time.secs, _x.planning_time.nsecs, _x.error_code.val,) = _struct_3i.unpack(str[start:end])
03524 start = end
03525 end += 4
03526 (length,) = _struct_I.unpack(str[start:end])
03527 self.trajectory_error_codes = []
03528 for i in xrange(0, length):
03529 val1 = motion_planning_msgs.msg.ArmNavigationErrorCodes()
03530 start = end
03531 end += 4
03532 (val1.val,) = _struct_i.unpack(str[start:end])
03533 self.trajectory_error_codes.append(val1)
03534 self.planning_time.canon()
03535 return self
03536 except struct.error, e:
03537 raise roslib.message.DeserializationError(e)
03538
03539 _struct_I = roslib.message.struct_I
03540 _struct_i = struct.Struct("<i")
03541 _struct_3i = struct.Struct("<3i")
03542 _struct_2I = struct.Struct("<2I")
03543 _struct_3I = struct.Struct("<3I")
03544 _struct_4d = struct.Struct("<4d")
03545 _struct_2i = struct.Struct("<2i")
03546 _struct_3d = struct.Struct("<3d")
03547 class GetMotionPlan(roslib.message.ServiceDefinition):
03548 _type = 'motion_planning_msgs/GetMotionPlan'
03549 _md5sum = 'dc1bde6dccfb9e1ff4f7ed84e081f964'
03550 _request_class = GetMotionPlanRequest
03551 _response_class = GetMotionPlanResponse