Stores depth data for a Kinect / PrimeSense camera. More...
#include <primesense_depth.hpp>
Public Member Functions | |
double | getBaseline () const |
uint16_t | getDisparity (int rgb_u, int rgb_v) const |
uint16_t | getDisparityAtIRPixel (int ir_u, int ir_v) const |
bool | getXyz (int u, int v, Eigen::Vector3d &xyz) |
void | getXyz (OdometryFrame *frame) |
bool | haveXyz (int u, int v) |
PrimeSenseDepth (const PrimeSenseCalibration *calib) | |
void | refineXyz (FeatureMatch *matches, int num_matches, OdometryFrame *frame) |
void | setDisparityData (const uint16_t *disparity) |
~PrimeSenseDepth () | |
Private Member Functions | |
bool | getXyzFast (KeypointData *kpdata) |
bool | getXyzInterp (KeypointData *kpdata) |
bool | haveXyz (float u_f, float v_f) |
Private Attributes | |
const PrimeSenseCalibration * | _calib |
uint16_t * | _disparity |
uint32_t | _disparity_map_max_index |
int | _ir_height |
int | _ir_width |
uint32_t * | _rgb_to_disparity_map |
Eigen::Matrix4d * | _uvd1_d_to_xyz_c |
Stores depth data for a Kinect / PrimeSense camera.
Definition at line 192 of file primesense_depth.hpp.
fovis::PrimeSenseDepth::PrimeSenseDepth | ( | const PrimeSenseCalibration * | calib | ) |
Definition at line 22 of file primesense_depth.cpp.
Definition at line 42 of file primesense_depth.cpp.
double fovis::PrimeSenseDepth::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 271 of file primesense_depth.hpp.
uint16_t fovis::PrimeSenseDepth::getDisparity | ( | int | rgb_u, |
int | rgb_v | ||
) | const [inline] |
Retrieve the disparity value at the IR pixel that projects on to the specified RGB pixel.
Disparity is not measured on the RGB image directly. Instead, it's measured on the IR image, then the points are projected onto the RGB image. This function looks up the IR pixel that projected onto the specified RGB pixel, and then returns the disparity of the IR pixel.
Returns: the measured disparity, or 0 if there is no disparity data for the specified pixel.
Definition at line 252 of file primesense_depth.hpp.
uint16_t fovis::PrimeSenseDepth::getDisparityAtIRPixel | ( | int | ir_u, |
int | ir_v | ||
) | const [inline] |
Retrieve the disparity value at the specified RGB pixel.
Definition at line 264 of file primesense_depth.hpp.
bool fovis::PrimeSenseDepth::getXyz | ( | int | u, |
int | v, | ||
Eigen::Vector3d & | xyz | ||
) |
Definition at line 161 of file primesense_depth.cpp.
void fovis::PrimeSenseDepth::getXyz | ( | OdometryFrame * | frame | ) | [virtual] |
Populate keypoints in frame with XYZ data.
Implements fovis::DepthSource.
Definition at line 100 of file primesense_depth.cpp.
bool fovis::PrimeSenseDepth::getXyzFast | ( | KeypointData * | kpdata | ) | [private] |
Definition at line 190 of file primesense_depth.cpp.
bool fovis::PrimeSenseDepth::getXyzInterp | ( | KeypointData * | kpdata | ) | [private] |
Definition at line 230 of file primesense_depth.cpp.
bool fovis::PrimeSenseDepth::haveXyz | ( | int | u, |
int | v | ||
) | [inline, 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 277 of file primesense_depth.hpp.
bool fovis::PrimeSenseDepth::haveXyz | ( | float | u_f, |
float | v_f | ||
) | [private] |
void fovis::PrimeSenseDepth::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 116 of file primesense_depth.cpp.
void fovis::PrimeSenseDepth::setDisparityData | ( | const uint16_t * | disparity | ) |
Definition at line 50 of file primesense_depth.cpp.
const PrimeSenseCalibration* fovis::PrimeSenseDepth::_calib [private] |
Definition at line 238 of file primesense_depth.hpp.
uint16_t* fovis::PrimeSenseDepth::_disparity [private] |
Definition at line 240 of file primesense_depth.hpp.
uint32_t fovis::PrimeSenseDepth::_disparity_map_max_index [private] |
Definition at line 246 of file primesense_depth.hpp.
int fovis::PrimeSenseDepth::_ir_height [private] |
Definition at line 236 of file primesense_depth.hpp.
int fovis::PrimeSenseDepth::_ir_width [private] |
Definition at line 235 of file primesense_depth.hpp.
uint32_t* fovis::PrimeSenseDepth::_rgb_to_disparity_map [private] |
Definition at line 244 of file primesense_depth.hpp.
Eigen::Matrix4d* fovis::PrimeSenseDepth::_uvd1_d_to_xyz_c [private] |
Definition at line 248 of file primesense_depth.hpp.