7 #ifndef FLOAM__LIDAR_OPTIMIZATION_HPP_
8 #define FLOAM__LIDAR_OPTIMIZATION_HPP_
10 #include <ceres/ceres.h>
11 #include <ceres/rotation.h>
12 #include <Eigen/Dense>
13 #include <Eigen/Geometry>
21 void getTransformFromSe3(
const Eigen::Matrix<double, 6, 1> &se3, Eigen::Quaterniond &q, Eigen::Vector3d &t);
22 Eigen::Matrix3d
skew(Eigen::Vector3d &mat_in);
29 Eigen::Vector3d currentPoint, Eigen::Vector3d lastPointA, Eigen::Vector3d lastPointB)
33 virtual bool Evaluate(
double const *
const *parameters,
double* residuals,
double** jacobians)
const
35 Eigen::Map<const Eigen::Quaterniond> q_last_curr(parameters[0]);
36 Eigen::Map<const Eigen::Vector3d> t_last_curr(parameters[0] + 4);
41 double de_norm = de.norm();
42 residuals[0] = nu.norm() / de_norm;
43 if (jacobians != NULL)
45 if (jacobians[0] != NULL)
47 Eigen::Matrix3d skew_lp =
skew(lp);
48 Eigen::Matrix<double, 3, 6> dp_by_se3;
49 dp_by_se3.block<3, 3>(0, 0) = -skew_lp;
50 (dp_by_se3.block<3, 3>(0, 3)).setIdentity();
51 Eigen::Map<Eigen::Matrix<double, 1, 7, Eigen::RowMajor>> J_se3(jacobians[0]);
53 Eigen::Matrix3d skew_de =
skew(de);
54 J_se3.block<1, 6>(0, 0) = -nu.transpose() / nu.norm() * skew_de * dp_by_se3 / de_norm;
67 LidarSurfaceFunctor(Eigen::Vector3d currentPoint, Eigen::Vector3d planeUnitNormal,
double negativeOADotNormal)
72 virtual bool Evaluate(
double const *
const *parameters,
double* residuals,
double** jacobians)
const
74 Eigen::Map<const Eigen::Quaterniond> q_w_curr(parameters[0]);
75 Eigen::Map<const Eigen::Vector3d> t_w_curr(parameters[0] + 4);
78 if (jacobians != NULL)
80 if (jacobians[0] != NULL)
82 Eigen::Matrix3d skew_point_w =
skew(point_w);
83 Eigen::Matrix<double, 3, 6> dp_by_se3;
84 dp_by_se3.block<3, 3>(0, 0) = -skew_point_w;
85 (dp_by_se3.block<3, 3>(0, 3)).setIdentity();
86 Eigen::Map<Eigen::Matrix<double, 1, 7, Eigen::RowMajor>> J_se3(jacobians[0]);
104 virtual bool Plus(
const double *x,
const double *delta,
double *x_plus_delta)
const;
112 #endif // FLOAM__LIDAR_OPTIMIZATION_HPP_