class mrpt::vision::CDifodo

This abstract class implements a method called “Difodo” to perform Visual odometry with range cameras.

It is based on the range flow equation and assumes that the scene is rigid. It can work with different image resolutions (640 x 480, 320 x 240 or 160 x 120) and a different number of coarse-to-fine levels which can be adjusted with the member variables (rows,cols,ctf_levels).

How to use:

  • A derived class must be created which defines the method “loadFrame(…)” according to the user application. This method has to load the depth image into the variable “depth_wf”.

For further information have a look at the apps:

  • DifOdometry-Camera

  • DifOdometry-Datasets

    Please refer to the respective publication when using this method:
        title = {Fast Visual Odometry for {3-D} Range Sensors},
        author = {Jaimez, Mariano and Gonzalez-Jimenez, Javier},
        journal = {IEEE Transactions on Robotics},
        volume = {31},
        number = {4},
        pages = {809 - 822},
        year = {2015}
    
    • JUN/2013: First design.

    • JAN/2014: Integrated into MRPT library.

    • DIC/2014: Reformulated and improved. The class now needs Eigen version 3.1.0 or above.

See also:

CDifodoCamera, CDifodoDatasets

#include <mrpt/vision/CDifodo.h>

class CDifodo
{
public:
    //
fields

    double fps;
    unsigned int cam_mode;
    unsigned int downsample;
    unsigned int num_valid_points;
    float execution_time;
    mrpt::poses::CPose3D cam_pose;
    mrpt::poses::CPose3D cam_oldpose;

    // construction

    CDifodo();

    //
methods

    void odometryCalculation();
    void getRowsAndCols(unsigned int& num_rows, unsigned int& num_cols) const;
    void getCTFLevels(unsigned int& levels) const;
    void setFOV(float new_fovh, float new_fovv);
    void getFOV(float& cur_fovh, float& cur_fovv) const;
    float getSpeedFilterConstWeight() const;
    float getSpeedFilterEigWeight() const;
    void setSpeedFilterConstWeight(float new_cweight);
    void setSpeedFilterEigWeight(float new_eweight);
    void getPointsCoord(mrpt::math::CMatrixFloat& x, mrpt::math::CMatrixFloat& y, mrpt::math::CMatrixFloat& z);
    void getDepthDerivatives(mrpt::math::CMatrixFloat& cur_du, mrpt::math::CMatrixFloat& cur_dv, mrpt::math::CMatrixFloat& cur_dt);
    mrpt::math::TTwist3D getSolverSolution() const;
    mrpt::math::TTwist3D getLastSpeedAbs() const;
    mrpt::math::CMatrixFloat66 getCovariance() const;
    void getWeights(mrpt::math::CMatrixFloat& we);
    virtual void loadFrame() = 0;
};

Fields

double fps

Frames per second (Hz)

unsigned int cam_mode

Resolution of the images taken by the range camera.

unsigned int downsample

Downsample the image taken by the range camera.

Useful to reduce the computational burden, as this downsampling is applied before the gaussian pyramid is built. It must be used when the virtual method “loadFrame()” is implemented

unsigned int num_valid_points

Num of valid points after removing null pixels.

float execution_time

Execution time (ms)

mrpt::poses::CPose3D cam_pose

Camera poses.

Last camera pose

mrpt::poses::CPose3D cam_oldpose

Previous camera pose.

Methods

void odometryCalculation()

This method performs all the necessary steps to estimate the camera velocity once the new image is read, and updates the camera pose.

void getRowsAndCols(unsigned int& num_rows, unsigned int& num_cols) const

Get the rows and cols of the depth image that are considered by the visual odometry method.

void getCTFLevels(unsigned int& levels) const

Get the number of coarse-to-fine levels that are considered by the visual odometry method.

void setFOV(float new_fovh, float new_fovv)

Set the horizontal and vertical field of vision (in degrees)

void getFOV(float& cur_fovh, float& cur_fovv) const

Get the horizontal and vertical field of vision (in degrees)

float getSpeedFilterConstWeight() const

Get the filter constant-weight of the velocity filter.

float getSpeedFilterEigWeight() const

Get the filter eigen-weight of the velocity filter.

void setSpeedFilterConstWeight(float new_cweight)

Set the filter constant-weight of the velocity filter.

void setSpeedFilterEigWeight(float new_eweight)

Set the filter eigen-weight of the velocity filter.

void getPointsCoord(mrpt::math::CMatrixFloat& x, mrpt::math::CMatrixFloat& y, mrpt::math::CMatrixFloat& z)

Get the coordinates of the points considered by the visual odometry method.

void getDepthDerivatives(mrpt::math::CMatrixFloat& cur_du, mrpt::math::CMatrixFloat& cur_dv, mrpt::math::CMatrixFloat& cur_dt)

Get the depth derivatives (last level) respect to u,v and t respectively.

mrpt::math::TTwist3D getSolverSolution() const

Get the camera velocity (vx, vy, vz, wx, wy, wz) expressed in local reference frame estimated by the solver (before filtering)

mrpt::math::TTwist3D getLastSpeedAbs() const

Get the last camera velocity (vx, vy, vz, wx, wy, wz) expressed in the world reference frame, obtained after filtering.

mrpt::math::CMatrixFloat66 getCovariance() const

Get the least-square covariance matrix.

void getWeights(mrpt::math::CMatrixFloat& we)

Get the matrix of weights.

virtual void loadFrame() = 0

Virtual method to be implemented in derived classes.

It should be used to load a new depth image into the variable depth_wf