Go to the documentation of this file.00001 #ifndef __fovis_depth_source_hpp__
00002 #define __fovis_depth_source_hpp__
00003
00004 #include <Eigen/Core>
00005
00006 namespace fovis
00007 {
00008
00009 class OdometryFrame;
00010 class FeatureMatch;
00011
00029 class DepthSource
00030 {
00031 public:
00038 virtual bool haveXyz(int u, int v) = 0;
00039
00043 virtual void getXyz(OdometryFrame * frame) = 0;
00044
00049 virtual void refineXyz(FeatureMatch * matches,
00050 int num_matches,
00051 OdometryFrame * frame) = 0;
00052
00057 virtual double getBaseline() const = 0;
00058
00059 };
00060
00061 }
00062
00063 #endif