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