$search
00001 """autogenerated by genmsg_py from GraspAdjustRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 import std_msgs.msg 00007 00008 class GraspAdjustRequest(roslib.message.Message): 00009 _md5sum = "e7ccb113bffaf7f7554b005b509b114a" 00010 _type = "pr2_grasp_adjust/GraspAdjustRequest" 00011 _has_header = False #flag to mark the presence of a Header object 00012 _full_text = """geometry_msgs/PoseStamped grasp_pose 00013 geometry_msgs/Vector3 roi_dims 00014 uint8 search_mode 00015 00016 int32 GLOBAL_SEARCH = 0 00017 int32 LOCAL_SEARCH = 1 00018 int32 SINGLE_POSE = 2 00019 00020 00021 ================================================================================ 00022 MSG: geometry_msgs/PoseStamped 00023 # A Pose with reference coordinate frame and timestamp 00024 Header header 00025 Pose pose 00026 00027 ================================================================================ 00028 MSG: std_msgs/Header 00029 # Standard metadata for higher-level stamped data types. 00030 # This is generally used to communicate timestamped data 00031 # in a particular coordinate frame. 00032 # 00033 # sequence ID: consecutively increasing ID 00034 uint32 seq 00035 #Two-integer timestamp that is expressed as: 00036 # * stamp.secs: seconds (stamp_secs) since epoch 00037 # * stamp.nsecs: nanoseconds since stamp_secs 00038 # time-handling sugar is provided by the client library 00039 time stamp 00040 #Frame this data is associated with 00041 # 0: no frame 00042 # 1: global frame 00043 string frame_id 00044 00045 ================================================================================ 00046 MSG: geometry_msgs/Pose 00047 # A representation of pose in free space, composed of postion and orientation. 00048 Point position 00049 Quaternion orientation 00050 00051 ================================================================================ 00052 MSG: geometry_msgs/Point 00053 # This contains the position of a point in free space 00054 float64 x 00055 float64 y 00056 float64 z 00057 00058 ================================================================================ 00059 MSG: geometry_msgs/Quaternion 00060 # This represents an orientation in free space in quaternion form. 00061 00062 float64 x 00063 float64 y 00064 float64 z 00065 float64 w 00066 00067 ================================================================================ 00068 MSG: geometry_msgs/Vector3 00069 # This represents a vector in free space. 00070 00071 float64 x 00072 float64 y 00073 float64 z 00074 """ 00075 # Pseudo-constants 00076 GLOBAL_SEARCH = 0 00077 LOCAL_SEARCH = 1 00078 SINGLE_POSE = 2 00079 00080 __slots__ = ['grasp_pose','roi_dims','search_mode'] 00081 _slot_types = ['geometry_msgs/PoseStamped','geometry_msgs/Vector3','uint8'] 00082 00083 def __init__(self, *args, **kwds): 00084 """ 00085 Constructor. Any message fields that are implicitly/explicitly 00086 set to None will be assigned a default value. The recommend 00087 use is keyword arguments as this is more robust to future message 00088 changes. You cannot mix in-order arguments and keyword arguments. 00089 00090 The available fields are: 00091 grasp_pose,roi_dims,search_mode 00092 00093 @param args: complete set of field values, in .msg order 00094 @param kwds: use keyword arguments corresponding to message field names 00095 to set specific fields. 00096 """ 00097 if args or kwds: 00098 super(GraspAdjustRequest, self).__init__(*args, **kwds) 00099 #message fields cannot be None, assign default values for those that are 00100 if self.grasp_pose is None: 00101 self.grasp_pose = geometry_msgs.msg.PoseStamped() 00102 if self.roi_dims is None: 00103 self.roi_dims = geometry_msgs.msg.Vector3() 00104 if self.search_mode is None: 00105 self.search_mode = 0 00106 else: 00107 self.grasp_pose = geometry_msgs.msg.PoseStamped() 00108 self.roi_dims = geometry_msgs.msg.Vector3() 00109 self.search_mode = 0 00110 00111 def _get_types(self): 00112 """ 00113 internal API method 00114 """ 00115 return self._slot_types 00116 00117 def serialize(self, buff): 00118 """ 00119 serialize message into buffer 00120 @param buff: buffer 00121 @type buff: StringIO 00122 """ 00123 try: 00124 _x = self 00125 buff.write(_struct_3I.pack(_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs)) 00126 _x = self.grasp_pose.header.frame_id 00127 length = len(_x) 00128 buff.write(struct.pack('<I%ss'%length, length, _x)) 00129 _x = self 00130 buff.write(_struct_10dB.pack(_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode)) 00131 except struct.error as se: self._check_types(se) 00132 except TypeError as te: self._check_types(te) 00133 00134 def deserialize(self, str): 00135 """ 00136 unpack serialized message in str into this message instance 00137 @param str: byte array of serialized message 00138 @type str: str 00139 """ 00140 try: 00141 if self.grasp_pose is None: 00142 self.grasp_pose = geometry_msgs.msg.PoseStamped() 00143 if self.roi_dims is None: 00144 self.roi_dims = geometry_msgs.msg.Vector3() 00145 end = 0 00146 _x = self 00147 start = end 00148 end += 12 00149 (_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00150 start = end 00151 end += 4 00152 (length,) = _struct_I.unpack(str[start:end]) 00153 start = end 00154 end += length 00155 self.grasp_pose.header.frame_id = str[start:end] 00156 _x = self 00157 start = end 00158 end += 81 00159 (_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode,) = _struct_10dB.unpack(str[start:end]) 00160 return self 00161 except struct.error as e: 00162 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00163 00164 00165 def serialize_numpy(self, buff, numpy): 00166 """ 00167 serialize message with numpy array types into buffer 00168 @param buff: buffer 00169 @type buff: StringIO 00170 @param numpy: numpy python module 00171 @type numpy module 00172 """ 00173 try: 00174 _x = self 00175 buff.write(_struct_3I.pack(_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs)) 00176 _x = self.grasp_pose.header.frame_id 00177 length = len(_x) 00178 buff.write(struct.pack('<I%ss'%length, length, _x)) 00179 _x = self 00180 buff.write(_struct_10dB.pack(_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode)) 00181 except struct.error as se: self._check_types(se) 00182 except TypeError as te: self._check_types(te) 00183 00184 def deserialize_numpy(self, str, numpy): 00185 """ 00186 unpack serialized message in str into this message instance using numpy for array types 00187 @param str: byte array of serialized message 00188 @type str: str 00189 @param numpy: numpy python module 00190 @type numpy: module 00191 """ 00192 try: 00193 if self.grasp_pose is None: 00194 self.grasp_pose = geometry_msgs.msg.PoseStamped() 00195 if self.roi_dims is None: 00196 self.roi_dims = geometry_msgs.msg.Vector3() 00197 end = 0 00198 _x = self 00199 start = end 00200 end += 12 00201 (_x.grasp_pose.header.seq, _x.grasp_pose.header.stamp.secs, _x.grasp_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00202 start = end 00203 end += 4 00204 (length,) = _struct_I.unpack(str[start:end]) 00205 start = end 00206 end += length 00207 self.grasp_pose.header.frame_id = str[start:end] 00208 _x = self 00209 start = end 00210 end += 81 00211 (_x.grasp_pose.pose.position.x, _x.grasp_pose.pose.position.y, _x.grasp_pose.pose.position.z, _x.grasp_pose.pose.orientation.x, _x.grasp_pose.pose.orientation.y, _x.grasp_pose.pose.orientation.z, _x.grasp_pose.pose.orientation.w, _x.roi_dims.x, _x.roi_dims.y, _x.roi_dims.z, _x.search_mode,) = _struct_10dB.unpack(str[start:end]) 00212 return self 00213 except struct.error as e: 00214 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00215 00216 _struct_I = roslib.message.struct_I 00217 _struct_10dB = struct.Struct("<10dB") 00218 _struct_3I = struct.Struct("<3I") 00219 """autogenerated by genmsg_py from GraspAdjustResponse.msg. Do not edit.""" 00220 import roslib.message 00221 import struct 00222 00223 import geometry_msgs.msg 00224 import object_manipulation_msgs.msg 00225 import std_msgs.msg 00226 00227 class GraspAdjustResponse(roslib.message.Message): 00228 _md5sum = "8204d8a3e105f84787abc62e550e0312" 00229 _type = "pr2_grasp_adjust/GraspAdjustResponse" 00230 _has_header = False #flag to mark the presence of a Header object 00231 _full_text = """geometry_msgs/PoseStamped[] grasp_poses 00232 float64[] pose_scores 00233 float32[] gripper_openings 00234 00235 object_manipulation_msgs/ManipulationResult result 00236 00237 00238 00239 ================================================================================ 00240 MSG: geometry_msgs/PoseStamped 00241 # A Pose with reference coordinate frame and timestamp 00242 Header header 00243 Pose pose 00244 00245 ================================================================================ 00246 MSG: std_msgs/Header 00247 # Standard metadata for higher-level stamped data types. 00248 # This is generally used to communicate timestamped data 00249 # in a particular coordinate frame. 00250 # 00251 # sequence ID: consecutively increasing ID 00252 uint32 seq 00253 #Two-integer timestamp that is expressed as: 00254 # * stamp.secs: seconds (stamp_secs) since epoch 00255 # * stamp.nsecs: nanoseconds since stamp_secs 00256 # time-handling sugar is provided by the client library 00257 time stamp 00258 #Frame this data is associated with 00259 # 0: no frame 00260 # 1: global frame 00261 string frame_id 00262 00263 ================================================================================ 00264 MSG: geometry_msgs/Pose 00265 # A representation of pose in free space, composed of postion and orientation. 00266 Point position 00267 Quaternion orientation 00268 00269 ================================================================================ 00270 MSG: geometry_msgs/Point 00271 # This contains the position of a point in free space 00272 float64 x 00273 float64 y 00274 float64 z 00275 00276 ================================================================================ 00277 MSG: geometry_msgs/Quaternion 00278 # This represents an orientation in free space in quaternion form. 00279 00280 float64 x 00281 float64 y 00282 float64 z 00283 float64 w 00284 00285 ================================================================================ 00286 MSG: object_manipulation_msgs/ManipulationResult 00287 # Result codes for manipulation tasks 00288 00289 # task completed as expected 00290 # generally means you can proceed as planned 00291 int32 SUCCESS = 1 00292 00293 # task not possible (e.g. out of reach or obstacles in the way) 00294 # generally means that the world was not disturbed, so you can try another task 00295 int32 UNFEASIBLE = -1 00296 00297 # task was thought possible, but failed due to unexpected events during execution 00298 # it is likely that the world was disturbed, so you are encouraged to refresh 00299 # your sensed world model before proceeding to another task 00300 int32 FAILED = -2 00301 00302 # a lower level error prevented task completion (e.g. joint controller not responding) 00303 # generally requires human attention 00304 int32 ERROR = -3 00305 00306 # means that at some point during execution we ended up in a state that the collision-aware 00307 # arm navigation module will not move out of. The world was likely not disturbed, but you 00308 # probably need a new collision map to move the arm out of the stuck position 00309 int32 ARM_MOVEMENT_PREVENTED = -4 00310 00311 # specific to grasp actions 00312 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested 00313 # it is likely that the collision environment will see collisions between the hand/object and the support surface 00314 int32 LIFT_FAILED = -5 00315 00316 # specific to place actions 00317 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested 00318 # it is likely that the collision environment will see collisions between the hand and the object 00319 int32 RETREAT_FAILED = -6 00320 00321 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else" 00322 int32 CANCELLED = -7 00323 00324 # the actual value of this error code 00325 int32 value 00326 00327 """ 00328 __slots__ = ['grasp_poses','pose_scores','gripper_openings','result'] 00329 _slot_types = ['geometry_msgs/PoseStamped[]','float64[]','float32[]','object_manipulation_msgs/ManipulationResult'] 00330 00331 def __init__(self, *args, **kwds): 00332 """ 00333 Constructor. Any message fields that are implicitly/explicitly 00334 set to None will be assigned a default value. The recommend 00335 use is keyword arguments as this is more robust to future message 00336 changes. You cannot mix in-order arguments and keyword arguments. 00337 00338 The available fields are: 00339 grasp_poses,pose_scores,gripper_openings,result 00340 00341 @param args: complete set of field values, in .msg order 00342 @param kwds: use keyword arguments corresponding to message field names 00343 to set specific fields. 00344 """ 00345 if args or kwds: 00346 super(GraspAdjustResponse, self).__init__(*args, **kwds) 00347 #message fields cannot be None, assign default values for those that are 00348 if self.grasp_poses is None: 00349 self.grasp_poses = [] 00350 if self.pose_scores is None: 00351 self.pose_scores = [] 00352 if self.gripper_openings is None: 00353 self.gripper_openings = [] 00354 if self.result is None: 00355 self.result = object_manipulation_msgs.msg.ManipulationResult() 00356 else: 00357 self.grasp_poses = [] 00358 self.pose_scores = [] 00359 self.gripper_openings = [] 00360 self.result = object_manipulation_msgs.msg.ManipulationResult() 00361 00362 def _get_types(self): 00363 """ 00364 internal API method 00365 """ 00366 return self._slot_types 00367 00368 def serialize(self, buff): 00369 """ 00370 serialize message into buffer 00371 @param buff: buffer 00372 @type buff: StringIO 00373 """ 00374 try: 00375 length = len(self.grasp_poses) 00376 buff.write(_struct_I.pack(length)) 00377 for val1 in self.grasp_poses: 00378 _v1 = val1.header 00379 buff.write(_struct_I.pack(_v1.seq)) 00380 _v2 = _v1.stamp 00381 _x = _v2 00382 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00383 _x = _v1.frame_id 00384 length = len(_x) 00385 buff.write(struct.pack('<I%ss'%length, length, _x)) 00386 _v3 = val1.pose 00387 _v4 = _v3.position 00388 _x = _v4 00389 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00390 _v5 = _v3.orientation 00391 _x = _v5 00392 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00393 length = len(self.pose_scores) 00394 buff.write(_struct_I.pack(length)) 00395 pattern = '<%sd'%length 00396 buff.write(struct.pack(pattern, *self.pose_scores)) 00397 length = len(self.gripper_openings) 00398 buff.write(_struct_I.pack(length)) 00399 pattern = '<%sf'%length 00400 buff.write(struct.pack(pattern, *self.gripper_openings)) 00401 buff.write(_struct_i.pack(self.result.value)) 00402 except struct.error as se: self._check_types(se) 00403 except TypeError as te: self._check_types(te) 00404 00405 def deserialize(self, str): 00406 """ 00407 unpack serialized message in str into this message instance 00408 @param str: byte array of serialized message 00409 @type str: str 00410 """ 00411 try: 00412 if self.result is None: 00413 self.result = object_manipulation_msgs.msg.ManipulationResult() 00414 end = 0 00415 start = end 00416 end += 4 00417 (length,) = _struct_I.unpack(str[start:end]) 00418 self.grasp_poses = [] 00419 for i in range(0, length): 00420 val1 = geometry_msgs.msg.PoseStamped() 00421 _v6 = val1.header 00422 start = end 00423 end += 4 00424 (_v6.seq,) = _struct_I.unpack(str[start:end]) 00425 _v7 = _v6.stamp 00426 _x = _v7 00427 start = end 00428 end += 8 00429 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00430 start = end 00431 end += 4 00432 (length,) = _struct_I.unpack(str[start:end]) 00433 start = end 00434 end += length 00435 _v6.frame_id = str[start:end] 00436 _v8 = val1.pose 00437 _v9 = _v8.position 00438 _x = _v9 00439 start = end 00440 end += 24 00441 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00442 _v10 = _v8.orientation 00443 _x = _v10 00444 start = end 00445 end += 32 00446 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00447 self.grasp_poses.append(val1) 00448 start = end 00449 end += 4 00450 (length,) = _struct_I.unpack(str[start:end]) 00451 pattern = '<%sd'%length 00452 start = end 00453 end += struct.calcsize(pattern) 00454 self.pose_scores = struct.unpack(pattern, str[start:end]) 00455 start = end 00456 end += 4 00457 (length,) = _struct_I.unpack(str[start:end]) 00458 pattern = '<%sf'%length 00459 start = end 00460 end += struct.calcsize(pattern) 00461 self.gripper_openings = struct.unpack(pattern, str[start:end]) 00462 start = end 00463 end += 4 00464 (self.result.value,) = _struct_i.unpack(str[start:end]) 00465 return self 00466 except struct.error as e: 00467 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00468 00469 00470 def serialize_numpy(self, buff, numpy): 00471 """ 00472 serialize message with numpy array types into buffer 00473 @param buff: buffer 00474 @type buff: StringIO 00475 @param numpy: numpy python module 00476 @type numpy module 00477 """ 00478 try: 00479 length = len(self.grasp_poses) 00480 buff.write(_struct_I.pack(length)) 00481 for val1 in self.grasp_poses: 00482 _v11 = val1.header 00483 buff.write(_struct_I.pack(_v11.seq)) 00484 _v12 = _v11.stamp 00485 _x = _v12 00486 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00487 _x = _v11.frame_id 00488 length = len(_x) 00489 buff.write(struct.pack('<I%ss'%length, length, _x)) 00490 _v13 = val1.pose 00491 _v14 = _v13.position 00492 _x = _v14 00493 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00494 _v15 = _v13.orientation 00495 _x = _v15 00496 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00497 length = len(self.pose_scores) 00498 buff.write(_struct_I.pack(length)) 00499 pattern = '<%sd'%length 00500 buff.write(self.pose_scores.tostring()) 00501 length = len(self.gripper_openings) 00502 buff.write(_struct_I.pack(length)) 00503 pattern = '<%sf'%length 00504 buff.write(self.gripper_openings.tostring()) 00505 buff.write(_struct_i.pack(self.result.value)) 00506 except struct.error as se: self._check_types(se) 00507 except TypeError as te: self._check_types(te) 00508 00509 def deserialize_numpy(self, str, numpy): 00510 """ 00511 unpack serialized message in str into this message instance using numpy for array types 00512 @param str: byte array of serialized message 00513 @type str: str 00514 @param numpy: numpy python module 00515 @type numpy: module 00516 """ 00517 try: 00518 if self.result is None: 00519 self.result = object_manipulation_msgs.msg.ManipulationResult() 00520 end = 0 00521 start = end 00522 end += 4 00523 (length,) = _struct_I.unpack(str[start:end]) 00524 self.grasp_poses = [] 00525 for i in range(0, length): 00526 val1 = geometry_msgs.msg.PoseStamped() 00527 _v16 = val1.header 00528 start = end 00529 end += 4 00530 (_v16.seq,) = _struct_I.unpack(str[start:end]) 00531 _v17 = _v16.stamp 00532 _x = _v17 00533 start = end 00534 end += 8 00535 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00536 start = end 00537 end += 4 00538 (length,) = _struct_I.unpack(str[start:end]) 00539 start = end 00540 end += length 00541 _v16.frame_id = str[start:end] 00542 _v18 = val1.pose 00543 _v19 = _v18.position 00544 _x = _v19 00545 start = end 00546 end += 24 00547 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00548 _v20 = _v18.orientation 00549 _x = _v20 00550 start = end 00551 end += 32 00552 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00553 self.grasp_poses.append(val1) 00554 start = end 00555 end += 4 00556 (length,) = _struct_I.unpack(str[start:end]) 00557 pattern = '<%sd'%length 00558 start = end 00559 end += struct.calcsize(pattern) 00560 self.pose_scores = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00561 start = end 00562 end += 4 00563 (length,) = _struct_I.unpack(str[start:end]) 00564 pattern = '<%sf'%length 00565 start = end 00566 end += struct.calcsize(pattern) 00567 self.gripper_openings = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 00568 start = end 00569 end += 4 00570 (self.result.value,) = _struct_i.unpack(str[start:end]) 00571 return self 00572 except struct.error as e: 00573 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00574 00575 _struct_I = roslib.message.struct_I 00576 _struct_i = struct.Struct("<i") 00577 _struct_4d = struct.Struct("<4d") 00578 _struct_2I = struct.Struct("<2I") 00579 _struct_3d = struct.Struct("<3d") 00580 class GraspAdjust(roslib.message.ServiceDefinition): 00581 _type = 'pr2_grasp_adjust/GraspAdjust' 00582 _md5sum = '155f94ed302ff095096df9b37ecc7886' 00583 _request_class = GraspAdjustRequest 00584 _response_class = GraspAdjustResponse