实用指南:Matlab通过GUI实现点云的GICP配准

        本节分享的是使用Matlab进行点云的GICP配准。GICP(Generalized Iterative Closest Point,广义迭代最近点)是 ICP 算法的改进版本,核心优势在于引入高斯混合模型(GMM)描述点云分布,并通过最大化两点云间的概率相似度实现配准,而非仅依赖 “最近点距离最小化”。相比传统 ICP,GICP 具有:

  • 更强鲁棒性:可处理点云密度不均、噪声干扰场景;

  • 更高精度:考虑点云局部几何特征(如法向量、协方差);

  • 更快收敛:通过概率模型优化迭代方向,减少迭代次数。

一、 MATLAB 对 GICP 的支持

MATLAB 通过Computer Vision Toolbox提供 GICP 点云配准的完整工具链,核心函数包括:

  • pcregistergicp:执行 GICP 配准,输出配准后点云及变换矩阵;

  • pcpreprocess:点云预处理(去噪、下采样),为配准优化输入数据;

  • pcshowpair:可视化配准前后两点云的叠加效果,辅助结果验证;

  • pccorrespondences:计算点云对应关系,可用于配准过程监控。

二、MATLAB 中 GICP 点云配准主要流程

1. 步骤 1:点云数据准备

  • 数据获取:导入待配准的两点云(源点云source、目标点云target),支持格式包括.pcd、.ply、.las等,通过pcread函数读取:

source = pcread('source.pcd'); % 源点云(待变换点云)
target = pcread('target.pcd'); % 目标点云(参考点云)
  • 预处理优化

  • 去噪:用pcpreprocess去除孤立噪声点(基于统计滤波):
source = pcpreprocess(source, 'NumNeighbors', 10, 'Sigma', 1.5);
target = pcpreprocess(target, 'NumNeighbors', 10, 'Sigma', 1.5);
  • 下采样:若点云密度过高,通过pcdownsample降低点数(保留关键几何特征),提升配准效率:
source = pcdownsample(source, 'gridAverage', 0.05); % 栅格尺寸0.05m
target = pcdownsample(target, 'gridAverage', 0.05);

2. 步骤 2:初始配准(可选但关键)

GICP 需依赖初始变换姿态(避免陷入局部最优),若两点云初始偏差较大,需先执行粗配准:

  • 常用方法:基于特征的配准(如 SIFT、FPFH),或使用 MATLAB 内置的 ICP 粗配准函数pcregistericp(设置InitialTransform参数):

% 粗配准获取初始变换矩阵
[~, initT] = pcregistericp(source, target, 'Metric', 'pointToPlane');

3. 步骤 3:GICP 配准参数设置与执行

调用pcregistergicp函数,核心参数需根据场景调整:

% 执行GICP配准
[registeredSource, tform] = pcregistergicp(
source, % 源点云
target, % 目标点云
'InitialTransform', initT, % 初始变换矩阵
'MaxIterations', 200, % 最大迭代次数(默认100)
'ConvergenceThreshold', 1e-6, % 收敛阈值(位置/姿态变化小于该值停止)
'CovarianceEstimation', 'knn', % 协方差估计方式(knn/grid,默认knn)
'NumNeighbors', 15 % 协方差估计的邻域点数(默认10)
);
  • 输出说明:registeredSource为配准后源点云,tform为 4×4 刚体变换矩阵(包含平移 + 旋转)。

4. 步骤 4:配准结果评估与可视化

  • 定量评估:计算配准后两点云的均方根误差(RMSE),反映配准精度:

% 计算对应点对距离
correspondences = pccorrespondences(registeredSource, target);
distances = sqrt(sum((correspondences.SourcePoints - correspondences.TargetPoints).^2, 2));
rmse = mean(distances); % RMSE越小,精度越高
  • 定性可视化:用pcshowpair对比配准前后效果:

figure;
% 配准前(红色:源点云,蓝色:目标点云)
subplot(1,2,1); pcshowpair(source, target, 'VerticalAxis', 'Y', 'HorizontalAxis', 'X');
title('配准前');
% 配准后
subplot(1,2,2); pcshowpair(registeredSource, target, 'VerticalAxis', 'Y', 'HorizontalAxis', 'X');
title(['配准后(RMSE=' num2str(rmse) ')']);

三、GICP 点云配准的应用领域

1. 三维重建领域

  • 场景:文物数字化、建筑三维建模、工业零件逆向工程;

  • 应用逻辑:通过多视角(如激光雷达、结构光相机)采集点云,用 GICP 配准拼接为完整三维模型,解决 “单视角点云遮挡” 问题;

  • MATLAB 优势:预处理工具链完善,可快速处理百万级点云,可视化结果便于模型验证。

2. 自动驾驶领域

  • 场景:激光雷达(LiDAR)点云与高精地图(HD Map)匹配、多传感器(LiDAR + 相机)数据融合;

  • 应用逻辑:通过 GICP 将实时 LiDAR 点云与预存高精地图配准,实现车辆定位(精度达厘米级),适应雨天、强光等复杂环境;

  • 核心需求:GICP 的鲁棒性可抵抗点云噪声(如路面杂物干扰),快速收敛满足实时性要求(MATLAB 可通过 GPU 加速进一步提升效率)。

3. 工业检测领域

  • 场景:零件尺寸公差检测、装配精度验证;

  • 应用逻辑:将实测零件点云与设计模型(CAD 导出点云)通过 GICP 配准,计算对应点距离偏差,判断是否符合公差标准;

  • MATLAB 价值:支持与 CAD 软件(如 SolidWorks)数据交互,pcregistergicp的高精度特性可满足工业级检测需求(公差≤0.1mm)。

4. 机器人导航领域

  • 场景:室内移动机器人定位、仓储机器人环境感知;

  • 应用逻辑:机器人携带深度相机采集环境点云,通过 GICP 与预建地图配准,实现自主定位与路径规划;

  • 适配性:GICP 对动态障碍物(如行人、货架)的鲁棒性,优于传统 ICP,减少导航偏差。

本次使用的数据。。。。兔呗

一、点云GICP配准的程序

1、最简版

%% GICP_Register_Fusion.m —— MATLAB 2024a 兼容(修复版)
clc; clear; close all;
%% 1. 读取源点云
[file, path] = uigetfile({'*.pcd;*.ply','点云文件 (*.pcd,*.ply)'}, ...
                         '请选择点云(例如 bunny.pcd)');
if file==0; return; end
sourcePtCloud = pcread(fullfile(path,file));
%% 2. 生成目标点云(修复只读属性问题)
rotAngle = 30;          % 旋转角度(度,绕Z轴)
transVec = [0.1 0.15 0.2];  % 平移向量
noiseStd = 0.0005;      % 低噪声标准差
targetPtCloud = createTargetCloud(sourcePtCloud, rotAngle, transVec, noiseStd);
%% 3. GICP配准(保留简洁传参)
[tform, regPtCloud, rmse] = pcregistericp(sourcePtCloud, targetPtCloud, ...
                                          'Metric', 'pointToPlane', ...
                                          'MaxIterations', 35, ...
                                          'InlierDistance', 0.2);
%% 4. 可视化结果
figure('Name','初始点云','Color','w');
pcshowpair(sourcePtCloud, targetPtCloud);
title('红色=源点云,绿色=目标点云(含旋转+平移+噪声)');
figure('Name','GICP配准结果','Color','w');
pcshowpair(regPtCloud, targetPtCloud);
title(['红色=配准后点云,绿色=目标点云 | RMSE = ' num2str(rmse,'%.6f')]);
%% 5. 多指标评估(修复距离计算函数)
evalResult = evaluateReg(regPtCloud, targetPtCloud, 0.2);
disp('================ 配准评估结果 ================');
disp(['内点比例:' num2str(evalResult.inlierRatio,'%.2f%%')]);
disp(['平均距离:' num2str(evalResult.meanDist,'%.6f')]);
disp(['RMSE(均方根误差):' num2str(evalResult.rmse,'%.6f')]);
disp('=============================================');
%% 子函数1:生成目标点云(修复只读属性问题)
function targetCloud = createTargetCloud(sourceCloud, rotAngle, transVec, noiseStd)
    srcPoints = sourceCloud.Location;  % N×3 源点坐标
    % 步骤1:计算点云中心并平移到原点
    cloudCenter = mean(srcPoints, 1);
    pointsCentered = srcPoints - cloudCenter;
    % 步骤2:绕Z轴旋转
    rotRad = deg2rad(rotAngle);
    rotMat = [cos(rotRad) -sin(rotRad) 0;
              sin(rotRad)  cos(rotRad) 0;
              0           0           1];
    pointsRotated = (rotMat * pointsCentered')';
    % 步骤3:平移回原中心 + 额外平移
    pointsTranslated = pointsRotated + cloudCenter + transVec;
    % 步骤4:添加噪声
    pointsNoisy = pointsTranslated + noiseStd * randn(size(pointsTranslated));
    % 关键修复:创建新的pointCloud对象(而非修改原有对象的Location)
    targetCloud = pointCloud(pointsNoisy, ...
                            'Normal', sourceCloud.Normal, ...
                            'Color', repmat([0 1 0], size(pointsNoisy,1), 1));
end
%% 子函数2:配准多指标评估(用knnsearch替代pcpdist)
function result = evaluateReg(regCloud, targetCloud, inlierThresh)
    % 获取两点云的坐标
    regPoints = regCloud.Location;    % M×3 矩阵
    targetPoints = targetCloud.Location;  % N×3 矩阵
    % 计算每个配准点到目标点云中最近点的距离(替代pcpdist)
    % 使用knnsearch寻找最近邻,兼容更多MATLAB版本
    [~, dists] = knnsearch(targetPoints, regPoints);  % 输出为列向量
    % 计算评估指标
    result.inlierRatio = mean(dists < inlierThresh) * 100;  % 内点比例(%)
    result.meanDist = mean(dists);                          % 平均距离
    result.rmse = sqrt(mean(dists.^2));                    % RMSE
end

2、GUI版本

function GICP_Register_GUI
%GICP_Register_GUI 基于GICP算法的点云配准GUI(三栏视图)
% 兼容MATLAB 2024a,无需额外工具箱
clc; clear; close all;
%% ---------------- 主窗口 ----------------
fig = figure('Name','GICP 配准工具', 'NumberTitle','off', ...
             'MenuBar','none', 'ToolBar','none', ...
             'Position',[100 100 1280 720], 'Color','w');
%% ---------------- 布局常量 ----------------
imgWidth = 0.78;               % 三栏总宽
panelW   = imgWidth/3 - 0.005; % 单栏宽
gap      = 0.005;
%% ---------------- 三栏 axes ----------------
pnlSrc = uipanel('Parent',fig, 'Units','normalized', ...
                 'FontSize',16, 'Position',[0.02 0.02 panelW 0.96], ...
                 'Title','源点云(红)');
pnlTgt = uipanel('Parent',fig, 'Units','normalized', ...
                 'FontSize',16, ...
                 'Position',[0.02+panelW+gap 0.02 panelW 0.96], ...
                 'Title','目标点云(绿)');
pnlReg = uipanel('Parent',fig, 'Units','normalized', ...
                 'FontSize',16, ...
                 'Position',[0.02+2*(panelW+gap) 0.02 panelW 0.96], ...
                 'Title','GICP 配准后(红→绿)');
axSrc = axes('Parent',pnlSrc, 'Units','normalized', 'Position',[0.05 0.05 0.9 0.9]);
axTgt = axes('Parent',pnlTgt, 'Units','normalized', 'Position',[0.05 0.05 0.9 0.9]);
axReg = axes('Parent',pnlReg, 'Units','normalized', 'Position',[0.05 0.05 0.9 0.9]);
%% ---------------- 控制面板 ----------------
pnlCtrl = uipanel('Parent',fig, 'Units','normalized', ...
                  'FontSize',16, 'Position',[0.78 0 0.22 1], ...
                  'Title','控制');
txtH  = 0.04;  btnH = 0.06;  yTop = 0.94;
% ① 加载
uicontrol('Parent',pnlCtrl, 'Style','pushbutton', 'String','浏览…', ...
          'FontSize',16, 'Units','normalized', ...
          'Position',[0.05 yTop-btnH 0.9 btnH], ...
          'Callback',@loadCloud);
yTop = yTop - btnH - 0.02;
% 状态提示
lblInfo = uicontrol('Parent',pnlCtrl, 'Style','text', ...
                    'String','未加载点云', 'FontSize',10, ...
                    'Units','normalized', ...
                    'Position',[0.05 yTop-txtH 0.9 txtH], ...
                    'HorizontalAlignment','left');
yTop = yTop - txtH - 0.02;
% ② 噪声标准差 / m
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','噪声标准差 / m', ...
          'FontSize',12, 'FontWeight','bold', 'Units','normalized', ...
          'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH - 0.01;
sliderNoise = uicontrol('Parent',pnlCtrl, 'Style','slider', ...
                        'Min',0, 'Max',0.01, 'Value',0.0005, ...
                        'Units','normalized', ...
                        'Position',[0.05 yTop-btnH 0.65 btnH], ...
                        'Callback',@refreshTarget);
txtNoise    = uicontrol('Parent',pnlCtrl, 'Style','edit', 'String','0.0005', ...
                        'FontSize',14, 'Units','normalized', ...
                        'Position',[0.75 yTop-btnH 0.2 btnH], ...
                        'Callback',@editNoiseCB);
yTop = yTop - btnH - 0.02;
% ③ 旋转角度 / 度
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','旋转角度(Z轴)/ 度', ...
          'FontSize',12, 'FontWeight','bold', 'Units','normalized', ...
          'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH - 0.01;
sliderRot = uicontrol('Parent',pnlCtrl, 'Style','slider', ...
                      'Min',0, 'Max',180, 'Value',30, ...
                      'Units','normalized', ...
                      'Position',[0.05 yTop-btnH 0.65 btnH], ...
                      'Callback',@refreshTarget);
txtRot    = uicontrol('Parent',pnlCtrl, 'Style','edit', 'String','30', ...
                      'FontSize',14, 'Units','normalized', ...
                      'Position',[0.75 yTop-btnH 0.2 btnH], ...
                      'Callback',@editRotCB);
yTop = yTop - btnH - 0.02;
% ④ 平移偏移 / m
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','平移偏移 / m', ...
          'FontSize',12, 'FontWeight','bold', 'Units','normalized', ...
          'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH - 0.01;
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','X', ...
          'FontSize',10, 'Units','normalized', ...
          'Position',[0.05 yTop-txtH 0.15 txtH]);
editX = uicontrol('Parent',pnlCtrl, 'Style','edit', 'String','0.1', ...
                  'FontSize',14, 'Units','normalized', ...
                  'Position',[0.20 yTop-txtH 0.20 txtH], ...
                  'Callback',@refreshTarget);
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','Y', ...
          'FontSize',10, 'Units','normalized', ...
          'Position',[0.45 yTop-txtH 0.15 txtH]);
editY = uicontrol('Parent',pnlCtrl, 'Style','edit', 'String','0.15', ...
                  'FontSize',14, 'Units','normalized', ...
                  'Position',[0.60 yTop-txtH 0.20 txtH], ...
                  'Callback',@refreshTarget);
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','Z', ...
          'FontSize',10, 'Units','normalized', ...
          'Position',[0.05 yTop-2*txtH 0.15 txtH]);
editZ = uicontrol('Parent',pnlCtrl, 'Style','edit', 'String','0.2', ...
                  'FontSize',14, 'Units','normalized', ...
                  'Position',[0.20 yTop-2*txtH 0.20 txtH], ...
                  'Callback',@refreshTarget);
yTop = yTop - 2*txtH - 0.02;
% ⑤ GICP参数
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','GICP 参数', ...
          'FontSize',12, 'FontWeight','bold', 'Units','normalized', ...
          'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH - 0.01;
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','最大迭代次数', ...
          'FontSize',10, 'Units','normalized', ...
          'Position',[0.05 yTop-txtH 0.4 txtH], 'HorizontalAlignment','left');
editMaxIter = uicontrol('Parent',pnlCtrl, 'Style','edit', 'String','35', ...
                        'FontSize',14, 'Units','normalized', ...
                        'Position',[0.50 yTop-txtH 0.45 txtH]);
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','内点距离阈值', ...
          'FontSize',10, 'Units','normalized', ...
          'Position',[0.05 yTop-2*txtH 0.4 txtH], 'HorizontalAlignment','left');
editInlierDist = uicontrol('Parent',pnlCtrl, 'Style','edit', 'String','0.2', ...
                           'FontSize',14, 'Units','normalized', ...
                           'Position',[0.50 yTop-2*txtH 0.45 txtH]);
yTop = yTop - 2*txtH - 0.02;
% ⑥ 运行 GICP
uicontrol('Parent',pnlCtrl, 'Style','pushbutton', 'String','运行 GICP 配准', ...
          'FontSize',16, 'Units','normalized', ...
          'Position',[0.05 yTop-btnH 0.9 btnH], ...
          'Callback',@runGICP);
yTop = yTop - btnH - 0.02;
% ⑦ 评估结果显示
uicontrol('Parent',pnlCtrl, 'Style','text', 'String','配准评估结果', ...
          'FontSize',12, 'FontWeight','bold', 'Units','normalized', ...
          'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH - 0.01;
lblInlier = uicontrol('Parent',pnlCtrl, 'Style','text', 'String','内点比例:--', ...
                      'FontSize',10, 'Units','normalized', ...
                      'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH;
lblMeanDist = uicontrol('Parent',pnlCtrl, 'Style','text', 'String','平均距离:--', ...
                        'FontSize',10, 'Units','normalized', ...
                        'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH;
lblRMSE = uicontrol('Parent',pnlCtrl, 'Style','text', 'String','RMSE:--', ...
                    'FontSize',10, 'Units','normalized', ...
                    'Position',[0.05 yTop-txtH 0.9 txtH], 'HorizontalAlignment','left');
yTop = yTop - txtH - 0.02;
% ⑧ 保存
uicontrol('Parent',pnlCtrl, 'Style','pushbutton', 'String','保存配准结果', ...
          'FontSize',16, 'Units','normalized', ...
          'Position',[0.05 yTop-btnH 0.9 btnH], ...
          'Callback',@(s,e)saveCloud(ptCloudReg));
%% ---------------- 数据容器 ----------------
ptCloudSrc = pointCloud.empty;
ptCloudTgt = pointCloud.empty;
ptCloudReg = pointCloud.empty;
tform = [];
rmse = 0;
    %% ---------------- 回调函数 ----------------
    function loadCloud(~,~)
        [file,path] = uigetfile({'*.ply;*.pcd;*.xyz','点云文件'},'选择点云');
        if isequal(file,0); return; end
        try
            ptCloudSrc = pcread(fullfile(path,file));
        catch ME
            errordlg(ME.message,'读取失败'); return;
        end
        set(lblInfo,'String',sprintf('已加载:%s  (%d 点)',file,ptCloudSrc.Count));
        refreshTarget();
    end
    function refreshTarget(~,~)
        if isempty(ptCloudSrc); return; end
        % 1. 读取界面参数
        noiseStd = get(sliderNoise,'Value');
        rotAngle = get(sliderRot,'Value');
        t = [str2double(get(editX,'String'));
             str2double(get(editY,'String'));
             str2double(get(editZ,'String'))];  % 3×1
        if any(isnan(t));  t = [0.1; 0.15; 0.2]; end
        transVec = t.';  % 1×3
        % 2. 生成目标点云
        ptCloudTgt = createTargetCloud(ptCloudSrc, rotAngle, transVec, noiseStd);
        % 3. 上色区分
        ptCloudSrc.Color = repmat(uint8([255 0 0]),size(ptCloudSrc.Location,1),1);  % 红色
        ptCloudTgt.Color = repmat(uint8([0 255 0]),size(ptCloudTgt.Location,1),1);  % 绿色
        % 4. 显示点云
        showPointCloud(axSrc,ptCloudSrc);
        showPointCloud(axTgt,ptCloudTgt);
        % 5. 清空上次结果
        ptCloudReg = pointCloud.empty;
        cla(axReg); title(axReg,'GICP 配准后(红→绿)');
        % 6. 清空评估结果
        set(lblInlier, 'String', '内点比例:--');
        set(lblMeanDist, 'String', '平均距离:--');
        set(lblRMSE, 'String', 'RMSE:--');
        % 7. 同步滑竿文本
        set(txtNoise,'String',num2str(get(sliderNoise,'Value')));
        set(txtRot,'String',num2str(get(sliderRot,'Value')));
    end
    function editNoiseCB(src,~)
        v = str2double(get(src,'String'));
        if isnan(v); v=0.0005; end
        v = max(0,min(0.01,v));  % 限制范围
        set(sliderNoise,'Value',v);
        refreshTarget();
    end
    function editRotCB(src,~)
        v = str2double(get(src,'String'));
        if isnan(v); v=30; end
        v = max(0,min(180,v));  % 限制范围
        set(sliderRot,'Value',v);
        refreshTarget();
    end
    function runGICP(~,~)
        if isempty(ptCloudSrc) || isempty(ptCloudTgt)
            errordlg('请先加载点云','提示'); return;
        end
        % 获取GICP参数
        maxIter = str2double(get(editMaxIter,'String'));
        if isnan(maxIter) || maxIter <= 0; maxIter = 35; end
        inlierDist = str2double(get(editInlierDist,'String'));
        if isnan(inlierDist) || inlierDist <= 0; inlierDist = 0.2; end
        % GICP配准
        try
            [tform, regPtCloud, rmse] = pcregistericp(ptCloudSrc, ptCloudTgt, ...
                                                      'Metric', 'pointToPlane', ...
                                                      'MaxIterations', maxIter, ...
                                                      'InlierDistance', inlierDist);
        catch ME
            errordlg(ME.message,'配准失败'); return;
        end
        ptCloudReg = regPtCloud;
        ptCloudReg.Color = repmat(uint8([255 0 0]),size(ptCloudReg.Location,1),1);
        % 可视化配准结果
        showPointCloud(axReg,ptCloudReg); hold(axReg,'on');
        pcshow(ptCloudTgt,'Parent',axReg); hold(axReg,'off');
        title(axReg,'GICP 配准结果:红→绿');
        % 评估配准结果
        evalResult = evaluateReg(ptCloudReg, ptCloudTgt, inlierDist);
        % 更新评估结果显示
        set(lblInlier, 'String', sprintf('内点比例:%.2f%%', evalResult.inlierRatio));
        set(lblMeanDist, 'String', sprintf('平均距离:%.6f', evalResult.meanDist));
        set(lblRMSE, 'String', sprintf('RMSE:%.6f', evalResult.rmse));
    end
    function saveCloud(cloud)
        if isempty(cloud)
            errordlg('请先运行 GICP 配准','提示'); return;
        end
        [file,path] = uiputfile({'*.pcd','PCD';'*.ply','PLY';'*.xyz','XYZ'},'保存配准点云');
        if isequal(file,0); return; end
        try
            pcwrite(cloud,fullfile(path,file),'Precision','double');
            msgbox('保存成功!','提示');
        catch ME
            errordlg(ME.message,'保存失败');
        end
    end
    function showPointCloud(ax,pc)
        cla(ax); set(ax,'Color','w');
        pcshow(pc,'Parent',ax,'MarkerSize',35);
        axis(ax,'tight'); grid(ax,'on'); view(ax,3); drawnow;
    end
    %% ---------------- 子函数1:生成目标点云 ----------------
    function targetCloud = createTargetCloud(sourceCloud, rotAngle, transVec, noiseStd)
        srcPoints = sourceCloud.Location;  % N×3 源点坐标
        % 步骤1:计算点云中心并平移到原点
        cloudCenter = mean(srcPoints, 1);
        pointsCentered = srcPoints - cloudCenter;
        % 步骤2:绕Z轴旋转
        rotRad = deg2rad(rotAngle);
        rotMat = [cos(rotRad) -sin(rotRad) 0;
                  sin(rotRad)  cos(rotRad) 0;
                  0           0           1];
        pointsRotated = (rotMat * pointsCentered')';
        % 步骤3:平移回原中心 + 额外平移
        pointsTranslated = pointsRotated + cloudCenter + transVec;
        % 步骤4:添加噪声
        pointsNoisy = pointsTranslated + noiseStd * randn(size(pointsTranslated));
        % 创建新的pointCloud对象
        targetCloud = pointCloud(pointsNoisy, ...
                                'Normal', sourceCloud.Normal, ...
                                'Color', repmat([0 1 0], size(pointsNoisy,1), 1));
    end
    %% ---------------- 子函数2:配准多指标评估 ----------------
    function result = evaluateReg(regCloud, targetCloud, inlierThresh)
        % 获取两点云的坐标
        regPoints = regCloud.Location;    % M×3 矩阵
        targetPoints = targetCloud.Location;  % N×3 矩阵
        % 计算每个配准点到目标点云中最近点的距离
        [~, dists] = knnsearch(targetPoints, regPoints);  % 输出为列向量
        % 计算评估指标
        result.inlierRatio = mean(dists < inlierThresh) * 100;  % 内点比例(%)
        result.meanDist = mean(dists);                          % 平均距离
        result.rmse = sqrt(mean(dists.^2));                    % RMSE
    end
end

二、点云进行GICP配准的结果

        我有罪,我忏悔,我不该抛弃matlab2020a,以上程序使用的是2024a。不过该说不说,高级版本是真的好用哎。话又说回来,既然人家开发了好的工具,为嘛不用呢,君子性非异也,善假于物也。你说是不?

就酱,下次见^-6

posted @ 2025-10-19 17:58  wzzkaifa  阅读(12)  评论(0)    收藏  举报