lidar_optimization.hpp
Go to the documentation of this file.
1 
3 
4 // Original Author of FLOAM: Wang Han
5 // Email wh200720041@gmail.com
6 // Homepage https://wanghan.pro
7 #ifndef FLOAM__LIDAR_OPTIMIZATION_HPP_
8 #define FLOAM__LIDAR_OPTIMIZATION_HPP_
9 
10 #include <ceres/ceres.h>
11 #include <ceres/rotation.h>
12 #include <Eigen/Dense>
13 #include <Eigen/Geometry>
14 
15 namespace floam
16 {
17 
18 namespace lidar
19 {
20 
21 void getTransformFromSe3(const Eigen::Matrix<double, 6, 1> &se3, Eigen::Quaterniond &q, Eigen::Vector3d &t);
22 Eigen::Matrix3d skew(Eigen::Vector3d &mat_in);
23 
24 
25 class LidarEdgeFunctor : public ceres::SizedCostFunction<1, 7>
26 {
27 public:
29  Eigen::Vector3d currentPoint, Eigen::Vector3d lastPointA, Eigen::Vector3d lastPointB)
30  : m_currentPoint(currentPoint), m_lastPointA(lastPointA), m_lastPointB(lastPointB)
31  {}
32 
33  virtual bool Evaluate(double const *const *parameters, double* residuals, double** jacobians) const
34  {
35  Eigen::Map<const Eigen::Quaterniond> q_last_curr(parameters[0]);
36  Eigen::Map<const Eigen::Vector3d> t_last_curr(parameters[0] + 4);
37  Eigen::Vector3d lp;
38  lp = q_last_curr * m_currentPoint + t_last_curr;
39  Eigen::Vector3d nu = (lp - m_lastPointA).cross(lp - m_lastPointB);
40  Eigen::Vector3d de = m_lastPointA - m_lastPointB;
41  double de_norm = de.norm();
42  residuals[0] = nu.norm() / de_norm;
43  if (jacobians != NULL)
44  {
45  if (jacobians[0] != NULL)
46  {
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]);
52  J_se3.setZero();
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;
55  }
56  }
57  return true;
58  }
59 
61 };
62 
63 
64 class LidarSurfaceFunctor : public ceres::SizedCostFunction<1, 7>
65 {
66 public:
67  LidarSurfaceFunctor(Eigen::Vector3d currentPoint, Eigen::Vector3d planeUnitNormal, double negativeOADotNormal)
68  : m_currentPoint(currentPoint),
69  m_planeUnitNormal(planeUnitNormal),
70  m_negativeOADotNormal(negativeOADotNormal) {}
71 
72  virtual bool Evaluate(double const *const *parameters, double* residuals, double** jacobians) const
73  {
74  Eigen::Map<const Eigen::Quaterniond> q_w_curr(parameters[0]);
75  Eigen::Map<const Eigen::Vector3d> t_w_curr(parameters[0] + 4);
76  Eigen::Vector3d point_w = q_w_curr * m_currentPoint + t_w_curr;
77  residuals[0] = m_planeUnitNormal.dot(point_w) + m_negativeOADotNormal;
78  if (jacobians != NULL)
79  {
80  if (jacobians[0] != NULL)
81  {
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]);
87  J_se3.setZero();
88  J_se3.block<1, 6>(0, 0) = m_planeUnitNormal.transpose() * dp_by_se3;
89  }
90  }
91  return true;
92  }
93 
96 };
97 
98 
99 class PoseSE3Parameterization : public ceres::LocalParameterization
100 {
101 public:
104  virtual bool Plus(const double *x, const double *delta, double *x_plus_delta) const;
105  virtual bool ComputeJacobian(const double *x, double *jacobian) const;
106  virtual int GlobalSize() const { return 7; }
107  virtual int LocalSize() const { return 6; }
108 };
109 } // namespace lidar
110 } // namespace floam
111 
112 #endif // FLOAM__LIDAR_OPTIMIZATION_HPP_
floam::lidar::getTransformFromSe3
void getTransformFromSe3(const Eigen::Matrix< double, 6, 1 > &se3, Eigen::Quaterniond &q, Eigen::Vector3d &t)
Definition: lidar_optimization.cpp:42
floam::lidar::PoseSE3Parameterization::~PoseSE3Parameterization
virtual ~PoseSE3Parameterization()
Definition: lidar_optimization.hpp:103
floam::lidar::PoseSE3Parameterization::ComputeJacobian
virtual bool ComputeJacobian(const double *x, double *jacobian) const
Definition: lidar_optimization.cpp:33
floam::lidar::LidarEdgeFunctor::m_lastPointA
Eigen::Vector3d m_lastPointA
Definition: lidar_optimization.hpp:60
floam::lidar::LidarSurfaceFunctor::LidarSurfaceFunctor
LidarSurfaceFunctor(Eigen::Vector3d currentPoint, Eigen::Vector3d planeUnitNormal, double negativeOADotNormal)
Definition: lidar_optimization.hpp:67
floam::lidar::LidarSurfaceFunctor
Definition: lidar_optimization.hpp:64
floam::lidar::LidarSurfaceFunctor::Evaluate
virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
Definition: lidar_optimization.hpp:72
floam::lidar::LidarSurfaceFunctor::m_planeUnitNormal
Eigen::Vector3d m_planeUnitNormal
Definition: lidar_optimization.hpp:94
floam::lidar::PoseSE3Parameterization::PoseSE3Parameterization
PoseSE3Parameterization()
Definition: lidar_optimization.hpp:102
floam::lidar::PoseSE3Parameterization
Definition: lidar_optimization.hpp:99
floam::lidar::LidarEdgeFunctor::m_currentPoint
Eigen::Vector3d m_currentPoint
Definition: lidar_optimization.hpp:60
floam::lidar::LidarSurfaceFunctor::m_negativeOADotNormal
double m_negativeOADotNormal
Definition: lidar_optimization.hpp:95
floam::lidar::PoseSE3Parameterization::LocalSize
virtual int LocalSize() const
Definition: lidar_optimization.hpp:107
floam::lidar::LidarEdgeFunctor::LidarEdgeFunctor
LidarEdgeFunctor(Eigen::Vector3d currentPoint, Eigen::Vector3d lastPointA, Eigen::Vector3d lastPointB)
Definition: lidar_optimization.hpp:28
floam::lidar::skew
Eigen::Matrix3d skew(Eigen::Vector3d &mat_in)
floam::lidar::PoseSE3Parameterization::Plus
virtual bool Plus(const double *x, const double *delta, double *x_plus_delta) const
Definition: lidar_optimization.cpp:16
floam::lidar::LidarSurfaceFunctor::m_currentPoint
Eigen::Vector3d m_currentPoint
Definition: lidar_optimization.hpp:94
floam::lidar::PoseSE3Parameterization::GlobalSize
virtual int GlobalSize() const
Definition: lidar_optimization.hpp:106
floam::lidar::LidarEdgeFunctor::m_lastPointB
Eigen::Vector3d m_lastPointB
Definition: lidar_optimization.hpp:60
floam::lidar::LidarEdgeFunctor::Evaluate
virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
Definition: lidar_optimization.hpp:33
floam::lidar::LidarEdgeFunctor
Definition: lidar_optimization.hpp:25
floam
Major rewrite Author: Evan Flynn.
Definition: lidar.hpp:15


floam
Author(s): Han Wang
autogenerated on Wed Mar 2 2022 00:23:09