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