;\\033[0m Image Projection Started.\");\n\n ros::spin();\n return 0;\n}\n\n```\n\n在 main 函数中,只是实例化了一个对象 IP ,所以 一旦创建了一个对象,就进入到了 Class 中去执行构造函数。\n\n```\n ImageProjection() : nh(\"~\")\n {\n \n // 订阅原始的激光点云\n subLaserCloud = nh.subscribe<;sensor_msgs::PointCloud2>;(pointCloudTopic, 1, &ImageProjection::cloudHandler, this);\n \n // 转换成图片的点云\n pubFullCloud = nh.advertise<;sensor_msgs::PointCloud2>;(\"/full_cloud_projected\", 1);\n // 转换成图片的并带有距离信息的点云\n pubFullInfoCloud = nh.advertise<;sensor_msgs::PointCloud2>;(\"/full_cloud_info\", 1);\n \n // 发布提取的地面特征\n pubGroundCloud = nh.advertise<;sensor_msgs::PointCloud2>;(\"/ground_cloud\", 1);\n \n // 发布已经分割的点云\n pubSegmentedCloud = nh.advertise<;sensor_msgs::PointCloud2>;(\"/segmented_cloud\", 1);\n // 具有几何信息的分割点云\n pubSegmentedCloudPure = nh.advertise<;sensor_msgs::PointCloud2>;(\"/segmented_cloud_pure\", 1);\n pubSegmentedCloudInfo = nh.advertise<;cloud_msgs::cloud_info>;(\"/segmented_cloud_info\", 1);\n \n // 含有异常信息的点云\n pubOutlierCloud = nh.advertise<;sensor_msgs::PointCloud2>;(\"/outlier_cloud\", 1);\n\n nanPoint.x = std::numeric_limits<;float>;::quiet_NaN();\n nanPoint.y = std::numeric_limits<;float>;::quiet_NaN();\n nanPoint.z = std::numeric_limits<;float>;::quiet_NaN();\n nanPoint.intensity = -1;\n\n allocateMemory();\n resetParameters();\n }\n\n```\n\nclass 中的构造函数中,订阅了原始的激光点云数据(subLaserCloud)然后就进入到了 回调函数(ImageProjection::cloudHandler)对点云数据进行处理。\n\n### 1. cloudHandler()\n\n订阅激光雷达点云信息之后的回调函数\n\n```\n void cloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){\n \n // 1. Convert ros message to pcl point cloud 将ros消息转换为pcl点云\n copyPointCloud(laserCloudMsg); \n // 2. Start and end angle of a scan 扫描的起始和结束角度\n findStartEndAngle();\n // 3. Range image projection 距离图像投影\n projectPointCloud();\n // 4. Mark ground points 标记地面点\n groundRemoval();\n // 5. Point cloud segmentation 点云分割\n cloudSegmentation();\n // 6. Publish all clouds 发布点云\n publishCloud();\n // 7. Reset parameters for next iteration 重置下一次迭代的参数\n resetParameters();\n }\n\n```\n\n回调函数中按照以上 7 个逻辑步骤对点云进行处理,主要的逻辑步骤通过一个个封装好的函数呈现出来。\n\n### 2. copyPointCloud()\n\n由于激光雷达点云消息在传递过程中使用的是ROS 类型的消息,所以在处理的过程中统一需要对消息类型转换,通常的办法就是使用 PCL 库\n\n```\n // 复制点云 将ros消息转换为pcl点云\n // 使用pcl库函数;\n \n void copyPointCloud(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){\n \n // 1. 读取ROS点云转换为PCL点云\n cloudHeader = laserCloudMsg->;header;\n // cloudHeader.stamp = ros::Time::now(); // Ouster lidar users may need to uncomment this line\n pcl::fromROSMsg(*laserCloudMsg, *laserCloudIn);\n\n //2.移除无效的点云 Remove Nan points\n std::vector<;int>; indices;\n pcl::removeNaNFromPointCloud(*laserCloudIn, *laserCloudIn, indices);\n\n // 3. have \"ring\" channel in the cloud or not\n // 如果点云有\"ring\"通过,则保存为laserCloudInRing\n // 判断是不是使用了 velodyne 的激光雷达\n if (useCloudRing == true){\n \n pcl::fromROSMsg(*laserCloudMsg, *laserCloudInRing);\n if (laserCloudInRing->;is_dense == false) {\n \n ROS_ERROR(\"Point cloud is not in dense format, please remove NaN points first!\");\n ros::shutdown();\n } \n }\n }\n\n```\n\n这个函数主体内容分为三个步骤,其中的第三步注意区分自己使用的激光雷达是否存在 CloudRing,没有这个的激光雷达接下来的步骤都不会去执行,所以在实际跑这个框架的时候一定要注意这个地方\n\n### 3. findStartEndAngle()\n\n```\n // 找到开始结束角度\n // 1.一圈数据的角度差,使用atan2计算;\n // 2.注意计算结果的范围合理性\n \n void findStartEndAngle(){\n \n // start and end orientation of this cloud\n // 1.开始点和结束点的航向角 (负号表示顺时针旋转) \n segMsg.startOrientation = -atan2(laserCloudIn->;points[0].y, laserCloudIn->;points[0].x);\n\n // 加 2 * M_PI 表示已经转转了一圈\n segMsg.endOrientation = -atan2(laserCloudIn->;points[laserCloudIn->;points.size() - 1].y,\n laserCloudIn->;points[laserCloudIn->;points.size() - 1].x) + 2 * M_PI;\n \n // 2.保证所有角度落在 [M_PI , 3M_PI] 上\n if (segMsg.endOrientation - segMsg.startOrientation >; 3 * M_PI) {\n \n segMsg.endOrientation -= 2 * M_PI;\n } else if (segMsg.endOrientation - segMsg.startOrientation <; M_PI)\n segMsg.endOrientation += 2 * M_PI;\n segMsg.orientationDiff = segMsg.endOrientation - segMsg.startOrientation;\n }\n\n```\n\n这个函数在 LOAM 代码里面也存在。
首先通过一个反正切函数,找到一帧激光点云起始时刻和结束时刻的航向角,第二步的作用是将一帧激光点云的航向角度限制在 [pi , 3pi] 之间,方便后续计算出一帧激光点云的时间。\n\n### 4. projectPointCloud()\n\n距离图像投影
将3D point cloud投影映射到2D range image
将激光雷达数据投影成一个16x1800(依雷达角分辨率而定)的点云阵列\n\n```\n // 距离图像投影\n // 将3D point cloud投影映射到2D range image\n // 将激光雷达数据投影成一个16x1800(依雷达角分辨率而定)的点云阵列\n void projectPointCloud(){\n \n // range image projection\n float verticalAngle, horizonAngle, range;\n size_t rowIdn, columnIdn, index, cloudSize; \n PointType thisPoint;\n\n cloudSize = laserCloudIn->;points.size();\n\n // 遍历整个点云 \n for (size_t i = 0; i <; cloudSize; ++i){\n \n // 提取点云中 x y z 坐标数值\n thisPoint.x = laserCloudIn->;points[i].x;\n thisPoint.y = laserCloudIn->;points[i].y;\n thisPoint.z = laserCloudIn->;points[i].z;\n\n // find the row and column index in the iamge for this point\n // 判断是不是使用了 velodyne 的雷达\n if (useCloudRing == true){\n \n // 提取激光雷达线束到 rowIdn \n rowIdn = laserCloudInRing->;points[i].ring;\n }\n // 是其他的雷达 就通过俯仰角 确定当前的激光点是来自哪个线束 index \n else{\n \n verticalAngle = atan2(thisPoint.z, sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y)) * 180 / M_PI;\n rowIdn = (verticalAngle + ang_bottom) / ang_res_y; //确定行索引\n }\n if (rowIdn <; 0 || rowIdn >;= N_SCAN)\n continue;\n\n horizonAngle = atan2(thisPoint.x, thisPoint.y) * 180 / M_PI;\n\n // 保证 columnIdn 的大小在 [0 , 1800)\n columnIdn = -round((horizonAngle-90.0)/ang_res_x) + Horizon_SCAN/2; //确定列索引\n if (columnIdn >;= Horizon_SCAN)\n columnIdn -= Horizon_SCAN;\n\n if (columnIdn <; 0 || columnIdn >;= Horizon_SCAN)\n continue;\n\n // 如果距离小于 1米 则过滤掉 通常是过滤自身(距离传感器比较近的点)\n range = sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y + thisPoint.z * thisPoint.z); //确定深度\n if (range <; sensorMinimumRange)\n continue;\n \n // 将计算下来的距离传感器的 数值保存到 rangeMat 中 \n // 这是一个 16 * 1800 的矩阵 rowIdn为线束数值 columnIdn 是 一圈圆形 滩平之后的数值\n // range 是特征点云点到原点的数值\n // 这样就将一个三维的坐标 转换到一个 矩阵中了.\n rangeMat.at<;float>;(rowIdn, columnIdn) = range;\n\n // 将 index 和 横坐标存储在 intensity 中 整数部分是线束数值 小数部分是方向角度\n thisPoint.intensity = (float)rowIdn + (float)columnIdn / 10000.0;\n\n //深度图的索引值 index = 列号 + 行号 * 1800 \n index = columnIdn + rowIdn * Horizon_SCAN;\n\n // fullCloud 存放的是坐标信息(二维的)\n // fullInfoCloud 增加了点到传感器的距离信息(三维的) \n fullCloud->;points[index] = thisPoint;\n fullInfoCloud->;points[index] = thisPoint;\n\n // intensity 中存放的是点云点到传感器的距离\n fullInfoCloud->;points[index].intensity = range; // the corresponding range of a point is saved as \"intensity\"\n }\n }\n\n```\n\n此处对激光点云的处理是 LEGO-LOAM 和 LOAM 的第一个区别。这里将一帧激光点云处理成一个 16 * 1800 像素的图片。 16代表的是激光雷达的线束,1800代表的是激光扫描一圈时候是 间隔0.5度发射一个激光束 所以 360 * 0.5 = 1800\n\n 再者,rangeMat.at(rowIdn, columnIdn) 这里调用了一个 opencv 的多维数组,数组中的行与列 对应的就是图片的长和宽,然后数组中存放的数值就是图片相应位置上面的点到激光雷达的距离。\n\n 最后将点云的坐标信息存储在 intensity 中,采用的方法是:整数+小数 存储。整数部分存储的是激光线束数值,小数部分存储的水平航向值。\n\natan2(y,x);\n\n反正切的角度等于X轴与通过原点和给定坐标点(x, y)的直线之间的夹角,结果为正表示从X轴逆时针旋转的角度,结果为负表示从X轴顺时针旋转的角度;\n\n1. 确定行索引 根据ring id或者根据坐标计算:

\n1. 确定列索引([ − π , π ] 转换为 [ 0 , 1800 ]):

\n1. 确定深度值:(注意数据的有效范围)

\n\n### 5. groundRemoval()\n\n首先。判断地面点的标志就是相邻两个激光线束扫描到点的坐标,如果两个坐标之间的差值 或者两个坐标之间的斜率大于一个设定的值,则将该点\n\n判断是地面点。所以此处用到了激光点云图片的深度信息\n\n```\n // 移除地面点\n // 根据上下两线之间点的位置计算两线之间俯仰角判断,小于10度则为地面点\n \n void groundRemoval(){\n \n size_t lowerInd, upperInd;\n float diffX, diffY, diffZ, angle;\n \n // groundMat\n // -1, no valid info to check if ground of not 没有有效的信息确认是不是地面\n // 0, initial value, after validation, means not ground 确认不是地面点\n // 1, ground\n for (size_t j = 0; j <; Horizon_SCAN; ++j){\n \n // 前7个激光雷达扫描线束足够满足地面点的检测 所以只遍历 7 次\n for (size_t i = 0; i <; groundScanInd; ++i){\n \n //groundScanInd定义打到地面上激光线的数目\n lowerInd = j + ( i )*Horizon_SCAN;\n upperInd = j + (i+1)*Horizon_SCAN;\n\n // 如果之前计算过的 intensity 是 -1 则直接默认为是一个无效点\n if (fullCloud->;points[lowerInd].intensity == -1 ||\n fullCloud->;points[upperInd].intensity == -1){\n \n // no info to check, invalid points 对这个无效点直接进行贴标签\n groundMat.at<;int8_t>;(i,j) = -1;\n continue;\n }\n \n diffX = fullCloud->;points[upperInd].x - fullCloud->;points[lowerInd].x;\n diffY = fullCloud->;points[upperInd].y - fullCloud->;points[lowerInd].y;\n diffZ = fullCloud->;points[upperInd].z - fullCloud->;points[lowerInd].z;\n\n // 计算相邻两个线束之间的夹角 \n angle = atan2(diffZ, sqrt(diffX*diffX + diffY*diffY) ) * 180 / M_PI;\n\n //垂直方向相邻两点俯仰角小于10度就判定为地面点;相邻扫描圈\n if (abs(angle - sensorMountAngle) <;= 10){\n \n groundMat.at<;int8_t>;(i,j) = 1;\n groundMat.at<;int8_t>;(i+1,j) = 1;\n }\n }\n }\n\n // extract ground cloud (groundMat == 1)\n // mark entry that doesn\'t need to label (ground and invalid point) for segmentation\n // note that ground remove is from 0~N_SCAN-1, need rangeMat for mark label matrix for the 16th scan\n\n // 给地面点 标记一个符号 为 -1 \n for (size_t i = 0; i <; N_SCAN; ++i){\n \n for (size_t j = 0; j <; Horizon_SCAN; ++j){\n \n if (groundMat.at<;int8_t>;(i,j) == 1 || rangeMat.at<;float>;(i,j) == FLT_MAX){\n \n labelMat.at<;int>;(i,j) = -1;\n }\n }\n }\n\n // 发布点云信息,只发布地面点云信息\n if (pubGroundCloud.getNumSubscribers() != 0){\n \n for (size_t i = 0; i <;= groundScanInd; ++i){\n \n for (size_t j = 0; j <; Horizon_SCAN; ++j){\n \n if (groundMat.at<;int8_t>;(i,j) == 1)\n groundCloud->;push_back(fullCloud->;points[j + i*Horizon_SCAN]);\n }\n }\n }\n }\n\n```\n\n垂直相邻两点俯仰角小于10度就判定为地面点。\n\n### 6. cloudSegmentation()\n\n从论文中可以看到,分割函数的来源参考了两篇论文 ( Effificient Online Segmentation for Sparse 3D Laser Scans ,另外一篇 Fast Range Image-Based Segmentation of Sparse 3D Laser Scans for Online Operation)的方法 。方法的原理可以参考知乎文章 [《地面点障碍物快速分割聚类》](https://zhuanlan.zhihu.com/p/72932303) 。\n\n```\n // 点云分割\n // 首先对点云进行聚类标记,根据标签进行对应点云块存储;\n \n void cloudSegmentation(){\n \n // segmentation process\n for (size_t i = 0; i <; N_SCAN; ++i) // 16线的 一个线束一个的遍历\n for (size_t j = 0; j <; Horizon_SCAN; ++j) // 水平 的 1800\n if (labelMat.at<;int>;(i,j) == 0) // 对非地面点进行点云分割\n labelComponents(i, j); // 调用这个函数对点云进行分割聚类\n\n int sizeOfSegCloud = 0;\n\n // extract segmented cloud for lidar odometry\n // 提取分割点云 用于激光雷达里程计\n for (size_t i = 0; i <; N_SCAN; ++i) {\n \n\n segMsg.startRingIndex[i] = sizeOfSegCloud-1 + 5;\n\n for (size_t j = 0; j <; Horizon_SCAN; ++j) {\n \n if (labelMat.at<;int>;(i,j) >; 0 || groundMat.at<;int8_t>;(i,j) == 1){\n \n // outliers that will not be used for optimization (always continue)\n // 勾勒出优化过程中不被使用的值\n\n // 1. 如果label为999999则跳过\n if (labelMat.at<;int>;(i,j) == 999999){\n \n if (i >; groundScanInd && j % 5 == 0){\n \n outlierCloud->;push_back(fullCloud->;points[j + i*Horizon_SCAN]);\n continue;\n }else{\n \n continue;\n }\n }\n\n // majority of ground points are skipped\n // 2. 如果为地,跳过index不是5的倍数的点\n if (groundMat.at<;int8_t>;(i,j) == 1){\n \n if (j%5!=0 && j>;5 && j<;Horizon_SCAN-5)\n continue;\n }\n // mark ground points so they will not be considered as edge features later\n segMsg.segmentedCloudGroundFlag[sizeOfSegCloud] = (groundMat.at<;int8_t>;(i,j) == 1);\n // mark the points\' column index for marking occlusion later\n segMsg.segmentedCloudColInd[sizeOfSegCloud] = j;\n // save range info\n segMsg.segmentedCloudRange[sizeOfSegCloud] = rangeMat.at<;float>;(i,j);\n // save seg cloud\n segmentedCloud->;push_back(fullCloud->;points[j + i*Horizon_SCAN]);\n // size of seg cloud\n ++sizeOfSegCloud;\n }\n }\n\n segMsg.endRingIndex[i] = sizeOfSegCloud-1 - 5;\n }\n \n // extract segmented cloud for visualization\n if (pubSegmentedCloudPure.getNumSubscribers() != 0){\n \n for (size_t i = 0; i <; N_SCAN; ++i){\n \n for (size_t j = 0; j <; Horizon_SCAN; ++j){\n \n if (labelMat.at<;int>;(i,j) >; 0 && labelMat.at<;int>;(i,j) != 999999){\n \n segmentedCloudPure->;push_back(fullCloud->;points[j + i*Horizon_SCAN]);\n segmentedCloudPure->;points.back().intensity = labelMat.at<;int>;(i,j);\n }\n }\n }\n }\n }\n\n```\n\n### 7. labelComponents()\n\n```\n // 标签组件\n // 局部特征检测聚类\n // 平面点与边缘点\n \n void labelComponents(int row, int col){\n \n // use std::queue std::vector std::deque will slow the program down greatly\n float d1, d2, alpha, angle;\n int fromIndX, fromIndY, thisIndX, thisIndY; \n bool lineCountFlag[N_SCAN] = {\n false};\n\n // 传进来的两个参数,按照坐标不同分别给他们放到 X 与 Y 的数组中\n queueIndX[0] = row;\n queueIndY[0] = col;\n int queueSize = 1; // 需要计算角度的点的数量\n int queueStartInd = 0;\n int queueEndInd = 1;\n\n allPushedIndX[0] = row;\n allPushedIndY[0] = col;\n int allPushedIndSize = 1;\n \n while(queueSize >; 0){\n \n // Pop point\n fromIndX = queueIndX[queueStartInd];\n fromIndY = queueIndY[queueStartInd];\n --queueSize;\n ++queueStartInd;\n // Mark popped point\n labelMat.at<;int>;(fromIndX, fromIndY) = labelCount;\n // Loop through all the neighboring grids of popped grid\n\n // 遍历整个点云,遍历前后左右四个邻域点,求点之间的角度数值 \n for (auto iter = neighborIterator.begin(); iter != neighborIterator.end(); ++iter){\n \n // new index\n thisIndX = fromIndX + (*iter).first;\n thisIndY = fromIndY + (*iter).second;\n // index should be within the boundary\n if (thisIndX <; 0 || thisIndX >;= N_SCAN)\n continue;\n // at range image margin (left or right side)\n if (thisIndY <; 0)\n thisIndY = Horizon_SCAN - 1;\n if (thisIndY >;= Horizon_SCAN)\n thisIndY = 0;\n // prevent infinite loop (caused by put already examined point back)\n if (labelMat.at<;int>;(thisIndX, thisIndY) != 0)\n continue;\n\n //比较得出较大深度与较小深度\n d1 = std::max(rangeMat.at<;float>;(fromIndX, fromIndY), \n rangeMat.at<;float>;(thisIndX, thisIndY));\n d2 = std::min(rangeMat.at<;float>;(fromIndX, fromIndY), \n rangeMat.at<;float>;(thisIndX, thisIndY));\n\n if ((*iter).first == 0)\n alpha = segmentAlphaX;\n else\n alpha = segmentAlphaY;\n\n angle = atan2(d2*sin(alpha), (d1 -d2*cos(alpha))); //平面聚类公式,角度越大两点越趋向于平面\n //segmentTheta=60度\n if (angle >; segmentTheta){\n \n\n queueIndX[queueEndInd] = thisIndX;\n queueIndY[queueEndInd] = thisIndY;\n ++queueSize;\n ++queueEndInd;\n\n labelMat.at<;int>;(thisIndX, thisIndY) = labelCount;\n lineCountFlag[thisIndX] = true;\n\n allPushedIndX[allPushedIndSize] = thisIndX;\n allPushedIndY[allPushedIndSize] = thisIndY;\n ++allPushedIndSize;\n }\n }\n }\n\n // check if this segment is valid\n bool feasibleSegment = false;\n\n // 如果是 allPushedIndSize 累加的数量增加到了30 个 则判断这部分点云属于一个聚类\n if (allPushedIndSize >;= 30)\n feasibleSegment = true; //面点\n\n // 如果垂直 方向上点的数量大于 5个 默认是一个有效的聚类\n else if (allPushedIndSize >;= segmentValidPointNum){\n \n int lineCount = 0;\n for (size_t i = 0; i <; N_SCAN; ++i)\n if (lineCountFlag[i] == true)\n ++lineCount;\n if (lineCount >;= segmentValidLineNum)\n feasibleSegment = true; //边点 \n }\n \n // segment is valid, mark these points\n if (feasibleSegment == true){\n \n ++labelCount;\n }else{\n // segment is invalid, mark these points\n for (size_t i = 0; i <; allPushedIndSize; ++i){\n \n labelMat.at<;int>;(allPushedIndX[i], allPushedIndY[i]) = 999999;\n }\n }\n }\n\n```\n\n取去除地面的 labelMat,逐点开始计算邻域4点(邻域的索引要注意有效范围),与中心点比较出距离的最大值与最小值,通过下面公式结合阈值π / 3,大于该值则构成平面特征为平面点,队列存储索引,labelMat 存储标签值,同时 lineCountFlag 置 true,直到不满足阈值跳出进行下步。\n\n\n\n

聚类,超过30个点聚为一类,labelCount++;
小于30超过5,统计垂直方向聚类点数,超过3个也标记为一类;
若都不满足,则赋值999999表示需要舍弃的聚类点。\n\n\n\n### 8. publishCloud()\n\n发布各类点云数据\n\n### 9. resetParameters()\n\n参数重置\n\n> \nLeGO-LOAM首先进行地面分割,找到地面之后,对地面之上的点进行聚类。聚类的算法如下图,主要是根据斜率对物体做切割,最后得到地面和分割后的点云。上述步骤的关键是要理解如何进行地面分割和点云分割。

\n点云分割完成之后,接下来对分割后的点云提取特征,提取的特征的目的是进行点云配准,从而得出当前位姿。\n\n\n## 2、featureAssociation —— 特征提取与匹配\n\n订阅分割点云、外点、imu数据,总体流程:\n\n### 0. main()\n\n主函数内部做了两件事情,一个是实例化一个对象,一个是循环执行类方法\n\n```\nint main(int argc, char** argv)\n{\n \n ros::init(argc, argv, \"lego_loam\");\n\n ROS_INFO(\"\\033[1;32m---->;\\033[0m Feature Association Started.\");\n\n // 1. 在构造函数中订阅消息和消息回调函数\n FeatureAssociation FA;\n\n ros::Rate rate(200);\n // 2. 循环调用runFeatureAssociation,函数的主流程所在\n while (ros::ok())\n {\n \n ros::spinOnce();\n\n FA.runFeatureAssociation();\n\n rate.sleep();\n }\n \n ros::spin();\n return 0;\n}\n\n```\n\n主函数里面首选实例化了一个对象 FA ,所以和之前的ImageProjection 处理过程一样,执行构造函数的内容,所以在构造函数中会订阅上一个cpp 文件中 pub 出来的消息。然后转到回调函数中处理数据,此处的回调函数都是将相应的信息存储到buff 中,所以不做详细分析。\n\n消息回调主要是接收上一个步骤(点云分割)中分割好的点云消息。\n\n```\n FeatureAssociation():\n nh(\"~\")\n {\n \n // 1. 接收消息,上一步分割好的点云\n // 订阅了分割之后的点云\n subLaserCloud = nh.subscribe<;sensor_msgs::PointCloud2>;(\"/segmented_cloud\", 1, &FeatureAssociation::laserCloudHandler, this);\n \n // 订阅的分割点云含有图像的深度信息\n subLaserCloudInfo = nh.subscribe<;cloud_msgs::cloud_info>;(\"/segmented_cloud_info\", 1, &FeatureAssociation::laserCloudInfoHandler, this);\n \n // 非聚类的点\n subOutlierCloud = nh.subscribe<;sensor_msgs::PointCloud2>;(\"/outlier_cloud\", 1, &FeatureAssociation::outlierCloudHandler, this);\n \n // IMU传感器的消息\n subImu = nh.subscribe<;sensor_msgs::Imu>;(imuTopic, 50, &FeatureAssociation::imuHandler, this);\n \n // 2. 发布消息\n // 发布面特征点 和 边特征点\n pubCornerPointsSharp = nh.advertise<;sensor_msgs::PointCloud2>;(\"/laser_cloud_sharp\", 1);\n pubCornerPointsLessSharp = nh.advertise<;sensor_msgs::PointCloud2>;(\"/laser_cloud_less_sharp\", 1);\n pubSurfPointsFlat = nh.advertise<;sensor_msgs::PointCloud2>;(\"/laser_cloud_flat\", 1);\n pubSurfPointsLessFlat = nh.advertise<;sensor_msgs::PointCloud2>;(\"/laser_cloud_less_flat\", 1);\n\n pubLaserCloudCornerLast = nh.advertise<;sensor_msgs::PointCloud2>;(\"/laser_cloud_corner_last\", 2);\n pubLaserCloudSurfLast = nh.advertise<;sensor_msgs::PointCloud2>;(\"/laser_cloud_surf_last\", 2);\n pubOutlierCloudLast = nh.advertise<;sensor_msgs::PointCloud2>;(\"/outlier_cloud_last\", 2);\n pubLaserOdometry = nh.advertise<;nav_msgs::Odometry>; (\"/laser_odom_to_init\", 5);\n \n initializationValue();\n }\n\n```\n\n下面我们具体看这4个消息\n\n在理解了上述4个消息之后,我们分别看下他们的回调,点云消息的回调主要是把ROS的消息转换为点云,IMU的回调主要是把IMU的消息放入buffer中。\n\n```\n // 1. 接收\"/segmented_cloud\"消息,保存到segmentedCloud\n void laserCloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){\n \n\n cloudHeader = laserCloudMsg->;header;\n\n timeScanCur = cloudHeader.stamp.toSec();\n timeNewSegmentedCloud = timeScanCur;\n\n \n```\n -->