$search
00001 """autogenerated by genmsg_py from GetPositionIKRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import arm_navigation_msgs.msg 00006 import kinematics_msgs.msg 00007 import roslib.rostime 00008 import geometry_msgs.msg 00009 import sensor_msgs.msg 00010 import std_msgs.msg 00011 00012 class GetPositionIKRequest(roslib.message.Message): 00013 _md5sum = "bf9ee33930d9eaff390b8af4a213ba62" 00014 _type = "kinematics_msgs/GetPositionIKRequest" 00015 _has_header = False #flag to mark the presence of a Header object 00016 _full_text = """ 00017 00018 kinematics_msgs/PositionIKRequest ik_request 00019 00020 duration timeout 00021 00022 ================================================================================ 00023 MSG: kinematics_msgs/PositionIKRequest 00024 # A Position IK request message 00025 # The name of the link for which we are computing IK 00026 string ik_link_name 00027 00028 # The (stamped) pose of the link 00029 geometry_msgs/PoseStamped pose_stamped 00030 00031 # A RobotState consisting of hint/seed positions for the IK computation. 00032 # These may be used to seed the IK search. 00033 # The seed state MUST contain state for all joints to be used by the IK solver 00034 # to compute IK. The list of joints that the IK solver deals with can be found using 00035 # the kinematics_msgs/GetKinematicSolverInfo 00036 arm_navigation_msgs/RobotState ik_seed_state 00037 00038 # Additional state information can be provided here to specify the starting positions 00039 # of other joints/links on the robot. 00040 arm_navigation_msgs/RobotState robot_state 00041 00042 ================================================================================ 00043 MSG: geometry_msgs/PoseStamped 00044 # A Pose with reference coordinate frame and timestamp 00045 Header header 00046 Pose pose 00047 00048 ================================================================================ 00049 MSG: std_msgs/Header 00050 # Standard metadata for higher-level stamped data types. 00051 # This is generally used to communicate timestamped data 00052 # in a particular coordinate frame. 00053 # 00054 # sequence ID: consecutively increasing ID 00055 uint32 seq 00056 #Two-integer timestamp that is expressed as: 00057 # * stamp.secs: seconds (stamp_secs) since epoch 00058 # * stamp.nsecs: nanoseconds since stamp_secs 00059 # time-handling sugar is provided by the client library 00060 time stamp 00061 #Frame this data is associated with 00062 # 0: no frame 00063 # 1: global frame 00064 string frame_id 00065 00066 ================================================================================ 00067 MSG: geometry_msgs/Pose 00068 # A representation of pose in free space, composed of postion and orientation. 00069 Point position 00070 Quaternion orientation 00071 00072 ================================================================================ 00073 MSG: geometry_msgs/Point 00074 # This contains the position of a point in free space 00075 float64 x 00076 float64 y 00077 float64 z 00078 00079 ================================================================================ 00080 MSG: geometry_msgs/Quaternion 00081 # This represents an orientation in free space in quaternion form. 00082 00083 float64 x 00084 float64 y 00085 float64 z 00086 float64 w 00087 00088 ================================================================================ 00089 MSG: arm_navigation_msgs/RobotState 00090 # This message contains information about the robot state, i.e. the positions of its joints and links 00091 sensor_msgs/JointState joint_state 00092 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state 00093 00094 ================================================================================ 00095 MSG: sensor_msgs/JointState 00096 # This is a message that holds data to describe the state of a set of torque controlled joints. 00097 # 00098 # The state of each joint (revolute or prismatic) is defined by: 00099 # * the position of the joint (rad or m), 00100 # * the velocity of the joint (rad/s or m/s) and 00101 # * the effort that is applied in the joint (Nm or N). 00102 # 00103 # Each joint is uniquely identified by its name 00104 # The header specifies the time at which the joint states were recorded. All the joint states 00105 # in one message have to be recorded at the same time. 00106 # 00107 # This message consists of a multiple arrays, one for each part of the joint state. 00108 # The goal is to make each of the fields optional. When e.g. your joints have no 00109 # effort associated with them, you can leave the effort array empty. 00110 # 00111 # All arrays in this message should have the same size, or be empty. 00112 # This is the only way to uniquely associate the joint name with the correct 00113 # states. 00114 00115 00116 Header header 00117 00118 string[] name 00119 float64[] position 00120 float64[] velocity 00121 float64[] effort 00122 00123 ================================================================================ 00124 MSG: arm_navigation_msgs/MultiDOFJointState 00125 #A representation of a multi-dof joint state 00126 time stamp 00127 string[] joint_names 00128 string[] frame_ids 00129 string[] child_frame_ids 00130 geometry_msgs/Pose[] poses 00131 00132 """ 00133 __slots__ = ['ik_request','timeout'] 00134 _slot_types = ['kinematics_msgs/PositionIKRequest','duration'] 00135 00136 def __init__(self, *args, **kwds): 00137 """ 00138 Constructor. Any message fields that are implicitly/explicitly 00139 set to None will be assigned a default value. The recommend 00140 use is keyword arguments as this is more robust to future message 00141 changes. You cannot mix in-order arguments and keyword arguments. 00142 00143 The available fields are: 00144 ik_request,timeout 00145 00146 @param args: complete set of field values, in .msg order 00147 @param kwds: use keyword arguments corresponding to message field names 00148 to set specific fields. 00149 """ 00150 if args or kwds: 00151 super(GetPositionIKRequest, self).__init__(*args, **kwds) 00152 #message fields cannot be None, assign default values for those that are 00153 if self.ik_request is None: 00154 self.ik_request = kinematics_msgs.msg.PositionIKRequest() 00155 if self.timeout is None: 00156 self.timeout = roslib.rostime.Duration() 00157 else: 00158 self.ik_request = kinematics_msgs.msg.PositionIKRequest() 00159 self.timeout = roslib.rostime.Duration() 00160 00161 def _get_types(self): 00162 """ 00163 internal API method 00164 """ 00165 return self._slot_types 00166 00167 def serialize(self, buff): 00168 """ 00169 serialize message into buffer 00170 @param buff: buffer 00171 @type buff: StringIO 00172 """ 00173 try: 00174 _x = self.ik_request.ik_link_name 00175 length = len(_x) 00176 buff.write(struct.pack('<I%ss'%length, length, _x)) 00177 _x = self 00178 buff.write(_struct_3I.pack(_x.ik_request.pose_stamped.header.seq, _x.ik_request.pose_stamped.header.stamp.secs, _x.ik_request.pose_stamped.header.stamp.nsecs)) 00179 _x = self.ik_request.pose_stamped.header.frame_id 00180 length = len(_x) 00181 buff.write(struct.pack('<I%ss'%length, length, _x)) 00182 _x = self 00183 buff.write(_struct_7d3I.pack(_x.ik_request.pose_stamped.pose.position.x, _x.ik_request.pose_stamped.pose.position.y, _x.ik_request.pose_stamped.pose.position.z, _x.ik_request.pose_stamped.pose.orientation.x, _x.ik_request.pose_stamped.pose.orientation.y, _x.ik_request.pose_stamped.pose.orientation.z, _x.ik_request.pose_stamped.pose.orientation.w, _x.ik_request.ik_seed_state.joint_state.header.seq, _x.ik_request.ik_seed_state.joint_state.header.stamp.secs, _x.ik_request.ik_seed_state.joint_state.header.stamp.nsecs)) 00184 _x = self.ik_request.ik_seed_state.joint_state.header.frame_id 00185 length = len(_x) 00186 buff.write(struct.pack('<I%ss'%length, length, _x)) 00187 length = len(self.ik_request.ik_seed_state.joint_state.name) 00188 buff.write(_struct_I.pack(length)) 00189 for val1 in self.ik_request.ik_seed_state.joint_state.name: 00190 length = len(val1) 00191 buff.write(struct.pack('<I%ss'%length, length, val1)) 00192 length = len(self.ik_request.ik_seed_state.joint_state.position) 00193 buff.write(_struct_I.pack(length)) 00194 pattern = '<%sd'%length 00195 buff.write(struct.pack(pattern, *self.ik_request.ik_seed_state.joint_state.position)) 00196 length = len(self.ik_request.ik_seed_state.joint_state.velocity) 00197 buff.write(_struct_I.pack(length)) 00198 pattern = '<%sd'%length 00199 buff.write(struct.pack(pattern, *self.ik_request.ik_seed_state.joint_state.velocity)) 00200 length = len(self.ik_request.ik_seed_state.joint_state.effort) 00201 buff.write(_struct_I.pack(length)) 00202 pattern = '<%sd'%length 00203 buff.write(struct.pack(pattern, *self.ik_request.ik_seed_state.joint_state.effort)) 00204 _x = self 00205 buff.write(_struct_2I.pack(_x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.secs, _x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.nsecs)) 00206 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names) 00207 buff.write(_struct_I.pack(length)) 00208 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names: 00209 length = len(val1) 00210 buff.write(struct.pack('<I%ss'%length, length, val1)) 00211 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids) 00212 buff.write(_struct_I.pack(length)) 00213 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids: 00214 length = len(val1) 00215 buff.write(struct.pack('<I%ss'%length, length, val1)) 00216 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids) 00217 buff.write(_struct_I.pack(length)) 00218 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids: 00219 length = len(val1) 00220 buff.write(struct.pack('<I%ss'%length, length, val1)) 00221 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.poses) 00222 buff.write(_struct_I.pack(length)) 00223 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.poses: 00224 _v1 = val1.position 00225 _x = _v1 00226 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00227 _v2 = val1.orientation 00228 _x = _v2 00229 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00230 _x = self 00231 buff.write(_struct_3I.pack(_x.ik_request.robot_state.joint_state.header.seq, _x.ik_request.robot_state.joint_state.header.stamp.secs, _x.ik_request.robot_state.joint_state.header.stamp.nsecs)) 00232 _x = self.ik_request.robot_state.joint_state.header.frame_id 00233 length = len(_x) 00234 buff.write(struct.pack('<I%ss'%length, length, _x)) 00235 length = len(self.ik_request.robot_state.joint_state.name) 00236 buff.write(_struct_I.pack(length)) 00237 for val1 in self.ik_request.robot_state.joint_state.name: 00238 length = len(val1) 00239 buff.write(struct.pack('<I%ss'%length, length, val1)) 00240 length = len(self.ik_request.robot_state.joint_state.position) 00241 buff.write(_struct_I.pack(length)) 00242 pattern = '<%sd'%length 00243 buff.write(struct.pack(pattern, *self.ik_request.robot_state.joint_state.position)) 00244 length = len(self.ik_request.robot_state.joint_state.velocity) 00245 buff.write(_struct_I.pack(length)) 00246 pattern = '<%sd'%length 00247 buff.write(struct.pack(pattern, *self.ik_request.robot_state.joint_state.velocity)) 00248 length = len(self.ik_request.robot_state.joint_state.effort) 00249 buff.write(_struct_I.pack(length)) 00250 pattern = '<%sd'%length 00251 buff.write(struct.pack(pattern, *self.ik_request.robot_state.joint_state.effort)) 00252 _x = self 00253 buff.write(_struct_2I.pack(_x.ik_request.robot_state.multi_dof_joint_state.stamp.secs, _x.ik_request.robot_state.multi_dof_joint_state.stamp.nsecs)) 00254 length = len(self.ik_request.robot_state.multi_dof_joint_state.joint_names) 00255 buff.write(_struct_I.pack(length)) 00256 for val1 in self.ik_request.robot_state.multi_dof_joint_state.joint_names: 00257 length = len(val1) 00258 buff.write(struct.pack('<I%ss'%length, length, val1)) 00259 length = len(self.ik_request.robot_state.multi_dof_joint_state.frame_ids) 00260 buff.write(_struct_I.pack(length)) 00261 for val1 in self.ik_request.robot_state.multi_dof_joint_state.frame_ids: 00262 length = len(val1) 00263 buff.write(struct.pack('<I%ss'%length, length, val1)) 00264 length = len(self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids) 00265 buff.write(_struct_I.pack(length)) 00266 for val1 in self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids: 00267 length = len(val1) 00268 buff.write(struct.pack('<I%ss'%length, length, val1)) 00269 length = len(self.ik_request.robot_state.multi_dof_joint_state.poses) 00270 buff.write(_struct_I.pack(length)) 00271 for val1 in self.ik_request.robot_state.multi_dof_joint_state.poses: 00272 _v3 = val1.position 00273 _x = _v3 00274 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00275 _v4 = val1.orientation 00276 _x = _v4 00277 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00278 _x = self 00279 buff.write(_struct_2i.pack(_x.timeout.secs, _x.timeout.nsecs)) 00280 except struct.error as se: self._check_types(se) 00281 except TypeError as te: self._check_types(te) 00282 00283 def deserialize(self, str): 00284 """ 00285 unpack serialized message in str into this message instance 00286 @param str: byte array of serialized message 00287 @type str: str 00288 """ 00289 try: 00290 if self.ik_request is None: 00291 self.ik_request = kinematics_msgs.msg.PositionIKRequest() 00292 if self.timeout is None: 00293 self.timeout = roslib.rostime.Duration() 00294 end = 0 00295 start = end 00296 end += 4 00297 (length,) = _struct_I.unpack(str[start:end]) 00298 start = end 00299 end += length 00300 self.ik_request.ik_link_name = str[start:end] 00301 _x = self 00302 start = end 00303 end += 12 00304 (_x.ik_request.pose_stamped.header.seq, _x.ik_request.pose_stamped.header.stamp.secs, _x.ik_request.pose_stamped.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00305 start = end 00306 end += 4 00307 (length,) = _struct_I.unpack(str[start:end]) 00308 start = end 00309 end += length 00310 self.ik_request.pose_stamped.header.frame_id = str[start:end] 00311 _x = self 00312 start = end 00313 end += 68 00314 (_x.ik_request.pose_stamped.pose.position.x, _x.ik_request.pose_stamped.pose.position.y, _x.ik_request.pose_stamped.pose.position.z, _x.ik_request.pose_stamped.pose.orientation.x, _x.ik_request.pose_stamped.pose.orientation.y, _x.ik_request.pose_stamped.pose.orientation.z, _x.ik_request.pose_stamped.pose.orientation.w, _x.ik_request.ik_seed_state.joint_state.header.seq, _x.ik_request.ik_seed_state.joint_state.header.stamp.secs, _x.ik_request.ik_seed_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end]) 00315 start = end 00316 end += 4 00317 (length,) = _struct_I.unpack(str[start:end]) 00318 start = end 00319 end += length 00320 self.ik_request.ik_seed_state.joint_state.header.frame_id = str[start:end] 00321 start = end 00322 end += 4 00323 (length,) = _struct_I.unpack(str[start:end]) 00324 self.ik_request.ik_seed_state.joint_state.name = [] 00325 for i in range(0, length): 00326 start = end 00327 end += 4 00328 (length,) = _struct_I.unpack(str[start:end]) 00329 start = end 00330 end += length 00331 val1 = str[start:end] 00332 self.ik_request.ik_seed_state.joint_state.name.append(val1) 00333 start = end 00334 end += 4 00335 (length,) = _struct_I.unpack(str[start:end]) 00336 pattern = '<%sd'%length 00337 start = end 00338 end += struct.calcsize(pattern) 00339 self.ik_request.ik_seed_state.joint_state.position = struct.unpack(pattern, str[start:end]) 00340 start = end 00341 end += 4 00342 (length,) = _struct_I.unpack(str[start:end]) 00343 pattern = '<%sd'%length 00344 start = end 00345 end += struct.calcsize(pattern) 00346 self.ik_request.ik_seed_state.joint_state.velocity = struct.unpack(pattern, str[start:end]) 00347 start = end 00348 end += 4 00349 (length,) = _struct_I.unpack(str[start:end]) 00350 pattern = '<%sd'%length 00351 start = end 00352 end += struct.calcsize(pattern) 00353 self.ik_request.ik_seed_state.joint_state.effort = struct.unpack(pattern, str[start:end]) 00354 _x = self 00355 start = end 00356 end += 8 00357 (_x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.secs, _x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00358 start = end 00359 end += 4 00360 (length,) = _struct_I.unpack(str[start:end]) 00361 self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names = [] 00362 for i in range(0, length): 00363 start = end 00364 end += 4 00365 (length,) = _struct_I.unpack(str[start:end]) 00366 start = end 00367 end += length 00368 val1 = str[start:end] 00369 self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names.append(val1) 00370 start = end 00371 end += 4 00372 (length,) = _struct_I.unpack(str[start:end]) 00373 self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids = [] 00374 for i in range(0, length): 00375 start = end 00376 end += 4 00377 (length,) = _struct_I.unpack(str[start:end]) 00378 start = end 00379 end += length 00380 val1 = str[start:end] 00381 self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids.append(val1) 00382 start = end 00383 end += 4 00384 (length,) = _struct_I.unpack(str[start:end]) 00385 self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids = [] 00386 for i in range(0, length): 00387 start = end 00388 end += 4 00389 (length,) = _struct_I.unpack(str[start:end]) 00390 start = end 00391 end += length 00392 val1 = str[start:end] 00393 self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids.append(val1) 00394 start = end 00395 end += 4 00396 (length,) = _struct_I.unpack(str[start:end]) 00397 self.ik_request.ik_seed_state.multi_dof_joint_state.poses = [] 00398 for i in range(0, length): 00399 val1 = geometry_msgs.msg.Pose() 00400 _v5 = val1.position 00401 _x = _v5 00402 start = end 00403 end += 24 00404 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00405 _v6 = val1.orientation 00406 _x = _v6 00407 start = end 00408 end += 32 00409 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00410 self.ik_request.ik_seed_state.multi_dof_joint_state.poses.append(val1) 00411 _x = self 00412 start = end 00413 end += 12 00414 (_x.ik_request.robot_state.joint_state.header.seq, _x.ik_request.robot_state.joint_state.header.stamp.secs, _x.ik_request.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00415 start = end 00416 end += 4 00417 (length,) = _struct_I.unpack(str[start:end]) 00418 start = end 00419 end += length 00420 self.ik_request.robot_state.joint_state.header.frame_id = str[start:end] 00421 start = end 00422 end += 4 00423 (length,) = _struct_I.unpack(str[start:end]) 00424 self.ik_request.robot_state.joint_state.name = [] 00425 for i in range(0, length): 00426 start = end 00427 end += 4 00428 (length,) = _struct_I.unpack(str[start:end]) 00429 start = end 00430 end += length 00431 val1 = str[start:end] 00432 self.ik_request.robot_state.joint_state.name.append(val1) 00433 start = end 00434 end += 4 00435 (length,) = _struct_I.unpack(str[start:end]) 00436 pattern = '<%sd'%length 00437 start = end 00438 end += struct.calcsize(pattern) 00439 self.ik_request.robot_state.joint_state.position = struct.unpack(pattern, str[start:end]) 00440 start = end 00441 end += 4 00442 (length,) = _struct_I.unpack(str[start:end]) 00443 pattern = '<%sd'%length 00444 start = end 00445 end += struct.calcsize(pattern) 00446 self.ik_request.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end]) 00447 start = end 00448 end += 4 00449 (length,) = _struct_I.unpack(str[start:end]) 00450 pattern = '<%sd'%length 00451 start = end 00452 end += struct.calcsize(pattern) 00453 self.ik_request.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end]) 00454 _x = self 00455 start = end 00456 end += 8 00457 (_x.ik_request.robot_state.multi_dof_joint_state.stamp.secs, _x.ik_request.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00458 start = end 00459 end += 4 00460 (length,) = _struct_I.unpack(str[start:end]) 00461 self.ik_request.robot_state.multi_dof_joint_state.joint_names = [] 00462 for i in range(0, length): 00463 start = end 00464 end += 4 00465 (length,) = _struct_I.unpack(str[start:end]) 00466 start = end 00467 end += length 00468 val1 = str[start:end] 00469 self.ik_request.robot_state.multi_dof_joint_state.joint_names.append(val1) 00470 start = end 00471 end += 4 00472 (length,) = _struct_I.unpack(str[start:end]) 00473 self.ik_request.robot_state.multi_dof_joint_state.frame_ids = [] 00474 for i in range(0, length): 00475 start = end 00476 end += 4 00477 (length,) = _struct_I.unpack(str[start:end]) 00478 start = end 00479 end += length 00480 val1 = str[start:end] 00481 self.ik_request.robot_state.multi_dof_joint_state.frame_ids.append(val1) 00482 start = end 00483 end += 4 00484 (length,) = _struct_I.unpack(str[start:end]) 00485 self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids = [] 00486 for i in range(0, length): 00487 start = end 00488 end += 4 00489 (length,) = _struct_I.unpack(str[start:end]) 00490 start = end 00491 end += length 00492 val1 = str[start:end] 00493 self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids.append(val1) 00494 start = end 00495 end += 4 00496 (length,) = _struct_I.unpack(str[start:end]) 00497 self.ik_request.robot_state.multi_dof_joint_state.poses = [] 00498 for i in range(0, length): 00499 val1 = geometry_msgs.msg.Pose() 00500 _v7 = val1.position 00501 _x = _v7 00502 start = end 00503 end += 24 00504 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00505 _v8 = val1.orientation 00506 _x = _v8 00507 start = end 00508 end += 32 00509 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00510 self.ik_request.robot_state.multi_dof_joint_state.poses.append(val1) 00511 _x = self 00512 start = end 00513 end += 8 00514 (_x.timeout.secs, _x.timeout.nsecs,) = _struct_2i.unpack(str[start:end]) 00515 self.timeout.canon() 00516 return self 00517 except struct.error as e: 00518 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00519 00520 00521 def serialize_numpy(self, buff, numpy): 00522 """ 00523 serialize message with numpy array types into buffer 00524 @param buff: buffer 00525 @type buff: StringIO 00526 @param numpy: numpy python module 00527 @type numpy module 00528 """ 00529 try: 00530 _x = self.ik_request.ik_link_name 00531 length = len(_x) 00532 buff.write(struct.pack('<I%ss'%length, length, _x)) 00533 _x = self 00534 buff.write(_struct_3I.pack(_x.ik_request.pose_stamped.header.seq, _x.ik_request.pose_stamped.header.stamp.secs, _x.ik_request.pose_stamped.header.stamp.nsecs)) 00535 _x = self.ik_request.pose_stamped.header.frame_id 00536 length = len(_x) 00537 buff.write(struct.pack('<I%ss'%length, length, _x)) 00538 _x = self 00539 buff.write(_struct_7d3I.pack(_x.ik_request.pose_stamped.pose.position.x, _x.ik_request.pose_stamped.pose.position.y, _x.ik_request.pose_stamped.pose.position.z, _x.ik_request.pose_stamped.pose.orientation.x, _x.ik_request.pose_stamped.pose.orientation.y, _x.ik_request.pose_stamped.pose.orientation.z, _x.ik_request.pose_stamped.pose.orientation.w, _x.ik_request.ik_seed_state.joint_state.header.seq, _x.ik_request.ik_seed_state.joint_state.header.stamp.secs, _x.ik_request.ik_seed_state.joint_state.header.stamp.nsecs)) 00540 _x = self.ik_request.ik_seed_state.joint_state.header.frame_id 00541 length = len(_x) 00542 buff.write(struct.pack('<I%ss'%length, length, _x)) 00543 length = len(self.ik_request.ik_seed_state.joint_state.name) 00544 buff.write(_struct_I.pack(length)) 00545 for val1 in self.ik_request.ik_seed_state.joint_state.name: 00546 length = len(val1) 00547 buff.write(struct.pack('<I%ss'%length, length, val1)) 00548 length = len(self.ik_request.ik_seed_state.joint_state.position) 00549 buff.write(_struct_I.pack(length)) 00550 pattern = '<%sd'%length 00551 buff.write(self.ik_request.ik_seed_state.joint_state.position.tostring()) 00552 length = len(self.ik_request.ik_seed_state.joint_state.velocity) 00553 buff.write(_struct_I.pack(length)) 00554 pattern = '<%sd'%length 00555 buff.write(self.ik_request.ik_seed_state.joint_state.velocity.tostring()) 00556 length = len(self.ik_request.ik_seed_state.joint_state.effort) 00557 buff.write(_struct_I.pack(length)) 00558 pattern = '<%sd'%length 00559 buff.write(self.ik_request.ik_seed_state.joint_state.effort.tostring()) 00560 _x = self 00561 buff.write(_struct_2I.pack(_x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.secs, _x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.nsecs)) 00562 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names) 00563 buff.write(_struct_I.pack(length)) 00564 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names: 00565 length = len(val1) 00566 buff.write(struct.pack('<I%ss'%length, length, val1)) 00567 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids) 00568 buff.write(_struct_I.pack(length)) 00569 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids: 00570 length = len(val1) 00571 buff.write(struct.pack('<I%ss'%length, length, val1)) 00572 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids) 00573 buff.write(_struct_I.pack(length)) 00574 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids: 00575 length = len(val1) 00576 buff.write(struct.pack('<I%ss'%length, length, val1)) 00577 length = len(self.ik_request.ik_seed_state.multi_dof_joint_state.poses) 00578 buff.write(_struct_I.pack(length)) 00579 for val1 in self.ik_request.ik_seed_state.multi_dof_joint_state.poses: 00580 _v9 = val1.position 00581 _x = _v9 00582 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00583 _v10 = val1.orientation 00584 _x = _v10 00585 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00586 _x = self 00587 buff.write(_struct_3I.pack(_x.ik_request.robot_state.joint_state.header.seq, _x.ik_request.robot_state.joint_state.header.stamp.secs, _x.ik_request.robot_state.joint_state.header.stamp.nsecs)) 00588 _x = self.ik_request.robot_state.joint_state.header.frame_id 00589 length = len(_x) 00590 buff.write(struct.pack('<I%ss'%length, length, _x)) 00591 length = len(self.ik_request.robot_state.joint_state.name) 00592 buff.write(_struct_I.pack(length)) 00593 for val1 in self.ik_request.robot_state.joint_state.name: 00594 length = len(val1) 00595 buff.write(struct.pack('<I%ss'%length, length, val1)) 00596 length = len(self.ik_request.robot_state.joint_state.position) 00597 buff.write(_struct_I.pack(length)) 00598 pattern = '<%sd'%length 00599 buff.write(self.ik_request.robot_state.joint_state.position.tostring()) 00600 length = len(self.ik_request.robot_state.joint_state.velocity) 00601 buff.write(_struct_I.pack(length)) 00602 pattern = '<%sd'%length 00603 buff.write(self.ik_request.robot_state.joint_state.velocity.tostring()) 00604 length = len(self.ik_request.robot_state.joint_state.effort) 00605 buff.write(_struct_I.pack(length)) 00606 pattern = '<%sd'%length 00607 buff.write(self.ik_request.robot_state.joint_state.effort.tostring()) 00608 _x = self 00609 buff.write(_struct_2I.pack(_x.ik_request.robot_state.multi_dof_joint_state.stamp.secs, _x.ik_request.robot_state.multi_dof_joint_state.stamp.nsecs)) 00610 length = len(self.ik_request.robot_state.multi_dof_joint_state.joint_names) 00611 buff.write(_struct_I.pack(length)) 00612 for val1 in self.ik_request.robot_state.multi_dof_joint_state.joint_names: 00613 length = len(val1) 00614 buff.write(struct.pack('<I%ss'%length, length, val1)) 00615 length = len(self.ik_request.robot_state.multi_dof_joint_state.frame_ids) 00616 buff.write(_struct_I.pack(length)) 00617 for val1 in self.ik_request.robot_state.multi_dof_joint_state.frame_ids: 00618 length = len(val1) 00619 buff.write(struct.pack('<I%ss'%length, length, val1)) 00620 length = len(self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids) 00621 buff.write(_struct_I.pack(length)) 00622 for val1 in self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids: 00623 length = len(val1) 00624 buff.write(struct.pack('<I%ss'%length, length, val1)) 00625 length = len(self.ik_request.robot_state.multi_dof_joint_state.poses) 00626 buff.write(_struct_I.pack(length)) 00627 for val1 in self.ik_request.robot_state.multi_dof_joint_state.poses: 00628 _v11 = val1.position 00629 _x = _v11 00630 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00631 _v12 = val1.orientation 00632 _x = _v12 00633 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00634 _x = self 00635 buff.write(_struct_2i.pack(_x.timeout.secs, _x.timeout.nsecs)) 00636 except struct.error as se: self._check_types(se) 00637 except TypeError as te: self._check_types(te) 00638 00639 def deserialize_numpy(self, str, numpy): 00640 """ 00641 unpack serialized message in str into this message instance using numpy for array types 00642 @param str: byte array of serialized message 00643 @type str: str 00644 @param numpy: numpy python module 00645 @type numpy: module 00646 """ 00647 try: 00648 if self.ik_request is None: 00649 self.ik_request = kinematics_msgs.msg.PositionIKRequest() 00650 if self.timeout is None: 00651 self.timeout = roslib.rostime.Duration() 00652 end = 0 00653 start = end 00654 end += 4 00655 (length,) = _struct_I.unpack(str[start:end]) 00656 start = end 00657 end += length 00658 self.ik_request.ik_link_name = str[start:end] 00659 _x = self 00660 start = end 00661 end += 12 00662 (_x.ik_request.pose_stamped.header.seq, _x.ik_request.pose_stamped.header.stamp.secs, _x.ik_request.pose_stamped.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00663 start = end 00664 end += 4 00665 (length,) = _struct_I.unpack(str[start:end]) 00666 start = end 00667 end += length 00668 self.ik_request.pose_stamped.header.frame_id = str[start:end] 00669 _x = self 00670 start = end 00671 end += 68 00672 (_x.ik_request.pose_stamped.pose.position.x, _x.ik_request.pose_stamped.pose.position.y, _x.ik_request.pose_stamped.pose.position.z, _x.ik_request.pose_stamped.pose.orientation.x, _x.ik_request.pose_stamped.pose.orientation.y, _x.ik_request.pose_stamped.pose.orientation.z, _x.ik_request.pose_stamped.pose.orientation.w, _x.ik_request.ik_seed_state.joint_state.header.seq, _x.ik_request.ik_seed_state.joint_state.header.stamp.secs, _x.ik_request.ik_seed_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end]) 00673 start = end 00674 end += 4 00675 (length,) = _struct_I.unpack(str[start:end]) 00676 start = end 00677 end += length 00678 self.ik_request.ik_seed_state.joint_state.header.frame_id = str[start:end] 00679 start = end 00680 end += 4 00681 (length,) = _struct_I.unpack(str[start:end]) 00682 self.ik_request.ik_seed_state.joint_state.name = [] 00683 for i in range(0, length): 00684 start = end 00685 end += 4 00686 (length,) = _struct_I.unpack(str[start:end]) 00687 start = end 00688 end += length 00689 val1 = str[start:end] 00690 self.ik_request.ik_seed_state.joint_state.name.append(val1) 00691 start = end 00692 end += 4 00693 (length,) = _struct_I.unpack(str[start:end]) 00694 pattern = '<%sd'%length 00695 start = end 00696 end += struct.calcsize(pattern) 00697 self.ik_request.ik_seed_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00698 start = end 00699 end += 4 00700 (length,) = _struct_I.unpack(str[start:end]) 00701 pattern = '<%sd'%length 00702 start = end 00703 end += struct.calcsize(pattern) 00704 self.ik_request.ik_seed_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00705 start = end 00706 end += 4 00707 (length,) = _struct_I.unpack(str[start:end]) 00708 pattern = '<%sd'%length 00709 start = end 00710 end += struct.calcsize(pattern) 00711 self.ik_request.ik_seed_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00712 _x = self 00713 start = end 00714 end += 8 00715 (_x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.secs, _x.ik_request.ik_seed_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00716 start = end 00717 end += 4 00718 (length,) = _struct_I.unpack(str[start:end]) 00719 self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names = [] 00720 for i in range(0, length): 00721 start = end 00722 end += 4 00723 (length,) = _struct_I.unpack(str[start:end]) 00724 start = end 00725 end += length 00726 val1 = str[start:end] 00727 self.ik_request.ik_seed_state.multi_dof_joint_state.joint_names.append(val1) 00728 start = end 00729 end += 4 00730 (length,) = _struct_I.unpack(str[start:end]) 00731 self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids = [] 00732 for i in range(0, length): 00733 start = end 00734 end += 4 00735 (length,) = _struct_I.unpack(str[start:end]) 00736 start = end 00737 end += length 00738 val1 = str[start:end] 00739 self.ik_request.ik_seed_state.multi_dof_joint_state.frame_ids.append(val1) 00740 start = end 00741 end += 4 00742 (length,) = _struct_I.unpack(str[start:end]) 00743 self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids = [] 00744 for i in range(0, length): 00745 start = end 00746 end += 4 00747 (length,) = _struct_I.unpack(str[start:end]) 00748 start = end 00749 end += length 00750 val1 = str[start:end] 00751 self.ik_request.ik_seed_state.multi_dof_joint_state.child_frame_ids.append(val1) 00752 start = end 00753 end += 4 00754 (length,) = _struct_I.unpack(str[start:end]) 00755 self.ik_request.ik_seed_state.multi_dof_joint_state.poses = [] 00756 for i in range(0, length): 00757 val1 = geometry_msgs.msg.Pose() 00758 _v13 = val1.position 00759 _x = _v13 00760 start = end 00761 end += 24 00762 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00763 _v14 = val1.orientation 00764 _x = _v14 00765 start = end 00766 end += 32 00767 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00768 self.ik_request.ik_seed_state.multi_dof_joint_state.poses.append(val1) 00769 _x = self 00770 start = end 00771 end += 12 00772 (_x.ik_request.robot_state.joint_state.header.seq, _x.ik_request.robot_state.joint_state.header.stamp.secs, _x.ik_request.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00773 start = end 00774 end += 4 00775 (length,) = _struct_I.unpack(str[start:end]) 00776 start = end 00777 end += length 00778 self.ik_request.robot_state.joint_state.header.frame_id = str[start:end] 00779 start = end 00780 end += 4 00781 (length,) = _struct_I.unpack(str[start:end]) 00782 self.ik_request.robot_state.joint_state.name = [] 00783 for i in range(0, length): 00784 start = end 00785 end += 4 00786 (length,) = _struct_I.unpack(str[start:end]) 00787 start = end 00788 end += length 00789 val1 = str[start:end] 00790 self.ik_request.robot_state.joint_state.name.append(val1) 00791 start = end 00792 end += 4 00793 (length,) = _struct_I.unpack(str[start:end]) 00794 pattern = '<%sd'%length 00795 start = end 00796 end += struct.calcsize(pattern) 00797 self.ik_request.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00798 start = end 00799 end += 4 00800 (length,) = _struct_I.unpack(str[start:end]) 00801 pattern = '<%sd'%length 00802 start = end 00803 end += struct.calcsize(pattern) 00804 self.ik_request.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00805 start = end 00806 end += 4 00807 (length,) = _struct_I.unpack(str[start:end]) 00808 pattern = '<%sd'%length 00809 start = end 00810 end += struct.calcsize(pattern) 00811 self.ik_request.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00812 _x = self 00813 start = end 00814 end += 8 00815 (_x.ik_request.robot_state.multi_dof_joint_state.stamp.secs, _x.ik_request.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00816 start = end 00817 end += 4 00818 (length,) = _struct_I.unpack(str[start:end]) 00819 self.ik_request.robot_state.multi_dof_joint_state.joint_names = [] 00820 for i in range(0, length): 00821 start = end 00822 end += 4 00823 (length,) = _struct_I.unpack(str[start:end]) 00824 start = end 00825 end += length 00826 val1 = str[start:end] 00827 self.ik_request.robot_state.multi_dof_joint_state.joint_names.append(val1) 00828 start = end 00829 end += 4 00830 (length,) = _struct_I.unpack(str[start:end]) 00831 self.ik_request.robot_state.multi_dof_joint_state.frame_ids = [] 00832 for i in range(0, length): 00833 start = end 00834 end += 4 00835 (length,) = _struct_I.unpack(str[start:end]) 00836 start = end 00837 end += length 00838 val1 = str[start:end] 00839 self.ik_request.robot_state.multi_dof_joint_state.frame_ids.append(val1) 00840 start = end 00841 end += 4 00842 (length,) = _struct_I.unpack(str[start:end]) 00843 self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids = [] 00844 for i in range(0, length): 00845 start = end 00846 end += 4 00847 (length,) = _struct_I.unpack(str[start:end]) 00848 start = end 00849 end += length 00850 val1 = str[start:end] 00851 self.ik_request.robot_state.multi_dof_joint_state.child_frame_ids.append(val1) 00852 start = end 00853 end += 4 00854 (length,) = _struct_I.unpack(str[start:end]) 00855 self.ik_request.robot_state.multi_dof_joint_state.poses = [] 00856 for i in range(0, length): 00857 val1 = geometry_msgs.msg.Pose() 00858 _v15 = val1.position 00859 _x = _v15 00860 start = end 00861 end += 24 00862 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00863 _v16 = val1.orientation 00864 _x = _v16 00865 start = end 00866 end += 32 00867 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00868 self.ik_request.robot_state.multi_dof_joint_state.poses.append(val1) 00869 _x = self 00870 start = end 00871 end += 8 00872 (_x.timeout.secs, _x.timeout.nsecs,) = _struct_2i.unpack(str[start:end]) 00873 self.timeout.canon() 00874 return self 00875 except struct.error as e: 00876 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00877 00878 _struct_I = roslib.message.struct_I 00879 _struct_7d3I = struct.Struct("<7d3I") 00880 _struct_3I = struct.Struct("<3I") 00881 _struct_4d = struct.Struct("<4d") 00882 _struct_2i = struct.Struct("<2i") 00883 _struct_2I = struct.Struct("<2I") 00884 _struct_3d = struct.Struct("<3d") 00885 """autogenerated by genmsg_py from GetPositionIKResponse.msg. Do not edit.""" 00886 import roslib.message 00887 import struct 00888 00889 import arm_navigation_msgs.msg 00890 import geometry_msgs.msg 00891 import std_msgs.msg 00892 import roslib.rostime 00893 import sensor_msgs.msg 00894 00895 class GetPositionIKResponse(roslib.message.Message): 00896 _md5sum = "5a8bbc4eb2775fe00cbd09858fd3dc65" 00897 _type = "kinematics_msgs/GetPositionIKResponse" 00898 _has_header = False #flag to mark the presence of a Header object 00899 _full_text = """ 00900 00901 arm_navigation_msgs/RobotState solution 00902 00903 arm_navigation_msgs/ArmNavigationErrorCodes error_code 00904 00905 00906 00907 ================================================================================ 00908 MSG: arm_navigation_msgs/RobotState 00909 # This message contains information about the robot state, i.e. the positions of its joints and links 00910 sensor_msgs/JointState joint_state 00911 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state 00912 00913 ================================================================================ 00914 MSG: sensor_msgs/JointState 00915 # This is a message that holds data to describe the state of a set of torque controlled joints. 00916 # 00917 # The state of each joint (revolute or prismatic) is defined by: 00918 # * the position of the joint (rad or m), 00919 # * the velocity of the joint (rad/s or m/s) and 00920 # * the effort that is applied in the joint (Nm or N). 00921 # 00922 # Each joint is uniquely identified by its name 00923 # The header specifies the time at which the joint states were recorded. All the joint states 00924 # in one message have to be recorded at the same time. 00925 # 00926 # This message consists of a multiple arrays, one for each part of the joint state. 00927 # The goal is to make each of the fields optional. When e.g. your joints have no 00928 # effort associated with them, you can leave the effort array empty. 00929 # 00930 # All arrays in this message should have the same size, or be empty. 00931 # This is the only way to uniquely associate the joint name with the correct 00932 # states. 00933 00934 00935 Header header 00936 00937 string[] name 00938 float64[] position 00939 float64[] velocity 00940 float64[] effort 00941 00942 ================================================================================ 00943 MSG: std_msgs/Header 00944 # Standard metadata for higher-level stamped data types. 00945 # This is generally used to communicate timestamped data 00946 # in a particular coordinate frame. 00947 # 00948 # sequence ID: consecutively increasing ID 00949 uint32 seq 00950 #Two-integer timestamp that is expressed as: 00951 # * stamp.secs: seconds (stamp_secs) since epoch 00952 # * stamp.nsecs: nanoseconds since stamp_secs 00953 # time-handling sugar is provided by the client library 00954 time stamp 00955 #Frame this data is associated with 00956 # 0: no frame 00957 # 1: global frame 00958 string frame_id 00959 00960 ================================================================================ 00961 MSG: arm_navigation_msgs/MultiDOFJointState 00962 #A representation of a multi-dof joint state 00963 time stamp 00964 string[] joint_names 00965 string[] frame_ids 00966 string[] child_frame_ids 00967 geometry_msgs/Pose[] poses 00968 00969 ================================================================================ 00970 MSG: geometry_msgs/Pose 00971 # A representation of pose in free space, composed of postion and orientation. 00972 Point position 00973 Quaternion orientation 00974 00975 ================================================================================ 00976 MSG: geometry_msgs/Point 00977 # This contains the position of a point in free space 00978 float64 x 00979 float64 y 00980 float64 z 00981 00982 ================================================================================ 00983 MSG: geometry_msgs/Quaternion 00984 # This represents an orientation in free space in quaternion form. 00985 00986 float64 x 00987 float64 y 00988 float64 z 00989 float64 w 00990 00991 ================================================================================ 00992 MSG: arm_navigation_msgs/ArmNavigationErrorCodes 00993 int32 val 00994 00995 # overall behavior 00996 int32 PLANNING_FAILED=-1 00997 int32 SUCCESS=1 00998 int32 TIMED_OUT=-2 00999 01000 # start state errors 01001 int32 START_STATE_IN_COLLISION=-3 01002 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4 01003 01004 # goal errors 01005 int32 GOAL_IN_COLLISION=-5 01006 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6 01007 01008 # robot state 01009 int32 INVALID_ROBOT_STATE=-7 01010 int32 INCOMPLETE_ROBOT_STATE=-8 01011 01012 # planning request errors 01013 int32 INVALID_PLANNER_ID=-9 01014 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10 01015 int32 INVALID_ALLOWED_PLANNING_TIME=-11 01016 int32 INVALID_GROUP_NAME=-12 01017 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13 01018 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14 01019 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15 01020 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16 01021 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17 01022 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18 01023 01024 # state/trajectory monitor errors 01025 int32 INVALID_TRAJECTORY=-19 01026 int32 INVALID_INDEX=-20 01027 int32 JOINT_LIMITS_VIOLATED=-21 01028 int32 PATH_CONSTRAINTS_VIOLATED=-22 01029 int32 COLLISION_CONSTRAINTS_VIOLATED=-23 01030 int32 GOAL_CONSTRAINTS_VIOLATED=-24 01031 int32 JOINTS_NOT_MOVING=-25 01032 int32 TRAJECTORY_CONTROLLER_FAILED=-26 01033 01034 # system errors 01035 int32 FRAME_TRANSFORM_FAILURE=-27 01036 int32 COLLISION_CHECKING_UNAVAILABLE=-28 01037 int32 ROBOT_STATE_STALE=-29 01038 int32 SENSOR_INFO_STALE=-30 01039 01040 # kinematics errors 01041 int32 NO_IK_SOLUTION=-31 01042 int32 INVALID_LINK_NAME=-32 01043 int32 IK_LINK_IN_COLLISION=-33 01044 int32 NO_FK_SOLUTION=-34 01045 int32 KINEMATICS_STATE_IN_COLLISION=-35 01046 01047 # general errors 01048 int32 INVALID_TIMEOUT=-36 01049 01050 01051 """ 01052 __slots__ = ['solution','error_code'] 01053 _slot_types = ['arm_navigation_msgs/RobotState','arm_navigation_msgs/ArmNavigationErrorCodes'] 01054 01055 def __init__(self, *args, **kwds): 01056 """ 01057 Constructor. Any message fields that are implicitly/explicitly 01058 set to None will be assigned a default value. The recommend 01059 use is keyword arguments as this is more robust to future message 01060 changes. You cannot mix in-order arguments and keyword arguments. 01061 01062 The available fields are: 01063 solution,error_code 01064 01065 @param args: complete set of field values, in .msg order 01066 @param kwds: use keyword arguments corresponding to message field names 01067 to set specific fields. 01068 """ 01069 if args or kwds: 01070 super(GetPositionIKResponse, self).__init__(*args, **kwds) 01071 #message fields cannot be None, assign default values for those that are 01072 if self.solution is None: 01073 self.solution = arm_navigation_msgs.msg.RobotState() 01074 if self.error_code is None: 01075 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes() 01076 else: 01077 self.solution = arm_navigation_msgs.msg.RobotState() 01078 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes() 01079 01080 def _get_types(self): 01081 """ 01082 internal API method 01083 """ 01084 return self._slot_types 01085 01086 def serialize(self, buff): 01087 """ 01088 serialize message into buffer 01089 @param buff: buffer 01090 @type buff: StringIO 01091 """ 01092 try: 01093 _x = self 01094 buff.write(_struct_3I.pack(_x.solution.joint_state.header.seq, _x.solution.joint_state.header.stamp.secs, _x.solution.joint_state.header.stamp.nsecs)) 01095 _x = self.solution.joint_state.header.frame_id 01096 length = len(_x) 01097 buff.write(struct.pack('<I%ss'%length, length, _x)) 01098 length = len(self.solution.joint_state.name) 01099 buff.write(_struct_I.pack(length)) 01100 for val1 in self.solution.joint_state.name: 01101 length = len(val1) 01102 buff.write(struct.pack('<I%ss'%length, length, val1)) 01103 length = len(self.solution.joint_state.position) 01104 buff.write(_struct_I.pack(length)) 01105 pattern = '<%sd'%length 01106 buff.write(struct.pack(pattern, *self.solution.joint_state.position)) 01107 length = len(self.solution.joint_state.velocity) 01108 buff.write(_struct_I.pack(length)) 01109 pattern = '<%sd'%length 01110 buff.write(struct.pack(pattern, *self.solution.joint_state.velocity)) 01111 length = len(self.solution.joint_state.effort) 01112 buff.write(_struct_I.pack(length)) 01113 pattern = '<%sd'%length 01114 buff.write(struct.pack(pattern, *self.solution.joint_state.effort)) 01115 _x = self 01116 buff.write(_struct_2I.pack(_x.solution.multi_dof_joint_state.stamp.secs, _x.solution.multi_dof_joint_state.stamp.nsecs)) 01117 length = len(self.solution.multi_dof_joint_state.joint_names) 01118 buff.write(_struct_I.pack(length)) 01119 for val1 in self.solution.multi_dof_joint_state.joint_names: 01120 length = len(val1) 01121 buff.write(struct.pack('<I%ss'%length, length, val1)) 01122 length = len(self.solution.multi_dof_joint_state.frame_ids) 01123 buff.write(_struct_I.pack(length)) 01124 for val1 in self.solution.multi_dof_joint_state.frame_ids: 01125 length = len(val1) 01126 buff.write(struct.pack('<I%ss'%length, length, val1)) 01127 length = len(self.solution.multi_dof_joint_state.child_frame_ids) 01128 buff.write(_struct_I.pack(length)) 01129 for val1 in self.solution.multi_dof_joint_state.child_frame_ids: 01130 length = len(val1) 01131 buff.write(struct.pack('<I%ss'%length, length, val1)) 01132 length = len(self.solution.multi_dof_joint_state.poses) 01133 buff.write(_struct_I.pack(length)) 01134 for val1 in self.solution.multi_dof_joint_state.poses: 01135 _v17 = val1.position 01136 _x = _v17 01137 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01138 _v18 = val1.orientation 01139 _x = _v18 01140 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01141 buff.write(_struct_i.pack(self.error_code.val)) 01142 except struct.error as se: self._check_types(se) 01143 except TypeError as te: self._check_types(te) 01144 01145 def deserialize(self, str): 01146 """ 01147 unpack serialized message in str into this message instance 01148 @param str: byte array of serialized message 01149 @type str: str 01150 """ 01151 try: 01152 if self.solution is None: 01153 self.solution = arm_navigation_msgs.msg.RobotState() 01154 if self.error_code is None: 01155 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes() 01156 end = 0 01157 _x = self 01158 start = end 01159 end += 12 01160 (_x.solution.joint_state.header.seq, _x.solution.joint_state.header.stamp.secs, _x.solution.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01161 start = end 01162 end += 4 01163 (length,) = _struct_I.unpack(str[start:end]) 01164 start = end 01165 end += length 01166 self.solution.joint_state.header.frame_id = str[start:end] 01167 start = end 01168 end += 4 01169 (length,) = _struct_I.unpack(str[start:end]) 01170 self.solution.joint_state.name = [] 01171 for i in range(0, length): 01172 start = end 01173 end += 4 01174 (length,) = _struct_I.unpack(str[start:end]) 01175 start = end 01176 end += length 01177 val1 = str[start:end] 01178 self.solution.joint_state.name.append(val1) 01179 start = end 01180 end += 4 01181 (length,) = _struct_I.unpack(str[start:end]) 01182 pattern = '<%sd'%length 01183 start = end 01184 end += struct.calcsize(pattern) 01185 self.solution.joint_state.position = struct.unpack(pattern, str[start:end]) 01186 start = end 01187 end += 4 01188 (length,) = _struct_I.unpack(str[start:end]) 01189 pattern = '<%sd'%length 01190 start = end 01191 end += struct.calcsize(pattern) 01192 self.solution.joint_state.velocity = struct.unpack(pattern, str[start:end]) 01193 start = end 01194 end += 4 01195 (length,) = _struct_I.unpack(str[start:end]) 01196 pattern = '<%sd'%length 01197 start = end 01198 end += struct.calcsize(pattern) 01199 self.solution.joint_state.effort = struct.unpack(pattern, str[start:end]) 01200 _x = self 01201 start = end 01202 end += 8 01203 (_x.solution.multi_dof_joint_state.stamp.secs, _x.solution.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 01204 start = end 01205 end += 4 01206 (length,) = _struct_I.unpack(str[start:end]) 01207 self.solution.multi_dof_joint_state.joint_names = [] 01208 for i in range(0, length): 01209 start = end 01210 end += 4 01211 (length,) = _struct_I.unpack(str[start:end]) 01212 start = end 01213 end += length 01214 val1 = str[start:end] 01215 self.solution.multi_dof_joint_state.joint_names.append(val1) 01216 start = end 01217 end += 4 01218 (length,) = _struct_I.unpack(str[start:end]) 01219 self.solution.multi_dof_joint_state.frame_ids = [] 01220 for i in range(0, length): 01221 start = end 01222 end += 4 01223 (length,) = _struct_I.unpack(str[start:end]) 01224 start = end 01225 end += length 01226 val1 = str[start:end] 01227 self.solution.multi_dof_joint_state.frame_ids.append(val1) 01228 start = end 01229 end += 4 01230 (length,) = _struct_I.unpack(str[start:end]) 01231 self.solution.multi_dof_joint_state.child_frame_ids = [] 01232 for i in range(0, length): 01233 start = end 01234 end += 4 01235 (length,) = _struct_I.unpack(str[start:end]) 01236 start = end 01237 end += length 01238 val1 = str[start:end] 01239 self.solution.multi_dof_joint_state.child_frame_ids.append(val1) 01240 start = end 01241 end += 4 01242 (length,) = _struct_I.unpack(str[start:end]) 01243 self.solution.multi_dof_joint_state.poses = [] 01244 for i in range(0, length): 01245 val1 = geometry_msgs.msg.Pose() 01246 _v19 = val1.position 01247 _x = _v19 01248 start = end 01249 end += 24 01250 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01251 _v20 = val1.orientation 01252 _x = _v20 01253 start = end 01254 end += 32 01255 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01256 self.solution.multi_dof_joint_state.poses.append(val1) 01257 start = end 01258 end += 4 01259 (self.error_code.val,) = _struct_i.unpack(str[start:end]) 01260 return self 01261 except struct.error as e: 01262 raise roslib.message.DeserializationError(e) #most likely buffer underfill 01263 01264 01265 def serialize_numpy(self, buff, numpy): 01266 """ 01267 serialize message with numpy array types into buffer 01268 @param buff: buffer 01269 @type buff: StringIO 01270 @param numpy: numpy python module 01271 @type numpy module 01272 """ 01273 try: 01274 _x = self 01275 buff.write(_struct_3I.pack(_x.solution.joint_state.header.seq, _x.solution.joint_state.header.stamp.secs, _x.solution.joint_state.header.stamp.nsecs)) 01276 _x = self.solution.joint_state.header.frame_id 01277 length = len(_x) 01278 buff.write(struct.pack('<I%ss'%length, length, _x)) 01279 length = len(self.solution.joint_state.name) 01280 buff.write(_struct_I.pack(length)) 01281 for val1 in self.solution.joint_state.name: 01282 length = len(val1) 01283 buff.write(struct.pack('<I%ss'%length, length, val1)) 01284 length = len(self.solution.joint_state.position) 01285 buff.write(_struct_I.pack(length)) 01286 pattern = '<%sd'%length 01287 buff.write(self.solution.joint_state.position.tostring()) 01288 length = len(self.solution.joint_state.velocity) 01289 buff.write(_struct_I.pack(length)) 01290 pattern = '<%sd'%length 01291 buff.write(self.solution.joint_state.velocity.tostring()) 01292 length = len(self.solution.joint_state.effort) 01293 buff.write(_struct_I.pack(length)) 01294 pattern = '<%sd'%length 01295 buff.write(self.solution.joint_state.effort.tostring()) 01296 _x = self 01297 buff.write(_struct_2I.pack(_x.solution.multi_dof_joint_state.stamp.secs, _x.solution.multi_dof_joint_state.stamp.nsecs)) 01298 length = len(self.solution.multi_dof_joint_state.joint_names) 01299 buff.write(_struct_I.pack(length)) 01300 for val1 in self.solution.multi_dof_joint_state.joint_names: 01301 length = len(val1) 01302 buff.write(struct.pack('<I%ss'%length, length, val1)) 01303 length = len(self.solution.multi_dof_joint_state.frame_ids) 01304 buff.write(_struct_I.pack(length)) 01305 for val1 in self.solution.multi_dof_joint_state.frame_ids: 01306 length = len(val1) 01307 buff.write(struct.pack('<I%ss'%length, length, val1)) 01308 length = len(self.solution.multi_dof_joint_state.child_frame_ids) 01309 buff.write(_struct_I.pack(length)) 01310 for val1 in self.solution.multi_dof_joint_state.child_frame_ids: 01311 length = len(val1) 01312 buff.write(struct.pack('<I%ss'%length, length, val1)) 01313 length = len(self.solution.multi_dof_joint_state.poses) 01314 buff.write(_struct_I.pack(length)) 01315 for val1 in self.solution.multi_dof_joint_state.poses: 01316 _v21 = val1.position 01317 _x = _v21 01318 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01319 _v22 = val1.orientation 01320 _x = _v22 01321 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01322 buff.write(_struct_i.pack(self.error_code.val)) 01323 except struct.error as se: self._check_types(se) 01324 except TypeError as te: self._check_types(te) 01325 01326 def deserialize_numpy(self, str, numpy): 01327 """ 01328 unpack serialized message in str into this message instance using numpy for array types 01329 @param str: byte array of serialized message 01330 @type str: str 01331 @param numpy: numpy python module 01332 @type numpy: module 01333 """ 01334 try: 01335 if self.solution is None: 01336 self.solution = arm_navigation_msgs.msg.RobotState() 01337 if self.error_code is None: 01338 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes() 01339 end = 0 01340 _x = self 01341 start = end 01342 end += 12 01343 (_x.solution.joint_state.header.seq, _x.solution.joint_state.header.stamp.secs, _x.solution.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01344 start = end 01345 end += 4 01346 (length,) = _struct_I.unpack(str[start:end]) 01347 start = end 01348 end += length 01349 self.solution.joint_state.header.frame_id = str[start:end] 01350 start = end 01351 end += 4 01352 (length,) = _struct_I.unpack(str[start:end]) 01353 self.solution.joint_state.name = [] 01354 for i in range(0, length): 01355 start = end 01356 end += 4 01357 (length,) = _struct_I.unpack(str[start:end]) 01358 start = end 01359 end += length 01360 val1 = str[start:end] 01361 self.solution.joint_state.name.append(val1) 01362 start = end 01363 end += 4 01364 (length,) = _struct_I.unpack(str[start:end]) 01365 pattern = '<%sd'%length 01366 start = end 01367 end += struct.calcsize(pattern) 01368 self.solution.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01369 start = end 01370 end += 4 01371 (length,) = _struct_I.unpack(str[start:end]) 01372 pattern = '<%sd'%length 01373 start = end 01374 end += struct.calcsize(pattern) 01375 self.solution.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01376 start = end 01377 end += 4 01378 (length,) = _struct_I.unpack(str[start:end]) 01379 pattern = '<%sd'%length 01380 start = end 01381 end += struct.calcsize(pattern) 01382 self.solution.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01383 _x = self 01384 start = end 01385 end += 8 01386 (_x.solution.multi_dof_joint_state.stamp.secs, _x.solution.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 01387 start = end 01388 end += 4 01389 (length,) = _struct_I.unpack(str[start:end]) 01390 self.solution.multi_dof_joint_state.joint_names = [] 01391 for i in range(0, length): 01392 start = end 01393 end += 4 01394 (length,) = _struct_I.unpack(str[start:end]) 01395 start = end 01396 end += length 01397 val1 = str[start:end] 01398 self.solution.multi_dof_joint_state.joint_names.append(val1) 01399 start = end 01400 end += 4 01401 (length,) = _struct_I.unpack(str[start:end]) 01402 self.solution.multi_dof_joint_state.frame_ids = [] 01403 for i in range(0, length): 01404 start = end 01405 end += 4 01406 (length,) = _struct_I.unpack(str[start:end]) 01407 start = end 01408 end += length 01409 val1 = str[start:end] 01410 self.solution.multi_dof_joint_state.frame_ids.append(val1) 01411 start = end 01412 end += 4 01413 (length,) = _struct_I.unpack(str[start:end]) 01414 self.solution.multi_dof_joint_state.child_frame_ids = [] 01415 for i in range(0, length): 01416 start = end 01417 end += 4 01418 (length,) = _struct_I.unpack(str[start:end]) 01419 start = end 01420 end += length 01421 val1 = str[start:end] 01422 self.solution.multi_dof_joint_state.child_frame_ids.append(val1) 01423 start = end 01424 end += 4 01425 (length,) = _struct_I.unpack(str[start:end]) 01426 self.solution.multi_dof_joint_state.poses = [] 01427 for i in range(0, length): 01428 val1 = geometry_msgs.msg.Pose() 01429 _v23 = val1.position 01430 _x = _v23 01431 start = end 01432 end += 24 01433 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01434 _v24 = val1.orientation 01435 _x = _v24 01436 start = end 01437 end += 32 01438 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01439 self.solution.multi_dof_joint_state.poses.append(val1) 01440 start = end 01441 end += 4 01442 (self.error_code.val,) = _struct_i.unpack(str[start:end]) 01443 return self 01444 except struct.error as e: 01445 raise roslib.message.DeserializationError(e) #most likely buffer underfill 01446 01447 _struct_I = roslib.message.struct_I 01448 _struct_i = struct.Struct("<i") 01449 _struct_4d = struct.Struct("<4d") 01450 _struct_3I = struct.Struct("<3I") 01451 _struct_2I = struct.Struct("<2I") 01452 _struct_3d = struct.Struct("<3d") 01453 class GetPositionIK(roslib.message.ServiceDefinition): 01454 _type = 'kinematics_msgs/GetPositionIK' 01455 _md5sum = '6d82fcb918d48c6d8a708bc55e34ace2' 01456 _request_class = GetPositionIKRequest 01457 _response_class = GetPositionIKResponse