libfovis
|
Stores depth data for a Kinect / PrimeSense camera. More...
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) |
Stores depth data for a Kinect / PrimeSense camera.
|
virtual |
Populate keypoints in frame with XYZ data.
Implements DepthSource.
|
virtual |
Refine XYZ data of target keypoints in matches (usually after subpixel refinement of the matches across time).
Implements DepthSource.
|
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.
|
inline |
Retrieve the disparity value at the specified RGB pixel.
|
inlinevirtual |
Return baseline of depth source, if applicable. If not applicable (e.g. for OpenNI devices) return 0.
Implements DepthSource.
|
inlinevirtual |
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 DepthSource.