Main MRPT website > C++ reference
MRPT logo
List of all members | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
mrpt::vision::CDifodo Class Referenceabstract

Detailed Description

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). Independently of the initial resolution chosen, the method normally makes use of a smaller amount of points which can be adjusted with the member variables (rows,cols).

How to use:

For further information have a look at the apps:

JUN/2013: First design.

Definition at line 53 of file CDifodo.h.

#include <mrpt/vision/CDifodo.h>

Public Member Functions

void OdometryCalculation ()
 This method performs the necessary steps to estimate the camera speed in local coordinates once the depth image has been loaded. More...
 
void setCameraFocalLenght (float new_f)
 It sets the camera focal lenght. More...
 
float getCameraFocalLenght () const
 It gets the camera focal lenght. More...
 
void setNumberOfRowsAndCols (unsigned int num_rows, unsigned int num_cols)
 It sets the number of rows and cols of the depth image that will be considered by the visual odometry method. More...
 
void getRowsAndCols (unsigned int &num_rows, unsigned int &num_cols) const
 It gets the rows and cols of the depth image that are considered by the visual odometry method. More...
 
void setFOV (float new_fovh, float new_fovv)
 It sets the horizontal and vertical field of vision (in degrees) More...
 
void getFOV (float &cur_fovh, float &cur_fovv) const
 It gets the horizontal and vertical field of vision (in degrees) More...
 
float getSpeedFilterConstWeight () const
 It gets the weight that ponders the previous speed in order to calculate the filtered speed. More...
 
float getSpeedFilterEigWeight () const
 It gets the weight that ponders the product of the corresponding eigenvalue and the previous speed in order to calculate the filtered speed. More...
 
void setSpeedFilterConstWeight (float new_cweight)
 It sets the weight that ponders the previous speed in order to calculate the filtered speed. More...
 
void setSpeedFilterEigWeight (float new_eweight)
 It sets the weight that ponders the product of the corresponding eigenvalue and the previous speed in order to calculate the filtered speed. More...
 
void getPointsCoord (MatrixXf &x, MatrixXf &y, MatrixXf &z)
 This method gets the coordinates of the points regarded by the visual odometry method. More...
 
void getDepthDerivatives (MatrixXf &cur_du, MatrixXf &cur_dv, MatrixXf &cur_dt)
 This method gets the depth derivatives respect to u,v and t respectively. More...
 
mrpt::math::CMatrixFloat61 getSolverSolution () const
 It gets the camera speed (vx, vy, vz, wx, wy, wz) expressed in local reference frame estimated by the solver (before filtering) More...
 
mrpt::math::CMatrixFloat61 getLastSpeedAbs () const
 It gets the last camera speed (vx, vy, vz, wx, wy, wz) expressed in the world reference frame, obtained after filtering. More...
 
mrpt::math::CMatrixFloat66 getCovariance () const
 It gets the least-square covariance matrix. More...
 
void getWeights (MatrixXf &we)
 It gets the matrix of weights. More...
 
void bordersThresholdToDefault ()
 It resets the border thresholds to their default values. More...
 
virtual void loadFrame ()=0
 Virtual method to be implemented in derived classes. More...
 
 CDifodo ()
 

Public Attributes

float lens_disp
 Camera properties. More...
 
float fps
 Frames per second (Hz) More...
 
unsigned int cam_mode
 Resolution of the images taken by the range camera. More...
 
unsigned int downsample
 Downsample the image taken by the range camera. More...
 
unsigned int num_valid_points
 Num of valid points after removing null pixels and borders. More...
 
float duv_threshold
 Thresholds used to remove borders and noisy points. More...
 
float dt_threshold
 Threshold to dt. More...
 
float dif_threshold
 Threshold to [abs(final_dx-ini_dx) + abs(final_dy-ini_dy)]. More...
 
float difuv_surroundings
 Threshold to the difference of (du,dv) at a pixel and the values of (du,dv) at its surroundings. More...
 
float dift_surroundings
 Threshold to the difference of dt at a pixel and the value of dt at its surroundings. More...
 
float execution_time
 Execution time (ms) More...
 
CPose3D cam_pose
 Camera poses. More...
 
CPose3D cam_oldpose
 Previous camera pose. More...
 

Protected Member Functions

void filterAndDownsample ()
 It filters the depth image with a gaussian kernel and downsample this filtered image according to the values of "rows" and "cols". More...
 
void calculateCoord ()
 It calculates the "average" coordinates of the points observed by the camera between two consecutive frames. More...
 
void calculateDepthDerivatives ()
 It calculates the depth derivatives respect to u,v (rows and cols) and t (time) More...
 
void findNullPoints ()
 This method finds pixels whose depth is zero to subsequently discard them. More...
 
void findBorders ()
 This method finds pixels which are not in planar or smooth surfaces, and also inaccurate (noisy) pixels. More...
 
void findValidPoints ()
 This method discards the pixels found by 'findNullPoints()' and 'findBorders()'. More...
 
void solveDepthSystem ()
 The Solver. More...
 
virtual void filterSpeedAndPoseUpdate ()
 Virtual method to filter the speed and update the camera pose. More...
 

Protected Attributes

MatrixXf depth_ft
 Matrices that store the original and filtered depth frames with the image resolution. More...
 
MatrixXf depth_wf
 
MatrixXf depth
 Matrices that store the point coordinates after downsampling. More...
 
MatrixXf depth_old
 
MatrixXf depth_inter
 
MatrixXf xx
 
MatrixXf xx_inter
 
MatrixXf xx_old
 
MatrixXf yy
 
MatrixXf yy_inter
 
MatrixXf yy_old
 
MatrixXf du
 Matrices that store the depth derivatives. More...
 
MatrixXf dv
 
MatrixXf dt
 
MatrixXf weights
 Weights used to ponder equations in the least square solution. More...
 
MatrixXi null
 Matrix which indicates wheter the depth of a pixel is zero (null = 1) or not (null = 00). More...
 
MatrixXi border
 Matrix which indicates wheter a point is in a border or has an inaccurate depth (border =1, border = 0 otherwise) More...
 
math::CMatrixFloat66 est_cov
 Least squares covariance matrix. More...
 
float f_dist
 Camera properties: More...
 
float x_incr
 Separation between pixels (cols) in the sensor array (meters) More...
 
float y_incr
 Separation between pixels (rows) in the sensor array (meters) More...
 
float fovh
 Horizontal field of view (rad) More...
 
float fovv
 Vertical field of view (rad) More...
 
unsigned int rows
 Number of rows and cols of the depth image that will be considered by the visual odometry method. More...
 
unsigned int cols
 
unsigned int gaussian_mask_size
 Size (rows) of the gaussian kernel used to filter the depth image. More...
 
float previous_speed_const_weight
 Speed filter parameters: Previous_speed_const_weight directly ponders the previous speed in order to calculate the filtered speed. More...
 
float previous_speed_eig_weight
 Default 300. More...
 
math::CMatrixFloat61 kai_solver
 Solution from the solver: kai before applying the filter in local coordinates. More...
 
math::CMatrixFloat61 kai_abs
 Last filtered speed in absolute coordinates. More...
 

Constructor & Destructor Documentation

mrpt::vision::CDifodo::CDifodo ( )

Member Function Documentation

void mrpt::vision::CDifodo::bordersThresholdToDefault ( )

It resets the border thresholds to their default values.

void mrpt::vision::CDifodo::calculateCoord ( )
protected

It calculates the "average" coordinates of the points observed by the camera between two consecutive frames.

void mrpt::vision::CDifodo::calculateDepthDerivatives ( )
protected

It calculates the depth derivatives respect to u,v (rows and cols) and t (time)

void mrpt::vision::CDifodo::filterAndDownsample ( )
protected

It filters the depth image with a gaussian kernel and downsample this filtered image according to the values of "rows" and "cols".

virtual void mrpt::vision::CDifodo::filterSpeedAndPoseUpdate ( )
protectedvirtual

Virtual method to filter the speed and update the camera pose.

void mrpt::vision::CDifodo::findBorders ( )
protected

This method finds pixels which are not in planar or smooth surfaces, and also inaccurate (noisy) pixels.

void mrpt::vision::CDifodo::findNullPoints ( )
protected

This method finds pixels whose depth is zero to subsequently discard them.

void mrpt::vision::CDifodo::findValidPoints ( )
protected

This method discards the pixels found by 'findNullPoints()' and 'findBorders()'.

float mrpt::vision::CDifodo::getCameraFocalLenght ( ) const
inline

It gets the camera focal lenght.

Definition at line 181 of file CDifodo.h.

mrpt::math::CMatrixFloat66 mrpt::vision::CDifodo::getCovariance ( ) const
inline

It gets the least-square covariance matrix.

Definition at line 220 of file CDifodo.h.

void mrpt::vision::CDifodo::getDepthDerivatives ( MatrixXf &  cur_du,
MatrixXf &  cur_dv,
MatrixXf &  cur_dt 
)
inline

This method gets the depth derivatives respect to u,v and t respectively.

void mrpt::vision::CDifodo::getFOV ( float &  cur_fovh,
float &  cur_fovv 
) const
inline

It gets the horizontal and vertical field of vision (in degrees)

Definition at line 193 of file CDifodo.h.

mrpt::math::CMatrixFloat61 mrpt::vision::CDifodo::getLastSpeedAbs ( ) const
inline

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

Definition at line 217 of file CDifodo.h.

void mrpt::vision::CDifodo::getPointsCoord ( MatrixXf &  x,
MatrixXf &  y,
MatrixXf &  z 
)
inline

This method gets the coordinates of the points regarded by the visual odometry method.

void mrpt::vision::CDifodo::getRowsAndCols ( unsigned int &  num_rows,
unsigned int &  num_cols 
) const
inline

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

Definition at line 187 of file CDifodo.h.

mrpt::math::CMatrixFloat61 mrpt::vision::CDifodo::getSolverSolution ( ) const
inline

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

Definition at line 214 of file CDifodo.h.

float mrpt::vision::CDifodo::getSpeedFilterConstWeight ( ) const
inline

It gets the weight that ponders the previous speed in order to calculate the filtered speed.

Definition at line 196 of file CDifodo.h.

float mrpt::vision::CDifodo::getSpeedFilterEigWeight ( ) const
inline

It gets the weight that ponders the product of the corresponding eigenvalue and the previous speed in order to calculate the filtered speed.

Definition at line 199 of file CDifodo.h.

void mrpt::vision::CDifodo::getWeights ( MatrixXf &  we)
inline

It gets the matrix of weights.

virtual void mrpt::vision::CDifodo::loadFrame ( )
pure virtual

Virtual method to be implemented in derived classes.

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

void mrpt::vision::CDifodo::OdometryCalculation ( )

This method performs the necessary steps to estimate the camera speed in local coordinates once the depth image has been loaded.

void mrpt::vision::CDifodo::setCameraFocalLenght ( float  new_f)
inline

It sets the camera focal lenght.

void mrpt::vision::CDifodo::setFOV ( float  new_fovh,
float  new_fovv 
)
inline

It sets the horizontal and vertical field of vision (in degrees)

void mrpt::vision::CDifodo::setNumberOfRowsAndCols ( unsigned int  num_rows,
unsigned int  num_cols 
)
inline

It sets the number of rows and cols of the depth image that will be considered by the visual odometry method.

void mrpt::vision::CDifodo::setSpeedFilterConstWeight ( float  new_cweight)
inline

It sets the weight that ponders the previous speed in order to calculate the filtered speed.

Definition at line 202 of file CDifodo.h.

void mrpt::vision::CDifodo::setSpeedFilterEigWeight ( float  new_eweight)
inline

It sets the weight that ponders the product of the corresponding eigenvalue and the previous speed in order to calculate the filtered speed.

Definition at line 205 of file CDifodo.h.

void mrpt::vision::CDifodo::solveDepthSystem ( )
protected

The Solver.

It buils the overdetermined system and gets the least-square solution. It also calculates the least-square covariance matrix

Member Data Documentation

MatrixXi mrpt::vision::CDifodo::border
protected

Matrix which indicates wheter a point is in a border or has an inaccurate depth (border =1, border = 0 otherwise)

Definition at line 84 of file CDifodo.h.

unsigned int mrpt::vision::CDifodo::cam_mode

Resolution of the images taken by the range camera.

Definition at line 151 of file CDifodo.h.

CPose3D mrpt::vision::CDifodo::cam_oldpose

Previous camera pose.

Definition at line 172 of file CDifodo.h.

CPose3D mrpt::vision::CDifodo::cam_pose

Camera poses.

Last camera pose

Definition at line 171 of file CDifodo.h.

unsigned int mrpt::vision::CDifodo::cols
protected

Definition at line 100 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::depth
protected

Matrices that store the point coordinates after downsampling.

Definition at line 62 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::depth_ft
protected

Matrices that store the original and filtered depth frames with the image resolution.

Definition at line 58 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::depth_inter
protected

Definition at line 64 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::depth_old
protected

Definition at line 63 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::depth_wf
protected

Definition at line 59 of file CDifodo.h.

float mrpt::vision::CDifodo::dif_threshold

Threshold to [abs(final_dx-ini_dx) + abs(final_dy-ini_dy)].

Definition at line 163 of file CDifodo.h.

float mrpt::vision::CDifodo::dift_surroundings

Threshold to the difference of dt at a pixel and the value of dt at its surroundings.

Definition at line 165 of file CDifodo.h.

float mrpt::vision::CDifodo::difuv_surroundings

Threshold to the difference of (du,dv) at a pixel and the values of (du,dv) at its surroundings.

Definition at line 164 of file CDifodo.h.

unsigned int mrpt::vision::CDifodo::downsample

Downsample the image taken by the range camera.

Useful to reduce the computational burden, as this downsampling is applied before the gaussian filter

Definition at line 155 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::dt
protected

Definition at line 75 of file CDifodo.h.

float mrpt::vision::CDifodo::dt_threshold

Threshold to dt.

Definition at line 162 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::du
protected

Matrices that store the depth derivatives.

Definition at line 73 of file CDifodo.h.

float mrpt::vision::CDifodo::duv_threshold

Thresholds used to remove borders and noisy points.

Threshold to du*du + dv*dv

Definition at line 161 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::dv
protected

Definition at line 74 of file CDifodo.h.

math::CMatrixFloat66 mrpt::vision::CDifodo::est_cov
protected

Least squares covariance matrix.

Definition at line 87 of file CDifodo.h.

float mrpt::vision::CDifodo::execution_time

Execution time (ms)

Definition at line 168 of file CDifodo.h.

float mrpt::vision::CDifodo::f_dist
protected

Camera properties:

Focal lenght (meters)

Definition at line 90 of file CDifodo.h.

float mrpt::vision::CDifodo::fovh
protected

Horizontal field of view (rad)

Definition at line 93 of file CDifodo.h.

float mrpt::vision::CDifodo::fovv
protected

Vertical field of view (rad)

Definition at line 94 of file CDifodo.h.

float mrpt::vision::CDifodo::fps

Frames per second (Hz)

Definition at line 148 of file CDifodo.h.

unsigned int mrpt::vision::CDifodo::gaussian_mask_size
protected

Size (rows) of the gaussian kernel used to filter the depth image.

Definition at line 103 of file CDifodo.h.

math::CMatrixFloat61 mrpt::vision::CDifodo::kai_abs
protected

Last filtered speed in absolute coordinates.

Definition at line 115 of file CDifodo.h.

math::CMatrixFloat61 mrpt::vision::CDifodo::kai_solver
protected

Solution from the solver: kai before applying the filter in local coordinates.

Definition at line 112 of file CDifodo.h.

float mrpt::vision::CDifodo::lens_disp

Camera properties.

Definition at line 145 of file CDifodo.h.

MatrixXi mrpt::vision::CDifodo::null
protected

Matrix which indicates wheter the depth of a pixel is zero (null = 1) or not (null = 00).

and border and noisy points

Definition at line 81 of file CDifodo.h.

unsigned int mrpt::vision::CDifodo::num_valid_points

Num of valid points after removing null pixels and borders.

Definition at line 158 of file CDifodo.h.

float mrpt::vision::CDifodo::previous_speed_const_weight
protected

Speed filter parameters: Previous_speed_const_weight directly ponders the previous speed in order to calculate the filtered speed.

Recommended range - (0, 0.5) Previous_speed_eig_weight ponders the product of the corresponding eigenvalue and the previous speed in order to calculate the filtered speed Default 0.2

Definition at line 108 of file CDifodo.h.

float mrpt::vision::CDifodo::previous_speed_eig_weight
protected

Default 300.

Definition at line 109 of file CDifodo.h.

unsigned int mrpt::vision::CDifodo::rows
protected

Number of rows and cols of the depth image that will be considered by the visual odometry method.

As a rule, the more rows and cols the slower and more accurate the method becomes. They always have to be less or equal to the size of the original depth image.

Definition at line 99 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::weights
protected

Weights used to ponder equations in the least square solution.

Definition at line 78 of file CDifodo.h.

float mrpt::vision::CDifodo::x_incr
protected

Separation between pixels (cols) in the sensor array (meters)

Definition at line 91 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::xx
protected

Definition at line 65 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::xx_inter
protected

Definition at line 66 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::xx_old
protected

Definition at line 67 of file CDifodo.h.

float mrpt::vision::CDifodo::y_incr
protected

Separation between pixels (rows) in the sensor array (meters)

Definition at line 92 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::yy
protected

Definition at line 68 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::yy_inter
protected

Definition at line 69 of file CDifodo.h.

MatrixXf mrpt::vision::CDifodo::yy_old
protected

Definition at line 70 of file CDifodo.h.




Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014