_Frame.py
Go to the documentation of this file.
00001 """autogenerated by genpy from sba/Frame.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 sba.msg
00008 import geometry_msgs.msg
00009 import std_msgs.msg
00010 
00011 class Frame(genpy.Message):
00012   _md5sum = "418ca143f82258a762de2cff21411737"
00013   _type = "sba/Frame"
00014   _has_header = True #flag to mark the presence of a Header object
00015   _full_text = """# New Frame
00016 Header header
00017 
00018 # New nodes (generally just 1, but want to leave this open)
00019 CameraNode[] nodes
00020 
00021 # New points added from the frame
00022 WorldPoint[] points
00023 
00024 # New projections
00025 Projection[] projections
00026 
00027 ================================================================================
00028 MSG: std_msgs/Header
00029 # Standard metadata for higher-level stamped data types.
00030 # This is generally used to communicate timestamped data 
00031 # in a particular coordinate frame.
00032 # 
00033 # sequence ID: consecutively increasing ID 
00034 uint32 seq
00035 #Two-integer timestamp that is expressed as:
00036 # * stamp.secs: seconds (stamp_secs) since epoch
00037 # * stamp.nsecs: nanoseconds since stamp_secs
00038 # time-handling sugar is provided by the client library
00039 time stamp
00040 #Frame this data is associated with
00041 # 0: no frame
00042 # 1: global frame
00043 string frame_id
00044 
00045 ================================================================================
00046 MSG: sba/CameraNode
00047 # Node Parameters
00048 uint32 index
00049 
00050 # Contains a translation and rotation
00051 geometry_msgs/Transform transform
00052 
00053 # Camera parameters from the K matrix
00054 float64 fx
00055 float64 fy
00056 float64 cx
00057 float64 cy
00058 
00059 # Only relevant for a stereo camera
00060 float64 baseline
00061 
00062 # Whether the camera is fixed in space: i.e., its position is known
00063 bool fixed
00064 
00065 ================================================================================
00066 MSG: geometry_msgs/Transform
00067 # This represents the transform between two coordinate frames in free space.
00068 
00069 Vector3 translation
00070 Quaternion rotation
00071 
00072 ================================================================================
00073 MSG: geometry_msgs/Vector3
00074 # This represents a vector in free space. 
00075 
00076 float64 x
00077 float64 y
00078 float64 z
00079 ================================================================================
00080 MSG: geometry_msgs/Quaternion
00081 # This represents an orientation in free space in quaternion form.
00082 
00083 float64 x
00084 float64 y
00085 float64 z
00086 float64 w
00087 
00088 ================================================================================
00089 MSG: sba/WorldPoint
00090 # World Point parameters
00091 
00092 # Point index
00093 uint32 index
00094 
00095 # Coordinates in the world frame
00096 float64 x
00097 float64 y
00098 float64 z
00099 float64 w
00100 
00101 ================================================================================
00102 MSG: sba/Projection
00103 # Projection
00104 
00105 # Camera index
00106 uint32 camindex
00107 
00108 # Point index
00109 uint32 pointindex
00110 
00111 # Projection into the image plane
00112 float64 u
00113 float64 v
00114 float64 d
00115 
00116 # Is this a stereo projection? (true if stereo, false if monocular)
00117 bool stereo
00118 
00119 # Use a covariance matrix?
00120 bool usecovariance
00121 
00122 # A 3x3 covariance matrix describing the error
00123 float64[9] covariance
00124 
00125 
00126 """
00127   __slots__ = ['header','nodes','points','projections']
00128   _slot_types = ['std_msgs/Header','sba/CameraNode[]','sba/WorldPoint[]','sba/Projection[]']
00129 
00130   def __init__(self, *args, **kwds):
00131     """
00132     Constructor. Any message fields that are implicitly/explicitly
00133     set to None will be assigned a default value. The recommend
00134     use is keyword arguments as this is more robust to future message
00135     changes.  You cannot mix in-order arguments and keyword arguments.
00136 
00137     The available fields are:
00138        header,nodes,points,projections
00139 
00140     :param args: complete set of field values, in .msg order
00141     :param kwds: use keyword arguments corresponding to message field names
00142     to set specific fields.
00143     """
00144     if args or kwds:
00145       super(Frame, self).__init__(*args, **kwds)
00146       #message fields cannot be None, assign default values for those that are
00147       if self.header is None:
00148         self.header = std_msgs.msg.Header()
00149       if self.nodes is None:
00150         self.nodes = []
00151       if self.points is None:
00152         self.points = []
00153       if self.projections is None:
00154         self.projections = []
00155     else:
00156       self.header = std_msgs.msg.Header()
00157       self.nodes = []
00158       self.points = []
00159       self.projections = []
00160 
00161   def _get_types(self):
00162     """
00163     internal API method
00164     """
00165     return self._slot_types
00166 
00167   def serialize(self, buff):
00168     """
00169     serialize message into buffer
00170     :param buff: buffer, ``StringIO``
00171     """
00172     try:
00173       _x = self
00174       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00175       _x = self.header.frame_id
00176       length = len(_x)
00177       if python3 or type(_x) == unicode:
00178         _x = _x.encode('utf-8')
00179         length = len(_x)
00180       buff.write(struct.pack('<I%ss'%length, length, _x))
00181       length = len(self.nodes)
00182       buff.write(_struct_I.pack(length))
00183       for val1 in self.nodes:
00184         buff.write(_struct_I.pack(val1.index))
00185         _v1 = val1.transform
00186         _v2 = _v1.translation
00187         _x = _v2
00188         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00189         _v3 = _v1.rotation
00190         _x = _v3
00191         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00192         _x = val1
00193         buff.write(_struct_5dB.pack(_x.fx, _x.fy, _x.cx, _x.cy, _x.baseline, _x.fixed))
00194       length = len(self.points)
00195       buff.write(_struct_I.pack(length))
00196       for val1 in self.points:
00197         _x = val1
00198         buff.write(_struct_I4d.pack(_x.index, _x.x, _x.y, _x.z, _x.w))
00199       length = len(self.projections)
00200       buff.write(_struct_I.pack(length))
00201       for val1 in self.projections:
00202         _x = val1
00203         buff.write(_struct_2I3d2B.pack(_x.camindex, _x.pointindex, _x.u, _x.v, _x.d, _x.stereo, _x.usecovariance))
00204         buff.write(_struct_9d.pack(*val1.covariance))
00205     except struct.error as se: self._check_types(se)
00206     except TypeError as te: self._check_types(te)
00207 
00208   def deserialize(self, str):
00209     """
00210     unpack serialized message in str into this message instance
00211     :param str: byte array of serialized message, ``str``
00212     """
00213     try:
00214       if self.header is None:
00215         self.header = std_msgs.msg.Header()
00216       if self.nodes is None:
00217         self.nodes = None
00218       if self.points is None:
00219         self.points = None
00220       if self.projections is None:
00221         self.projections = None
00222       end = 0
00223       _x = self
00224       start = end
00225       end += 12
00226       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00227       start = end
00228       end += 4
00229       (length,) = _struct_I.unpack(str[start:end])
00230       start = end
00231       end += length
00232       if python3:
00233         self.header.frame_id = str[start:end].decode('utf-8')
00234       else:
00235         self.header.frame_id = str[start:end]
00236       start = end
00237       end += 4
00238       (length,) = _struct_I.unpack(str[start:end])
00239       self.nodes = []
00240       for i in range(0, length):
00241         val1 = sba.msg.CameraNode()
00242         start = end
00243         end += 4
00244         (val1.index,) = _struct_I.unpack(str[start:end])
00245         _v4 = val1.transform
00246         _v5 = _v4.translation
00247         _x = _v5
00248         start = end
00249         end += 24
00250         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00251         _v6 = _v4.rotation
00252         _x = _v6
00253         start = end
00254         end += 32
00255         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00256         _x = val1
00257         start = end
00258         end += 41
00259         (_x.fx, _x.fy, _x.cx, _x.cy, _x.baseline, _x.fixed,) = _struct_5dB.unpack(str[start:end])
00260         val1.fixed = bool(val1.fixed)
00261         self.nodes.append(val1)
00262       start = end
00263       end += 4
00264       (length,) = _struct_I.unpack(str[start:end])
00265       self.points = []
00266       for i in range(0, length):
00267         val1 = sba.msg.WorldPoint()
00268         _x = val1
00269         start = end
00270         end += 36
00271         (_x.index, _x.x, _x.y, _x.z, _x.w,) = _struct_I4d.unpack(str[start:end])
00272         self.points.append(val1)
00273       start = end
00274       end += 4
00275       (length,) = _struct_I.unpack(str[start:end])
00276       self.projections = []
00277       for i in range(0, length):
00278         val1 = sba.msg.Projection()
00279         _x = val1
00280         start = end
00281         end += 34
00282         (_x.camindex, _x.pointindex, _x.u, _x.v, _x.d, _x.stereo, _x.usecovariance,) = _struct_2I3d2B.unpack(str[start:end])
00283         val1.stereo = bool(val1.stereo)
00284         val1.usecovariance = bool(val1.usecovariance)
00285         start = end
00286         end += 72
00287         val1.covariance = _struct_9d.unpack(str[start:end])
00288         self.projections.append(val1)
00289       return self
00290     except struct.error as e:
00291       raise genpy.DeserializationError(e) #most likely buffer underfill
00292 
00293 
00294   def serialize_numpy(self, buff, numpy):
00295     """
00296     serialize message with numpy array types into buffer
00297     :param buff: buffer, ``StringIO``
00298     :param numpy: numpy python module
00299     """
00300     try:
00301       _x = self
00302       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00303       _x = self.header.frame_id
00304       length = len(_x)
00305       if python3 or type(_x) == unicode:
00306         _x = _x.encode('utf-8')
00307         length = len(_x)
00308       buff.write(struct.pack('<I%ss'%length, length, _x))
00309       length = len(self.nodes)
00310       buff.write(_struct_I.pack(length))
00311       for val1 in self.nodes:
00312         buff.write(_struct_I.pack(val1.index))
00313         _v7 = val1.transform
00314         _v8 = _v7.translation
00315         _x = _v8
00316         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00317         _v9 = _v7.rotation
00318         _x = _v9
00319         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00320         _x = val1
00321         buff.write(_struct_5dB.pack(_x.fx, _x.fy, _x.cx, _x.cy, _x.baseline, _x.fixed))
00322       length = len(self.points)
00323       buff.write(_struct_I.pack(length))
00324       for val1 in self.points:
00325         _x = val1
00326         buff.write(_struct_I4d.pack(_x.index, _x.x, _x.y, _x.z, _x.w))
00327       length = len(self.projections)
00328       buff.write(_struct_I.pack(length))
00329       for val1 in self.projections:
00330         _x = val1
00331         buff.write(_struct_2I3d2B.pack(_x.camindex, _x.pointindex, _x.u, _x.v, _x.d, _x.stereo, _x.usecovariance))
00332         buff.write(val1.covariance.tostring())
00333     except struct.error as se: self._check_types(se)
00334     except TypeError as te: self._check_types(te)
00335 
00336   def deserialize_numpy(self, str, numpy):
00337     """
00338     unpack serialized message in str into this message instance using numpy for array types
00339     :param str: byte array of serialized message, ``str``
00340     :param numpy: numpy python module
00341     """
00342     try:
00343       if self.header is None:
00344         self.header = std_msgs.msg.Header()
00345       if self.nodes is None:
00346         self.nodes = None
00347       if self.points is None:
00348         self.points = None
00349       if self.projections is None:
00350         self.projections = None
00351       end = 0
00352       _x = self
00353       start = end
00354       end += 12
00355       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00356       start = end
00357       end += 4
00358       (length,) = _struct_I.unpack(str[start:end])
00359       start = end
00360       end += length
00361       if python3:
00362         self.header.frame_id = str[start:end].decode('utf-8')
00363       else:
00364         self.header.frame_id = str[start:end]
00365       start = end
00366       end += 4
00367       (length,) = _struct_I.unpack(str[start:end])
00368       self.nodes = []
00369       for i in range(0, length):
00370         val1 = sba.msg.CameraNode()
00371         start = end
00372         end += 4
00373         (val1.index,) = _struct_I.unpack(str[start:end])
00374         _v10 = val1.transform
00375         _v11 = _v10.translation
00376         _x = _v11
00377         start = end
00378         end += 24
00379         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00380         _v12 = _v10.rotation
00381         _x = _v12
00382         start = end
00383         end += 32
00384         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00385         _x = val1
00386         start = end
00387         end += 41
00388         (_x.fx, _x.fy, _x.cx, _x.cy, _x.baseline, _x.fixed,) = _struct_5dB.unpack(str[start:end])
00389         val1.fixed = bool(val1.fixed)
00390         self.nodes.append(val1)
00391       start = end
00392       end += 4
00393       (length,) = _struct_I.unpack(str[start:end])
00394       self.points = []
00395       for i in range(0, length):
00396         val1 = sba.msg.WorldPoint()
00397         _x = val1
00398         start = end
00399         end += 36
00400         (_x.index, _x.x, _x.y, _x.z, _x.w,) = _struct_I4d.unpack(str[start:end])
00401         self.points.append(val1)
00402       start = end
00403       end += 4
00404       (length,) = _struct_I.unpack(str[start:end])
00405       self.projections = []
00406       for i in range(0, length):
00407         val1 = sba.msg.Projection()
00408         _x = val1
00409         start = end
00410         end += 34
00411         (_x.camindex, _x.pointindex, _x.u, _x.v, _x.d, _x.stereo, _x.usecovariance,) = _struct_2I3d2B.unpack(str[start:end])
00412         val1.stereo = bool(val1.stereo)
00413         val1.usecovariance = bool(val1.usecovariance)
00414         start = end
00415         end += 72
00416         val1.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00417         self.projections.append(val1)
00418       return self
00419     except struct.error as e:
00420       raise genpy.DeserializationError(e) #most likely buffer underfill
00421 
00422 _struct_I = genpy.struct_I
00423 _struct_I4d = struct.Struct("<I4d")
00424 _struct_2I3d2B = struct.Struct("<2I3d2B")
00425 _struct_9d = struct.Struct("<9d")
00426 _struct_5dB = struct.Struct("<5dB")
00427 _struct_3I = struct.Struct("<3I")
00428 _struct_4d = struct.Struct("<4d")
00429 _struct_3d = struct.Struct("<3d")


sba
Author(s): Kurt Konolige, Helen Oleynikova
autogenerated on Thu Jan 2 2014 12:12:08