Depth source for a calibrated stereo camera pair where a dense disparity map has been precomputed. More...
#include <stereo_disparity.hpp>
Public Member Functions | |
double | getBaseline () const |
void | getXyz (OdometryFrame *frame) |
bool | haveXyz (int u, int v) |
void | refineXyz (FeatureMatch *matches, int num_matches, OdometryFrame *frame) |
void | setDisparityData (const float *disparity_data) |
StereoDisparity (const StereoCalibration *calib) | |
~StereoDisparity () | |
Private Types | |
typedef std::vector< std::pair < double, double > > | Points2d |
Private Member Functions | |
bool | getXyzInterp (KeypointData *kpdata) |
Interpolate feature position of a non-unit uvd using the 4 neighbouring pixels. | |
Eigen::Vector3d | getXyzValues (int u, int v, float disparity) |
Given a uvd, determine the xyz reprojection position. | |
Private Attributes | |
const StereoCalibration * | _calib |
float * | _disparity_data |
int | _height |
Eigen::Matrix4d * | _uvd1_to_xyz |
int | _width |
Depth source for a calibrated stereo camera pair where a dense disparity map has been precomputed.
Supports VO where input is left and disparity. No right image required. Disparity values are floats with no disparity values given by disparity==0 Similar in concept to DepthImage and PrimesenseDepth
Definition at line 22 of file stereo_disparity.hpp.
typedef std::vector<std::pair<double, double> > fovis::StereoDisparity::Points2d [private] |
Definition at line 47 of file stereo_disparity.hpp.
fovis::StereoDisparity::StereoDisparity | ( | const StereoCalibration * | calib | ) |
Definition at line 11 of file stereo_disparity.cpp.
Definition at line 20 of file stereo_disparity.cpp.
double fovis::StereoDisparity::getBaseline | ( | ) | const [inline, virtual] |
Return baseline of depth source, if applicable. If not applicable (e.g. for OpenNI devices) return 0.
Implements fovis::DepthSource.
Definition at line 44 of file stereo_disparity.hpp.
void fovis::StereoDisparity::getXyz | ( | OdometryFrame * | frame | ) | [virtual] |
Populate keypoints in frame with XYZ data.
Implements fovis::DepthSource.
Definition at line 57 of file stereo_disparity.cpp.
bool fovis::StereoDisparity::haveXyz | ( | int | u, |
int | v | ||
) | [virtual] |
This should return true if it's not certain there's no depth at (u,v). It should be an inexpensive check that is used to avoid pointless (hah!) creation of keypoints. False positives are fine as ling as getXyz gets rid of them.
Implements fovis::DepthSource.
Definition at line 35 of file stereo_disparity.cpp.
void fovis::StereoDisparity::refineXyz | ( | FeatureMatch * | matches, |
int | num_matches, | ||
OdometryFrame * | frame | ||
) | [virtual] |
Refine XYZ data of target keypoints in matches (usually after subpixel refinement of the matches across time).
Implements fovis::DepthSource.
Definition at line 88 of file stereo_disparity.cpp.
void fovis::StereoDisparity::setDisparityData | ( | const float * | disparity_data | ) |
Sets the disparity map. An internal copy of the disparity data is made, so the memory at
disparity_data | is not used after this method returns. |
Definition at line 27 of file stereo_disparity.cpp.
const StereoCalibration* fovis::StereoDisparity::_calib [private] |
Definition at line 65 of file stereo_disparity.hpp.
float* fovis::StereoDisparity::_disparity_data [private] |
Definition at line 72 of file stereo_disparity.hpp.
int fovis::StereoDisparity::_height [private] |
Definition at line 68 of file stereo_disparity.hpp.
Eigen::Matrix4d* fovis::StereoDisparity::_uvd1_to_xyz [private] |
Definition at line 70 of file stereo_disparity.hpp.
int fovis::StereoDisparity::_width [private] |
Definition at line 67 of file stereo_disparity.hpp.