_mesh.py
Go to the documentation of this file.
00001 """autogenerated by genpy from srs_object_database_msgs/mesh.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 arm_navigation_msgs.msg
00008 import geometry_msgs.msg
00009 
00010 class mesh(genpy.Message):
00011   _md5sum = "1730abcb9e222ac87717c4ce8068089b"
00012   _type = "srs_object_database_msgs/mesh"
00013   _has_header = False #flag to mark the presence of a Header object
00014   _full_text = """int32 objectId
00015 arm_navigation_msgs/Shape mesh
00016 string type
00017 uint8[] data
00018 ================================================================================
00019 MSG: arm_navigation_msgs/Shape
00020 byte SPHERE=0
00021 byte BOX=1
00022 byte CYLINDER=2
00023 byte MESH=3
00024 
00025 byte type
00026 
00027 
00028 #### define sphere, box, cylinder ####
00029 # the origin of each shape is considered at the shape's center
00030 
00031 # for sphere
00032 # radius := dimensions[0]
00033 
00034 # for cylinder
00035 # radius := dimensions[0]
00036 # length := dimensions[1]
00037 # the length is along the Z axis
00038 
00039 # for box
00040 # size_x := dimensions[0]
00041 # size_y := dimensions[1]
00042 # size_z := dimensions[2]
00043 float64[] dimensions
00044 
00045 
00046 #### define mesh ####
00047 
00048 # list of triangles; triangle k is defined by tre vertices located
00049 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00050 int32[] triangles
00051 geometry_msgs/Point[] vertices
00052 
00053 ================================================================================
00054 MSG: geometry_msgs/Point
00055 # This contains the position of a point in free space
00056 float64 x
00057 float64 y
00058 float64 z
00059 
00060 """
00061   __slots__ = ['objectId','mesh','type','data']
00062   _slot_types = ['int32','arm_navigation_msgs/Shape','string','uint8[]']
00063 
00064   def __init__(self, *args, **kwds):
00065     """
00066     Constructor. Any message fields that are implicitly/explicitly
00067     set to None will be assigned a default value. The recommend
00068     use is keyword arguments as this is more robust to future message
00069     changes.  You cannot mix in-order arguments and keyword arguments.
00070 
00071     The available fields are:
00072        objectId,mesh,type,data
00073 
00074     :param args: complete set of field values, in .msg order
00075     :param kwds: use keyword arguments corresponding to message field names
00076     to set specific fields.
00077     """
00078     if args or kwds:
00079       super(mesh, self).__init__(*args, **kwds)
00080       #message fields cannot be None, assign default values for those that are
00081       if self.objectId is None:
00082         self.objectId = 0
00083       if self.mesh is None:
00084         self.mesh = arm_navigation_msgs.msg.Shape()
00085       if self.type is None:
00086         self.type = ''
00087       if self.data is None:
00088         self.data = ''
00089     else:
00090       self.objectId = 0
00091       self.mesh = arm_navigation_msgs.msg.Shape()
00092       self.type = ''
00093       self.data = ''
00094 
00095   def _get_types(self):
00096     """
00097     internal API method
00098     """
00099     return self._slot_types
00100 
00101   def serialize(self, buff):
00102     """
00103     serialize message into buffer
00104     :param buff: buffer, ``StringIO``
00105     """
00106     try:
00107       _x = self
00108       buff.write(_struct_ib.pack(_x.objectId, _x.mesh.type))
00109       length = len(self.mesh.dimensions)
00110       buff.write(_struct_I.pack(length))
00111       pattern = '<%sd'%length
00112       buff.write(struct.pack(pattern, *self.mesh.dimensions))
00113       length = len(self.mesh.triangles)
00114       buff.write(_struct_I.pack(length))
00115       pattern = '<%si'%length
00116       buff.write(struct.pack(pattern, *self.mesh.triangles))
00117       length = len(self.mesh.vertices)
00118       buff.write(_struct_I.pack(length))
00119       for val1 in self.mesh.vertices:
00120         _x = val1
00121         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00122       _x = self.type
00123       length = len(_x)
00124       if python3 or type(_x) == unicode:
00125         _x = _x.encode('utf-8')
00126         length = len(_x)
00127       buff.write(struct.pack('<I%ss'%length, length, _x))
00128       _x = self.data
00129       length = len(_x)
00130       # - if encoded as a list instead, serialize as bytes instead of string
00131       if type(_x) in [list, tuple]:
00132         buff.write(struct.pack('<I%sB'%length, length, *_x))
00133       else:
00134         buff.write(struct.pack('<I%ss'%length, length, _x))
00135     except struct.error as se: self._check_types(se)
00136     except TypeError as te: self._check_types(te)
00137 
00138   def deserialize(self, str):
00139     """
00140     unpack serialized message in str into this message instance
00141     :param str: byte array of serialized message, ``str``
00142     """
00143     try:
00144       if self.mesh is None:
00145         self.mesh = arm_navigation_msgs.msg.Shape()
00146       end = 0
00147       _x = self
00148       start = end
00149       end += 5
00150       (_x.objectId, _x.mesh.type,) = _struct_ib.unpack(str[start:end])
00151       start = end
00152       end += 4
00153       (length,) = _struct_I.unpack(str[start:end])
00154       pattern = '<%sd'%length
00155       start = end
00156       end += struct.calcsize(pattern)
00157       self.mesh.dimensions = struct.unpack(pattern, str[start:end])
00158       start = end
00159       end += 4
00160       (length,) = _struct_I.unpack(str[start:end])
00161       pattern = '<%si'%length
00162       start = end
00163       end += struct.calcsize(pattern)
00164       self.mesh.triangles = struct.unpack(pattern, str[start:end])
00165       start = end
00166       end += 4
00167       (length,) = _struct_I.unpack(str[start:end])
00168       self.mesh.vertices = []
00169       for i in range(0, length):
00170         val1 = geometry_msgs.msg.Point()
00171         _x = val1
00172         start = end
00173         end += 24
00174         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00175         self.mesh.vertices.append(val1)
00176       start = end
00177       end += 4
00178       (length,) = _struct_I.unpack(str[start:end])
00179       start = end
00180       end += length
00181       if python3:
00182         self.type = str[start:end].decode('utf-8')
00183       else:
00184         self.type = str[start:end]
00185       start = end
00186       end += 4
00187       (length,) = _struct_I.unpack(str[start:end])
00188       start = end
00189       end += length
00190       self.data = str[start:end]
00191       return self
00192     except struct.error as e:
00193       raise genpy.DeserializationError(e) #most likely buffer underfill
00194 
00195 
00196   def serialize_numpy(self, buff, numpy):
00197     """
00198     serialize message with numpy array types into buffer
00199     :param buff: buffer, ``StringIO``
00200     :param numpy: numpy python module
00201     """
00202     try:
00203       _x = self
00204       buff.write(_struct_ib.pack(_x.objectId, _x.mesh.type))
00205       length = len(self.mesh.dimensions)
00206       buff.write(_struct_I.pack(length))
00207       pattern = '<%sd'%length
00208       buff.write(self.mesh.dimensions.tostring())
00209       length = len(self.mesh.triangles)
00210       buff.write(_struct_I.pack(length))
00211       pattern = '<%si'%length
00212       buff.write(self.mesh.triangles.tostring())
00213       length = len(self.mesh.vertices)
00214       buff.write(_struct_I.pack(length))
00215       for val1 in self.mesh.vertices:
00216         _x = val1
00217         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00218       _x = self.type
00219       length = len(_x)
00220       if python3 or type(_x) == unicode:
00221         _x = _x.encode('utf-8')
00222         length = len(_x)
00223       buff.write(struct.pack('<I%ss'%length, length, _x))
00224       _x = self.data
00225       length = len(_x)
00226       # - if encoded as a list instead, serialize as bytes instead of string
00227       if type(_x) in [list, tuple]:
00228         buff.write(struct.pack('<I%sB'%length, length, *_x))
00229       else:
00230         buff.write(struct.pack('<I%ss'%length, length, _x))
00231     except struct.error as se: self._check_types(se)
00232     except TypeError as te: self._check_types(te)
00233 
00234   def deserialize_numpy(self, str, numpy):
00235     """
00236     unpack serialized message in str into this message instance using numpy for array types
00237     :param str: byte array of serialized message, ``str``
00238     :param numpy: numpy python module
00239     """
00240     try:
00241       if self.mesh is None:
00242         self.mesh = arm_navigation_msgs.msg.Shape()
00243       end = 0
00244       _x = self
00245       start = end
00246       end += 5
00247       (_x.objectId, _x.mesh.type,) = _struct_ib.unpack(str[start:end])
00248       start = end
00249       end += 4
00250       (length,) = _struct_I.unpack(str[start:end])
00251       pattern = '<%sd'%length
00252       start = end
00253       end += struct.calcsize(pattern)
00254       self.mesh.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00255       start = end
00256       end += 4
00257       (length,) = _struct_I.unpack(str[start:end])
00258       pattern = '<%si'%length
00259       start = end
00260       end += struct.calcsize(pattern)
00261       self.mesh.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00262       start = end
00263       end += 4
00264       (length,) = _struct_I.unpack(str[start:end])
00265       self.mesh.vertices = []
00266       for i in range(0, length):
00267         val1 = geometry_msgs.msg.Point()
00268         _x = val1
00269         start = end
00270         end += 24
00271         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00272         self.mesh.vertices.append(val1)
00273       start = end
00274       end += 4
00275       (length,) = _struct_I.unpack(str[start:end])
00276       start = end
00277       end += length
00278       if python3:
00279         self.type = str[start:end].decode('utf-8')
00280       else:
00281         self.type = str[start:end]
00282       start = end
00283       end += 4
00284       (length,) = _struct_I.unpack(str[start:end])
00285       start = end
00286       end += length
00287       self.data = str[start:end]
00288       return self
00289     except struct.error as e:
00290       raise genpy.DeserializationError(e) #most likely buffer underfill
00291 
00292 _struct_I = genpy.struct_I
00293 _struct_ib = struct.Struct("<ib")
00294 _struct_3d = struct.Struct("<3d")


srs_object_database_msgs
Author(s): Georg Arbeiter
autogenerated on Wed Nov 27 2013 14:14:38