#include "WES-ICP.h"
#include <cmath>
#include <iostream>
#include <Eigen/Geometry>
#include <Sophus/SE3.hpp>
#include <pcl/kdtree/kdtree_flann.h>
// 构造函数
WES_ICP::WES_ICP()
: max_icp_iterations_(50),
max_outer_iterations_(10),
max_inner_iterations_(5),
p_norm_(2.5f),
w_pTp_(0.5f),
w_pTpln_(0.5f),
final_transformation_(Eigen::Matrix4f::Identity()) {}
// 设置参数
void WES_ICP::setParameters(int max_icp, int max_outer, int max_inner, float p/*, float w_pTp, float w_pTpln*/) // 权重为自动更新
{
max_icp_iterations_ = max_icp;
max_outer_iterations_ = max_outer;
max_inner_iterations_ = max_inner;
p_norm_ = p;
//w_pTp_ = w_pTp;
//w_pTpln_ = w_pTpln;
}
// 辅助函数:反对称矩阵
Eigen::Matrix3f WES_ICP::skew(const Eigen::Vector3f& v)
{
Eigen::Matrix3f mat;
mat << 0, -v.z(), v.y(),
v.z(), 0, -v.x(),
-v.y(), v.x(), 0;
return mat;
}
// 稀疏收缩函数(向量)
Eigen::Vector3f WES_ICP::shrink(const Eigen::Vector3f& h, double p, double mu)
{
Eigen::Vector3f result;
for (int i = 0; i < 3; ++i)
{
double abs_h = std::abs(h[i]);
if (abs_h <= 1.0 / mu)
{
result[i] = 0.0;
}
else
{
result[i] = std::copysign(abs_h - 1.0 / mu, h[i]) * std::pow(abs_h, p - 1);
}
}
return result;
}
// 稀疏收缩函数(标量)
double WES_ICP::shrink(double h, double p, double mu)
{
double abs_h = std::abs(h);
if (abs_h <= 1.0 / mu)
{
return 0.0;
}
else
{
return std::copysign(abs_h - 1.0 / mu, h) * std::pow(abs_h, p - 1);
}
}
// 优化步骤
Eigen::Matrix4f WES_ICP::WES_ICP_Optimization(
const pcl::PointCloud<pcl::PointXYZ>& source_cloud,
const pcl::PointCloud<pcl::PointXYZ>& inter_cloud,
const pcl::PointCloud<pcl::PointXYZ>& target_cloud,
const pcl::PointCloud<pcl::Normal>& normals_cloud,
const Eigen::VectorXf& d,
float w1, float w2)
{
Eigen::Matrix<float, 6, 6> A = Eigen::Matrix<float, 6, 6>::Zero();
Eigen::Matrix<float, 6, 1> b = Eigen::Matrix<float, 6, 1>::Zero();
for (size_t i = 0; i < source_cloud.size(); ++i)
{
Eigen::Vector3f source_pt = source_cloud.points[i].getVector3fMap();
Eigen::Vector3f inter_pt = inter_cloud.points[i].getVector3fMap();
Eigen::Vector3f target_pt = target_cloud.points[i].getVector3fMap();
Eigen::Vector3f normal = normals_cloud.points[i].getNormalVector3fMap();
float d_i = d[i];
// 构造生成元矩阵G (4x6)
Eigen::Matrix<float, 4, 6> G;
G.setZero();
G.block<3, 3>(0, 0) = Eigen::Matrix3f::Identity();
G.block<3, 3>(0, 3) = -skew(source_pt);
// 残差项
Eigen::Vector4f e1;
e1.head<3>() = source_pt - inter_pt;
e1(3) = 0.0;
float e2 = (source_pt - target_pt).dot(normal) - d_i;
// 雅可比矩阵
Eigen::Matrix<float, 4, 6> A1 = G;
Eigen::Vector4f normal_hom(normal.x(), normal.y(), normal.z(), 0.0);
Eigen::Matrix<float, 1, 6> A2 = normal_hom.transpose() * G;
// 更新线性系统
A += w1 * A1.transpose() * A1 + w2 * A2.transpose() * A2;
b -= w1 * A1.transpose() * e1 + w2 * A2.transpose() * e2;
}
// 求解
Eigen::Matrix<float, 6, 1> x = A.ldlt().solve(b);
// 检查无效值并退出
if (x.hasNaN() || x.array().isInf().any())
{
std::cerr << "WES optin result has Inf values." << std::endl;
Eigen::Matrix4f Ti = Eigen::Matrix4f::Identity();
return Ti;
}
else
{
// 李代数到SE(3)
Sophus::SE3f T_update = Sophus::SE3f::exp(x);
return T_update.matrix();
}
}
// 主配准函数
Eigen::Matrix4f WES_ICP::align(
const pcl::PointCloud<pcl::PointXYZ>& source_cloud,
const pcl::PointCloud<pcl::PointXYZ>& target_cloud,
const pcl::PointCloud<pcl::Normal>& target_normals)
{
if (source_cloud.empty() || target_cloud.empty())
{
std::cerr << "Error: Empty input clouds!" << std::endl;
return Eigen::Matrix4f::Identity();
}
pcl::PointCloud<pcl::PointXYZ> move_points = source_cloud;
pcl::PointCloud<pcl::PointXYZ> old_points = source_cloud;
final_transformation_ = Eigen::Matrix4f::Identity();
// ADMM变量
const size_t num_points = source_cloud.size();
Eigen::MatrixXf lambda_pTp = Eigen::MatrixXf::Zero(3, num_points);
Eigen::MatrixXf Z_pTp = Eigen::MatrixXf::Zero(3, num_points);
Eigen::VectorXf lambda_pTpln = Eigen::VectorXf::Zero(num_points);
Eigen::VectorXf Z_pTpln = Eigen::VectorXf::Zero(num_points);
Eigen::VectorXf delta_pTpln = Eigen::VectorXf::Zero(num_points);
float mu = 10.0;
// 构建KD树
pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
kdtree.setInputCloud(target_cloud.makeShared());
for (int icp = 0; icp < max_icp_iterations_; ++icp)
{
// 匹配点
std::vector<int> indices(1);
std::vector<float> distances(1);
pcl::PointCloud<pcl::PointXYZ> match_points;
pcl::PointCloud<pcl::Normal> match_normals;
for (size_t i = 0; i < move_points.size(); ++i)
{
if (kdtree.nearestKSearch(move_points[i], 1, indices, distances) <= 0)
{
continue;
}
int nearest_idx = indices[0];
match_points.push_back(target_cloud[nearest_idx]);
match_normals.push_back(target_normals[nearest_idx]);
}
// 动态权重
float w_pTp = 2.0 / (1.0 + std::exp(max_icp_iterations_ - icp));
float w_pTpln = 1.0 - w_pTp;
// ADMM外层循环
for (int outer = 0; outer < max_outer_iterations_; ++outer)
{
// ADMM内层循环
for (int inner = 0; inner < max_inner_iterations_; ++inner)
{
// 点对点收缩
Eigen::MatrixXf H_pTp = move_points.getMatrixXfMap(3, 4, 0).transpose() -
match_points.getMatrixXfMap(3, 4, 0).transpose() +
lambda_pTp / mu;
for (size_t k = 0; k < num_points; ++k)
{
Z_pTp.col(k) = shrink(H_pTp.col(k), p_norm_, mu);
}
pcl::PointCloud<pcl::PointXYZ> inter_points;
for (size_t k = 0; k < num_points; ++k)
{
Eigen::Vector3f pt = match_points[k].getVector3fMap() +
Z_pTp.col(k) - lambda_pTp.col(k) / mu;
inter_points.push_back(pcl::PointXYZ(pt.x(), pt.y(), pt.z()));
}
// 点对面收缩
Eigen::VectorXf H_pTpln(num_points);
for (size_t k = 0; k < num_points; ++k)
{
H_pTpln(k) = match_normals[k].getNormalVector3fMap().dot(
move_points[k].getVector3fMap() - match_points[k].getVector3fMap());
}
H_pTpln += lambda_pTpln / mu;
for (size_t k = 0; k < num_points; ++k)
{
Z_pTpln(k) = shrink(H_pTpln(k), p_norm_, mu);
}
Eigen::VectorXf inter_d = Z_pTpln - lambda_pTpln / mu;
// 优化步骤
Eigen::Matrix4f T1 = WES_ICP_Optimization(
move_points, inter_points, match_points, match_normals, inter_d, w_pTp, w_pTpln);
// 更新变换
final_transformation_ = T1 * final_transformation_;
pcl::transformPointCloud(move_points, move_points, T1);
// 检查收敛
float dual_max = 0.0;
for (size_t k = 0; k < num_points; ++k)
{
Eigen::Vector3f diff = old_points[k].getVector3fMap() - move_points[k].getVector3fMap();
float dual_pTpln = diff.dot(match_normals[k].getNormalVector3fMap());
float dual_pTp = diff.norm();
dual_max = std::max(dual_max, std::max(dual_pTpln, dual_pTp));
}
old_points = move_points;
if (dual_max < 1e-5)
{
break;
}
}
// 更新拉格朗日乘子
Eigen::MatrixXf delta_pTp = move_points.getMatrixXfMap(3, 4, 0).transpose() -
match_points.getMatrixXfMap(3, 4, 0).transpose() - Z_pTp;
for (size_t k = 0; k < num_points; ++k)
{
delta_pTpln(k) = match_normals[k].getNormalVector3fMap().dot(
move_points[k].getVector3fMap() - match_points[k].getVector3fMap()) - Z_pTpln(k);
}
lambda_pTp += mu * delta_pTp;
lambda_pTpln += mu * delta_pTpln;
}
}
return final_transformation_;
}
// 获取最终变换矩阵
Eigen::Matrix4f WES_ICP::getFinalTransformation() const
{
return final_transformation_;
}
匹配点对获取部分添加距离约束和几何一致性约束