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