Main MRPT website > C++ reference
MRPT logo
CDifodo.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2015, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 
10 #ifndef CDifodo_H
11 #define CDifodo_H
12 
13 #include <mrpt/utils/types_math.h> // Eigen
15 #include <mrpt/poses/CPose3D.h>
17 #include <unsupported/Eigen/MatrixFunctions>
18 
19 //class CDeflodo Acronim for "Depth Flow odometry" -> otra opción de nombre...
20 namespace mrpt
21 {
22  namespace vision
23  {
24  /** This abstract class implements a method called "Difodo" to perform Visual odometry with range cameras.
25  * It is based on the range flow equation and assumes that the scene is rigid.
26  * It can work with different image resolutions (640 x 480, 320 x 240 or 160 x 120) and a different number of
27  * coarse-to-fine levels which can be adjusted with the member variables (rows,cols,ctf_levels).
28  *
29  * How to use:
30  * - A derived class must be created which defines the method "loadFrame(...)" according to the user application.
31  * This method has to load the depth image into the variable "depth_wf".
32  * - Call loadFrame();
33  * - Call odometryCalculation();
34  *
35  * For further information have a look at the apps:
36  * - [DifOdometry-Camera](http://www.mrpt.org/list-of-mrpt-apps/application-difodometry-camera/)
37  * - [DifOdometry-Datasets](http://www.mrpt.org/list-of-mrpt-apps/application-difodometry-datasets/)
38  *
39  * Please refer to the respective publication when using this method: *************************
40  *
41  * - JUN/2013: First design.
42  * - JAN/2014: Integrated into MRPT library.
43  * - DIC/2014: Reformulated and improved. The class now needs Eigen version 3.1.0 or above.
44  *
45  * \sa CDifodoCamera, CDifodoDatasets
46  * \ingroup mrpt_vision_grp
47  */
48 
50  protected:
51 
52  /** Matrix that stores the original depth frames with the image resolution */
53  Eigen::MatrixXf depth_wf;
54 
55  /** Matrices that store the point coordinates after downsampling. */
56  std::vector<Eigen::MatrixXf> depth;
57  std::vector<Eigen::MatrixXf> depth_old;
58  std::vector<Eigen::MatrixXf> depth_inter;
59  std::vector<Eigen::MatrixXf> depth_warped;
60  std::vector<Eigen::MatrixXf> xx;
61  std::vector<Eigen::MatrixXf> xx_inter;
62  std::vector<Eigen::MatrixXf> xx_old;
63  std::vector<Eigen::MatrixXf> xx_warped;
64  std::vector<Eigen::MatrixXf> yy;
65  std::vector<Eigen::MatrixXf> yy_inter;
66  std::vector<Eigen::MatrixXf> yy_old;
67  std::vector<Eigen::MatrixXf> yy_warped;
68 
69 
70 
71  /** Matrices that store the depth derivatives */
72  Eigen::MatrixXf du;
73  Eigen::MatrixXf dv;
74  Eigen::MatrixXf dt;
75 
76  /** Weights for the range flow constraint equations in the least square solution */
77  Eigen::MatrixXf weights;
78 
79  /** Matrix which indicates whether the depth of a pixel is zero (null = 1) or not (null = 00).*/
80  Eigen::MatrixXi null;
81 
82  /** Least squares covariance matrix */
84 
85  /** Gaussian mask used to build the pyramid */
86  float g_mask[5][5];
87 
88  /** Camera properties: */
89  float f_dist; //!<Focal lenght (meters)
90  float x_incr; //!<Separation between pixels (cols) in the sensor array (meters)
91  float y_incr; //!<Separation between pixels (rows) in the sensor array (meters)
92  float fovh; //!<Horizontal field of view (rad)
93  float fovv; //!<Vertical field of view (rad)
94 
95  /** The maximum resolution that will be considered by the visual odometry method.
96  * As a rule, the higher the resolution the slower but more accurate the method becomes.
97  * They always have to be less or equal to the size of the original depth image. */
98  unsigned int rows;
99  unsigned int cols;
100 
101  /** Aux variables: size from which the pyramid starts to be built */
102  unsigned int width;
103  unsigned int height;
104 
105  /** Aux variables: number of rows and cols at a given level */
106  unsigned int rows_i;
107  unsigned int cols_i;
108 
109  /** Number of coarse-to-fine levels. I has to be consistent with the number of rows and cols, because the
110  * coarsest level cannot be smaller than 15 x 20. */
111  unsigned int ctf_levels;
112 
113  /** Aux varibles: levels of the image pyramid and the solver, respectively */
114  unsigned int image_level;
115  unsigned int level;
116 
117  /** Speed filter parameters:
118  * Previous_speed_const_weight - Directly weights the previous speed in order to calculate the filtered velocity. Recommended range - (0, 0.5)
119  * Previous_speed_eig_weight - Weights the product of the corresponding eigenvalue and the previous velocity to calculate the filtered velocity*/
120  float previous_speed_const_weight; //!<Default 0.05
121  float previous_speed_eig_weight; //!<Default 0.5
122 
123  /** Transformations of the coarse-to-fine levels */
124  std::vector<Eigen::MatrixXf> transformations;
125 
126  /** Solution from the solver at a given level */
128 
129  /** Last filtered velocity in absolute coordinates */
131 
132  /** Filtered velocity in local coordinates */
135 
136  /** Create the gaussian image pyramid according to the number of coarse-to-fine levels */
137  void buildImagePyramid();
138 
139  /** Warp the second depth image against the first one according to the 3D transformations accumulated up to a given level */
140  void performWarping();
141 
142  /** Calculate the "average" coordinates of the points observed by the camera between two consecutive frames */
143  void calculateCoord();
144 
145  /** Calculates the depth derivatives respect to u,v (rows and cols) and t (time) */
146  void calculateDepthDerivatives();
147 
148  /** This method finds pixels whose depth is zero to subsequently discard them */
149  void findNullPoints();
150 
151  /** This method computes the weighting fuction associated to measurement and linearization errors */
152  void computeWeights();
153 
154  /** The Solver. It buils the overdetermined system and gets the least-square solution.
155  * It also calculates the least-square covariance matrix */
156  void solveOneLevel();
157 
158  /** Method to filter the velocity at each level of the pyramid. */
159  void filterLevelSolution();
160 
161  /** Update camera pose and the velocities for the filter */
162  void poseUpdate();
163 
164 
165  public:
166 
167  /** Lateral displacement of the lens with respect to the center of the camera (meters) */
168  float lens_disp;
169 
170  /** Frames per second (Hz) */
171  float fps;
172 
173  /** Resolution of the images taken by the range camera */
174  unsigned int cam_mode; // (1 - 640 x 480, 2 - 320 x 240, 4 - 160 x 120)
175 
176  /** Downsample the image taken by the range camera. Useful to reduce the computational burden,
177  * as this downsampling is applied before the gaussian pyramid is built. It must be used when
178  the virtual method "loadFrame()" is implemented */
179  unsigned int downsample; // (1 - original size, 2 - res/2, 4 - res/4)
180 
181  /** Num of valid points after removing null pixels*/
182  unsigned int num_valid_points;
183 
184  /** Execution time (ms) */
186 
187  /** Camera poses */
188  mrpt::poses::CPose3D cam_pose; //!< Last camera pose
189  mrpt::poses::CPose3D cam_oldpose; //!< Previous camera pose
190 
191  /** This method performs all the necessary steps to estimate the camera velocity once the new image is read,
192  and updates the camera pose */
193  void odometryCalculation();
194 
195  /** Set the camera focal lenght */
196  inline void setCameraFocalLenght(float new_f) {f_dist = new_f;}
197 
198  /** Get the camera focal lenght */
199  inline float getCameraFocalLenght() const {return f_dist;}
200 
201  /** Get the rows and cols of the depth image that are considered by the visual odometry method. */
202  inline void getRowsAndCols(unsigned int &num_rows, unsigned int &num_cols) const {num_rows = rows; num_cols = cols;}
203 
204  /** Get the number of coarse-to-fine levels that are considered by the visual odometry method. */
205  inline void getCTFLevels(unsigned int &levels) const {levels = ctf_levels;}
206 
207  /** Set the horizontal and vertical field of vision (in degrees) */
208  inline void setFOV(float new_fovh, float new_fovv);
209 
210  /** Get the horizontal and vertical field of vision (in degrees) */
211  inline void getFOV(float &cur_fovh, float &cur_fovv) const {cur_fovh = 57.296*fovh; cur_fovv = 57.296*fovv;}
212 
213  /** Get the filter constant-weight of the velocity filter. */
214  inline float getSpeedFilterConstWeight() const {return previous_speed_const_weight;}
215 
216  /** Get the filter eigen-weight of the velocity filter. */
217  inline float getSpeedFilterEigWeight() const {return previous_speed_eig_weight;}
218 
219  /** Set the filter constant-weight of the velocity filter. */
220  inline void setSpeedFilterConstWeight(float new_cweight) { previous_speed_const_weight = new_cweight;}
221 
222  /** Set the filter eigen-weight of the velocity filter. */
223  inline void setSpeedFilterEigWeight(float new_eweight) { previous_speed_eig_weight = new_eweight;}
224 
225  /** Get the coordinates of the points considered by the visual odometry method */
226  inline void getPointsCoord(Eigen::MatrixXf &x, Eigen::MatrixXf &y, Eigen::MatrixXf &z);
227 
228  /** Get the depth derivatives (last level) respect to u,v and t respectively */
229  inline void getDepthDerivatives(Eigen::MatrixXf &cur_du, Eigen::MatrixXf &cur_dv, Eigen::MatrixXf &cur_dt);
230 
231  /** Get the camera velocity (vx, vy, vz, wx, wy, wz) expressed in local reference frame estimated by the solver (before filtering) */
232  inline mrpt::math::CMatrixFloat61 getSolverSolution() const {return kai_loc_level;}
233 
234  /** Get the last camera velocity (vx, vy, vz, wx, wy, wz) expressed in the world reference frame, obtained after filtering */
235  inline mrpt::math::CMatrixFloat61 getLastSpeedAbs() const {return kai_abs;}
236 
237  /** Get the least-square covariance matrix */
238  inline mrpt::math::CMatrixFloat66 getCovariance() const {return est_cov;}
239 
240  /** Get the matrix of weights */
241  inline void getWeights(Eigen::MatrixXf &we);
242 
243  /** Virtual method to be implemented in derived classes.
244  * It should be used to load a new depth image into the variable depth_wf */
245  virtual void loadFrame() = 0;
246 
247  //Constructor. Initialize variables and matrix sizes
248  CDifodo();
249 
250  };
251  }
252 }
253 
254 
255 
256 #endif
unsigned int cols_i
Definition: CDifodo.h:107
float previous_speed_const_weight
Speed filter parameters: Previous_speed_const_weight - Directly weights the previous speed in order t...
Definition: CDifodo.h:120
unsigned int image_level
Aux varibles: levels of the image pyramid and the solver, respectively.
Definition: CDifodo.h:114
std::vector< Eigen::MatrixXf > xx
Definition: CDifodo.h:60
mrpt::poses::CPose3D cam_oldpose
Previous camera pose.
Definition: CDifodo.h:189
std::vector< Eigen::MatrixXf > depth_warped
Definition: CDifodo.h:59
void setCameraFocalLenght(float new_f)
Set the camera focal lenght.
Definition: CDifodo.h:196
std::vector< Eigen::MatrixXf > yy_warped
Definition: CDifodo.h:67
float fps
Frames per second (Hz)
Definition: CDifodo.h:171
unsigned int rows_i
Aux variables: number of rows and cols at a given level.
Definition: CDifodo.h:106
Eigen::MatrixXi null
Matrix which indicates whether the depth of a pixel is zero (null = 1) or not (null = 00)...
Definition: CDifodo.h:80
float previous_speed_eig_weight
Default 0.5.
Definition: CDifodo.h:121
float y_incr
Separation between pixels (rows) in the sensor array (meters)
Definition: CDifodo.h:91
mrpt::math::CMatrixFloat66 getCovariance() const
Get the least-square covariance matrix.
Definition: CDifodo.h:238
unsigned int cols
Definition: CDifodo.h:99
std::vector< Eigen::MatrixXf > xx_old
Definition: CDifodo.h:62
std::vector< Eigen::MatrixXf > xx_warped
Definition: CDifodo.h:63
mrpt::math::CMatrixFloat61 getLastSpeedAbs() const
Get the last camera velocity (vx, vy, vz, wx, wy, wz) expressed in the world reference frame...
Definition: CDifodo.h:235
std::vector< Eigen::MatrixXf > transformations
Transformations of the coarse-to-fine levels.
Definition: CDifodo.h:124
unsigned int rows
The maximum resolution that will be considered by the visual odometry method.
Definition: CDifodo.h:98
Eigen::MatrixXf depth_wf
Matrix that stores the original depth frames with the image resolution.
Definition: CDifodo.h:53
Eigen::MatrixXf dv
Definition: CDifodo.h:73
float lens_disp
Lateral displacement of the lens with respect to the center of the camera (meters) ...
Definition: CDifodo.h:168
std::vector< Eigen::MatrixXf > yy_old
Definition: CDifodo.h:66
float getCameraFocalLenght() const
Get the camera focal lenght.
Definition: CDifodo.h:199
float execution_time
Execution time (ms)
Definition: CDifodo.h:185
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...
Definition: CDifodo.h:202
A numeric matrix of compile-time fixed size.
math::CMatrixFloat66 est_cov
Least squares covariance matrix.
Definition: CDifodo.h:83
math::CMatrixFloat61 kai_abs
Last filtered velocity in absolute coordinates.
Definition: CDifodo.h:130
Eigen::MatrixXf weights
Weights for the range flow constraint equations in the least square solution.
Definition: CDifodo.h:77
unsigned int height
Definition: CDifodo.h:103
Eigen::MatrixXf dt
Definition: CDifodo.h:74
std::vector< Eigen::MatrixXf > depth_inter
Definition: CDifodo.h:58
unsigned int width
Aux variables: size from which the pyramid starts to be built.
Definition: CDifodo.h:102
std::vector< Eigen::MatrixXf > depth_old
Definition: CDifodo.h:57
mrpt::math::CMatrixFloat61 getSolverSolution() const
Get the camera velocity (vx, vy, vz, wx, wy, wz) expressed in local reference frame estimated by the ...
Definition: CDifodo.h:232
This abstract class implements a method called "Difodo" to perform Visual odometry with range cameras...
Definition: CDifodo.h:49
void getFOV(float &cur_fovh, float &cur_fovv) const
Get the horizontal and vertical field of vision (in degrees)
Definition: CDifodo.h:211
unsigned int ctf_levels
Number of coarse-to-fine levels.
Definition: CDifodo.h:111
math::CMatrixFloat61 kai_loc_old
Definition: CDifodo.h:134
float x_incr
Separation between pixels (cols) in the sensor array (meters)
Definition: CDifodo.h:90
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::vector< Eigen::MatrixXf > yy
Definition: CDifodo.h:64
std::vector< Eigen::MatrixXf > yy_inter
Definition: CDifodo.h:65
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:69
unsigned int num_valid_points
Num of valid points after removing null pixels.
Definition: CDifodo.h:182
math::CMatrixFloat61 kai_loc_level
Solution from the solver at a given level.
Definition: CDifodo.h:127
float fovh
Horizontal field of view (rad)
Definition: CDifodo.h:92
void setSpeedFilterConstWeight(float new_cweight)
Set the filter constant-weight of the velocity filter.
Definition: CDifodo.h:220
void getCTFLevels(unsigned int &levels) const
Get the number of coarse-to-fine levels that are considered by the visual odometry method...
Definition: CDifodo.h:205
mrpt::poses::CPose3D cam_pose
Camera poses.
Definition: CDifodo.h:188
void setSpeedFilterEigWeight(float new_eweight)
Set the filter eigen-weight of the velocity filter.
Definition: CDifodo.h:223
float getSpeedFilterConstWeight() const
Get the filter constant-weight of the velocity filter.
Definition: CDifodo.h:214
std::vector< Eigen::MatrixXf > depth
Matrices that store the point coordinates after downsampling.
Definition: CDifodo.h:56
float fovv
Vertical field of view (rad)
Definition: CDifodo.h:93
unsigned int downsample
Downsample the image taken by the range camera.
Definition: CDifodo.h:179
math::CMatrixFloat61 kai_loc
Filtered velocity in local coordinates.
Definition: CDifodo.h:133
std::vector< Eigen::MatrixXf > xx_inter
Definition: CDifodo.h:61
unsigned int level
Definition: CDifodo.h:115
float getSpeedFilterEigWeight() const
Get the filter eigen-weight of the velocity filter.
Definition: CDifodo.h:217
unsigned int cam_mode
Resolution of the images taken by the range camera.
Definition: CDifodo.h:174
float f_dist
Camera properties:
Definition: CDifodo.h:89
Eigen::MatrixXf du
Matrices that store the depth derivatives.
Definition: CDifodo.h:72



Page generated by Doxygen 1.8.9.1 for MRPT 1.3.0 SVN: at Sun Sep 13 03:55:12 UTC 2015