$search
00001 """autogenerated by genmsg_py from ModelHypothesisList.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import object_recognition_gui.msg 00006 import arm_navigation_msgs.msg 00007 import geometry_msgs.msg 00008 import std_msgs.msg 00009 00010 class ModelHypothesisList(roslib.message.Message): 00011 _md5sum = "8d08459b65fa27d555aca1d8d3e6c944" 00012 _type = "object_recognition_gui/ModelHypothesisList" 00013 _has_header = False #flag to mark the presence of a Header object 00014 _full_text = """ModelHypothesis[] hypotheses 00015 00016 #initial guess if this can be a correct recognition result at all 00017 bool accept 00018 ================================================================================ 00019 MSG: object_recognition_gui/ModelHypothesis 00020 #describes a hypothesis about a recognized object (mesh+pose) 00021 00022 arm_navigation_msgs/Shape mesh 00023 geometry_msgs/PoseStamped pose 00024 00025 ================================================================================ 00026 MSG: arm_navigation_msgs/Shape 00027 byte SPHERE=0 00028 byte BOX=1 00029 byte CYLINDER=2 00030 byte MESH=3 00031 00032 byte type 00033 00034 00035 #### define sphere, box, cylinder #### 00036 # the origin of each shape is considered at the shape's center 00037 00038 # for sphere 00039 # radius := dimensions[0] 00040 00041 # for cylinder 00042 # radius := dimensions[0] 00043 # length := dimensions[1] 00044 # the length is along the Z axis 00045 00046 # for box 00047 # size_x := dimensions[0] 00048 # size_y := dimensions[1] 00049 # size_z := dimensions[2] 00050 float64[] dimensions 00051 00052 00053 #### define mesh #### 00054 00055 # list of triangles; triangle k is defined by tre vertices located 00056 # at indices triangles[3k], triangles[3k+1], triangles[3k+2] 00057 int32[] triangles 00058 geometry_msgs/Point[] vertices 00059 00060 ================================================================================ 00061 MSG: geometry_msgs/Point 00062 # This contains the position of a point in free space 00063 float64 x 00064 float64 y 00065 float64 z 00066 00067 ================================================================================ 00068 MSG: geometry_msgs/PoseStamped 00069 # A Pose with reference coordinate frame and timestamp 00070 Header header 00071 Pose pose 00072 00073 ================================================================================ 00074 MSG: std_msgs/Header 00075 # Standard metadata for higher-level stamped data types. 00076 # This is generally used to communicate timestamped data 00077 # in a particular coordinate frame. 00078 # 00079 # sequence ID: consecutively increasing ID 00080 uint32 seq 00081 #Two-integer timestamp that is expressed as: 00082 # * stamp.secs: seconds (stamp_secs) since epoch 00083 # * stamp.nsecs: nanoseconds since stamp_secs 00084 # time-handling sugar is provided by the client library 00085 time stamp 00086 #Frame this data is associated with 00087 # 0: no frame 00088 # 1: global frame 00089 string frame_id 00090 00091 ================================================================================ 00092 MSG: geometry_msgs/Pose 00093 # A representation of pose in free space, composed of postion and orientation. 00094 Point position 00095 Quaternion orientation 00096 00097 ================================================================================ 00098 MSG: geometry_msgs/Quaternion 00099 # This represents an orientation in free space in quaternion form. 00100 00101 float64 x 00102 float64 y 00103 float64 z 00104 float64 w 00105 00106 """ 00107 __slots__ = ['hypotheses','accept'] 00108 _slot_types = ['object_recognition_gui/ModelHypothesis[]','bool'] 00109 00110 def __init__(self, *args, **kwds): 00111 """ 00112 Constructor. Any message fields that are implicitly/explicitly 00113 set to None will be assigned a default value. The recommend 00114 use is keyword arguments as this is more robust to future message 00115 changes. You cannot mix in-order arguments and keyword arguments. 00116 00117 The available fields are: 00118 hypotheses,accept 00119 00120 @param args: complete set of field values, in .msg order 00121 @param kwds: use keyword arguments corresponding to message field names 00122 to set specific fields. 00123 """ 00124 if args or kwds: 00125 super(ModelHypothesisList, self).__init__(*args, **kwds) 00126 #message fields cannot be None, assign default values for those that are 00127 if self.hypotheses is None: 00128 self.hypotheses = [] 00129 if self.accept is None: 00130 self.accept = False 00131 else: 00132 self.hypotheses = [] 00133 self.accept = False 00134 00135 def _get_types(self): 00136 """ 00137 internal API method 00138 """ 00139 return self._slot_types 00140 00141 def serialize(self, buff): 00142 """ 00143 serialize message into buffer 00144 @param buff: buffer 00145 @type buff: StringIO 00146 """ 00147 try: 00148 length = len(self.hypotheses) 00149 buff.write(_struct_I.pack(length)) 00150 for val1 in self.hypotheses: 00151 _v1 = val1.mesh 00152 buff.write(_struct_b.pack(_v1.type)) 00153 length = len(_v1.dimensions) 00154 buff.write(_struct_I.pack(length)) 00155 pattern = '<%sd'%length 00156 buff.write(struct.pack(pattern, *_v1.dimensions)) 00157 length = len(_v1.triangles) 00158 buff.write(_struct_I.pack(length)) 00159 pattern = '<%si'%length 00160 buff.write(struct.pack(pattern, *_v1.triangles)) 00161 length = len(_v1.vertices) 00162 buff.write(_struct_I.pack(length)) 00163 for val3 in _v1.vertices: 00164 _x = val3 00165 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00166 _v2 = val1.pose 00167 _v3 = _v2.header 00168 buff.write(_struct_I.pack(_v3.seq)) 00169 _v4 = _v3.stamp 00170 _x = _v4 00171 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00172 _x = _v3.frame_id 00173 length = len(_x) 00174 buff.write(struct.pack('<I%ss'%length, length, _x)) 00175 _v5 = _v2.pose 00176 _v6 = _v5.position 00177 _x = _v6 00178 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00179 _v7 = _v5.orientation 00180 _x = _v7 00181 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00182 buff.write(_struct_B.pack(self.accept)) 00183 except struct.error as se: self._check_types(se) 00184 except TypeError as te: self._check_types(te) 00185 00186 def deserialize(self, str): 00187 """ 00188 unpack serialized message in str into this message instance 00189 @param str: byte array of serialized message 00190 @type str: str 00191 """ 00192 try: 00193 end = 0 00194 start = end 00195 end += 4 00196 (length,) = _struct_I.unpack(str[start:end]) 00197 self.hypotheses = [] 00198 for i in range(0, length): 00199 val1 = object_recognition_gui.msg.ModelHypothesis() 00200 _v8 = val1.mesh 00201 start = end 00202 end += 1 00203 (_v8.type,) = _struct_b.unpack(str[start:end]) 00204 start = end 00205 end += 4 00206 (length,) = _struct_I.unpack(str[start:end]) 00207 pattern = '<%sd'%length 00208 start = end 00209 end += struct.calcsize(pattern) 00210 _v8.dimensions = struct.unpack(pattern, str[start:end]) 00211 start = end 00212 end += 4 00213 (length,) = _struct_I.unpack(str[start:end]) 00214 pattern = '<%si'%length 00215 start = end 00216 end += struct.calcsize(pattern) 00217 _v8.triangles = struct.unpack(pattern, str[start:end]) 00218 start = end 00219 end += 4 00220 (length,) = _struct_I.unpack(str[start:end]) 00221 _v8.vertices = [] 00222 for i in range(0, length): 00223 val3 = geometry_msgs.msg.Point() 00224 _x = val3 00225 start = end 00226 end += 24 00227 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00228 _v8.vertices.append(val3) 00229 _v9 = val1.pose 00230 _v10 = _v9.header 00231 start = end 00232 end += 4 00233 (_v10.seq,) = _struct_I.unpack(str[start:end]) 00234 _v11 = _v10.stamp 00235 _x = _v11 00236 start = end 00237 end += 8 00238 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00239 start = end 00240 end += 4 00241 (length,) = _struct_I.unpack(str[start:end]) 00242 start = end 00243 end += length 00244 _v10.frame_id = str[start:end] 00245 _v12 = _v9.pose 00246 _v13 = _v12.position 00247 _x = _v13 00248 start = end 00249 end += 24 00250 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00251 _v14 = _v12.orientation 00252 _x = _v14 00253 start = end 00254 end += 32 00255 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00256 self.hypotheses.append(val1) 00257 start = end 00258 end += 1 00259 (self.accept,) = _struct_B.unpack(str[start:end]) 00260 self.accept = bool(self.accept) 00261 return self 00262 except struct.error as e: 00263 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00264 00265 00266 def serialize_numpy(self, buff, numpy): 00267 """ 00268 serialize message with numpy array types into buffer 00269 @param buff: buffer 00270 @type buff: StringIO 00271 @param numpy: numpy python module 00272 @type numpy module 00273 """ 00274 try: 00275 length = len(self.hypotheses) 00276 buff.write(_struct_I.pack(length)) 00277 for val1 in self.hypotheses: 00278 _v15 = val1.mesh 00279 buff.write(_struct_b.pack(_v15.type)) 00280 length = len(_v15.dimensions) 00281 buff.write(_struct_I.pack(length)) 00282 pattern = '<%sd'%length 00283 buff.write(_v15.dimensions.tostring()) 00284 length = len(_v15.triangles) 00285 buff.write(_struct_I.pack(length)) 00286 pattern = '<%si'%length 00287 buff.write(_v15.triangles.tostring()) 00288 length = len(_v15.vertices) 00289 buff.write(_struct_I.pack(length)) 00290 for val3 in _v15.vertices: 00291 _x = val3 00292 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00293 _v16 = val1.pose 00294 _v17 = _v16.header 00295 buff.write(_struct_I.pack(_v17.seq)) 00296 _v18 = _v17.stamp 00297 _x = _v18 00298 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00299 _x = _v17.frame_id 00300 length = len(_x) 00301 buff.write(struct.pack('<I%ss'%length, length, _x)) 00302 _v19 = _v16.pose 00303 _v20 = _v19.position 00304 _x = _v20 00305 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00306 _v21 = _v19.orientation 00307 _x = _v21 00308 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00309 buff.write(_struct_B.pack(self.accept)) 00310 except struct.error as se: self._check_types(se) 00311 except TypeError as te: self._check_types(te) 00312 00313 def deserialize_numpy(self, str, numpy): 00314 """ 00315 unpack serialized message in str into this message instance using numpy for array types 00316 @param str: byte array of serialized message 00317 @type str: str 00318 @param numpy: numpy python module 00319 @type numpy: module 00320 """ 00321 try: 00322 end = 0 00323 start = end 00324 end += 4 00325 (length,) = _struct_I.unpack(str[start:end]) 00326 self.hypotheses = [] 00327 for i in range(0, length): 00328 val1 = object_recognition_gui.msg.ModelHypothesis() 00329 _v22 = val1.mesh 00330 start = end 00331 end += 1 00332 (_v22.type,) = _struct_b.unpack(str[start:end]) 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 _v22.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00340 start = end 00341 end += 4 00342 (length,) = _struct_I.unpack(str[start:end]) 00343 pattern = '<%si'%length 00344 start = end 00345 end += struct.calcsize(pattern) 00346 _v22.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00347 start = end 00348 end += 4 00349 (length,) = _struct_I.unpack(str[start:end]) 00350 _v22.vertices = [] 00351 for i in range(0, length): 00352 val3 = geometry_msgs.msg.Point() 00353 _x = val3 00354 start = end 00355 end += 24 00356 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00357 _v22.vertices.append(val3) 00358 _v23 = val1.pose 00359 _v24 = _v23.header 00360 start = end 00361 end += 4 00362 (_v24.seq,) = _struct_I.unpack(str[start:end]) 00363 _v25 = _v24.stamp 00364 _x = _v25 00365 start = end 00366 end += 8 00367 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00368 start = end 00369 end += 4 00370 (length,) = _struct_I.unpack(str[start:end]) 00371 start = end 00372 end += length 00373 _v24.frame_id = str[start:end] 00374 _v26 = _v23.pose 00375 _v27 = _v26.position 00376 _x = _v27 00377 start = end 00378 end += 24 00379 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00380 _v28 = _v26.orientation 00381 _x = _v28 00382 start = end 00383 end += 32 00384 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00385 self.hypotheses.append(val1) 00386 start = end 00387 end += 1 00388 (self.accept,) = _struct_B.unpack(str[start:end]) 00389 self.accept = bool(self.accept) 00390 return self 00391 except struct.error as e: 00392 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00393 00394 _struct_I = roslib.message.struct_I 00395 _struct_b = struct.Struct("<b") 00396 _struct_B = struct.Struct("<B") 00397 _struct_4d = struct.Struct("<4d") 00398 _struct_2I = struct.Struct("<2I") 00399 _struct_3d = struct.Struct("<3d")