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