LeGO-LOAM 源码阅读笔记(imageProjecion.cpp)

2023-10-27

LeGO-LOAM是一种在LOAM之上进行改进的激光雷达建图方法,建图效果比LOAM要好,但是建图较为稀疏,计算量也更小了。

本文原地址:wykxwyc的博客

github注释后LeGO-LOAM源码:LeGO-LOAM_NOTED
关于代码的详细理解,建议阅读:

1.地图优化代码理解

2.图像重投影代码理解

3.特征关联代码理解

4.LeGO-LOAM中的数学公式推导

以上博客会随时更新,如果对你有帮助,请点击注释代码的github仓库右上角star按钮,你的鼓励将给我更多动力。

imageProjecion.cpp概述

imageProjecion.cpp进行的数据处理是图像映射,将得到的激光数据分割,并在得到的激光数据上进行坐标变换。

imageProjecion

imageProjecion()构造函数的内容如下:

  1. 订阅话题:订阅来自velodyne雷达驱动的topic
    • "/velodyne_points"(sensor_msgs::PointCloud2),订阅的subscriber是subLaserCloud
  2. 发布话题,这些topic有:
    • "/full_cloud_projected"(sensor_msgs::PointCloud2)
    • "/full_cloud_info"(sensor_msgs::PointCloud2)
    • "/ground_cloud"(sensor_msgs::PointCloud2)
    • "/segmented_cloud"(sensor_msgs::PointCloud2)
    • "/segmented_cloud_pure"(sensor_msgs::PointCloud2)
    • "/segmented_cloud_info"(cloud_msgs::cloud_info)
    • "/outlier_cloud"(sensor_msgs::PointCloud2)

然后分配内存(对智能指针初始化),初始化各类参数。

上述的cloud_msgs::cloud_info是自定义的消息类型,其具体定义如下:

Header header 

int32[] startRingIndex  // 长度:N_SCAN
int32[] endRingIndex    // 长度:N_SCAN

float32 startOrientation
float32 endOrientation
float32 orientationDiff

// 以下长度都是 N_SCAN*Horizon_SCAN
bool[]    segmentedCloudGroundFlag 
uint32[]  segmentedCloudColInd 
float32[] segmentedCloudRange

关于上面的自定义消息,另外还需要说明的是,segMsg.startRingIndex[i] = sizeOfSegCloud-1 + 5;或者segMsg.endRingIndex[i] = sizeOfSegCloud-1 - 5;表示的是将第0线和第16线点云横着排列后。每一线点云有一个startRingIndexendRingIndex,表示这一线点云中的一部分,如下图绿色部分。
黑色部分是整体这一线点云中筛选出来满足条件的。
在这里插入图片描述

cloudHandler

void cloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg)是这个文件中最主要的一个函数。由它调用其他的函数:

void cloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){
    copyPointCloud(laserCloudMsg);
    findStartEndAngle();
    projectPointCloud();
    groundRemoval();
    cloudSegmentation();
    publishCloud();
    resetParameters();
}
  • 整体过程如下:
    1.复制点云数据
    2.找到开始和结束的角度
    3.移除地面点
    4.点云分块
    5.发布处理后的点云数据
    6.重置参数

上面第一部分复制点云数据函数copyPointCloud(laserCloudMsg) 是将ROS中的sensor_msgs::PointCloud2ConstPtr类型转换到pcl点云库指针。

velodyne 雷达数据

首先从VLP给的雷达数据手册上(63-9243 Rev B User Manual and Programming Guide,VLP-16.pdf)查找一下它的坐标系定义:
VLP雷达坐标系
velodyne雷达在上面的坐标系下输出"/velodyne_points"(sensor_msgs::PointCloud2) 的点云数据。其数据格式可以理解为x,y,z,intensity 这4个量(它的定义比sensor_msgs::PointCloud要复杂一点,但本质还是这几个量)。

findStartEndAngle

void findStartEndAngle()进行关于segMsg(cloud_msgs::cloud_info segMsg)的三个内容的计算:
1)计算开始角度(segMsg.startOrientation);
2)计算结束角度(segMsg.endOrientation);
3)计算雷达转过的角度(开始和结束的角度差,segMsg.orientationDiff)。

关于具体计算,需要清楚整个雷达的坐标系定义,参考上面雷达坐标系的那张图。

另外在计算segMsg.startOrientationsegMsg.endOrientation时,atan2(..)函数取了负数的原因是:雷达旋转方向和坐标系定义下的右手定则正方向不一致。参考下图:
在这里插入图片描述

projectPointCloud

void projectPointCloud()将激光雷达得到的数据看成一个16x1800的点云阵列。然后根据每个点云返回的XYZ数据将他们对应到这个阵列里去。

  1. 计算竖直角度,用atan2函数进行计算。
  2. 通过计算的竖直角度得到对应的行的序号rowIdnrowIdn计算出该点激光雷达是水平方向上第几线的。从下往上计数,-15度记为初始线,第0线,一共16线(N_SCAN=16)。
  3. 求水平方向上的角度horizonAngle = atan2(thisPoint.x, thisPoint.y) * 180 / M_PI;
  4. 根据水平方向上的角度计算列向量columnIdn
    这里对数据的处理比较巧妙,一开始觉得很奇怪,但后来发现这样做其实让数据更不容易失真。
    计算columnIdn主要是下面这三个语句:
columnIdn = -round((horizonAngle-90.0)/ang_res_x) + Horizon_SCAN/2;
if (columnIdn >= Horizon_SCAN)
		columnIdn -= Horizon_SCAN;
if (columnIdn < 0 || columnIdn >= Horizon_SCAN)
		continue;

先把columnIdnhorizonAngle:(-PI,PI]转换到columnIdn:[H/4,5H/4],然后判断columnIdn大小,再讲它的范围转换到了[0,H] (H:Horizon_SCAN)
这样就把扫描开始的地方角度为0与角度为360的连在了一起,非常巧妙。
5. 接着在thisPoint.intensity中保存一个点的位置信息rowIdn+columnIdn / 10000.0fullInfoCloud的点保存点的距离信息;

具体的转换过程可以看下面这个两张图:
在这里插入图片描述

各种标记的含义

  • groundMat:
    1) groundMat.at<int8_t>(i,j) = 0,初始值;
    2) groundMat.at<int8_t>(i,j) = 1,有效的地面点;
    3) groundMat.at<int8_t>(i,j) = -1,无效地面点;

  • rangeMat
    1) rangeMat.at(i,j) = FLT_MAX,浮点数的最大值,初始化信息;
    2) rangeMat.at(rowIdn, columnIdn) = range,保存图像深度;

  • labelMat
    1) labelMat.at(i,j) = 0,初始值;
    2) labelMat.at(i,j) = -1,无效点;
    3)labelMat.at(thisIndX, thisIndY) = labelCount,平面点;
    4)labelMat.at(allPushedIndX[i], allPushedIndY[i]) = 999999,需要舍弃的点,数量不到30。

groundRemoval

void groundRemoval()由三个部分的程序组成。

  1. 由上下两线之间点的XYZ位置得到两线之间的俯仰角,如果俯仰角在10度以内,则判定(i,j)和(i,j+1)为地面点,groundMat[i][j]=1,否则,则不是地面点,进行后续操作;
  2. 找到所有点中的地面点,并将他们的labelMat标记为-1,rangeMat[i][j]==FLT_MAX 判定为无效的另一个条件。
  3. 如果有节点订阅groundCloud,那么就需要把地面点发布出来。具体实现过程:把点放到groundCloud队列中去。这样就把地面点和非地面点标记并且区分开来了。

cloudSegmentation

void cloudSegmentation()进行的是点云分割的操作,将不同类型的点云放到不同的点云块中去,例如outlierCloudsegmentedCloudPure等。具体步骤:

  1. 首先判断点云标签,这个点云没有进行过分类(在原先的处理中没有被分到地面点中去或没有分到平面中),则通过labelComponents(i, j);对点云进行分类。进行分类的过程在labelComponents中进行介绍。
  2. 分类完成后,找到可用的特征点或者地面点(不选择labelMat[i][j]=0的点),按照它的标签值进行判断,将部分界外点放进outlierCloud中。continue继续处理下一个点。
  3. 然后将大部分地面点去掉,省下的那些点进行信息的拷贝与保存操作。
  4. 最后如果有节点订阅SegmentedCloudPure,那么把点云数据保存到segmentedCloudPure中去。

labelComponents

void labelComponents(int row, int col)对点云进行标记。通过标准的BFS算法对点进行标记:以(row,col)为中心向外面扩散,判断(row,col)是否属于平面中一点。

  • BFS过程:
    1.用queueIndXqueueIndY保存进行分割的点云行列值,用queueStartInd作为索引。
    2.求这个点的4个邻接点,求其中离原点距离的最大值d1最小值d2。根据下面这部分代码来评价这两点之间是否具有平面特征。注意因为两个点上下或者水平对应的分辨率不一样,所以alpha是用来选择分辨率的。
// alpha代表角度分辨率,
// Y方向上角度分辨率是segmentAlphaY(rad)
if ((*iter).first == 0)
		alpha = segmentAlphaX;
else
		alpha = segmentAlphaY;

// 通过下面的公式计算这两点之间是否有平面特征
// atan2(y,x)的值越大,d1,d2之间的差距越小,越平坦
angle = atan2(d2*sin(alpha), (d1 -d2*cos(alpha)));
  • 在这之后通过判断角度是否大于60度来决定是否要将这个点加入保存的队列。加入的话则假设这个点是个平面点。
  • 然后进行聚类,聚类的规则是:
    1.如果聚类超过30个点,直接标记为一个可用聚类,labelCount需要递增;
    2.如果聚类点数小于30大于等于5,统计竖直方向上的聚类点数
    3.竖直方向上超过3个也将它标记为有效聚类
    4.标记为999999的是需要舍弃的聚类的点,因为他们的数量小于30个

publishCloud

void publishCloud()发布各类点云数据。

// 发布各类点云内容
void publishCloud(){
	// 发布cloud_msgs::cloud_info消息
    segMsg.header = cloudHeader;
    pubSegmentedCloudInfo.publish(segMsg);

    sensor_msgs::PointCloud2 laserCloudTemp;

	// pubOutlierCloud发布界外点云
    pcl::toROSMsg(*outlierCloud, laserCloudTemp);
    laserCloudTemp.header.stamp = cloudHeader.stamp;
    laserCloudTemp.header.frame_id = "base_link";
    pubOutlierCloud.publish(laserCloudTemp);

	// pubSegmentedCloud发布分块点云
    pcl::toROSMsg(*segmentedCloud, laserCloudTemp);
    laserCloudTemp.header.stamp = cloudHeader.stamp;
    laserCloudTemp.header.frame_id = "base_link";
    pubSegmentedCloud.publish(laserCloudTemp);

    if (pubFullCloud.getNumSubscribers() != 0){
        pcl::toROSMsg(*fullCloud, laserCloudTemp);
        laserCloudTemp.header.stamp = cloudHeader.stamp;
        laserCloudTemp.header.frame_id = "base_link";
        pubFullCloud.publish(laserCloudTemp);
    }

    if (pubGroundCloud.getNumSubscribers() != 0){
        pcl::toROSMsg(*groundCloud, laserCloudTemp);
        laserCloudTemp.header.stamp = cloudHeader.stamp;
        laserCloudTemp.header.frame_id = "base_link";
        pubGroundCloud.publish(laserCloudTemp);
    }

    if (pubSegmentedCloudPure.getNumSubscribers() != 0){
        pcl::toROSMsg(*segmentedCloudPure, laserCloudTemp);
        laserCloudTemp.header.stamp = cloudHeader.stamp;
        laserCloudTemp.header.frame_id = "base_link";
        pubSegmentedCloudPure.publish(laserCloudTemp);
    }

    if (pubFullInfoCloud.getNumSubscribers() != 0){
        pcl::toROSMsg(*fullInfoCloud, laserCloudTemp);
        laserCloudTemp.header.stamp = cloudHeader.stamp;
        laserCloudTemp.header.frame_id = "base_link";
        pubFullInfoCloud.publish(laserCloudTemp);
    }
}

resetParameters

void resetParameters()具体代码:

// 初始化/重置各类参数内容
void resetParameters(){
    laserCloudIn->clear();
    groundCloud->clear();
    segmentedCloud->clear();
    segmentedCloudPure->clear();
    outlierCloud->clear();

    rangeMat = cv::Mat(N_SCAN, Horizon_SCAN, CV_32F, cv::Scalar::all(FLT_MAX));
    groundMat = cv::Mat(N_SCAN, Horizon_SCAN, CV_8S, cv::Scalar::all(0));
    labelMat = cv::Mat(N_SCAN, Horizon_SCAN, CV_32S, cv::Scalar::all(0));
    labelCount = 1;

    std::fill(fullCloud->points.begin(), fullCloud->points.end(), nanPoint);
    std::fill(fullInfoCloud->points.begin(), fullInfoCloud->points.end(), nanPoint);
}

(imageProjection.cpp完)

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

LeGO-LOAM 源码阅读笔记(imageProjecion.cpp) 的相关文章

  • SLAM笔记(四)运动恢复结构的几何数学(本征矩阵、单应矩阵、基础矩阵)

    1 间接法进行运动恢复的前提假设 对于结构与运动或视觉三维重建中 通常假设已经通过特征匹配等方法获取了匹配好的点对 先求出匹配点对再获取结构和运动信息的方法称作间接法 间接法最重要的三个假设是 1 拥有一系列两帧之间的匹配点对 但同时假设匹
  • ubuntu系统下配置vscode编译cmake

    文章目录 一 配置vs code运行c 代码 三个关键文件介绍 1 tasks json run helloworld cpp 1 1 打开cpp文件 使其成为活动文件 1 2 按编辑器右上角的播放按钮 1 3生成task文件 1 4 此时
  • 速腾聚创雷达最新驱动安装(包含ring和timestamp)运行lio-sam

    记录一下搞slam的过程 ring和timestamp 最近想跑lio sam 需要用到ring和timestamp两个参数 lio sam作者用的velodyne雷达是带这两个参数的 但是rs雷达的老版驱动录制的点云包没有这两个参数 在g
  • 使用EKF融合odometry及imu数据

    整理资料发现早前学习robot pose ekf的笔记 大抵是一些原理基础的东西加一些自己的理解 可能有不太正确的地方 当时做工程遇到的情况为机器人在一些如光滑的地面上打滑的情形 期望使用EKF利用imu对odom数据进行校正 就结果来看
  • SLAM评估工具evo的使用

    evo官方指南 参考博客 lt 官方手册 这篇参考博客 完全可以掌握evo的基本操作 gt Then 实践出真知 1 安装evo sudo apt install python pip pip install evo upgrade no
  • 经典坐标变换案例代码剖析

    题目 设有小萝卜一号和小萝卜二号位于世界坐标系中 记世界坐标系为W 小萝卜们的坐标系为R1和 R2 小萝卜一号的位姿为q2 0 35 0 2 0 3 0 1 T t1 0 3 0 1 0 1 T 小萝卜二号的位姿为q2 0 5 0 4 0
  • 深度相机Kinect2.0三维点云拼接实验(一)

    文章目录 摘要 Kinect2 0简介 工作原理 RGB相机成像原理 深度相机成像原理 总结 参考文献 摘要 Kinect2 0是微软推出的一款RGB D相机 它即支持普通相机的拍摄 也支持脉冲测量深度信息 本系列文章基于该传感器给出基本的
  • vscode配置eigen3

    目录 1 头文件包含 2 c cpp properties json 3 CMakeList txt 4 完整代码 1 头文件包含 Eigen 核心部分 include
  • 关于GPS、惯导、视觉里程计的几个定义

    1 首先写几个定义 惯性导航系统 Inertial Navigation System INS 全球定位卫星系统 Global Navigation Satellite System GNSS GNSS 包括全球定位系统 Global Po
  • 视觉SLAM技术及其应用(章国锋--复杂环境下的鲁棒SfM与SLAM)

    SLAM 同时定位与地图构建 机器人和计算机视觉领域的基本问题 在未知环境中定位自身方位并同时构建环境三维地图 应用广泛 增强现实 虚拟现实 机器人 无人驾驶 SLAM常用的传感器 红外传感器 较近距离感应 常用与扫地机器人 激光雷达 单线
  • 动态场景下基于实例分割的SLAM(毕业设计开题及语义分割部分)

    动态场景下基于实例分割的SLAM 毕业论文设计思路及流水 前言 今年选了个比较难的毕设题目 这里记录一下自己思路和流程 为之后的学弟学妹 划掉 铺个方向 会按日期不定期的更新 一 开题 2019 12 24 考研前选择课题是 利用深度学习对
  • SLAM-hector_slam 简介与使用

    hector slam功能包使用高斯牛顿方法 不需要里程计数据 只根据激光信息便可构建地图 所以他的总体框架如下 hector slam功能包 hector slam的核心节点是hector mapping 它订阅 scan 话题以获取SL
  • 高斯牛顿法求非线性最小二乘的步骤和c++代码实现

    slam图优化的本质是一个非线性优化问题 Gauss Newton求解步骤 1 线性化误差函数 2 构建线性系统 3 求解线性系统 4 更新解 并不断迭代直至收敛 一个简单的代码实现 一维参数xy 高维变为对应的矩阵即可 include
  • docker dbus-x11

    本来想用terminator启动nvidia docker 显示出图形界面的 结果发现启动的时候出问题了 terminator 1 dbind WARNING 07 31 53 725 Couldn t connect to accessi
  • 用Eigen库练习代数运算方式以便后续对刚体旋转和移动做基础

    include
  • 快看!那个学vSLAM的上吊了! —— (一)综述

    不同于之前发布的文章 我将使用一种全新的方式 iPad Notability Blog的方式打开这个板块的大门 原因有两个 1 Notability更方便手写长公式 也方便手绘坐标系变换等等 2 之前Apple Pencil找不到了新破费买
  • 舒尔补-边际概率-条件概率

    margin求边际概率的时候喜欢通过舒尔补的形式去操作信息矩阵 如p b c 求积分p a b c da 从上图可知 边缘概率直接看协方差矩阵比较方便 边际概率的方差就是取对应联合分布中相应的协方差块 信息矩阵是由舒尔补的形式计算 此形式也
  • Ubuntu18.04安装pcl(过程/坑记录式教程)

    Ubuntu18 04安装pcl 1 下载pcl 2 安装依赖项 3 编译 4 安装 5 网上教程说要安装QT5和VTK 但按照本文的 本文记录了安装时出现的问题 出错的安装命令也记录了 建议浏览一遍再参考 不要错用了错误的指令 1 下载p
  • Object SLAM: An Object SLAM Framework for Association, Mapping, and High-Level Tasks 论文解读

    是一篇来自机器人顶刊T RO的文章 发表于2023 5 An Object SLAM Framework for Association Mapping and High Level Tasks 论文 An Object SLAM Fram
  • KITTI校准文件中参数的格式

    我从以下位置访问了校准文件KITTI 的部分里程计 http www cvlibs net datasets kitti eval odometry php 其中一个校准文件的内容如下 P0 7 188560000000e 02 0 000

随机推荐

  • 4.4.2 中文标点符号验证

    英文标点符号比较多 如 逗号 点号 问号 冒号 分号 单引号 感叹号 双引号 连接号 破折号 省略号 小括号 中括号 大括号 顿号 书名号等 以下正则表达式能够验证英文标点符号 2 64 正则表达式 64 解释 匹配 符号 2 匹配破折号
  • Java 添加背景图片

    import java awt import javax swing public class TestBackgroundColor extends JFrame public static void main String args T
  • IF语句例题(一)

    石头剪刀布 需求 1 从控制台输入要出的拳 石头 1 剪刀 2 布 3 2 电脑随机出拳 先假定电脑会出石头 完成代码功能 3 比较正负 解题 首先我们先会议一些input函数 在input函数中内部都是字符串 所以说要把字符串变成整数 p
  • k8s安全管理:认证、授权、准入控制概述

    概述信息 k8s对我们整个系统的认证 授权 访问控制做了精密的设置 对于k8s集群来说 apiserver是整个集群访问控制的唯一入口 我们在k8s集群之上部署应用程序的时候 也可以通过宿主机的NodePort暴露的端口访问里面的程序 用户
  • linux备份工具

    这本阿里P8撰写的算法笔记 再次推荐给大家 身边不少朋友学完这本书最后加入大厂 Github 疯传 史上最强悍 阿里大佬 LeetCode刷题手册 开放下载了 经常备份计算机上的数据是个好的做法 它可以手动完成 也可以设置成自动执行 许多备
  • Java____西财大图书管理系统 代码实现

    西财大图书管理项目代码 book类 1 book 2 bookist operation类 1 AddOperation 2 BorrowOperation 3 DisplayOperation 4 FindOperation 5 Remo
  • 信号与系统matlab心得体会,实验五 Matlab在信号与系统分析中的应用

    实验五Matlab在信号与系统分析中的应用 08电子 3 班E08610308 陈建能 一 实验目的 1 学会用MATLAB进行Laplace正 反变换及Z正 反变换 2 掌握利用MATLAB画出系统的幅频响应 相频响应的方法 3 掌握利用
  • 【C语言】N 阶矩阵的转置

    非主对角线元素的调换 只需要将蓝色虚线左边的元素进行调换 include
  • u盘装系统

    1 用ultraiso将ios写入u盘 2 U盘插入电脑 3 开机狂按某键进入 boot启动页面 4 选择该u盘 enter回车确认安装
  • ag-grid表格基本使用方法-React版本

    AG表格基本用法及Api 在要使用的项目中 首次使用需要引入相关组件包 注 项目中所有组件都是封装之后的 引入方式如下 import Table from pkg common table 引入完成后 在view层需要用到表格的地方直接放入
  • Vue3的filter过滤器代替方法

    Vue3的过滤器代替方法 前言 一 使用步骤 1 vue2的filter 2 vue3的computed 总结 前言 最近博主从vue2转到vue3 惊奇的发现vue2里面的filter在vue3中不再支持 官方建议用计算属性或方法代替过滤
  • 现代博弈论与多智能体强化学习系统

    如今 大多数人工智能 AI 系统都是基于处理任务的单个代理 或者在对抗模型的情况下 是一些相互竞争以改善系统整体行为的代理 然而 现实世界中的许多认知问题是大群人建立的知识的结果 以自动驾驶汽车场景为例 任何座席的决策都是场景中许多其他座席
  • 遭遇难缠的病毒群ntldr.exe和c0nime.exe等,可杀

    据当事人说中毒后就上不了网了 我没有确认 每个硬盘分区下都有 Autorun inf和ntldr exe C Windows System 目录 下有 c0nime exe 那是数字0不是字母o 等若干个可疑的可执行文件 硬盘上N多exe可
  • Vue模板语法

    Vue js使用了基于HTML的模板语法 允许开发者声明式地将DOM绑定至底层Vue实例的数据 所有Vue js的模板都是合法的HTML 所以能够被遵循规范的浏览器和HTML解析器解析 在底层的实现上 Vue将模板编译成虚拟DOM渲染函数
  • Andorid与其他操作系统的知识

    安卓用的是LINUX的内核 利用LINUX的几个库 应用层运行JAVA虚拟机上 这点和iPhone很想 只不过 iphone是基于unix系统 是微内核结构 同样运行在java虚拟机上 所以 安卓只是一个linux的衍生系统 是LINUX的
  • Opecv检测多个圆形(霍夫圆检测,轮廓面积筛选,C/C++)

    主要是利用霍夫圆检测 面积筛选等完成多个圆形检测 具体代码及结果如下 第一部分是头文件 common h pragma once include
  • Springboot+Mybatis中typeAliasesPackage正则扫描实现

    mybatis默认配置typeAliasesPackage是不支持正则扫描package的 因此需要手动继承org mybatis spring SqlSessionFactoryBean 自己实现正则扫描 方法和传统的spring myb
  • uniapp封装请求失败的提示

    当数据请求失败之后 经常需要调用uni showToast 方法来提示用户 可以在全局封装一个uni showMsg 方法 来简化uni showToast 方法的调用 在main js中 将自定义的 showMsg 方法挂载到uni对象上
  • JSONObject 获取全部键(键值对)

    JSONObject也是迭代器 故可使用Itear的方式进行获取全部键 主要是针对不确定键的情况下使用 直接上代码 JSONObject jsonObject new JSONObject response response 为str It
  • LeGO-LOAM 源码阅读笔记(imageProjecion.cpp)

    LeGO LOAM是一种在LOAM之上进行改进的激光雷达建图方法 建图效果比LOAM要好 但是建图较为稀疏 计算量也更小了 本文原地址 wykxwyc的博客 github注释后LeGO LOAM源码 LeGO LOAM NOTED 关于代码