00001 """autogenerated by genpy from iri_perception_msgs/detection.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
00009 class detection(genpy.Message):
00010 _md5sum = "4c99ac73fd86f80cae8aed3c8660456c"
00011 _type = "iri_perception_msgs/detection"
00012 _has_header = False
00013 _full_text = """geometry_msgs/Point position
00014 geometry_msgs/Point velocity
00015 float32[36] covariances
00016 int32 id
00017 float32 probability
00018
00019 ================================================================================
00020 MSG: geometry_msgs/Point
00021 # This contains the position of a point in free space
00022 float64 x
00023 float64 y
00024 float64 z
00025
00026 """
00027 __slots__ = ['position','velocity','covariances','id','probability']
00028 _slot_types = ['geometry_msgs/Point','geometry_msgs/Point','float32[36]','int32','float32']
00029
00030 def __init__(self, *args, **kwds):
00031 """
00032 Constructor. Any message fields that are implicitly/explicitly
00033 set to None will be assigned a default value. The recommend
00034 use is keyword arguments as this is more robust to future message
00035 changes. You cannot mix in-order arguments and keyword arguments.
00036
00037 The available fields are:
00038 position,velocity,covariances,id,probability
00039
00040 :param args: complete set of field values, in .msg order
00041 :param kwds: use keyword arguments corresponding to message field names
00042 to set specific fields.
00043 """
00044 if args or kwds:
00045 super(detection, self).__init__(*args, **kwds)
00046
00047 if self.position is None:
00048 self.position = geometry_msgs.msg.Point()
00049 if self.velocity is None:
00050 self.velocity = geometry_msgs.msg.Point()
00051 if self.covariances is None:
00052 self.covariances = [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.]
00053 if self.id is None:
00054 self.id = 0
00055 if self.probability is None:
00056 self.probability = 0.
00057 else:
00058 self.position = geometry_msgs.msg.Point()
00059 self.velocity = geometry_msgs.msg.Point()
00060 self.covariances = [0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.,0.]
00061 self.id = 0
00062 self.probability = 0.
00063
00064 def _get_types(self):
00065 """
00066 internal API method
00067 """
00068 return self._slot_types
00069
00070 def serialize(self, buff):
00071 """
00072 serialize message into buffer
00073 :param buff: buffer, ``StringIO``
00074 """
00075 try:
00076 _x = self
00077 buff.write(_struct_6d.pack(_x.position.x, _x.position.y, _x.position.z, _x.velocity.x, _x.velocity.y, _x.velocity.z))
00078 buff.write(_struct_36f.pack(*self.covariances))
00079 _x = self
00080 buff.write(_struct_if.pack(_x.id, _x.probability))
00081 except struct.error as se: self._check_types(se)
00082 except TypeError as te: self._check_types(te)
00083
00084 def deserialize(self, str):
00085 """
00086 unpack serialized message in str into this message instance
00087 :param str: byte array of serialized message, ``str``
00088 """
00089 try:
00090 if self.position is None:
00091 self.position = geometry_msgs.msg.Point()
00092 if self.velocity is None:
00093 self.velocity = geometry_msgs.msg.Point()
00094 end = 0
00095 _x = self
00096 start = end
00097 end += 48
00098 (_x.position.x, _x.position.y, _x.position.z, _x.velocity.x, _x.velocity.y, _x.velocity.z,) = _struct_6d.unpack(str[start:end])
00099 start = end
00100 end += 144
00101 self.covariances = _struct_36f.unpack(str[start:end])
00102 _x = self
00103 start = end
00104 end += 8
00105 (_x.id, _x.probability,) = _struct_if.unpack(str[start:end])
00106 return self
00107 except struct.error as e:
00108 raise genpy.DeserializationError(e)
00109
00110
00111 def serialize_numpy(self, buff, numpy):
00112 """
00113 serialize message with numpy array types into buffer
00114 :param buff: buffer, ``StringIO``
00115 :param numpy: numpy python module
00116 """
00117 try:
00118 _x = self
00119 buff.write(_struct_6d.pack(_x.position.x, _x.position.y, _x.position.z, _x.velocity.x, _x.velocity.y, _x.velocity.z))
00120 buff.write(self.covariances.tostring())
00121 _x = self
00122 buff.write(_struct_if.pack(_x.id, _x.probability))
00123 except struct.error as se: self._check_types(se)
00124 except TypeError as te: self._check_types(te)
00125
00126 def deserialize_numpy(self, str, numpy):
00127 """
00128 unpack serialized message in str into this message instance using numpy for array types
00129 :param str: byte array of serialized message, ``str``
00130 :param numpy: numpy python module
00131 """
00132 try:
00133 if self.position is None:
00134 self.position = geometry_msgs.msg.Point()
00135 if self.velocity is None:
00136 self.velocity = geometry_msgs.msg.Point()
00137 end = 0
00138 _x = self
00139 start = end
00140 end += 48
00141 (_x.position.x, _x.position.y, _x.position.z, _x.velocity.x, _x.velocity.y, _x.velocity.z,) = _struct_6d.unpack(str[start:end])
00142 start = end
00143 end += 144
00144 self.covariances = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=36)
00145 _x = self
00146 start = end
00147 end += 8
00148 (_x.id, _x.probability,) = _struct_if.unpack(str[start:end])
00149 return self
00150 except struct.error as e:
00151 raise genpy.DeserializationError(e)
00152
00153 _struct_I = genpy.struct_I
00154 _struct_36f = struct.Struct("<36f")
00155 _struct_6d = struct.Struct("<6d")
00156 _struct_if = struct.Struct("<if")