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