libfovis
Public Member Functions | List of all members
DepthImage Class Reference

Depth source where a fully dense, metric depth image is available. More...

Inheritance diagram for DepthImage:
DepthSource

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)
 

Detailed Description

Depth source where a fully dense, metric depth image is available.

TODO

Member Function Documentation

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 bool 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 DepthSource.

virtual void getXyz ( OdometryFrame frame)
virtual

Populate keypoints in frame with XYZ data.

Implements DepthSource.

virtual void 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 DepthSource.

virtual double getBaseline ( ) const
inlinevirtual

Return baseline of depth source, if applicable. If not applicable (e.g. for OpenNI devices) return 0.

Implements DepthSource.


The documentation for this class was generated from the following file: