_ModelHypothesisList.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_recognition_gui/ModelHypothesisList.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 object_recognition_gui.msg
00008 import arm_navigation_msgs.msg
00009 import geometry_msgs.msg
00010 import std_msgs.msg
00011 
00012 class ModelHypothesisList(genpy.Message):
00013   _md5sum = "8d08459b65fa27d555aca1d8d3e6c944"
00014   _type = "object_recognition_gui/ModelHypothesisList"
00015   _has_header = False #flag to mark the presence of a Header object
00016   _full_text = """ModelHypothesis[] hypotheses
00017 
00018 #initial guess if this can be a correct recognition result at all
00019 bool accept
00020 ================================================================================
00021 MSG: object_recognition_gui/ModelHypothesis
00022 #describes a hypothesis about a recognized object (mesh+pose)
00023 
00024 arm_navigation_msgs/Shape mesh
00025 geometry_msgs/PoseStamped pose
00026 
00027 ================================================================================
00028 MSG: arm_navigation_msgs/Shape
00029 byte SPHERE=0
00030 byte BOX=1
00031 byte CYLINDER=2
00032 byte MESH=3
00033 
00034 byte type
00035 
00036 
00037 #### define sphere, box, cylinder ####
00038 # the origin of each shape is considered at the shape's center
00039 
00040 # for sphere
00041 # radius := dimensions[0]
00042 
00043 # for cylinder
00044 # radius := dimensions[0]
00045 # length := dimensions[1]
00046 # the length is along the Z axis
00047 
00048 # for box
00049 # size_x := dimensions[0]
00050 # size_y := dimensions[1]
00051 # size_z := dimensions[2]
00052 float64[] dimensions
00053 
00054 
00055 #### define mesh ####
00056 
00057 # list of triangles; triangle k is defined by tre vertices located
00058 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00059 int32[] triangles
00060 geometry_msgs/Point[] vertices
00061 
00062 ================================================================================
00063 MSG: geometry_msgs/Point
00064 # This contains the position of a point in free space
00065 float64 x
00066 float64 y
00067 float64 z
00068 
00069 ================================================================================
00070 MSG: geometry_msgs/PoseStamped
00071 # A Pose with reference coordinate frame and timestamp
00072 Header header
00073 Pose pose
00074 
00075 ================================================================================
00076 MSG: std_msgs/Header
00077 # Standard metadata for higher-level stamped data types.
00078 # This is generally used to communicate timestamped data 
00079 # in a particular coordinate frame.
00080 # 
00081 # sequence ID: consecutively increasing ID 
00082 uint32 seq
00083 #Two-integer timestamp that is expressed as:
00084 # * stamp.secs: seconds (stamp_secs) since epoch
00085 # * stamp.nsecs: nanoseconds since stamp_secs
00086 # time-handling sugar is provided by the client library
00087 time stamp
00088 #Frame this data is associated with
00089 # 0: no frame
00090 # 1: global frame
00091 string frame_id
00092 
00093 ================================================================================
00094 MSG: geometry_msgs/Pose
00095 # A representation of pose in free space, composed of postion and orientation. 
00096 Point position
00097 Quaternion orientation
00098 
00099 ================================================================================
00100 MSG: geometry_msgs/Quaternion
00101 # This represents an orientation in free space in quaternion form.
00102 
00103 float64 x
00104 float64 y
00105 float64 z
00106 float64 w
00107 
00108 """
00109   __slots__ = ['hypotheses','accept']
00110   _slot_types = ['object_recognition_gui/ModelHypothesis[]','bool']
00111 
00112   def __init__(self, *args, **kwds):
00113     """
00114     Constructor. Any message fields that are implicitly/explicitly
00115     set to None will be assigned a default value. The recommend
00116     use is keyword arguments as this is more robust to future message
00117     changes.  You cannot mix in-order arguments and keyword arguments.
00118 
00119     The available fields are:
00120        hypotheses,accept
00121 
00122     :param args: complete set of field values, in .msg order
00123     :param kwds: use keyword arguments corresponding to message field names
00124     to set specific fields.
00125     """
00126     if args or kwds:
00127       super(ModelHypothesisList, self).__init__(*args, **kwds)
00128       #message fields cannot be None, assign default values for those that are
00129       if self.hypotheses is None:
00130         self.hypotheses = []
00131       if self.accept is None:
00132         self.accept = False
00133     else:
00134       self.hypotheses = []
00135       self.accept = False
00136 
00137   def _get_types(self):
00138     """
00139     internal API method
00140     """
00141     return self._slot_types
00142 
00143   def serialize(self, buff):
00144     """
00145     serialize message into buffer
00146     :param buff: buffer, ``StringIO``
00147     """
00148     try:
00149       length = len(self.hypotheses)
00150       buff.write(_struct_I.pack(length))
00151       for val1 in self.hypotheses:
00152         _v1 = val1.mesh
00153         buff.write(_struct_b.pack(_v1.type))
00154         length = len(_v1.dimensions)
00155         buff.write(_struct_I.pack(length))
00156         pattern = '<%sd'%length
00157         buff.write(struct.pack(pattern, *_v1.dimensions))
00158         length = len(_v1.triangles)
00159         buff.write(_struct_I.pack(length))
00160         pattern = '<%si'%length
00161         buff.write(struct.pack(pattern, *_v1.triangles))
00162         length = len(_v1.vertices)
00163         buff.write(_struct_I.pack(length))
00164         for val3 in _v1.vertices:
00165           _x = val3
00166           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00167         _v2 = val1.pose
00168         _v3 = _v2.header
00169         buff.write(_struct_I.pack(_v3.seq))
00170         _v4 = _v3.stamp
00171         _x = _v4
00172         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00173         _x = _v3.frame_id
00174         length = len(_x)
00175         if python3 or type(_x) == unicode:
00176           _x = _x.encode('utf-8')
00177           length = len(_x)
00178         buff.write(struct.pack('<I%ss'%length, length, _x))
00179         _v5 = _v2.pose
00180         _v6 = _v5.position
00181         _x = _v6
00182         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00183         _v7 = _v5.orientation
00184         _x = _v7
00185         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00186       buff.write(_struct_B.pack(self.accept))
00187     except struct.error as se: self._check_types(se)
00188     except TypeError as te: self._check_types(te)
00189 
00190   def deserialize(self, str):
00191     """
00192     unpack serialized message in str into this message instance
00193     :param str: byte array of serialized message, ``str``
00194     """
00195     try:
00196       if self.hypotheses is None:
00197         self.hypotheses = None
00198       end = 0
00199       start = end
00200       end += 4
00201       (length,) = _struct_I.unpack(str[start:end])
00202       self.hypotheses = []
00203       for i in range(0, length):
00204         val1 = object_recognition_gui.msg.ModelHypothesis()
00205         _v8 = val1.mesh
00206         start = end
00207         end += 1
00208         (_v8.type,) = _struct_b.unpack(str[start:end])
00209         start = end
00210         end += 4
00211         (length,) = _struct_I.unpack(str[start:end])
00212         pattern = '<%sd'%length
00213         start = end
00214         end += struct.calcsize(pattern)
00215         _v8.dimensions = struct.unpack(pattern, str[start:end])
00216         start = end
00217         end += 4
00218         (length,) = _struct_I.unpack(str[start:end])
00219         pattern = '<%si'%length
00220         start = end
00221         end += struct.calcsize(pattern)
00222         _v8.triangles = struct.unpack(pattern, str[start:end])
00223         start = end
00224         end += 4
00225         (length,) = _struct_I.unpack(str[start:end])
00226         _v8.vertices = []
00227         for i in range(0, length):
00228           val3 = geometry_msgs.msg.Point()
00229           _x = val3
00230           start = end
00231           end += 24
00232           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00233           _v8.vertices.append(val3)
00234         _v9 = val1.pose
00235         _v10 = _v9.header
00236         start = end
00237         end += 4
00238         (_v10.seq,) = _struct_I.unpack(str[start:end])
00239         _v11 = _v10.stamp
00240         _x = _v11
00241         start = end
00242         end += 8
00243         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00244         start = end
00245         end += 4
00246         (length,) = _struct_I.unpack(str[start:end])
00247         start = end
00248         end += length
00249         if python3:
00250           _v10.frame_id = str[start:end].decode('utf-8')
00251         else:
00252           _v10.frame_id = str[start:end]
00253         _v12 = _v9.pose
00254         _v13 = _v12.position
00255         _x = _v13
00256         start = end
00257         end += 24
00258         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00259         _v14 = _v12.orientation
00260         _x = _v14
00261         start = end
00262         end += 32
00263         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00264         self.hypotheses.append(val1)
00265       start = end
00266       end += 1
00267       (self.accept,) = _struct_B.unpack(str[start:end])
00268       self.accept = bool(self.accept)
00269       return self
00270     except struct.error as e:
00271       raise genpy.DeserializationError(e) #most likely buffer underfill
00272 
00273 
00274   def serialize_numpy(self, buff, numpy):
00275     """
00276     serialize message with numpy array types into buffer
00277     :param buff: buffer, ``StringIO``
00278     :param numpy: numpy python module
00279     """
00280     try:
00281       length = len(self.hypotheses)
00282       buff.write(_struct_I.pack(length))
00283       for val1 in self.hypotheses:
00284         _v15 = val1.mesh
00285         buff.write(_struct_b.pack(_v15.type))
00286         length = len(_v15.dimensions)
00287         buff.write(_struct_I.pack(length))
00288         pattern = '<%sd'%length
00289         buff.write(_v15.dimensions.tostring())
00290         length = len(_v15.triangles)
00291         buff.write(_struct_I.pack(length))
00292         pattern = '<%si'%length
00293         buff.write(_v15.triangles.tostring())
00294         length = len(_v15.vertices)
00295         buff.write(_struct_I.pack(length))
00296         for val3 in _v15.vertices:
00297           _x = val3
00298           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00299         _v16 = val1.pose
00300         _v17 = _v16.header
00301         buff.write(_struct_I.pack(_v17.seq))
00302         _v18 = _v17.stamp
00303         _x = _v18
00304         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00305         _x = _v17.frame_id
00306         length = len(_x)
00307         if python3 or type(_x) == unicode:
00308           _x = _x.encode('utf-8')
00309           length = len(_x)
00310         buff.write(struct.pack('<I%ss'%length, length, _x))
00311         _v19 = _v16.pose
00312         _v20 = _v19.position
00313         _x = _v20
00314         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00315         _v21 = _v19.orientation
00316         _x = _v21
00317         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00318       buff.write(_struct_B.pack(self.accept))
00319     except struct.error as se: self._check_types(se)
00320     except TypeError as te: self._check_types(te)
00321 
00322   def deserialize_numpy(self, str, numpy):
00323     """
00324     unpack serialized message in str into this message instance using numpy for array types
00325     :param str: byte array of serialized message, ``str``
00326     :param numpy: numpy python module
00327     """
00328     try:
00329       if self.hypotheses is None:
00330         self.hypotheses = None
00331       end = 0
00332       start = end
00333       end += 4
00334       (length,) = _struct_I.unpack(str[start:end])
00335       self.hypotheses = []
00336       for i in range(0, length):
00337         val1 = object_recognition_gui.msg.ModelHypothesis()
00338         _v22 = val1.mesh
00339         start = end
00340         end += 1
00341         (_v22.type,) = _struct_b.unpack(str[start:end])
00342         start = end
00343         end += 4
00344         (length,) = _struct_I.unpack(str[start:end])
00345         pattern = '<%sd'%length
00346         start = end
00347         end += struct.calcsize(pattern)
00348         _v22.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00349         start = end
00350         end += 4
00351         (length,) = _struct_I.unpack(str[start:end])
00352         pattern = '<%si'%length
00353         start = end
00354         end += struct.calcsize(pattern)
00355         _v22.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00356         start = end
00357         end += 4
00358         (length,) = _struct_I.unpack(str[start:end])
00359         _v22.vertices = []
00360         for i in range(0, length):
00361           val3 = geometry_msgs.msg.Point()
00362           _x = val3
00363           start = end
00364           end += 24
00365           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00366           _v22.vertices.append(val3)
00367         _v23 = val1.pose
00368         _v24 = _v23.header
00369         start = end
00370         end += 4
00371         (_v24.seq,) = _struct_I.unpack(str[start:end])
00372         _v25 = _v24.stamp
00373         _x = _v25
00374         start = end
00375         end += 8
00376         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00377         start = end
00378         end += 4
00379         (length,) = _struct_I.unpack(str[start:end])
00380         start = end
00381         end += length
00382         if python3:
00383           _v24.frame_id = str[start:end].decode('utf-8')
00384         else:
00385           _v24.frame_id = str[start:end]
00386         _v26 = _v23.pose
00387         _v27 = _v26.position
00388         _x = _v27
00389         start = end
00390         end += 24
00391         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00392         _v28 = _v26.orientation
00393         _x = _v28
00394         start = end
00395         end += 32
00396         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00397         self.hypotheses.append(val1)
00398       start = end
00399       end += 1
00400       (self.accept,) = _struct_B.unpack(str[start:end])
00401       self.accept = bool(self.accept)
00402       return self
00403     except struct.error as e:
00404       raise genpy.DeserializationError(e) #most likely buffer underfill
00405 
00406 _struct_I = genpy.struct_I
00407 _struct_b = struct.Struct("<b")
00408 _struct_B = struct.Struct("<B")
00409 _struct_4d = struct.Struct("<4d")
00410 _struct_2I = struct.Struct("<2I")
00411 _struct_3d = struct.Struct("<3d")


object_recognition_gui
Author(s): David Gossow
autogenerated on Fri Jan 3 2014 12:01:17