libfovis
stereo_disparity.hpp
1 #ifndef __fovis_stereo_disparity_hpp__
2 #define __fovis_stereo_disparity_hpp__
3 
4 #include <inttypes.h>
5 
6 #include "stereo_calibration.hpp"
7 #include "depth_source.hpp"
8 #include "frame.hpp"
9 
10 namespace fovis
11 {
12 
23 {
24  public:
25  StereoDisparity(const StereoCalibration* calib);
26 
27  ~StereoDisparity();
28 
34  void setDisparityData(const float* disparity_data);
35 
36  bool haveXyz(int u, int v);
37 
38  void getXyz(OdometryFrame* frame);
39 
40  void refineXyz(FeatureMatch* matches,
41  int num_matches,
42  OdometryFrame* frame);
43 
44  double getBaseline() const { return _calib->getBaseline(); }
45 
46  private:
47  typedef std::vector<std::pair<double, double> > Points2d;
48 
55  bool getXyzInterp(KeypointData* kpdata);
56 
63  Eigen::Vector3d getXyzValues(int u, int v, float disparity);
64 
65  const StereoCalibration* _calib;
66 
67  int _width;
68  int _height;
69 
70  Eigen::Matrix4d *_uvd1_to_xyz;
71 
72  float* _disparity_data;
73 };
74 
75 }
76 
77 #endif
bool haveXyz(int u, int v)
Stores data specific to an input frame.
Definition: frame.hpp:33
Provides depth estimates for input image pixels.
Definition: depth_source.hpp:29
Represents a single image feature matched between two camera images taken at different times...
Definition: feature_match.hpp:41
Image feature used for motion estimation.
Definition: keypoint.hpp:49
void getXyz(OdometryFrame *frame)
Computes useful information from a StereoCalibrationParameters object.
Definition: stereo_calibration.hpp:42
quick and dirty profiling tool.inspired by the matlab tic/toc command
Definition: camera_intrinsics.hpp:6
void refineXyz(FeatureMatch *matches, int num_matches, OdometryFrame *frame)
void setDisparityData(const float *disparity_data)
Depth source for a calibrated stereo camera pair where a dense disparity map has been precomputed...
Definition: stereo_disparity.hpp:22
double getBaseline() const
Definition: stereo_disparity.hpp:44