$search
00001 """autogenerated by genmsg_py from GetFeasibleGraspsRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 00007 class GetFeasibleGraspsRequest(roslib.message.Message): 00008 _md5sum = "2f992715efcc4a20cb1f1eaaa8982d56" 00009 _type = "srs_grasping/GetFeasibleGraspsRequest" 00010 _has_header = False #flag to mark the presence of a Header object 00011 _full_text = """int32 object_id 00012 geometry_msgs/Pose object_pose 00013 float32[] pregrasp_offsets 00014 00015 ================================================================================ 00016 MSG: geometry_msgs/Pose 00017 # A representation of pose in free space, composed of postion and orientation. 00018 Point position 00019 Quaternion orientation 00020 00021 ================================================================================ 00022 MSG: geometry_msgs/Point 00023 # This contains the position of a point in free space 00024 float64 x 00025 float64 y 00026 float64 z 00027 00028 ================================================================================ 00029 MSG: geometry_msgs/Quaternion 00030 # This represents an orientation in free space in quaternion form. 00031 00032 float64 x 00033 float64 y 00034 float64 z 00035 float64 w 00036 00037 """ 00038 __slots__ = ['object_id','object_pose','pregrasp_offsets'] 00039 _slot_types = ['int32','geometry_msgs/Pose','float32[]'] 00040 00041 def __init__(self, *args, **kwds): 00042 """ 00043 Constructor. Any message fields that are implicitly/explicitly 00044 set to None will be assigned a default value. The recommend 00045 use is keyword arguments as this is more robust to future message 00046 changes. You cannot mix in-order arguments and keyword arguments. 00047 00048 The available fields are: 00049 object_id,object_pose,pregrasp_offsets 00050 00051 @param args: complete set of field values, in .msg order 00052 @param kwds: use keyword arguments corresponding to message field names 00053 to set specific fields. 00054 """ 00055 if args or kwds: 00056 super(GetFeasibleGraspsRequest, self).__init__(*args, **kwds) 00057 #message fields cannot be None, assign default values for those that are 00058 if self.object_id is None: 00059 self.object_id = 0 00060 if self.object_pose is None: 00061 self.object_pose = geometry_msgs.msg.Pose() 00062 if self.pregrasp_offsets is None: 00063 self.pregrasp_offsets = [] 00064 else: 00065 self.object_id = 0 00066 self.object_pose = geometry_msgs.msg.Pose() 00067 self.pregrasp_offsets = [] 00068 00069 def _get_types(self): 00070 """ 00071 internal API method 00072 """ 00073 return self._slot_types 00074 00075 def serialize(self, buff): 00076 """ 00077 serialize message into buffer 00078 @param buff: buffer 00079 @type buff: StringIO 00080 """ 00081 try: 00082 _x = self 00083 buff.write(_struct_i7d.pack(_x.object_id, _x.object_pose.position.x, _x.object_pose.position.y, _x.object_pose.position.z, _x.object_pose.orientation.x, _x.object_pose.orientation.y, _x.object_pose.orientation.z, _x.object_pose.orientation.w)) 00084 length = len(self.pregrasp_offsets) 00085 buff.write(_struct_I.pack(length)) 00086 pattern = '<%sf'%length 00087 buff.write(struct.pack(pattern, *self.pregrasp_offsets)) 00088 except struct.error as se: self._check_types(se) 00089 except TypeError as te: self._check_types(te) 00090 00091 def deserialize(self, str): 00092 """ 00093 unpack serialized message in str into this message instance 00094 @param str: byte array of serialized message 00095 @type str: str 00096 """ 00097 try: 00098 if self.object_pose is None: 00099 self.object_pose = geometry_msgs.msg.Pose() 00100 end = 0 00101 _x = self 00102 start = end 00103 end += 60 00104 (_x.object_id, _x.object_pose.position.x, _x.object_pose.position.y, _x.object_pose.position.z, _x.object_pose.orientation.x, _x.object_pose.orientation.y, _x.object_pose.orientation.z, _x.object_pose.orientation.w,) = _struct_i7d.unpack(str[start:end]) 00105 start = end 00106 end += 4 00107 (length,) = _struct_I.unpack(str[start:end]) 00108 pattern = '<%sf'%length 00109 start = end 00110 end += struct.calcsize(pattern) 00111 self.pregrasp_offsets = struct.unpack(pattern, str[start:end]) 00112 return self 00113 except struct.error as e: 00114 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00115 00116 00117 def serialize_numpy(self, buff, numpy): 00118 """ 00119 serialize message with numpy array types into buffer 00120 @param buff: buffer 00121 @type buff: StringIO 00122 @param numpy: numpy python module 00123 @type numpy module 00124 """ 00125 try: 00126 _x = self 00127 buff.write(_struct_i7d.pack(_x.object_id, _x.object_pose.position.x, _x.object_pose.position.y, _x.object_pose.position.z, _x.object_pose.orientation.x, _x.object_pose.orientation.y, _x.object_pose.orientation.z, _x.object_pose.orientation.w)) 00128 length = len(self.pregrasp_offsets) 00129 buff.write(_struct_I.pack(length)) 00130 pattern = '<%sf'%length 00131 buff.write(self.pregrasp_offsets.tostring()) 00132 except struct.error as se: self._check_types(se) 00133 except TypeError as te: self._check_types(te) 00134 00135 def deserialize_numpy(self, str, numpy): 00136 """ 00137 unpack serialized message in str into this message instance using numpy for array types 00138 @param str: byte array of serialized message 00139 @type str: str 00140 @param numpy: numpy python module 00141 @type numpy: module 00142 """ 00143 try: 00144 if self.object_pose is None: 00145 self.object_pose = geometry_msgs.msg.Pose() 00146 end = 0 00147 _x = self 00148 start = end 00149 end += 60 00150 (_x.object_id, _x.object_pose.position.x, _x.object_pose.position.y, _x.object_pose.position.z, _x.object_pose.orientation.x, _x.object_pose.orientation.y, _x.object_pose.orientation.z, _x.object_pose.orientation.w,) = _struct_i7d.unpack(str[start:end]) 00151 start = end 00152 end += 4 00153 (length,) = _struct_I.unpack(str[start:end]) 00154 pattern = '<%sf'%length 00155 start = end 00156 end += struct.calcsize(pattern) 00157 self.pregrasp_offsets = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 00158 return self 00159 except struct.error as e: 00160 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00161 00162 _struct_I = roslib.message.struct_I 00163 _struct_i7d = struct.Struct("<i7d") 00164 """autogenerated by genmsg_py from GetFeasibleGraspsResponse.msg. Do not edit.""" 00165 import roslib.message 00166 import struct 00167 00168 import geometry_msgs.msg 00169 import srs_msgs.msg 00170 import std_msgs.msg 00171 00172 class GetFeasibleGraspsResponse(roslib.message.Message): 00173 _md5sum = "cc5caf9c9653f4aec8db6f1a617e1589" 00174 _type = "srs_grasping/GetFeasibleGraspsResponse" 00175 _has_header = False #flag to mark the presence of a Header object 00176 _full_text = """bool feasible_grasp_available 00177 srs_msgs/FeasibleGrasp[] grasp_configuration 00178 srs_msgs/GraspingErrorCodes error_code 00179 00180 00181 ================================================================================ 00182 MSG: srs_msgs/FeasibleGrasp 00183 float64[] sdh_joint_values 00184 string target_link #link which should be moved to pre_grasp (e.g. sdh_palm_link) 00185 geometry_msgs/PoseStamped grasp 00186 geometry_msgs/PoseStamped pre_grasp 00187 string category 00188 00189 ================================================================================ 00190 MSG: geometry_msgs/PoseStamped 00191 # A Pose with reference coordinate frame and timestamp 00192 Header header 00193 Pose pose 00194 00195 ================================================================================ 00196 MSG: std_msgs/Header 00197 # Standard metadata for higher-level stamped data types. 00198 # This is generally used to communicate timestamped data 00199 # in a particular coordinate frame. 00200 # 00201 # sequence ID: consecutively increasing ID 00202 uint32 seq 00203 #Two-integer timestamp that is expressed as: 00204 # * stamp.secs: seconds (stamp_secs) since epoch 00205 # * stamp.nsecs: nanoseconds since stamp_secs 00206 # time-handling sugar is provided by the client library 00207 time stamp 00208 #Frame this data is associated with 00209 # 0: no frame 00210 # 1: global frame 00211 string frame_id 00212 00213 ================================================================================ 00214 MSG: geometry_msgs/Pose 00215 # A representation of pose in free space, composed of postion and orientation. 00216 Point position 00217 Quaternion orientation 00218 00219 ================================================================================ 00220 MSG: geometry_msgs/Point 00221 # This contains the position of a point in free space 00222 float64 x 00223 float64 y 00224 float64 z 00225 00226 ================================================================================ 00227 MSG: geometry_msgs/Quaternion 00228 # This represents an orientation in free space in quaternion form. 00229 00230 float64 x 00231 float64 y 00232 float64 z 00233 float64 w 00234 00235 ================================================================================ 00236 MSG: srs_msgs/GraspingErrorCodes 00237 int32 val 00238 00239 int32 SUCCESS=1 00240 int32 SERVICE_DID_NOT_PROCESS_REQUEST=-1 00241 int32 UNKNOWN_OBJECT=-2 00242 int32 CORRUPTED_MESH_FILE=-3 00243 int32 CORRUPTED_ROBOT_MESH_FILE=-4 00244 int32 CORRUPTED_GRASP_FILE=-5 00245 int32 NON_GENERATED_INFO=-6 00246 int32 OBJECT_INFO_NOT_FOUND=-7 00247 int32 UNKNOWN_CATEGORY=-8 00248 int32 GOAL_UNREACHABLE=-9 00249 00250 """ 00251 __slots__ = ['feasible_grasp_available','grasp_configuration','error_code'] 00252 _slot_types = ['bool','srs_msgs/FeasibleGrasp[]','srs_msgs/GraspingErrorCodes'] 00253 00254 def __init__(self, *args, **kwds): 00255 """ 00256 Constructor. Any message fields that are implicitly/explicitly 00257 set to None will be assigned a default value. The recommend 00258 use is keyword arguments as this is more robust to future message 00259 changes. You cannot mix in-order arguments and keyword arguments. 00260 00261 The available fields are: 00262 feasible_grasp_available,grasp_configuration,error_code 00263 00264 @param args: complete set of field values, in .msg order 00265 @param kwds: use keyword arguments corresponding to message field names 00266 to set specific fields. 00267 """ 00268 if args or kwds: 00269 super(GetFeasibleGraspsResponse, self).__init__(*args, **kwds) 00270 #message fields cannot be None, assign default values for those that are 00271 if self.feasible_grasp_available is None: 00272 self.feasible_grasp_available = False 00273 if self.grasp_configuration is None: 00274 self.grasp_configuration = [] 00275 if self.error_code is None: 00276 self.error_code = srs_msgs.msg.GraspingErrorCodes() 00277 else: 00278 self.feasible_grasp_available = False 00279 self.grasp_configuration = [] 00280 self.error_code = srs_msgs.msg.GraspingErrorCodes() 00281 00282 def _get_types(self): 00283 """ 00284 internal API method 00285 """ 00286 return self._slot_types 00287 00288 def serialize(self, buff): 00289 """ 00290 serialize message into buffer 00291 @param buff: buffer 00292 @type buff: StringIO 00293 """ 00294 try: 00295 buff.write(_struct_B.pack(self.feasible_grasp_available)) 00296 length = len(self.grasp_configuration) 00297 buff.write(_struct_I.pack(length)) 00298 for val1 in self.grasp_configuration: 00299 length = len(val1.sdh_joint_values) 00300 buff.write(_struct_I.pack(length)) 00301 pattern = '<%sd'%length 00302 buff.write(struct.pack(pattern, *val1.sdh_joint_values)) 00303 _x = val1.target_link 00304 length = len(_x) 00305 buff.write(struct.pack('<I%ss'%length, length, _x)) 00306 _v1 = val1.grasp 00307 _v2 = _v1.header 00308 buff.write(_struct_I.pack(_v2.seq)) 00309 _v3 = _v2.stamp 00310 _x = _v3 00311 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00312 _x = _v2.frame_id 00313 length = len(_x) 00314 buff.write(struct.pack('<I%ss'%length, length, _x)) 00315 _v4 = _v1.pose 00316 _v5 = _v4.position 00317 _x = _v5 00318 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00319 _v6 = _v4.orientation 00320 _x = _v6 00321 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00322 _v7 = val1.pre_grasp 00323 _v8 = _v7.header 00324 buff.write(_struct_I.pack(_v8.seq)) 00325 _v9 = _v8.stamp 00326 _x = _v9 00327 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00328 _x = _v8.frame_id 00329 length = len(_x) 00330 buff.write(struct.pack('<I%ss'%length, length, _x)) 00331 _v10 = _v7.pose 00332 _v11 = _v10.position 00333 _x = _v11 00334 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00335 _v12 = _v10.orientation 00336 _x = _v12 00337 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00338 _x = val1.category 00339 length = len(_x) 00340 buff.write(struct.pack('<I%ss'%length, length, _x)) 00341 buff.write(_struct_i.pack(self.error_code.val)) 00342 except struct.error as se: self._check_types(se) 00343 except TypeError as te: self._check_types(te) 00344 00345 def deserialize(self, str): 00346 """ 00347 unpack serialized message in str into this message instance 00348 @param str: byte array of serialized message 00349 @type str: str 00350 """ 00351 try: 00352 if self.error_code is None: 00353 self.error_code = srs_msgs.msg.GraspingErrorCodes() 00354 end = 0 00355 start = end 00356 end += 1 00357 (self.feasible_grasp_available,) = _struct_B.unpack(str[start:end]) 00358 self.feasible_grasp_available = bool(self.feasible_grasp_available) 00359 start = end 00360 end += 4 00361 (length,) = _struct_I.unpack(str[start:end]) 00362 self.grasp_configuration = [] 00363 for i in range(0, length): 00364 val1 = srs_msgs.msg.FeasibleGrasp() 00365 start = end 00366 end += 4 00367 (length,) = _struct_I.unpack(str[start:end]) 00368 pattern = '<%sd'%length 00369 start = end 00370 end += struct.calcsize(pattern) 00371 val1.sdh_joint_values = struct.unpack(pattern, str[start:end]) 00372 start = end 00373 end += 4 00374 (length,) = _struct_I.unpack(str[start:end]) 00375 start = end 00376 end += length 00377 val1.target_link = str[start:end] 00378 _v13 = val1.grasp 00379 _v14 = _v13.header 00380 start = end 00381 end += 4 00382 (_v14.seq,) = _struct_I.unpack(str[start:end]) 00383 _v15 = _v14.stamp 00384 _x = _v15 00385 start = end 00386 end += 8 00387 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00388 start = end 00389 end += 4 00390 (length,) = _struct_I.unpack(str[start:end]) 00391 start = end 00392 end += length 00393 _v14.frame_id = str[start:end] 00394 _v16 = _v13.pose 00395 _v17 = _v16.position 00396 _x = _v17 00397 start = end 00398 end += 24 00399 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00400 _v18 = _v16.orientation 00401 _x = _v18 00402 start = end 00403 end += 32 00404 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00405 _v19 = val1.pre_grasp 00406 _v20 = _v19.header 00407 start = end 00408 end += 4 00409 (_v20.seq,) = _struct_I.unpack(str[start:end]) 00410 _v21 = _v20.stamp 00411 _x = _v21 00412 start = end 00413 end += 8 00414 (_x.secs, _x.nsecs,) = _struct_2I.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 _v20.frame_id = str[start:end] 00421 _v22 = _v19.pose 00422 _v23 = _v22.position 00423 _x = _v23 00424 start = end 00425 end += 24 00426 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00427 _v24 = _v22.orientation 00428 _x = _v24 00429 start = end 00430 end += 32 00431 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00432 start = end 00433 end += 4 00434 (length,) = _struct_I.unpack(str[start:end]) 00435 start = end 00436 end += length 00437 val1.category = str[start:end] 00438 self.grasp_configuration.append(val1) 00439 start = end 00440 end += 4 00441 (self.error_code.val,) = _struct_i.unpack(str[start:end]) 00442 return self 00443 except struct.error as e: 00444 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00445 00446 00447 def serialize_numpy(self, buff, numpy): 00448 """ 00449 serialize message with numpy array types into buffer 00450 @param buff: buffer 00451 @type buff: StringIO 00452 @param numpy: numpy python module 00453 @type numpy module 00454 """ 00455 try: 00456 buff.write(_struct_B.pack(self.feasible_grasp_available)) 00457 length = len(self.grasp_configuration) 00458 buff.write(_struct_I.pack(length)) 00459 for val1 in self.grasp_configuration: 00460 length = len(val1.sdh_joint_values) 00461 buff.write(_struct_I.pack(length)) 00462 pattern = '<%sd'%length 00463 buff.write(val1.sdh_joint_values.tostring()) 00464 _x = val1.target_link 00465 length = len(_x) 00466 buff.write(struct.pack('<I%ss'%length, length, _x)) 00467 _v25 = val1.grasp 00468 _v26 = _v25.header 00469 buff.write(_struct_I.pack(_v26.seq)) 00470 _v27 = _v26.stamp 00471 _x = _v27 00472 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00473 _x = _v26.frame_id 00474 length = len(_x) 00475 buff.write(struct.pack('<I%ss'%length, length, _x)) 00476 _v28 = _v25.pose 00477 _v29 = _v28.position 00478 _x = _v29 00479 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00480 _v30 = _v28.orientation 00481 _x = _v30 00482 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00483 _v31 = val1.pre_grasp 00484 _v32 = _v31.header 00485 buff.write(_struct_I.pack(_v32.seq)) 00486 _v33 = _v32.stamp 00487 _x = _v33 00488 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00489 _x = _v32.frame_id 00490 length = len(_x) 00491 buff.write(struct.pack('<I%ss'%length, length, _x)) 00492 _v34 = _v31.pose 00493 _v35 = _v34.position 00494 _x = _v35 00495 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00496 _v36 = _v34.orientation 00497 _x = _v36 00498 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00499 _x = val1.category 00500 length = len(_x) 00501 buff.write(struct.pack('<I%ss'%length, length, _x)) 00502 buff.write(_struct_i.pack(self.error_code.val)) 00503 except struct.error as se: self._check_types(se) 00504 except TypeError as te: self._check_types(te) 00505 00506 def deserialize_numpy(self, str, numpy): 00507 """ 00508 unpack serialized message in str into this message instance using numpy for array types 00509 @param str: byte array of serialized message 00510 @type str: str 00511 @param numpy: numpy python module 00512 @type numpy: module 00513 """ 00514 try: 00515 if self.error_code is None: 00516 self.error_code = srs_msgs.msg.GraspingErrorCodes() 00517 end = 0 00518 start = end 00519 end += 1 00520 (self.feasible_grasp_available,) = _struct_B.unpack(str[start:end]) 00521 self.feasible_grasp_available = bool(self.feasible_grasp_available) 00522 start = end 00523 end += 4 00524 (length,) = _struct_I.unpack(str[start:end]) 00525 self.grasp_configuration = [] 00526 for i in range(0, length): 00527 val1 = srs_msgs.msg.FeasibleGrasp() 00528 start = end 00529 end += 4 00530 (length,) = _struct_I.unpack(str[start:end]) 00531 pattern = '<%sd'%length 00532 start = end 00533 end += struct.calcsize(pattern) 00534 val1.sdh_joint_values = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00535 start = end 00536 end += 4 00537 (length,) = _struct_I.unpack(str[start:end]) 00538 start = end 00539 end += length 00540 val1.target_link = str[start:end] 00541 _v37 = val1.grasp 00542 _v38 = _v37.header 00543 start = end 00544 end += 4 00545 (_v38.seq,) = _struct_I.unpack(str[start:end]) 00546 _v39 = _v38.stamp 00547 _x = _v39 00548 start = end 00549 end += 8 00550 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00551 start = end 00552 end += 4 00553 (length,) = _struct_I.unpack(str[start:end]) 00554 start = end 00555 end += length 00556 _v38.frame_id = str[start:end] 00557 _v40 = _v37.pose 00558 _v41 = _v40.position 00559 _x = _v41 00560 start = end 00561 end += 24 00562 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00563 _v42 = _v40.orientation 00564 _x = _v42 00565 start = end 00566 end += 32 00567 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00568 _v43 = val1.pre_grasp 00569 _v44 = _v43.header 00570 start = end 00571 end += 4 00572 (_v44.seq,) = _struct_I.unpack(str[start:end]) 00573 _v45 = _v44.stamp 00574 _x = _v45 00575 start = end 00576 end += 8 00577 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00578 start = end 00579 end += 4 00580 (length,) = _struct_I.unpack(str[start:end]) 00581 start = end 00582 end += length 00583 _v44.frame_id = str[start:end] 00584 _v46 = _v43.pose 00585 _v47 = _v46.position 00586 _x = _v47 00587 start = end 00588 end += 24 00589 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00590 _v48 = _v46.orientation 00591 _x = _v48 00592 start = end 00593 end += 32 00594 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00595 start = end 00596 end += 4 00597 (length,) = _struct_I.unpack(str[start:end]) 00598 start = end 00599 end += length 00600 val1.category = str[start:end] 00601 self.grasp_configuration.append(val1) 00602 start = end 00603 end += 4 00604 (self.error_code.val,) = _struct_i.unpack(str[start:end]) 00605 return self 00606 except struct.error as e: 00607 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00608 00609 _struct_I = roslib.message.struct_I 00610 _struct_B = struct.Struct("<B") 00611 _struct_i = struct.Struct("<i") 00612 _struct_4d = struct.Struct("<4d") 00613 _struct_2I = struct.Struct("<2I") 00614 _struct_3d = struct.Struct("<3d") 00615 class GetFeasibleGrasps(roslib.message.ServiceDefinition): 00616 _type = 'srs_grasping/GetFeasibleGrasps' 00617 _md5sum = '784b27be1f50ac2f91c4f1ce4b6ad528' 00618 _request_class = GetFeasibleGraspsRequest 00619 _response_class = GetFeasibleGraspsResponse