Public Member Functions
fovis::DepthSource Class Reference

Provides depth estimates for input image pixels. More...

#include <depth_source.hpp>

Inheritance diagram for fovis::DepthSource:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual double getBaseline () const =0
virtual void getXyz (OdometryFrame *frame)=0
virtual bool haveXyz (int u, int v)=0
virtual void refineXyz (FeatureMatch *matches, int num_matches, OdometryFrame *frame)=0

Detailed Description

Provides depth estimates for input image pixels.

A reliable source of depth estimates at as many pixels in an image as possible is crucial to producing useful visual odometry estimates. The DepthSource class abstracts out the process of determining depth at each pixel.

DepthSource is used in a lazy fashion. First, keypoints in the input image are identified. Next, keypoints without depth information are filtered out (pixels where haveXyz() returns false) and discarded. Later, the actual depth of the remaining keypoints is retrieved using getXyz(). Finally, after features are temporally matched across frames and their keypoint positions refined, DepthSource is used again to refine the depth estimates of the refined keypoint image positions.

Definition at line 29 of file depth_source.hpp.


Member Function Documentation

virtual double fovis::DepthSource::getBaseline ( ) const [pure virtual]

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

Implemented in fovis::PrimeSenseDepth, fovis::StereoDisparity, fovis::StereoDepth, and fovis::DepthImage.

virtual void fovis::DepthSource::getXyz ( OdometryFrame frame) [pure virtual]

Populate keypoints in frame with XYZ data.

Implemented in fovis::PrimeSenseDepth, fovis::StereoDisparity, fovis::StereoDepth, and fovis::DepthImage.

virtual bool fovis::DepthSource::haveXyz ( int  u,
int  v 
) [pure 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.

Implemented in fovis::PrimeSenseDepth, fovis::StereoDisparity, fovis::StereoDepth, and fovis::DepthImage.

virtual void fovis::DepthSource::refineXyz ( FeatureMatch matches,
int  num_matches,
OdometryFrame frame 
) [pure virtual]

Refine XYZ data of target keypoints in matches (usually after subpixel refinement of the matches across time).

Implemented in fovis::PrimeSenseDepth, fovis::StereoDisparity, fovis::StereoDepth, and fovis::DepthImage.


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


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12