feat:给solver添加中文注释

main
邱棚 2025-02-02 01:54:21 +08:00
parent 9bf19d5ff3
commit 3c4963d289
2 changed files with 361 additions and 36 deletions

View File

@ -7,99 +7,234 @@
namespace oh_my_loam { namespace oh_my_loam {
// ============================================================================
// 数据结构定义
// ============================================================================
/**
* @brief -线
*
* 线线线
*/
struct PointLinePair { struct PointLinePair {
TPoint pt; TPoint pt; // 待优化的点
// 内部结构体,用于描述直线
struct Line { struct Line {
TPoint pt1, pt2; TPoint pt1, pt2; // 定义直线的两个点
// 默认构造函数
Line() = default; Line() = default;
// 构造函数,根据传入的两个点构造直线
Line(const TPoint &pt1, const TPoint &pt2) : pt1(pt1), pt2(pt2) {} Line(const TPoint &pt1, const TPoint &pt2) : pt1(pt1), pt2(pt2) {}
}; };
Line line;
Line line; // 与点对应的直线
// 构造函数,根据点和直线结构体构造匹配对
PointLinePair(const TPoint &pt, const Line &line) : pt(pt), line(line) {} PointLinePair(const TPoint &pt, const Line &line) : pt(pt), line(line) {}
// 构造函数,根据点和直线上的两个点构造匹配对
PointLinePair(const TPoint &pt, const TPoint &pt1, const TPoint &pt2) PointLinePair(const TPoint &pt, const TPoint &pt1, const TPoint &pt2)
: pt(pt), line(pt1, pt2) {} : pt(pt), line(pt1, pt2) {}
}; };
/**
* @brief -
*
*
*/
struct PointPlanePair { struct PointPlanePair {
TPoint pt; TPoint pt; // 待优化的点
// 内部结构体,用于描述平面
struct Plane { struct Plane {
TPoint pt1, pt2, pt3; TPoint pt1, pt2, pt3; // 定义平面的三个点
// 默认构造函数
Plane() = default; Plane() = default;
// 构造函数,根据三个点构造平面
Plane(const TPoint &pt1, const TPoint &pt2, const TPoint &pt3) Plane(const TPoint &pt1, const TPoint &pt2, const TPoint &pt3)
: pt1(pt1), pt2(pt2), pt3(pt3) {} : pt1(pt1), pt2(pt2), pt3(pt3) {}
}; };
Plane plane;
Plane plane; // 与点对应的平面
// 构造函数,根据点和平面结构体构造匹配对
PointPlanePair(const TPoint &pt, const Plane &plane) : pt(pt), plane(plane) {} PointPlanePair(const TPoint &pt, const Plane &plane) : pt(pt), plane(plane) {}
// 构造函数,根据点和平面上的三个点构造匹配对
PointPlanePair(const TPoint &pt, const TPoint &pt1, const TPoint &pt2, PointPlanePair(const TPoint &pt, const TPoint &pt1, const TPoint &pt2,
const TPoint &pt3) const TPoint &pt3)
: pt(pt), plane(pt1, pt2, pt3) {} : pt(pt), plane(pt1, pt2, pt3) {}
}; };
/**
* @brief -线
*
* 线 6×1
* 3 线 3 线
*/
struct PointLineCoeffPair { struct PointLineCoeffPair {
TPoint pt; TPoint pt; // 待优化的点
Eigen::Matrix<double, 6, 1> line_coeff; Eigen::Matrix<double, 6, 1> line_coeff; // 直线系数6维向量
// 构造函数,根据点和直线系数构造匹配对
PointLineCoeffPair(const TPoint &pt, PointLineCoeffPair(const TPoint &pt,
const Eigen::Matrix<double, 6, 1> &line_coeff) const Eigen::Matrix<double, 6, 1> &line_coeff)
: pt(pt), line_coeff(line_coeff) {} : pt(pt), line_coeff(line_coeff) {}
}; };
/**
* @brief -
*
* 4
* ax+by+cz+d=0
*/
struct PointPlaneCoeffPair { struct PointPlaneCoeffPair {
TPoint pt; TPoint pt; // 待优化的点
Eigen::Vector4d plane_coeff; Eigen::Vector4d plane_coeff; // 平面系数4维向量
// 构造函数,根据点和平面系数构造匹配对
PointPlaneCoeffPair(const TPoint &pt, const Eigen::Vector4d &plane_coeff) PointPlaneCoeffPair(const TPoint &pt, const Eigen::Vector4d &plane_coeff)
: pt(pt), plane_coeff(plane_coeff) {} : pt(pt), plane_coeff(plane_coeff) {}
}; };
// ============================================================================
// 成本函数定义
// ============================================================================
/**
* @brief -线
*
* 使线
* 线
*/
class PointLineCostFunction { class PointLineCostFunction {
public: public:
// 构造函数,传入匹配对和时间因子
PointLineCostFunction(const PointLinePair &pair, double time) PointLineCostFunction(const PointLinePair &pair, double time)
: pair_(pair), time_(time){}; : pair_(pair), time_(time) {};
/**
* @brief
*
* Ceres
*
* @param r_quat 4
* @param t_vec 3
* @param residual 3
* @return true
*/
template <typename T> template <typename T>
bool operator()(const T *const r_quat, const T *const t_vec, bool operator()(const T *const r_quat, const T *const t_vec,
T *residual) const; T *residual) const;
/**
* @brief
*
* Ceres
*
* @param pair -线
* @param time
* @return ceres::CostFunction*
*/
static ceres::CostFunction *Create(const PointLinePair &pair, double time) { static ceres::CostFunction *Create(const PointLinePair &pair, double time) {
return new ceres::AutoDiffCostFunction<PointLineCostFunction, 3, 4, 3>( return new ceres::AutoDiffCostFunction<PointLineCostFunction, 3, 4, 3>(
new PointLineCostFunction(pair, time)); new PointLineCostFunction(pair, time));
} }
private: private:
PointLinePair pair_; PointLinePair pair_; // 当前匹配对
double time_; double time_; // 时间因子
// 禁止拷贝构造函数和赋值操作(宏定义,确保对象不可复制)
DISALLOW_COPY_AND_ASSIGN(PointLineCostFunction) DISALLOW_COPY_AND_ASSIGN(PointLineCostFunction)
}; };
/**
* @brief -
*
* 使
*
*/
class PointPlaneCostFunction { class PointPlaneCostFunction {
public: public:
// 构造函数,传入匹配对和时间因子
PointPlaneCostFunction(const PointPlanePair &pair, double time) PointPlaneCostFunction(const PointPlanePair &pair, double time)
: pair_(pair), time_(time){}; : pair_(pair), time_(time) {};
/**
* @brief
*
*
*
* @param r_quat 4
* @param t_vec 3
* @param residual
* @return true
*/
template <typename T> template <typename T>
bool operator()(const T *const r_quat, const T *const t_vec, bool operator()(const T *const r_quat, const T *const t_vec,
T *residual) const; T *residual) const;
/**
* @brief
*
* -
*
* @param pair -
* @param time
* @return ceres::CostFunction*
*/
static ceres::CostFunction *Create(const PointPlanePair &pair, double time) { static ceres::CostFunction *Create(const PointPlanePair &pair, double time) {
return new ceres::AutoDiffCostFunction<PointPlaneCostFunction, 1, 4, 3>( return new ceres::AutoDiffCostFunction<PointPlaneCostFunction, 1, 4, 3>(
new PointPlaneCostFunction(pair, time)); new PointPlaneCostFunction(pair, time));
} }
private: private:
PointPlanePair pair_; PointPlanePair pair_; // 当前匹配对
double time_; double time_; // 时间因子
DISALLOW_COPY_AND_ASSIGN(PointPlaneCostFunction) DISALLOW_COPY_AND_ASSIGN(PointPlaneCostFunction)
}; };
/**
* @brief -线
*
* 线线
*/
class PointLineCoeffCostFunction { class PointLineCoeffCostFunction {
public: public:
// 构造函数,传入匹配对和时间因子
PointLineCoeffCostFunction(const PointLineCoeffPair &pair, double time) PointLineCoeffCostFunction(const PointLineCoeffPair &pair, double time)
: pair_(pair), time_(time){}; : pair_(pair), time_(time) {};
/**
* @brief
*
* 3
*
* @param r_quat 4
* @param t_vec 3
* @param residual 3
* @return true
*/
template <typename T> template <typename T>
bool operator()(const T *const r_quat, const T *const t_vec, bool operator()(const T *const r_quat, const T *const t_vec,
T *residual) const; T *residual) const;
/**
* @brief
*
* -线
*
* @param pair -线
* @param time
* @return ceres::CostFunction*
*/
static ceres::CostFunction *Create(const PointLineCoeffPair &pair, static ceres::CostFunction *Create(const PointLineCoeffPair &pair,
double time) { double time) {
return new ceres::AutoDiffCostFunction<PointLineCoeffCostFunction, 1, 4, 3>( return new ceres::AutoDiffCostFunction<PointLineCoeffCostFunction, 1, 4, 3>(
@ -107,20 +242,46 @@ class PointLineCoeffCostFunction {
} }
private: private:
PointLineCoeffPair pair_; PointLineCoeffPair pair_; // 当前匹配对(含直线系数)
double time_; double time_; // 时间因子
DISALLOW_COPY_AND_ASSIGN(PointLineCoeffCostFunction) DISALLOW_COPY_AND_ASSIGN(PointLineCoeffCostFunction)
}; };
/**
* @brief -
*
*
*/
class PointPlaneCoeffCostFunction { class PointPlaneCoeffCostFunction {
public: public:
// 构造函数,传入匹配对和时间因子
PointPlaneCoeffCostFunction(const PointPlaneCoeffPair &pair, double time) PointPlaneCoeffCostFunction(const PointPlaneCoeffPair &pair, double time)
: pair_(pair), time_(time){}; : pair_(pair), time_(time) {};
/**
* @brief
*
*
*
* @param r_quat 4
* @param t_vec 3
* @param residual
* @return true
*/
template <typename T> template <typename T>
bool operator()(const T *const r_quat, const T *const t_vec, bool operator()(const T *const r_quat, const T *const t_vec,
T *residual) const; T *residual) const;
/**
* @brief
*
* -
*
* @param pair -
* @param time
* @return ceres::CostFunction*
*/
static ceres::CostFunction *Create(const PointPlaneCoeffPair &pair, static ceres::CostFunction *Create(const PointPlaneCoeffPair &pair,
double time) { double time) {
return new ceres::AutoDiffCostFunction<PointPlaneCoeffCostFunction, 1, 4, return new ceres::AutoDiffCostFunction<PointPlaneCoeffCostFunction, 1, 4,
@ -129,78 +290,144 @@ class PointPlaneCoeffCostFunction {
} }
private: private:
PointPlaneCoeffPair pair_; PointPlaneCoeffPair pair_; // 当前匹配对(含平面系数)
double time_; double time_; // 时间因子
DISALLOW_COPY_AND_ASSIGN(PointPlaneCoeffCostFunction) DISALLOW_COPY_AND_ASSIGN(PointPlaneCoeffCostFunction)
}; };
// ============================================================================
// 成本函数实现(模板函数)
// ============================================================================
/**
* @brief -线
*
* 姿
* 线
* 线
*
* @tparam T float double
* @param r_quat 4
* @param t_vec 3
* @param residual 3
* @return true
*/
template <typename T> template <typename T>
bool PointLineCostFunction::operator()(const T *const r_quat, bool PointLineCostFunction::operator()(const T *const r_quat,
const T *const t_vec, const T *const t_vec,
T *residual) const { T *residual) const {
// 提取匹配对中的点和直线上的两个点
const auto &pt = pair_.pt, &pt1 = pair_.line.pt1, &pt2 = pair_.line.pt2; const auto &pt = pair_.pt, &pt1 = pair_.line.pt1, &pt2 = pair_.line.pt2;
// 将点转换为 Eigen 向量3维
Eigen::Matrix<T, 3, 1> p(T(pt.x), T(pt.y), T(pt.z)); Eigen::Matrix<T, 3, 1> p(T(pt.x), T(pt.y), T(pt.z));
Eigen::Matrix<T, 3, 1> p1(T(pt1.x), T(pt1.y), T(pt1.z)); Eigen::Matrix<T, 3, 1> p1(T(pt1.x), T(pt1.y), T(pt1.z));
Eigen::Matrix<T, 3, 1> p2(T(pt2.x), T(pt2.y), T(pt2.z)); Eigen::Matrix<T, 3, 1> p2(T(pt2.x), T(pt2.y), T(pt2.z));
// 根据输入的旋转参数构造四元数注意Ceres中四元数存储顺序可能为 [x,y,z,w]
Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]); Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]);
// 构造平移向量
Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]); Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]);
if (time_ <= 1.0 - 1.0e-6) { // 如果时间因子小于 1则对旋转和平移进行插值运动补偿
if (time_ <= T(1.0) - T(1.0e-6)) {
r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r); r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r);
t = T(time_) * t; t = T(time_) * t;
} }
// 计算变换后的点位置
Eigen::Matrix<T, 3, 1> p0 = r * p + t; Eigen::Matrix<T, 3, 1> p0 = r * p + t;
// norm of cross product: triangle area x 2 // 利用交叉乘积计算三角形面积(面积 = 0.5 * |(p0-p1) x (p0-p2)|
Eigen::Matrix<T, 3, 1> area = (p0 - p1).cross(p0 - p2) * 0.5; Eigen::Matrix<T, 3, 1> area = (p0 - p1).cross(p0 - p2) * T(0.5);
// 计算直线基底的长度(两点之间的距离)
T base_length = (p2 - p1).norm(); T base_length = (p2 - p1).norm();
// 将面积除以基底长度,即可得到点到直线的距离(与三角形高等价)
// 注意这里残差为3维分别保存了每个坐标轴上的误差也可看作向量形式
residual[0] = area[0] / base_length; residual[0] = area[0] / base_length;
residual[1] = area[1] / base_length; residual[1] = area[1] / base_length;
residual[2] = area[2] / base_length; residual[2] = area[2] / base_length;
return true; return true;
} }
/**
* @brief -
*
* 姿
*
*
*
* @tparam T
* @param r_quat 4
* @param t_vec 3
* @param residual
* @return true
*/
template <typename T> template <typename T>
bool PointPlaneCostFunction::operator()(const T *const r_quat, bool PointPlaneCostFunction::operator()(const T *const r_quat,
const T *const t_vec, const T *const t_vec,
T *residual) const { T *residual) const {
// 提取匹配对中的点和平面上三个点
const auto &pt = pair_.pt, &pt1 = pair_.plane.pt1, &pt2 = pair_.plane.pt2, const auto &pt = pair_.pt, &pt1 = pair_.plane.pt1, &pt2 = pair_.plane.pt2,
&pt3 = pair_.plane.pt3; &pt3 = pair_.plane.pt3;
// 将各点转换为 Eigen 向量
Eigen::Matrix<T, 3, 1> p(T(pt.x), T(pt.y), T(pt.z)); Eigen::Matrix<T, 3, 1> p(T(pt.x), T(pt.y), T(pt.z));
Eigen::Matrix<T, 3, 1> p1(T(pt1.x), T(pt1.y), T(pt1.z)); Eigen::Matrix<T, 3, 1> p1(T(pt1.x), T(pt1.y), T(pt1.z));
Eigen::Matrix<T, 3, 1> p2(T(pt2.x), T(pt2.y), T(pt2.z)); Eigen::Matrix<T, 3, 1> p2(T(pt2.x), T(pt2.y), T(pt2.z));
Eigen::Matrix<T, 3, 1> p3(T(pt3.x), T(pt3.y), T(pt3.z)); Eigen::Matrix<T, 3, 1> p3(T(pt3.x), T(pt3.y), T(pt3.z));
// 构造旋转四元数和平移向量
Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]); Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]);
Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]); Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]);
if (time_ <= 1.0 - 1.0e-6) { // 进行运动补偿插值
if (time_ <= T(1.0) - T(1.0e-6)) {
r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r); r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r);
t = T(time_) * t; t = T(time_) * t;
} }
// 计算变换后的点位置
Eigen::Matrix<T, 3, 1> p0 = r * p + t; Eigen::Matrix<T, 3, 1> p0 = r * p + t;
// 计算平面法向量:由平面内两个向量叉乘后归一化得到
Eigen::Matrix<T, 3, 1> normal = (p2 - p1).cross(p3 - p1).normalized(); Eigen::Matrix<T, 3, 1> normal = (p2 - p1).cross(p3 - p1).normalized();
// 计算点到平面的距离(点与平面上一点连线与法向量的内积)
residual[0] = (p0 - p1).dot(normal); residual[0] = (p0 - p1).dot(normal);
return true; return true;
} }
/**
* @brief -线
*
* 使线 3 线
* 3 线线
* 3
*
* @tparam T
* @param r_quat 4
* @param t_vec 3
* @param residual 3
* @return true
*/
template <typename T> template <typename T>
bool PointLineCoeffCostFunction::operator()(const T *const r_quat, bool PointLineCoeffCostFunction::operator()(const T *const r_quat,
const T *const t_vec, const T *const t_vec,
T *residual) const { T *residual) const {
// 将待优化点转换为 Eigen 向量
Eigen::Matrix<T, 3, 1> p(T(pair_.pt.x), T(pair_.pt.y), T(pair_.pt.z)); Eigen::Matrix<T, 3, 1> p(T(pair_.pt.x), T(pair_.pt.y), T(pair_.pt.z));
// 将直线系数转换为模板类型,并分解为直线上的一点 p1 和方向向量 dir
Eigen::Matrix<T, 6, 1> coeff = pair_.line_coeff.template cast<T>(); Eigen::Matrix<T, 6, 1> coeff = pair_.line_coeff.template cast<T>();
Eigen::Matrix<T, 3, 1> p1 = coeff.topRows(3); Eigen::Matrix<T, 3, 1> p1 = coeff.topRows(3);
Eigen::Matrix<T, 3, 1> dir = coeff.bottomRows(3); Eigen::Matrix<T, 3, 1> dir = coeff.bottomRows(3);
// 构造旋转和平移参数
Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]); Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]);
Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]); Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]);
if (time_ <= 1.0 - 1.0e-6) { // 如果时间因子小于1则进行插值
if (time_ <= T(1.0) - T(1.0e-6)) {
r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r); r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r);
t = T(time_) * t; t = T(time_) * t;
} }
// 计算变换后的点位置
Eigen::Matrix<T, 3, 1> p0 = r * p + t; Eigen::Matrix<T, 3, 1> p0 = r * p + t;
// 计算待优化点到直线的距离误差:计算 (p0-p1) 与直线方向的叉积
Eigen::Matrix<T, 3, 1> cross = (p0 - p1).cross(dir); Eigen::Matrix<T, 3, 1> cross = (p0 - p1).cross(dir);
residual[0] = cross[0]; residual[0] = cross[0];
residual[1] = cross[1]; residual[1] = cross[1];
@ -208,24 +435,42 @@ bool PointLineCoeffCostFunction::operator()(const T *const r_quat,
return true; return true;
} }
/**
* @brief -
*
* 4 ax+by+cz+d=0
*
*
* @tparam T
* @param r_quat 4
* @param t_vec 3
* @param residual
* @return true
*/
template <typename T> template <typename T>
bool PointPlaneCoeffCostFunction::operator()(const T *const r_quat, bool PointPlaneCoeffCostFunction::operator()(const T *const r_quat,
const T *const t_vec, const T *const t_vec,
T *residual) const { T *residual) const {
// 将待优化点转换为 Eigen 向量
Eigen::Matrix<T, 3, 1> p(T(pair_.pt.x), T(pair_.pt.y), T(pair_.pt.z)); Eigen::Matrix<T, 3, 1> p(T(pair_.pt.x), T(pair_.pt.y), T(pair_.pt.z));
// 将平面系数转换为模板类型的 4 维向量
Eigen::Matrix<T, 4, 1> coeff = pair_.plane_coeff.template cast<T>(); Eigen::Matrix<T, 4, 1> coeff = pair_.plane_coeff.template cast<T>();
// 构造旋转四元数和平移向量
Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]); Eigen::Quaternion<T> r(r_quat[3], r_quat[0], r_quat[1], r_quat[2]);
Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]); Eigen::Matrix<T, 3, 1> t(t_vec[0], t_vec[1], t_vec[2]);
if (time_ <= 1.0 - 1.0e-6) { // 对时间因子小于1的情况进行插值
if (time_ <= T(1.0) - T(1.0e-6)) {
r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r); r = Eigen::Quaternion<T>::Identity().slerp(T(time_), r);
t = T(time_) * t; t = T(time_) * t;
} }
// 计算变换后的点位置
Eigen::Matrix<T, 3, 1> p0 = r * p + t; Eigen::Matrix<T, 3, 1> p0 = r * p + t;
// 计算点到平面的距离残差:将点 p0 代入平面方程,得到 ax+by+cz+d
residual[0] = coeff.topRows(3).transpose() * p0; residual[0] = coeff.topRows(3).transpose() * p0;
residual[0] += coeff(3); residual[0] += coeff(3);
return true; return true;
} }
} // namespace oh_my_loam } // namespace oh_my_loam

View File

@ -8,60 +8,140 @@
namespace oh_my_loam { namespace oh_my_loam {
// 定义一个局部变量,表示 Huber 损失的尺度参数
namespace { namespace {
double kHuberLossScale = 0.1; double kHuberLossScale = 0.1;
} }
/**
* @brief PoseSolver
*
* 姿姿
* Ceres 使 Eigen
* Huber
*
* @param pose 姿 common::Pose3d
*/
PoseSolver::PoseSolver(const common::Pose3d &pose) { PoseSolver::PoseSolver(const common::Pose3d &pose) {
// 将输入位姿的旋转部分(四元数的系数)复制到内部数组 r_quat_ 中,四元数有 4 个元素
std::copy_n(pose.r_quat().coeffs().data(), 4, r_quat_); std::copy_n(pose.r_quat().coeffs().data(), 4, r_quat_);
// 将输入位姿的平移向量复制到内部数组 t_vec_ 中,平移向量有 3 个元素
std::copy_n(pose.t_vec().data(), 3, t_vec_); std::copy_n(pose.t_vec().data(), 3, t_vec_);
// 创建一个 Ceres 的 Huber 损失函数对象,参数 kHuberLossScale 控制损失函数的尺度
loss_function_ = new ceres::HuberLoss(kHuberLossScale); loss_function_ = new ceres::HuberLoss(kHuberLossScale);
problem_.AddParameterBlock(r_quat_, 4, // 向问题中添加旋转参数块,使用 Eigen 四元数参数化以确保单位四元数的约束
new ceres::EigenQuaternionParameterization()); problem_.AddParameterBlock(r_quat_, 4, new ceres::EigenQuaternionParameterization());
// 向问题中添加平移参数块3个自由度
problem_.AddParameterBlock(t_vec_, 3); problem_.AddParameterBlock(t_vec_, 3);
} }
/**
* @brief Solve
*
* Ceres 姿线
* 姿 pose
*
* @param max_iter_num
* @param verbose
* @param pose 姿
* @return bool true false
*/
bool PoseSolver::Solve(int max_iter_num, bool verbose, bool PoseSolver::Solve(int max_iter_num, bool verbose,
common::Pose3d *const pose) { common::Pose3d *const pose) {
// 配置 Ceres 求解选项
ceres::Solver::Options options; ceres::Solver::Options options;
options.linear_solver_type = ceres::DENSE_QR; options.linear_solver_type = ceres::DENSE_QR; // 使用密集 QR 分解作为线性求解器
options.max_num_iterations = max_iter_num; options.max_num_iterations = max_iter_num; // 最大迭代次数
options.minimizer_progress_to_stdout = false; options.minimizer_progress_to_stdout = false; // 是否将求解进度输出到标准输出
ceres::Solver::Summary summary; ceres::Solver::Summary summary; // 用于存储求解过程和结果的摘要信息
// 调用 Ceres 求解器求解问题
ceres::Solve(options, &problem_, &summary); ceres::Solve(options, &problem_, &summary);
// 如果 verbose 为 true则输出求解摘要报告
AINFO_IF(verbose) << summary.BriefReport(); AINFO_IF(verbose) << summary.BriefReport();
// 如果 pose 非空,则将当前求解得到的旋转和平移参数构造为 common::Pose3d 对象输出
if (pose) *pose = common::Pose3d(r_quat_, t_vec_); if (pose) *pose = common::Pose3d(r_quat_, t_vec_);
// 返回求解是否收敛的状态Ceres 的 termination_type 为 CONVERGENCE 表示收敛)
return summary.termination_type == ceres::CONVERGENCE; return summary.termination_type == ceres::CONVERGENCE;
} }
/**
* @brief -线
*
* -线 pair time
* CostFunction Ceres
*
* @param pair -线线
* @param time
*/
void PoseSolver::AddPointLinePair(const PointLinePair &pair, double time) { void PoseSolver::AddPointLinePair(const PointLinePair &pair, double time) {
// 通过静态工厂函数创建点-直线匹配的代价函数
ceres::CostFunction *cost_function = ceres::CostFunction *cost_function =
PointLineCostFunction::Create(pair, time); PointLineCostFunction::Create(pair, time);
// 将代价函数添加到问题中设置损失函数Huber 损失)和待优化参数(旋转和平移)
problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_); problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_);
} }
/**
* @brief -
*
* - pair time
* CostFunction Ceres
*
* @param pair -
* @param time
*/
void PoseSolver::AddPointPlanePair(const PointPlanePair &pair, double time) { void PoseSolver::AddPointPlanePair(const PointPlanePair &pair, double time) {
// 创建点-平面对代价函数
ceres::CostFunction *cost_function = ceres::CostFunction *cost_function =
PointPlaneCostFunction::Create(pair, time); PointPlaneCostFunction::Create(pair, time);
// 添加残差块到优化问题中,待优化参数为旋转和平移
problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_); problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_);
} }
/**
* @brief -线
*
* -线
*
* @param pair -线
* @param time
*/
void PoseSolver::AddPointLineCoeffPair(const PointLineCoeffPair &pair, void PoseSolver::AddPointLineCoeffPair(const PointLineCoeffPair &pair,
double time) { double time) {
// 通过工厂函数创建带系数的点-直线代价函数
ceres::CostFunction *cost_function = ceres::CostFunction *cost_function =
PointLineCoeffCostFunction::Create(pair, time); PointLineCoeffCostFunction::Create(pair, time);
// 将代价函数加入到问题中
problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_); problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_);
} }
/**
* @brief -
*
* -
*
* @param pair -
* @param time
*/
void PoseSolver::AddPointPlaneCoeffPair(const PointPlaneCoeffPair &pair, void PoseSolver::AddPointPlaneCoeffPair(const PointPlaneCoeffPair &pair,
double time) { double time) {
// 创建带系数的点-平面代价函数
ceres::CostFunction *cost_function = ceres::CostFunction *cost_function =
PointPlaneCoeffCostFunction::Create(pair, time); PointPlaneCoeffCostFunction::Create(pair, time);
// 将代价函数添加到 Ceres 问题中,优化参数为旋转和平移
problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_); problem_.AddResidualBlock(cost_function, loss_function_, r_quat_, t_vec_);
} }
/**
* @brief 姿
*
* common::Pose3d
* 姿
*
* @return common::Pose3d 姿
*/
common::Pose3d PoseSolver::GetPose() const { common::Pose3d PoseSolver::GetPose() const {
return common::Pose3d(r_quat_, t_vec_); return common::Pose3d(r_quat_, t_vec_);
} }
} // namespace oh_my_loam } // namespace oh_my_loam