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


hector_worldmodel_msgs
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:36:27