$search
00001 """autogenerated by genmsg_py from VerifyGraspRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 00007 class VerifyGraspRequest(roslib.message.Message): 00008 _md5sum = "3ea5e3d1b2abb601b42af9afe28d351f" 00009 _type = "graspit_ros_planning_msgs/VerifyGraspRequest" 00010 _has_header = False #flag to mark the presence of a Header object 00011 _full_text = """ 00012 00013 00014 int32 scaled_model_id 00015 00016 geometry_msgs/Pose grasp_pose 00017 00018 float64 grasp_joint_angle 00019 00020 string table_file_name 00021 00022 00023 ================================================================================ 00024 MSG: geometry_msgs/Pose 00025 # A representation of pose in free space, composed of postion and orientation. 00026 Point position 00027 Quaternion orientation 00028 00029 ================================================================================ 00030 MSG: geometry_msgs/Point 00031 # This contains the position of a point in free space 00032 float64 x 00033 float64 y 00034 float64 z 00035 00036 ================================================================================ 00037 MSG: geometry_msgs/Quaternion 00038 # This represents an orientation in free space in quaternion form. 00039 00040 float64 x 00041 float64 y 00042 float64 z 00043 float64 w 00044 00045 """ 00046 __slots__ = ['scaled_model_id','grasp_pose','grasp_joint_angle','table_file_name'] 00047 _slot_types = ['int32','geometry_msgs/Pose','float64','string'] 00048 00049 def __init__(self, *args, **kwds): 00050 """ 00051 Constructor. Any message fields that are implicitly/explicitly 00052 set to None will be assigned a default value. The recommend 00053 use is keyword arguments as this is more robust to future message 00054 changes. You cannot mix in-order arguments and keyword arguments. 00055 00056 The available fields are: 00057 scaled_model_id,grasp_pose,grasp_joint_angle,table_file_name 00058 00059 @param args: complete set of field values, in .msg order 00060 @param kwds: use keyword arguments corresponding to message field names 00061 to set specific fields. 00062 """ 00063 if args or kwds: 00064 super(VerifyGraspRequest, self).__init__(*args, **kwds) 00065 #message fields cannot be None, assign default values for those that are 00066 if self.scaled_model_id is None: 00067 self.scaled_model_id = 0 00068 if self.grasp_pose is None: 00069 self.grasp_pose = geometry_msgs.msg.Pose() 00070 if self.grasp_joint_angle is None: 00071 self.grasp_joint_angle = 0. 00072 if self.table_file_name is None: 00073 self.table_file_name = '' 00074 else: 00075 self.scaled_model_id = 0 00076 self.grasp_pose = geometry_msgs.msg.Pose() 00077 self.grasp_joint_angle = 0. 00078 self.table_file_name = '' 00079 00080 def _get_types(self): 00081 """ 00082 internal API method 00083 """ 00084 return self._slot_types 00085 00086 def serialize(self, buff): 00087 """ 00088 serialize message into buffer 00089 @param buff: buffer 00090 @type buff: StringIO 00091 """ 00092 try: 00093 _x = self 00094 buff.write(_struct_i8d.pack(_x.scaled_model_id, _x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.grasp_joint_angle)) 00095 _x = self.table_file_name 00096 length = len(_x) 00097 buff.write(struct.pack('<I%ss'%length, length, _x)) 00098 except struct.error as se: self._check_types(se) 00099 except TypeError as te: self._check_types(te) 00100 00101 def deserialize(self, str): 00102 """ 00103 unpack serialized message in str into this message instance 00104 @param str: byte array of serialized message 00105 @type str: str 00106 """ 00107 try: 00108 if self.grasp_pose is None: 00109 self.grasp_pose = geometry_msgs.msg.Pose() 00110 end = 0 00111 _x = self 00112 start = end 00113 end += 68 00114 (_x.scaled_model_id, _x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.grasp_joint_angle,) = _struct_i8d.unpack(str[start:end]) 00115 start = end 00116 end += 4 00117 (length,) = _struct_I.unpack(str[start:end]) 00118 start = end 00119 end += length 00120 self.table_file_name = str[start:end] 00121 return self 00122 except struct.error as e: 00123 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00124 00125 00126 def serialize_numpy(self, buff, numpy): 00127 """ 00128 serialize message with numpy array types into buffer 00129 @param buff: buffer 00130 @type buff: StringIO 00131 @param numpy: numpy python module 00132 @type numpy module 00133 """ 00134 try: 00135 _x = self 00136 buff.write(_struct_i8d.pack(_x.scaled_model_id, _x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.grasp_joint_angle)) 00137 _x = self.table_file_name 00138 length = len(_x) 00139 buff.write(struct.pack('<I%ss'%length, length, _x)) 00140 except struct.error as se: self._check_types(se) 00141 except TypeError as te: self._check_types(te) 00142 00143 def deserialize_numpy(self, str, numpy): 00144 """ 00145 unpack serialized message in str into this message instance using numpy for array types 00146 @param str: byte array of serialized message 00147 @type str: str 00148 @param numpy: numpy python module 00149 @type numpy: module 00150 """ 00151 try: 00152 if self.grasp_pose is None: 00153 self.grasp_pose = geometry_msgs.msg.Pose() 00154 end = 0 00155 _x = self 00156 start = end 00157 end += 68 00158 (_x.scaled_model_id, _x.grasp_pose.position.x, _x.grasp_pose.position.y, _x.grasp_pose.position.z, _x.grasp_pose.orientation.x, _x.grasp_pose.orientation.y, _x.grasp_pose.orientation.z, _x.grasp_pose.orientation.w, _x.grasp_joint_angle,) = _struct_i8d.unpack(str[start:end]) 00159 start = end 00160 end += 4 00161 (length,) = _struct_I.unpack(str[start:end]) 00162 start = end 00163 end += length 00164 self.table_file_name = str[start:end] 00165 return self 00166 except struct.error as e: 00167 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00168 00169 _struct_I = roslib.message.struct_I 00170 _struct_i8d = struct.Struct("<i8d") 00171 """autogenerated by genmsg_py from VerifyGraspResponse.msg. Do not edit.""" 00172 import roslib.message 00173 import struct 00174 00175 00176 class VerifyGraspResponse(roslib.message.Message): 00177 _md5sum = "264475d04654958284f6216319e478e9" 00178 _type = "graspit_ros_planning_msgs/VerifyGraspResponse" 00179 _has_header = False #flag to mark the presence of a Header object 00180 _full_text = """ 00181 bool hand_environment_collision 00182 00183 bool hand_object_collision 00184 00185 float64 gripper_tabletop_clearance 00186 00187 float64 gripper_object_distance 00188 00189 00190 int32 LOAD_OBJECT_FAILURE = 0 00191 int32 LOAD_OBSTACLE_FAILURE = 1 00192 int32 LOAD_GRIPPER_FAILURE = 2 00193 int32 CHECK_SUCCESS = 3 00194 int32 result 00195 00196 00197 """ 00198 # Pseudo-constants 00199 LOAD_OBJECT_FAILURE = 0 00200 LOAD_OBSTACLE_FAILURE = 1 00201 LOAD_GRIPPER_FAILURE = 2 00202 CHECK_SUCCESS = 3 00203 00204 __slots__ = ['hand_environment_collision','hand_object_collision','gripper_tabletop_clearance','gripper_object_distance','result'] 00205 _slot_types = ['bool','bool','float64','float64','int32'] 00206 00207 def __init__(self, *args, **kwds): 00208 """ 00209 Constructor. Any message fields that are implicitly/explicitly 00210 set to None will be assigned a default value. The recommend 00211 use is keyword arguments as this is more robust to future message 00212 changes. You cannot mix in-order arguments and keyword arguments. 00213 00214 The available fields are: 00215 hand_environment_collision,hand_object_collision,gripper_tabletop_clearance,gripper_object_distance,result 00216 00217 @param args: complete set of field values, in .msg order 00218 @param kwds: use keyword arguments corresponding to message field names 00219 to set specific fields. 00220 """ 00221 if args or kwds: 00222 super(VerifyGraspResponse, self).__init__(*args, **kwds) 00223 #message fields cannot be None, assign default values for those that are 00224 if self.hand_environment_collision is None: 00225 self.hand_environment_collision = False 00226 if self.hand_object_collision is None: 00227 self.hand_object_collision = False 00228 if self.gripper_tabletop_clearance is None: 00229 self.gripper_tabletop_clearance = 0. 00230 if self.gripper_object_distance is None: 00231 self.gripper_object_distance = 0. 00232 if self.result is None: 00233 self.result = 0 00234 else: 00235 self.hand_environment_collision = False 00236 self.hand_object_collision = False 00237 self.gripper_tabletop_clearance = 0. 00238 self.gripper_object_distance = 0. 00239 self.result = 0 00240 00241 def _get_types(self): 00242 """ 00243 internal API method 00244 """ 00245 return self._slot_types 00246 00247 def serialize(self, buff): 00248 """ 00249 serialize message into buffer 00250 @param buff: buffer 00251 @type buff: StringIO 00252 """ 00253 try: 00254 _x = self 00255 buff.write(_struct_2B2di.pack(_x.hand_environment_collision, _x.hand_object_collision, _x.gripper_tabletop_clearance, _x.gripper_object_distance, _x.result)) 00256 except struct.error as se: self._check_types(se) 00257 except TypeError as te: self._check_types(te) 00258 00259 def deserialize(self, str): 00260 """ 00261 unpack serialized message in str into this message instance 00262 @param str: byte array of serialized message 00263 @type str: str 00264 """ 00265 try: 00266 end = 0 00267 _x = self 00268 start = end 00269 end += 22 00270 (_x.hand_environment_collision, _x.hand_object_collision, _x.gripper_tabletop_clearance, _x.gripper_object_distance, _x.result,) = _struct_2B2di.unpack(str[start:end]) 00271 self.hand_environment_collision = bool(self.hand_environment_collision) 00272 self.hand_object_collision = bool(self.hand_object_collision) 00273 return self 00274 except struct.error as e: 00275 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00276 00277 00278 def serialize_numpy(self, buff, numpy): 00279 """ 00280 serialize message with numpy array types into buffer 00281 @param buff: buffer 00282 @type buff: StringIO 00283 @param numpy: numpy python module 00284 @type numpy module 00285 """ 00286 try: 00287 _x = self 00288 buff.write(_struct_2B2di.pack(_x.hand_environment_collision, _x.hand_object_collision, _x.gripper_tabletop_clearance, _x.gripper_object_distance, _x.result)) 00289 except struct.error as se: self._check_types(se) 00290 except TypeError as te: self._check_types(te) 00291 00292 def deserialize_numpy(self, str, numpy): 00293 """ 00294 unpack serialized message in str into this message instance using numpy for array types 00295 @param str: byte array of serialized message 00296 @type str: str 00297 @param numpy: numpy python module 00298 @type numpy: module 00299 """ 00300 try: 00301 end = 0 00302 _x = self 00303 start = end 00304 end += 22 00305 (_x.hand_environment_collision, _x.hand_object_collision, _x.gripper_tabletop_clearance, _x.gripper_object_distance, _x.result,) = _struct_2B2di.unpack(str[start:end]) 00306 self.hand_environment_collision = bool(self.hand_environment_collision) 00307 self.hand_object_collision = bool(self.hand_object_collision) 00308 return self 00309 except struct.error as e: 00310 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00311 00312 _struct_I = roslib.message.struct_I 00313 _struct_2B2di = struct.Struct("<2B2di") 00314 class VerifyGrasp(roslib.message.ServiceDefinition): 00315 _type = 'graspit_ros_planning_msgs/VerifyGrasp' 00316 _md5sum = '14498cf3d29129af22a365ada2629e17' 00317 _request_class = VerifyGraspRequest 00318 _response_class = VerifyGraspResponse