00001 """autogenerated by genpy from ias_table_msgs/TableObjectReconstructed.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 TableObjectReconstructed(genpy.Message):
00010 _md5sum = "b4b3b5abce1b49d448a2f19def949463"
00011 _type = "ias_table_msgs/TableObjectReconstructed"
00012 _has_header = False
00013 _full_text = """# constants:
00014 uint32 PLANE=1
00015 uint32 SPHERE=2
00016 uint32 CYLINDER=4
00017 uint32 ROTATIONAL=8
00018 uint32 BOX=16
00019 uint32 MESH=32 # "else"
00020
00021 uint32 type # one of the above
00022 float64[] coefficients # depending on shape type
00023 float64 score # quality of fit
00024
00025 geometry_msgs/Point32[] vertices
00026 int32[] triangles # indices into vertices list
00027
00028
00029 ================================================================================
00030 MSG: geometry_msgs/Point32
00031 # This contains the position of a point in free space(with 32 bits of precision).
00032 # It is recommeded to use Point wherever possible instead of Point32.
00033 #
00034 # This recommendation is to promote interoperability.
00035 #
00036 # This message is designed to take up less space when sending
00037 # lots of points at once, as in the case of a PointCloud.
00038
00039 float32 x
00040 float32 y
00041 float32 z
00042 """
00043
00044 PLANE = 1
00045 SPHERE = 2
00046 CYLINDER = 4
00047 ROTATIONAL = 8
00048 BOX = 16
00049 MESH = 32
00050
00051 __slots__ = ['type','coefficients','score','vertices','triangles']
00052 _slot_types = ['uint32','float64[]','float64','geometry_msgs/Point32[]','int32[]']
00053
00054 def __init__(self, *args, **kwds):
00055 """
00056 Constructor. Any message fields that are implicitly/explicitly
00057 set to None will be assigned a default value. The recommend
00058 use is keyword arguments as this is more robust to future message
00059 changes. You cannot mix in-order arguments and keyword arguments.
00060
00061 The available fields are:
00062 type,coefficients,score,vertices,triangles
00063
00064 :param args: complete set of field values, in .msg order
00065 :param kwds: use keyword arguments corresponding to message field names
00066 to set specific fields.
00067 """
00068 if args or kwds:
00069 super(TableObjectReconstructed, self).__init__(*args, **kwds)
00070
00071 if self.type is None:
00072 self.type = 0
00073 if self.coefficients is None:
00074 self.coefficients = []
00075 if self.score is None:
00076 self.score = 0.
00077 if self.vertices is None:
00078 self.vertices = []
00079 if self.triangles is None:
00080 self.triangles = []
00081 else:
00082 self.type = 0
00083 self.coefficients = []
00084 self.score = 0.
00085 self.vertices = []
00086 self.triangles = []
00087
00088 def _get_types(self):
00089 """
00090 internal API method
00091 """
00092 return self._slot_types
00093
00094 def serialize(self, buff):
00095 """
00096 serialize message into buffer
00097 :param buff: buffer, ``StringIO``
00098 """
00099 try:
00100 buff.write(_struct_I.pack(self.type))
00101 length = len(self.coefficients)
00102 buff.write(_struct_I.pack(length))
00103 pattern = '<%sd'%length
00104 buff.write(struct.pack(pattern, *self.coefficients))
00105 buff.write(_struct_d.pack(self.score))
00106 length = len(self.vertices)
00107 buff.write(_struct_I.pack(length))
00108 for val1 in self.vertices:
00109 _x = val1
00110 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00111 length = len(self.triangles)
00112 buff.write(_struct_I.pack(length))
00113 pattern = '<%si'%length
00114 buff.write(struct.pack(pattern, *self.triangles))
00115 except struct.error as se: self._check_types(se)
00116 except TypeError as te: self._check_types(te)
00117
00118 def deserialize(self, str):
00119 """
00120 unpack serialized message in str into this message instance
00121 :param str: byte array of serialized message, ``str``
00122 """
00123 try:
00124 if self.vertices is None:
00125 self.vertices = None
00126 end = 0
00127 start = end
00128 end += 4
00129 (self.type,) = _struct_I.unpack(str[start:end])
00130 start = end
00131 end += 4
00132 (length,) = _struct_I.unpack(str[start:end])
00133 pattern = '<%sd'%length
00134 start = end
00135 end += struct.calcsize(pattern)
00136 self.coefficients = struct.unpack(pattern, str[start:end])
00137 start = end
00138 end += 8
00139 (self.score,) = _struct_d.unpack(str[start:end])
00140 start = end
00141 end += 4
00142 (length,) = _struct_I.unpack(str[start:end])
00143 self.vertices = []
00144 for i in range(0, length):
00145 val1 = geometry_msgs.msg.Point32()
00146 _x = val1
00147 start = end
00148 end += 12
00149 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00150 self.vertices.append(val1)
00151 start = end
00152 end += 4
00153 (length,) = _struct_I.unpack(str[start:end])
00154 pattern = '<%si'%length
00155 start = end
00156 end += struct.calcsize(pattern)
00157 self.triangles = struct.unpack(pattern, str[start:end])
00158 return self
00159 except struct.error as e:
00160 raise genpy.DeserializationError(e)
00161
00162
00163 def serialize_numpy(self, buff, numpy):
00164 """
00165 serialize message with numpy array types into buffer
00166 :param buff: buffer, ``StringIO``
00167 :param numpy: numpy python module
00168 """
00169 try:
00170 buff.write(_struct_I.pack(self.type))
00171 length = len(self.coefficients)
00172 buff.write(_struct_I.pack(length))
00173 pattern = '<%sd'%length
00174 buff.write(self.coefficients.tostring())
00175 buff.write(_struct_d.pack(self.score))
00176 length = len(self.vertices)
00177 buff.write(_struct_I.pack(length))
00178 for val1 in self.vertices:
00179 _x = val1
00180 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00181 length = len(self.triangles)
00182 buff.write(_struct_I.pack(length))
00183 pattern = '<%si'%length
00184 buff.write(self.triangles.tostring())
00185 except struct.error as se: self._check_types(se)
00186 except TypeError as te: self._check_types(te)
00187
00188 def deserialize_numpy(self, str, numpy):
00189 """
00190 unpack serialized message in str into this message instance using numpy for array types
00191 :param str: byte array of serialized message, ``str``
00192 :param numpy: numpy python module
00193 """
00194 try:
00195 if self.vertices is None:
00196 self.vertices = None
00197 end = 0
00198 start = end
00199 end += 4
00200 (self.type,) = _struct_I.unpack(str[start:end])
00201 start = end
00202 end += 4
00203 (length,) = _struct_I.unpack(str[start:end])
00204 pattern = '<%sd'%length
00205 start = end
00206 end += struct.calcsize(pattern)
00207 self.coefficients = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00208 start = end
00209 end += 8
00210 (self.score,) = _struct_d.unpack(str[start:end])
00211 start = end
00212 end += 4
00213 (length,) = _struct_I.unpack(str[start:end])
00214 self.vertices = []
00215 for i in range(0, length):
00216 val1 = geometry_msgs.msg.Point32()
00217 _x = val1
00218 start = end
00219 end += 12
00220 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00221 self.vertices.append(val1)
00222 start = end
00223 end += 4
00224 (length,) = _struct_I.unpack(str[start:end])
00225 pattern = '<%si'%length
00226 start = end
00227 end += struct.calcsize(pattern)
00228 self.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00229 return self
00230 except struct.error as e:
00231 raise genpy.DeserializationError(e)
00232
00233 _struct_I = genpy.struct_I
00234 _struct_d = struct.Struct("<d")
00235 _struct_3f = struct.Struct("<3f")