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