17 #include <unsupported/Eigen/MatrixFunctions>
56 std::vector<Eigen::MatrixXf>
depth;
60 std::vector<Eigen::MatrixXf>
xx;
64 std::vector<Eigen::MatrixXf>
yy;
137 void buildImagePyramid();
140 void performWarping();
143 void calculateCoord();
146 void calculateDepthDerivatives();
149 void findNullPoints();
152 void computeWeights();
156 void solveOneLevel();
159 void filterLevelSolution();
193 void odometryCalculation();
202 inline void getRowsAndCols(
unsigned int &num_rows,
unsigned int &num_cols)
const {num_rows = rows; num_cols = cols;}
205 inline void getCTFLevels(
unsigned int &levels)
const {levels = ctf_levels;}
208 inline void setFOV(
float new_fovh,
float new_fovv);
211 inline void getFOV(
float &cur_fovh,
float &cur_fovv)
const {cur_fovh = 57.296*fovh; cur_fovv = 57.296*fovv;}
226 inline void getPointsCoord(Eigen::MatrixXf &x, Eigen::MatrixXf &y, Eigen::MatrixXf &z);
229 inline void getDepthDerivatives(Eigen::MatrixXf &cur_du, Eigen::MatrixXf &cur_dv, Eigen::MatrixXf &cur_dt);
241 inline void getWeights(Eigen::MatrixXf &we);
245 virtual void loadFrame() = 0;
float previous_speed_const_weight
Speed filter parameters: Previous_speed_const_weight - Directly weights the previous speed in order t...
unsigned int image_level
Aux varibles: levels of the image pyramid and the solver, respectively.
std::vector< Eigen::MatrixXf > xx
mrpt::poses::CPose3D cam_oldpose
Previous camera pose.
std::vector< Eigen::MatrixXf > depth_warped
void setCameraFocalLenght(float new_f)
Set the camera focal lenght.
std::vector< Eigen::MatrixXf > yy_warped
float fps
Frames per second (Hz)
unsigned int rows_i
Aux variables: number of rows and cols at a given level.
Eigen::MatrixXi null
Matrix which indicates whether the depth of a pixel is zero (null = 1) or not (null = 00)...
float previous_speed_eig_weight
Default 0.5.
float y_incr
Separation between pixels (rows) in the sensor array (meters)
mrpt::math::CMatrixFloat66 getCovariance() const
Get the least-square covariance matrix.
std::vector< Eigen::MatrixXf > xx_old
std::vector< Eigen::MatrixXf > xx_warped
mrpt::math::CMatrixFloat61 getLastSpeedAbs() const
Get the last camera velocity (vx, vy, vz, wx, wy, wz) expressed in the world reference frame...
std::vector< Eigen::MatrixXf > transformations
Transformations of the coarse-to-fine levels.
unsigned int rows
The maximum resolution that will be considered by the visual odometry method.
Eigen::MatrixXf depth_wf
Matrix that stores the original depth frames with the image resolution.
float lens_disp
Lateral displacement of the lens with respect to the center of the camera (meters) ...
std::vector< Eigen::MatrixXf > yy_old
float getCameraFocalLenght() const
Get the camera focal lenght.
float execution_time
Execution time (ms)
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...
A numeric matrix of compile-time fixed size.
math::CMatrixFloat66 est_cov
Least squares covariance matrix.
math::CMatrixFloat61 kai_abs
Last filtered velocity in absolute coordinates.
Eigen::MatrixXf weights
Weights for the range flow constraint equations in the least square solution.
std::vector< Eigen::MatrixXf > depth_inter
unsigned int width
Aux variables: size from which the pyramid starts to be built.
std::vector< Eigen::MatrixXf > depth_old
mrpt::math::CMatrixFloat61 getSolverSolution() const
Get the camera velocity (vx, vy, vz, wx, wy, wz) expressed in local reference frame estimated by the ...
This abstract class implements a method called "Difodo" to perform Visual odometry with range cameras...
void getFOV(float &cur_fovh, float &cur_fovv) const
Get the horizontal and vertical field of vision (in degrees)
unsigned int ctf_levels
Number of coarse-to-fine levels.
math::CMatrixFloat61 kai_loc_old
float x_incr
Separation between pixels (cols) in the sensor array (meters)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::vector< Eigen::MatrixXf > yy
std::vector< Eigen::MatrixXf > yy_inter
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
unsigned int num_valid_points
Num of valid points after removing null pixels.
math::CMatrixFloat61 kai_loc_level
Solution from the solver at a given level.
float fovh
Horizontal field of view (rad)
void setSpeedFilterConstWeight(float new_cweight)
Set the filter constant-weight of the velocity filter.
void getCTFLevels(unsigned int &levels) const
Get the number of coarse-to-fine levels that are considered by the visual odometry method...
mrpt::poses::CPose3D cam_pose
Camera poses.
void setSpeedFilterEigWeight(float new_eweight)
Set the filter eigen-weight of the velocity filter.
float getSpeedFilterConstWeight() const
Get the filter constant-weight of the velocity filter.
std::vector< Eigen::MatrixXf > depth
Matrices that store the point coordinates after downsampling.
float fovv
Vertical field of view (rad)
unsigned int downsample
Downsample the image taken by the range camera.
math::CMatrixFloat61 kai_loc
Filtered velocity in local coordinates.
std::vector< Eigen::MatrixXf > xx_inter
float getSpeedFilterEigWeight() const
Get the filter eigen-weight of the velocity filter.
unsigned int cam_mode
Resolution of the images taken by the range camera.
float f_dist
Camera properties:
Eigen::MatrixXf du
Matrices that store the depth derivatives.