libfovis
|
Depth source where a fully dense, metric depth image is available. More...
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) |
Depth source where a fully dense, metric depth image is available.
TODO
void 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.
|
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 DepthSource.
|
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.
|
inlinevirtual |
Return baseline of depth source, if applicable. If not applicable (e.g. for OpenNI devices) return 0.
Implements DepthSource.