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