Depth source where a fully dense, metric depth image is available. More...
#include <depth_image.hpp>
Public Member Functions | |
DepthImage (const CameraIntrinsicsParameters &rgb_camera_params, int depth_width, int depth_height) | |
virtual double | getBaseline () const |
virtual void | getXyz (OdometryFrame *frame) |
virtual bool | haveXyz (int u, int v) |
virtual void | refineXyz (FeatureMatch *matches, int num_matches, OdometryFrame *frame) |
void | setDepthImage (const float *depth_data) |
~DepthImage () | |
Private Member Functions | |
bool | getXyzInterp (KeypointData *kpdata) |
int | rgbToDepthIndex (double u, double v) const |
Private Attributes | |
float * | _depth_data |
int | _depth_height |
int | _depth_width |
double | _fx_inv |
double | _fy_inv |
double | _neg_cx_div_fx |
double | _neg_cy_div_fy |
Eigen::Matrix< double, 3, Eigen::Dynamic > * | _rays |
int | _rgb_height |
int | _rgb_width |
float | _x_scale |
float | _y_scale |
Depth source where a fully dense, metric depth image is available.
TODO
Definition at line 19 of file depth_image.hpp.
fovis::DepthImage::DepthImage | ( | const CameraIntrinsicsParameters & | rgb_camera_params, |
int | depth_width, | ||
int | depth_height | ||
) |
Definition at line 10 of file depth_image.cpp.
Definition at line 44 of file depth_image.cpp.
virtual double fovis::DepthImage::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 39 of file depth_image.hpp.
void fovis::DepthImage::getXyz | ( | OdometryFrame * | frame | ) | [virtual] |
Populate keypoints in frame with XYZ data.
Implements fovis::DepthSource.
Definition at line 65 of file depth_image.cpp.
bool fovis::DepthImage::getXyzInterp | ( | KeypointData * | kpdata | ) | [private] |
Definition at line 116 of file depth_image.cpp.
bool fovis::DepthImage::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 59 of file depth_image.cpp.
void fovis::DepthImage::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 97 of file depth_image.cpp.
int fovis::DepthImage::rgbToDepthIndex | ( | double | u, |
double | v | ||
) | const [inline, private] |
Definition at line 42 of file depth_image.hpp.
void fovis::DepthImage::setDepthImage | ( | const float * | depth_data | ) |
Set the depth image, a width x height array of distances, units given in meters. Each pixel of the depth image corresponds to a point in the rectified RGB image.
Definition at line 51 of file depth_image.cpp.
float* fovis::DepthImage::_depth_data [private] |
Definition at line 56 of file depth_image.hpp.
int fovis::DepthImage::_depth_height [private] |
Definition at line 51 of file depth_image.hpp.
int fovis::DepthImage::_depth_width [private] |
Definition at line 50 of file depth_image.hpp.
double fovis::DepthImage::_fx_inv [private] |
Definition at line 58 of file depth_image.hpp.
double fovis::DepthImage::_fy_inv [private] |
Definition at line 59 of file depth_image.hpp.
double fovis::DepthImage::_neg_cx_div_fx [private] |
Definition at line 60 of file depth_image.hpp.
double fovis::DepthImage::_neg_cy_div_fy [private] |
Definition at line 61 of file depth_image.hpp.
Eigen::Matrix<double, 3, Eigen::Dynamic>* fovis::DepthImage::_rays [private] |
Definition at line 55 of file depth_image.hpp.
int fovis::DepthImage::_rgb_height [private] |
Definition at line 48 of file depth_image.hpp.
int fovis::DepthImage::_rgb_width [private] |
Definition at line 47 of file depth_image.hpp.
float fovis::DepthImage::_x_scale [private] |
Definition at line 52 of file depth_image.hpp.
float fovis::DepthImage::_y_scale [private] |
Definition at line 53 of file depth_image.hpp.