00001 """autogenerated by genpy from mesh_label_node/LabelMeshRequest.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 triangle_mesh_msgs.msg
00009 import std_msgs.msg
00010
00011 class LabelMeshRequest(genpy.Message):
00012 _md5sum = "c9fa2982cc45237506b1b8c8a4d4623c"
00013 _type = "mesh_label_node/LabelMeshRequest"
00014 _has_header = False
00015 _full_text = """triangle_mesh_msgs/TriangleMesh mesh
00016
00017 ================================================================================
00018 MSG: triangle_mesh_msgs/TriangleMesh
00019 Header header
00020 geometry_msgs/Point32[] points
00021 geometry_msgs/Point32[] normals
00022 float32[] intensities
00023 triangle_mesh_msgs/Triangle[] triangles
00024 string sending_node
00025
00026 ================================================================================
00027 MSG: std_msgs/Header
00028 # Standard metadata for higher-level stamped data types.
00029 # This is generally used to communicate timestamped data
00030 # in a particular coordinate frame.
00031 #
00032 # sequence ID: consecutively increasing ID
00033 uint32 seq
00034 #Two-integer timestamp that is expressed as:
00035 # * stamp.secs: seconds (stamp_secs) since epoch
00036 # * stamp.nsecs: nanoseconds since stamp_secs
00037 # time-handling sugar is provided by the client library
00038 time stamp
00039 #Frame this data is associated with
00040 # 0: no frame
00041 # 1: global frame
00042 string frame_id
00043
00044 ================================================================================
00045 MSG: geometry_msgs/Point32
00046 # This contains the position of a point in free space(with 32 bits of precision).
00047 # It is recommeded to use Point wherever possible instead of Point32.
00048 #
00049 # This recommendation is to promote interoperability.
00050 #
00051 # This message is designed to take up less space when sending
00052 # lots of points at once, as in the case of a PointCloud.
00053
00054 float32 x
00055 float32 y
00056 float32 z
00057 ================================================================================
00058 MSG: triangle_mesh_msgs/Triangle
00059 int32 i
00060 int32 j
00061 int32 k
00062
00063
00064
00065 """
00066 __slots__ = ['mesh']
00067 _slot_types = ['triangle_mesh_msgs/TriangleMesh']
00068
00069 def __init__(self, *args, **kwds):
00070 """
00071 Constructor. Any message fields that are implicitly/explicitly
00072 set to None will be assigned a default value. The recommend
00073 use is keyword arguments as this is more robust to future message
00074 changes. You cannot mix in-order arguments and keyword arguments.
00075
00076 The available fields are:
00077 mesh
00078
00079 :param args: complete set of field values, in .msg order
00080 :param kwds: use keyword arguments corresponding to message field names
00081 to set specific fields.
00082 """
00083 if args or kwds:
00084 super(LabelMeshRequest, self).__init__(*args, **kwds)
00085
00086 if self.mesh is None:
00087 self.mesh = triangle_mesh_msgs.msg.TriangleMesh()
00088 else:
00089 self.mesh = triangle_mesh_msgs.msg.TriangleMesh()
00090
00091 def _get_types(self):
00092 """
00093 internal API method
00094 """
00095 return self._slot_types
00096
00097 def serialize(self, buff):
00098 """
00099 serialize message into buffer
00100 :param buff: buffer, ``StringIO``
00101 """
00102 try:
00103 _x = self
00104 buff.write(_struct_3I.pack(_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs))
00105 _x = self.mesh.header.frame_id
00106 length = len(_x)
00107 if python3 or type(_x) == unicode:
00108 _x = _x.encode('utf-8')
00109 length = len(_x)
00110 buff.write(struct.pack('<I%ss'%length, length, _x))
00111 length = len(self.mesh.points)
00112 buff.write(_struct_I.pack(length))
00113 for val1 in self.mesh.points:
00114 _x = val1
00115 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00116 length = len(self.mesh.normals)
00117 buff.write(_struct_I.pack(length))
00118 for val1 in self.mesh.normals:
00119 _x = val1
00120 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00121 length = len(self.mesh.intensities)
00122 buff.write(_struct_I.pack(length))
00123 pattern = '<%sf'%length
00124 buff.write(struct.pack(pattern, *self.mesh.intensities))
00125 length = len(self.mesh.triangles)
00126 buff.write(_struct_I.pack(length))
00127 for val1 in self.mesh.triangles:
00128 _x = val1
00129 buff.write(_struct_3i.pack(_x.i, _x.j, _x.k))
00130 _x = self.mesh.sending_node
00131 length = len(_x)
00132 if python3 or type(_x) == unicode:
00133 _x = _x.encode('utf-8')
00134 length = len(_x)
00135 buff.write(struct.pack('<I%ss'%length, length, _x))
00136 except struct.error as se: self._check_types(se)
00137 except TypeError as te: self._check_types(te)
00138
00139 def deserialize(self, str):
00140 """
00141 unpack serialized message in str into this message instance
00142 :param str: byte array of serialized message, ``str``
00143 """
00144 try:
00145 if self.mesh is None:
00146 self.mesh = triangle_mesh_msgs.msg.TriangleMesh()
00147 end = 0
00148 _x = self
00149 start = end
00150 end += 12
00151 (_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00152 start = end
00153 end += 4
00154 (length,) = _struct_I.unpack(str[start:end])
00155 start = end
00156 end += length
00157 if python3:
00158 self.mesh.header.frame_id = str[start:end].decode('utf-8')
00159 else:
00160 self.mesh.header.frame_id = str[start:end]
00161 start = end
00162 end += 4
00163 (length,) = _struct_I.unpack(str[start:end])
00164 self.mesh.points = []
00165 for i in range(0, length):
00166 val1 = geometry_msgs.msg.Point32()
00167 _x = val1
00168 start = end
00169 end += 12
00170 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00171 self.mesh.points.append(val1)
00172 start = end
00173 end += 4
00174 (length,) = _struct_I.unpack(str[start:end])
00175 self.mesh.normals = []
00176 for i in range(0, length):
00177 val1 = geometry_msgs.msg.Point32()
00178 _x = val1
00179 start = end
00180 end += 12
00181 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00182 self.mesh.normals.append(val1)
00183 start = end
00184 end += 4
00185 (length,) = _struct_I.unpack(str[start:end])
00186 pattern = '<%sf'%length
00187 start = end
00188 end += struct.calcsize(pattern)
00189 self.mesh.intensities = struct.unpack(pattern, str[start:end])
00190 start = end
00191 end += 4
00192 (length,) = _struct_I.unpack(str[start:end])
00193 self.mesh.triangles = []
00194 for i in range(0, length):
00195 val1 = triangle_mesh_msgs.msg.Triangle()
00196 _x = val1
00197 start = end
00198 end += 12
00199 (_x.i, _x.j, _x.k,) = _struct_3i.unpack(str[start:end])
00200 self.mesh.triangles.append(val1)
00201 start = end
00202 end += 4
00203 (length,) = _struct_I.unpack(str[start:end])
00204 start = end
00205 end += length
00206 if python3:
00207 self.mesh.sending_node = str[start:end].decode('utf-8')
00208 else:
00209 self.mesh.sending_node = str[start:end]
00210 return self
00211 except struct.error as e:
00212 raise genpy.DeserializationError(e)
00213
00214
00215 def serialize_numpy(self, buff, numpy):
00216 """
00217 serialize message with numpy array types into buffer
00218 :param buff: buffer, ``StringIO``
00219 :param numpy: numpy python module
00220 """
00221 try:
00222 _x = self
00223 buff.write(_struct_3I.pack(_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs))
00224 _x = self.mesh.header.frame_id
00225 length = len(_x)
00226 if python3 or type(_x) == unicode:
00227 _x = _x.encode('utf-8')
00228 length = len(_x)
00229 buff.write(struct.pack('<I%ss'%length, length, _x))
00230 length = len(self.mesh.points)
00231 buff.write(_struct_I.pack(length))
00232 for val1 in self.mesh.points:
00233 _x = val1
00234 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00235 length = len(self.mesh.normals)
00236 buff.write(_struct_I.pack(length))
00237 for val1 in self.mesh.normals:
00238 _x = val1
00239 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00240 length = len(self.mesh.intensities)
00241 buff.write(_struct_I.pack(length))
00242 pattern = '<%sf'%length
00243 buff.write(self.mesh.intensities.tostring())
00244 length = len(self.mesh.triangles)
00245 buff.write(_struct_I.pack(length))
00246 for val1 in self.mesh.triangles:
00247 _x = val1
00248 buff.write(_struct_3i.pack(_x.i, _x.j, _x.k))
00249 _x = self.mesh.sending_node
00250 length = len(_x)
00251 if python3 or type(_x) == unicode:
00252 _x = _x.encode('utf-8')
00253 length = len(_x)
00254 buff.write(struct.pack('<I%ss'%length, length, _x))
00255 except struct.error as se: self._check_types(se)
00256 except TypeError as te: self._check_types(te)
00257
00258 def deserialize_numpy(self, str, numpy):
00259 """
00260 unpack serialized message in str into this message instance using numpy for array types
00261 :param str: byte array of serialized message, ``str``
00262 :param numpy: numpy python module
00263 """
00264 try:
00265 if self.mesh is None:
00266 self.mesh = triangle_mesh_msgs.msg.TriangleMesh()
00267 end = 0
00268 _x = self
00269 start = end
00270 end += 12
00271 (_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00272 start = end
00273 end += 4
00274 (length,) = _struct_I.unpack(str[start:end])
00275 start = end
00276 end += length
00277 if python3:
00278 self.mesh.header.frame_id = str[start:end].decode('utf-8')
00279 else:
00280 self.mesh.header.frame_id = str[start:end]
00281 start = end
00282 end += 4
00283 (length,) = _struct_I.unpack(str[start:end])
00284 self.mesh.points = []
00285 for i in range(0, length):
00286 val1 = geometry_msgs.msg.Point32()
00287 _x = val1
00288 start = end
00289 end += 12
00290 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00291 self.mesh.points.append(val1)
00292 start = end
00293 end += 4
00294 (length,) = _struct_I.unpack(str[start:end])
00295 self.mesh.normals = []
00296 for i in range(0, length):
00297 val1 = geometry_msgs.msg.Point32()
00298 _x = val1
00299 start = end
00300 end += 12
00301 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00302 self.mesh.normals.append(val1)
00303 start = end
00304 end += 4
00305 (length,) = _struct_I.unpack(str[start:end])
00306 pattern = '<%sf'%length
00307 start = end
00308 end += struct.calcsize(pattern)
00309 self.mesh.intensities = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00310 start = end
00311 end += 4
00312 (length,) = _struct_I.unpack(str[start:end])
00313 self.mesh.triangles = []
00314 for i in range(0, length):
00315 val1 = triangle_mesh_msgs.msg.Triangle()
00316 _x = val1
00317 start = end
00318 end += 12
00319 (_x.i, _x.j, _x.k,) = _struct_3i.unpack(str[start:end])
00320 self.mesh.triangles.append(val1)
00321 start = end
00322 end += 4
00323 (length,) = _struct_I.unpack(str[start:end])
00324 start = end
00325 end += length
00326 if python3:
00327 self.mesh.sending_node = str[start:end].decode('utf-8')
00328 else:
00329 self.mesh.sending_node = str[start:end]
00330 return self
00331 except struct.error as e:
00332 raise genpy.DeserializationError(e)
00333
00334 _struct_I = genpy.struct_I
00335 _struct_3I = struct.Struct("<3I")
00336 _struct_3f = struct.Struct("<3f")
00337 _struct_3i = struct.Struct("<3i")
00338 """autogenerated by genpy from mesh_label_node/LabelMeshResponse.msg. Do not edit."""
00339 import sys
00340 python3 = True if sys.hexversion > 0x03000000 else False
00341 import genpy
00342 import struct
00343
00344
00345 class LabelMeshResponse(genpy.Message):
00346 _md5sum = "ea23f97416b04c6151d2b576c0665ac1"
00347 _type = "mesh_label_node/LabelMeshResponse"
00348 _has_header = False
00349 _full_text = """string label
00350
00351
00352 """
00353 __slots__ = ['label']
00354 _slot_types = ['string']
00355
00356 def __init__(self, *args, **kwds):
00357 """
00358 Constructor. Any message fields that are implicitly/explicitly
00359 set to None will be assigned a default value. The recommend
00360 use is keyword arguments as this is more robust to future message
00361 changes. You cannot mix in-order arguments and keyword arguments.
00362
00363 The available fields are:
00364 label
00365
00366 :param args: complete set of field values, in .msg order
00367 :param kwds: use keyword arguments corresponding to message field names
00368 to set specific fields.
00369 """
00370 if args or kwds:
00371 super(LabelMeshResponse, self).__init__(*args, **kwds)
00372
00373 if self.label is None:
00374 self.label = ''
00375 else:
00376 self.label = ''
00377
00378 def _get_types(self):
00379 """
00380 internal API method
00381 """
00382 return self._slot_types
00383
00384 def serialize(self, buff):
00385 """
00386 serialize message into buffer
00387 :param buff: buffer, ``StringIO``
00388 """
00389 try:
00390 _x = self.label
00391 length = len(_x)
00392 if python3 or type(_x) == unicode:
00393 _x = _x.encode('utf-8')
00394 length = len(_x)
00395 buff.write(struct.pack('<I%ss'%length, length, _x))
00396 except struct.error as se: self._check_types(se)
00397 except TypeError as te: self._check_types(te)
00398
00399 def deserialize(self, str):
00400 """
00401 unpack serialized message in str into this message instance
00402 :param str: byte array of serialized message, ``str``
00403 """
00404 try:
00405 end = 0
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.label = str[start:end].decode('utf-8')
00413 else:
00414 self.label = str[start:end]
00415 return self
00416 except struct.error as e:
00417 raise genpy.DeserializationError(e)
00418
00419
00420 def serialize_numpy(self, buff, numpy):
00421 """
00422 serialize message with numpy array types into buffer
00423 :param buff: buffer, ``StringIO``
00424 :param numpy: numpy python module
00425 """
00426 try:
00427 _x = self.label
00428 length = len(_x)
00429 if python3 or type(_x) == unicode:
00430 _x = _x.encode('utf-8')
00431 length = len(_x)
00432 buff.write(struct.pack('<I%ss'%length, length, _x))
00433 except struct.error as se: self._check_types(se)
00434 except TypeError as te: self._check_types(te)
00435
00436 def deserialize_numpy(self, str, numpy):
00437 """
00438 unpack serialized message in str into this message instance using numpy for array types
00439 :param str: byte array of serialized message, ``str``
00440 :param numpy: numpy python module
00441 """
00442 try:
00443 end = 0
00444 start = end
00445 end += 4
00446 (length,) = _struct_I.unpack(str[start:end])
00447 start = end
00448 end += length
00449 if python3:
00450 self.label = str[start:end].decode('utf-8')
00451 else:
00452 self.label = str[start:end]
00453 return self
00454 except struct.error as e:
00455 raise genpy.DeserializationError(e)
00456
00457 _struct_I = genpy.struct_I
00458 class LabelMesh(object):
00459 _type = 'mesh_label_node/LabelMesh'
00460 _md5sum = 'c72758085d3ced91fded54b08891bd78'
00461 _request_class = LabelMeshRequest
00462 _response_class = LabelMeshResponse