这是LOAM第二部分Lidar laserOdometry雷达里程计。
在第一章提取完特征点后,需要对特征点云进行关联匹配,之后估计姿态。
主要分为两部分:

特征点关联使用scan-to-scan方式t和t+1时刻相邻两帧的点云数据进行配准,分为边缘点匹配和平面点匹配两部分。计算点到直线的距离和点到平面的距离。
姿态解算根据匹配的特征点云使用LM算法估计接收端位姿。

这部分代码完全是放在main函数。
首先介绍前面的参数。后面出现的会重点标注下。

//一个点云周期
const float scanPeriod = 0.1;//接收到边缘点和平面点
pcl::PointCloud<PointType>::Ptr cornerPointsSharp(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr cornerPointsLessSharp(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr surfPointsFlat(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr surfPointsLessFlat(new pcl::PointCloud<PointType>());
//上一帧点云的边缘点和平面点
pcl::PointCloud<PointType>::Ptr laserCloudCornerLast(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr laserCloudSurfLast(new pcl::PointCloud<PointType>());
//保存前一个节点发过来的未经处理过的特征点和权重
pcl::PointCloud<PointType>::Ptr laserCloudOri(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr coeffSel(new pcl::PointCloud<PointType>());
//全部点云
pcl::PointCloud<PointType>::Ptr laserCloudFullRes(new pcl::PointCloud<PointType>());
//imu信息
pcl::PointCloud<pcl::PointXYZ>::Ptr imuTrans(new pcl::PointCloud<pcl::PointXYZ>());
//上一帧边缘点、平面点构建的KD-tree
pcl::KdTreeFLANN<PointType>::Ptr kdtreeCornerLast(new pcl::KdTreeFLANN<PointType>());
pcl::KdTreeFLANN<PointType>::Ptr kdtreeSurfLast(new pcl::KdTreeFLANN<PointType>());//当前帧相对上一帧的状态转移量,局部坐标系
float transform[6] = {0};
//当前帧相对于第一帧的状态转移量,全局坐标系
float transformSum[6] = {0};//点云第一个点的RPY、最后一个点的RPY
float imuRollStart = 0, imuPitchStart = 0, imuYawStart = 0;
float imuRollLast = 0, imuPitchLast = 0, imuYawLast = 0;
//点云最后一个点相对于第一个点由于加减速产生的畸变位移、速度
float imuShiftFromStartX = 0, imuShiftFromStartY = 0, imuShiftFromStartZ = 0;
float imuVeloFromStartX = 0, imuVeloFromStartY = 0, imuVeloFromStartZ = 0;

0、预处理

  1. 订阅节点,发布消息
  2. 创建里程计对象、坐标转换对象
  3. 同步作用,确保同时收到同一个点云的特征点以及IMU信息才进入

    6个sub订阅器分别订阅scanRegistration节点发布的6个消息:/laser_cloud_sharp、/laser_cloud_less_sharp、pubSurfPointFlat、pubSurfPointLessFlat、/velodyne_cloud_2、/imu_trans消息。
    调用6个Handler回调函数处理这些边特征、面特征、全部点云和IMU数据,把他们从ROS::Msg类型转换成程序可以处理的pcl点云类型;
    4个pub发布器发布/laser_cloud_corner_last、/laser_cloud_surf_last、/velodyne_cloud_3、/laser_odom_to_init消息。
int main(int argc, char** argv)
{/****************0、预处理************************/ros::init(argc, argv, "laserOdometry");ros::NodeHandle nh;// 1.订阅节点,发布消息// 订阅scanRegistration发布的六个节点,调用六个回调函数ros::Subscriber subCornerPointsSharp = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_sharp", 2, laserCloudSharpHandler);ros::Subscriber subCornerPointsLessSharp = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_less_sharp", 2, laserCloudLessSharpHandler);ros::Subscriber subSurfPointsFlat = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_flat", 2, laserCloudFlatHandler);ros::Subscriber subSurfPointsLessFlat = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_less_flat", 2, laserCloudLessFlatHandler);ros::Subscriber subLaserCloudFullRes = nh.subscribe<sensor_msgs::PointCloud2> ("/velodyne_cloud_2", 2, laserCloudFullResHandler);ros::Subscriber subImuTrans = nh.subscribe<sensor_msgs::PointCloud2> ("/imu_trans", 5, imuTransHandler);// imu队列长度5// 发布四个节点,发布消息ros::Publisher pubLaserCloudCornerLast = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_corner_last", 2);// 队列长度2ros::Publisher pubLaserCloudSurfLast = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_surf_last", 2);ros::Publisher pubLaserCloudFullRes = nh.advertise<sensor_msgs::PointCloud2> ("/velodyne_cloud_3", 2);ros::Publisher pubLaserOdometry = nh.advertise<nav_msgs::Odometry> ("/laser_odom_to_init", 5);// 队列长度5// 2.创建里程计对象、坐标转换对象// 创建里程计对象 laserOdometrynav_msgs::Odometry laserOdometry;laserOdometry.header.frame_id = "/camera_init";laserOdometry.child_frame_id = "/laser_odom";tf::TransformBroadcaster tfBroadcaster;// 创建坐标变换对象 laserOdometryTranstf::StampedTransform laserOdometryTrans;laserOdometryTrans.frame_id_ = "/camera_init";laserOdometryTrans.child_frame_id_ = "/laser_odom";std::vector<int> pointSearchInd;//搜索到的点序std::vector<float> pointSearchSqDis;//搜索到的点平方距离PointType pointOri, pointSel/*选中的特征点*/, tripod1, tripod2, tripod3/*特征点的对应点*/, pointProj/*unused*/, coeff;//退化标志bool isDegenerate = false;//P矩阵,预测矩阵cv::Mat matP(6, 6, CV_32F, cv::Scalar::all(0));int frameCount = skipFrameNum;ros::Rate rate(100);bool status = ros::ok();while (status) {// 调用一次回调函数,订阅当前时刻msg和发布上一时刻处理后的msgros::spinOnce();// 3.同步作用,确保同时收到同一个点云的特征点以及IMU信息才进入if (newCornerPointsSharp && newCornerPointsLessSharp && newSurfPointsFlat && newSurfPointsLessFlat && newLaserCloudFullRes && newImuTrans &&fabs(timeCornerPointsSharp - timeSurfPointsLessFlat) < 0.005 &&fabs(timeCornerPointsLessSharp - timeSurfPointsLessFlat) < 0.005 &&fabs(timeSurfPointsFlat - timeSurfPointsLessFlat) < 0.005 &&fabs(timeLaserCloudFullRes - timeSurfPointsLessFlat) < 0.005 &&fabs(timeImuTrans - timeSurfPointsLessFlat) < 0.005) {  newCornerPointsSharp = false;newCornerPointsLessSharp = false;newSurfPointsFlat = false;newSurfPointsLessFlat = false;newLaserCloudFullRes = false;newImuTrans = false;

接下来分为:初始化、点云处理、构建Jacobian矩阵估计位姿、坐标转换。

1、初始化

将第一个点云数据集发送给laserMapping,从下一个点云数据开始配准。

  1. 将第一个点云订阅的数据保存为上一时刻数据
  2. 从ROS转化为pcl,再发布出去
  3. 记住原点的翻滚角和俯仰角为imu
  4. T平移量的初值赋值为imu加减速的位移量,为其梯度下降的方向
    //********************1、初始化:将第一个点云数据集发送给laserMapping,从下一个点云数据开始配准****************if (!systemInited) {// 1.将订阅的数据保存为上一时刻数据。// 将边缘点和上一帧边缘点交换,保存当前帧边缘点值cornerPointsLessSharp下轮使用pcl::PointCloud<PointType>::Ptr laserCloudTemp = cornerPointsLessSharp;cornerPointsLessSharp = laserCloudCornerLast;laserCloudCornerLast = laserCloudTemp;//将平面点和上一帧平面点交换,,保存当前帧平面点surfPointsLessFlat的值下轮使用laserCloudTemp = surfPointsLessFlat;surfPointsLessFlat = laserCloudSurfLast;laserCloudSurfLast = laserCloudTemp;//使用上一帧的特征点(边缘+平面)构建kd-treekdtreeCornerLast->setInputCloud(laserCloudCornerLast);//所有的边沿点集合kdtreeSurfLast->setInputCloud(laserCloudSurfLast);//所有的平面点集合// 2.将上一时刻数据(边缘+平面)从ROS转化为pcl,再发布出去sensor_msgs::PointCloud2 laserCloudCornerLast2;pcl::toROSMsg(*laserCloudCornerLast, laserCloudCornerLast2);laserCloudCornerLast2.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);laserCloudCornerLast2.header.frame_id = "/camera";pubLaserCloudCornerLast.publish(laserCloudCornerLast2);sensor_msgs::PointCloud2 laserCloudSurfLast2;pcl::toROSMsg(*laserCloudSurfLast, laserCloudSurfLast2);laserCloudSurfLast2.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);laserCloudSurfLast2.header.frame_id = "/camera";pubLaserCloudSurfLast.publish(laserCloudSurfLast2);//3.记住原点的翻滚角和俯仰角transformSum[0] += imuPitchStart;transformSum[2] += imuRollStart;systemInited = true;continue;}//4.T平移量的初值赋值为加减速的位移量,为其梯度下降的方向//(沿用上次转换的T(一个sweep匀速模型),同时在其基础上减去匀速运动位移,即只考虑加减速的位移量)transform[3] -= imuVeloFromStartX * scanPeriod;transform[4] -= imuVeloFromStartY * scanPeriod;transform[5] -= imuVeloFromStartZ * scanPeriod;

2、点云配准

点云配准前言:首先保证上一时刻特征点(边缘+平面)数量足够再开始进行匹配,其次,后面需要25次迭代LM算法求解位姿。
重要参数:

laserCloudOri:点云过滤:保留距离小,权重大的点;舍弃距离为零的点。
coeffSel:权重

      if (laserCloudCornerLastNum > 10 && laserCloudSurfLastNum > 100) {//上一时刻特征点数量足够// 当前时刻特征点(边缘+平面)数量std::vector<int> indices;pcl::removeNaNFromPointCloud(*cornerPointsSharp,*cornerPointsSharp, indices);int cornerPointsSharpNum = cornerPointsSharp->points.size();int surfPointsFlatNum = surfPointsFlat->points.size();//多次迭代LM算法求解前后位姿变化,这里25次for (int iterCount = 0; iterCount < 25; iterCount++) {laserCloudOri->clear();coeffSel->clear();

针对边缘点和平面点两部分分别进行匹配关系处理。
以边缘点为例:

  1. kd-tree查找一个最近距离点j,Ind为索引,SqDis为距离平方
  2. 寻找最邻近点j附近的次临近点l:分为scanID增加和减小两个方向分别进行寻找。
  3. 计算点到线的距离,根据距离分配权重

边缘点处理:

/********************边缘点处理************///从上个点云中边缘点中找两个最近距离点j和l//一个点j使用kd-tree查找,在最邻近点j附近(向上下三条扫描线以内)找到次临近点lfor (int i = 0; i < cornerPointsSharpNum; i++) {// 0、t+1时刻的边缘点转换到初始imu坐标系的点坐标 pointSelTransformToStart(&cornerPointsSharp->points[i], &pointSel);// ???每迭代五次,重新查找最近点(降采样)if (iterCount % 5 == 0) {std::vector<int> indices;pcl::removeNaNFromPointCloud(*laserCloudCornerLast,*laserCloudCornerLast, indices);// 1、kd-tree查找一个最近距离点j,Ind为索引,SqDis为距离平方kdtreeCornerLast->nearestKSearch(pointSel, 1, pointSearchInd, pointSearchSqDis);int closestPointInd = -1, minPointInd2 = -1;//在最邻近点j附近(向上下三条扫描线以内)找到次临近点l//再次提醒:velodyne是2度一线,scanID相邻并不代表线号相邻,相邻线度数相差2度,也即线号scanID相差2if (pointSearchSqDis[0] < 25) {//找到的最近点距离的确很近的话closestPointInd = pointSearchInd[0];// 最近点j//提取最近点线号int closestPointScan = int(laserCloudCornerLast->points[closestPointInd].intensity);float pointSqDis, minPointSqDis2 = 25;//初始门槛值5米,可大致过滤掉scanID相邻,但实际线不相邻的值// 2、寻找最邻近点j附近的次临近点l// 向scanID增大的方向查找for (int j = closestPointInd + 1; j < cornerPointsSharpNum; j++) {//非相邻线结束,距离超过三条线跳出if (int(laserCloudCornerLast->points[j].intensity) > closestPointScan + 2.5) {break;}// 计算所有点和最近邻点j距离平方pointSqDis = (laserCloudCornerLast->points[j].x - pointSel.x) * (laserCloudCornerLast->points[j].x - pointSel.x) + (laserCloudCornerLast->points[j].y - pointSel.y) * (laserCloudCornerLast->points[j].y - pointSel.y) + (laserCloudCornerLast->points[j].z - pointSel.z) * (laserCloudCornerLast->points[j].z - pointSel.z);if (int(laserCloudCornerLast->points[j].intensity) > closestPointScan) {//确保两个点不在同一条scan上(相邻线查找应该可以用scanID == closestPointScan +/- 1 来做)if (pointSqDis < minPointSqDis2) {//距离更近,要小于初始值5米//更新最小距离与点序minPointSqDis2 = pointSqDis;minPointInd2 = j;}}}//向scanID减小的方向查找,向下三条线for (int j = closestPointInd - 1; j >= 0; j--) {if (int(laserCloudCornerLast->points[j].intensity) < closestPointScan - 2.5) {break;}pointSqDis = (laserCloudCornerLast->points[j].x - pointSel.x) * (laserCloudCornerLast->points[j].x - pointSel.x) + (laserCloudCornerLast->points[j].y - pointSel.y) * (laserCloudCornerLast->points[j].y - pointSel.y) + (laserCloudCornerLast->points[j].z - pointSel.z) * (laserCloudCornerLast->points[j].z - pointSel.z);if (int(laserCloudCornerLast->points[j].intensity) < closestPointScan) {if (pointSqDis < minPointSqDis2) {minPointSqDis2 = pointSqDis;minPointInd2 = j;}}}}//记住组成线的点序pointSearchCornerInd1[i] = closestPointInd;//kd-tree最近距离点j,-1表示未找到满足的点pointSearchCornerInd2[i] = minPointInd2;//另一个最近的l,-1表示未找到满足的点}// 3、计算点到线的距离,根据距离分配权重if (pointSearchCornerInd2[i] >= 0) {//次临近点l大于等于0,不等于-1,说明两个点都找到了tripod1 = laserCloudCornerLast->points[pointSearchCornerInd1[i]];// 最邻近点tripod2 = laserCloudCornerLast->points[pointSearchCornerInd2[i]];// 次临近点//三个点的坐标:t+1时刻点i,t时刻的j和lfloat x0 = pointSel.x;float y0 = pointSel.y;float z0 = pointSel.z;float x1 = tripod1.x;float y1 = tripod1.y;float z1 = tripod1.z;float x2 = tripod2.x;float y2 = tripod2.y;float z2 = tripod2.z;//向量OA = (x0 - x1, y0 - y1, z0 - z1), 向量OB = (x0 - x2, y0 - y2, z0 - z2),向量AB = (x1 - x2, y1 - y2, z1 - z2)//分子的模:向量OA OB的向量积(即叉乘)为://|  i      j      k  |//|x0-x1  y0-y1  z0-z1|//|x0-x2  y0-y2  z0-z2|float a012 = sqrt(((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))* ((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) + ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))* ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1)) + ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))* ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1)));//分母AB的模:两个最近距离点之间的距离float l12 = sqrt((x1 - x2)*(x1 - x2) + (y1 - y2)*(y1 - y2) + (z1 - z2)*(z1 - z2));//点到线的距离,d = |向量OA 叉乘 向量OB|/|AB|float ld2 = a012 / l12;//AB方向的单位向量与OAB平面的单位法向量的向量积在各轴上的分量(d的方向)//x轴分量ifloat la = ((y1 - y2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) + (z1 - z2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))) / a012 / l12;//y轴分量jfloat lb = -((x1 - x2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) - (z1 - z2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;//z轴分量kfloat lc = -((x1 - x2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1)) + (y1 - y2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;//unusedpointProj = pointSel;pointProj.x -= la * ld2;pointProj.y -= lb * ld2;pointProj.z -= lc * ld2;//权重计算,距离越大权重越小,距离越小权重越大,得到的权重范围<=1float s = 1;if (iterCount >= 5) {//5次迭代之后开始增加权重因素s = 1 - 1.8 * fabs(ld2);}//考虑权重coeff.x = s * la;coeff.y = s * lb;coeff.z = s * lc;coeff.intensity = s * ld2;if (s > 0.1 && ld2 != 0) {//只保留权重大的,也即距离比较小的点,同时也舍弃距离为零的laserCloudOri->push_back(cornerPointsSharp->points[i]);coeffSel->push_back(coeff);}}}

同理,平面点也是相同步骤

/********************平面点处理************///对本次接收到的平面点,从上次接收到的点云曲率比较小的点中找三点组成平面,一个使用kd-tree查找,//另外一个在同一线上查找满足要求的,第三个在不同线上查找满足要求的for (int i = 0; i < surfPointsFlatNum; i++) {TransformToStart(&surfPointsFlat->points[i], &pointSel);if (iterCount % 5 == 0) {//kd-tree最近点查找,在经过体素栅格滤波之后的平面点中查找,一般平面点太多,滤波后最近点查找数据量小kdtreeSurfLast->nearestKSearch(pointSel, 1, pointSearchInd, pointSearchSqDis);int closestPointInd = -1, minPointInd2 = -1, minPointInd3 = -1;if (pointSearchSqDis[0] < 25) {closestPointInd = pointSearchInd[0];int closestPointScan = int(laserCloudSurfLast->points[closestPointInd].intensity);float pointSqDis, minPointSqDis2 = 25, minPointSqDis3 = 25;for (int j = closestPointInd + 1; j < surfPointsFlatNum; j++) {if (int(laserCloudSurfLast->points[j].intensity) > closestPointScan + 2.5) {break;}pointSqDis = (laserCloudSurfLast->points[j].x - pointSel.x) * (laserCloudSurfLast->points[j].x - pointSel.x) + (laserCloudSurfLast->points[j].y - pointSel.y) * (laserCloudSurfLast->points[j].y - pointSel.y) + (laserCloudSurfLast->points[j].z - pointSel.z) * (laserCloudSurfLast->points[j].z - pointSel.z);if (int(laserCloudSurfLast->points[j].intensity) <= closestPointScan) {//如果点的线号小于等于最近点的线号(应该最多取等,也即同一线上的点)if (pointSqDis < minPointSqDis2) {minPointSqDis2 = pointSqDis;minPointInd2 = j;}} else {//如果点处在大于该线上if (pointSqDis < minPointSqDis3) {minPointSqDis3 = pointSqDis;minPointInd3 = j;}}}//同理for (int j = closestPointInd - 1; j >= 0; j--) {if (int(laserCloudSurfLast->points[j].intensity) < closestPointScan - 2.5) {break;}pointSqDis = (laserCloudSurfLast->points[j].x - pointSel.x) * (laserCloudSurfLast->points[j].x - pointSel.x) + (laserCloudSurfLast->points[j].y - pointSel.y) * (laserCloudSurfLast->points[j].y - pointSel.y) + (laserCloudSurfLast->points[j].z - pointSel.z) * (laserCloudSurfLast->points[j].z - pointSel.z);if (int(laserCloudSurfLast->points[j].intensity) >= closestPointScan) {if (pointSqDis < minPointSqDis2) {minPointSqDis2 = pointSqDis;minPointInd2 = j;}} else {if (pointSqDis < minPointSqDis3) {minPointSqDis3 = pointSqDis;minPointInd3 = j;}}}}pointSearchSurfInd1[i] = closestPointInd;//kd-tree最近距离点,-1表示未找到满足要求的点pointSearchSurfInd2[i] = minPointInd2;//同一线号上的距离最近的点,-1表示未找到满足要求的点pointSearchSurfInd3[i] = minPointInd3;//不同线号上的距离最近的点,-1表示未找到满足要求的点}if (pointSearchSurfInd2[i] >= 0 && pointSearchSurfInd3[i] >= 0) {//找到了三个点tripod1 = laserCloudSurfLast->points[pointSearchSurfInd1[i]];//A点tripod2 = laserCloudSurfLast->points[pointSearchSurfInd2[i]];//B点tripod3 = laserCloudSurfLast->points[pointSearchSurfInd3[i]];//C点//向量AB = (tripod2.x - tripod1.x, tripod2.y - tripod1.y, tripod2.z - tripod1.z)//向量AC = (tripod3.x - tripod1.x, tripod3.y - tripod1.y, tripod3.z - tripod1.z)//向量AB AC的向量积(即叉乘),得到的是法向量//x轴方向分向量ifloat pa = (tripod2.y - tripod1.y) * (tripod3.z - tripod1.z) - (tripod3.y - tripod1.y) * (tripod2.z - tripod1.z);//y轴方向分向量jfloat pb = (tripod2.z - tripod1.z) * (tripod3.x - tripod1.x) - (tripod3.z - tripod1.z) * (tripod2.x - tripod1.x);//z轴方向分向量kfloat pc = (tripod2.x - tripod1.x) * (tripod3.y - tripod1.y) - (tripod3.x - tripod1.x) * (tripod2.y - tripod1.y);float pd = -(pa * tripod1.x + pb * tripod1.y + pc * tripod1.z);//法向量的模float ps = sqrt(pa * pa + pb * pb + pc * pc);//pa pb pc为法向量各方向上的单位向量pa /= ps;pb /= ps;pc /= ps;pd /= ps;//点到面的距离:向量OA与与法向量的点积除以法向量的模float pd2 = pa * pointSel.x + pb * pointSel.y + pc * pointSel.z + pd;//unusedpointProj = pointSel;pointProj.x -= pa * pd2;pointProj.y -= pb * pd2;pointProj.z -= pc * pd2;//同理计算权重float s = 1;if (iterCount >= 5) {s = 1 - 1.8 * fabs(pd2) / sqrt(sqrt(pointSel.x * pointSel.x+ pointSel.y * pointSel.y + pointSel.z * pointSel.z));}//考虑权重coeff.x = s * pa;coeff.y = s * pb;coeff.z = s * pc;coeff.intensity = s * pd2;if (s > 0.1 && pd2 != 0) {//保存原始点与相应的系数laserCloudOri->push_back(surfPointsFlat->points[i]);coeffSel->push_back(coeff);}}}

3、构建Jacobian矩阵估计位姿

LM 的计算流程为:

  1. 计算matA,matB矩阵,可以Ax=B
  2. 最小二乘法计算(QR分解),为了让左边满秩,同乘At-> AtAX = At*B
  3. 出现退化用预测矩阵P
          /*****************************3、构建Jacobian矩阵估计位姿 ********************/cv::Mat matA(pointSelNum, 6, CV_32F, cv::Scalar::all(0));cv::Mat matAt(6, pointSelNum, CV_32F, cv::Scalar::all(0));cv::Mat matAtA(6, 6, CV_32F, cv::Scalar::all(0));cv::Mat matB(pointSelNum, 1, CV_32F, cv::Scalar::all(0));cv::Mat matAtB(6, 1, CV_32F, cv::Scalar::all(0));cv::Mat matX(6, 1, CV_32F, cv::Scalar::all(0));// 1.计算matA,matB矩阵// A=[J的偏导]; B=[权重系数*(点到直线的距离/点到平面的距离)] 求解公式: AX=B// 为了让左边满秩,同乘At-> At*A*X = At*Bfor (int i = 0; i < pointSelNum; i++) {pointOri = laserCloudOri->points[i];coeff = coeffSel->points[i];float s = 1;float srx = sin(s * transform[0]);float crx = cos(s * transform[0]);float sry = sin(s * transform[1]);float cry = cos(s * transform[1]);float srz = sin(s * transform[2]);float crz = cos(s * transform[2]);float tx = s * transform[3];float ty = s * transform[4];float tz = s * transform[5];// J对rx,ry,rz,tx,ty,tz求解偏导float arx = (-s*crx*sry*srz*pointOri.x + s*crx*crz*sry*pointOri.y + s*srx*sry*pointOri.z + s*tx*crx*sry*srz - s*ty*crx*crz*sry - s*tz*srx*sry) * coeff.x+ (s*srx*srz*pointOri.x - s*crz*srx*pointOri.y + s*crx*pointOri.z+ s*ty*crz*srx - s*tz*crx - s*tx*srx*srz) * coeff.y+ (s*crx*cry*srz*pointOri.x - s*crx*cry*crz*pointOri.y - s*cry*srx*pointOri.z+ s*tz*cry*srx + s*ty*crx*cry*crz - s*tx*crx*cry*srz) * coeff.z;float ary = ((-s*crz*sry - s*cry*srx*srz)*pointOri.x + (s*cry*crz*srx - s*sry*srz)*pointOri.y - s*crx*cry*pointOri.z + tx*(s*crz*sry + s*cry*srx*srz) + ty*(s*sry*srz - s*cry*crz*srx) + s*tz*crx*cry) * coeff.x+ ((s*cry*crz - s*srx*sry*srz)*pointOri.x + (s*cry*srz + s*crz*srx*sry)*pointOri.y - s*crx*sry*pointOri.z+ s*tz*crx*sry - ty*(s*cry*srz + s*crz*srx*sry) - tx*(s*cry*crz - s*srx*sry*srz)) * coeff.z;float arz = ((-s*cry*srz - s*crz*srx*sry)*pointOri.x + (s*cry*crz - s*srx*sry*srz)*pointOri.y+ tx*(s*cry*srz + s*crz*srx*sry) - ty*(s*cry*crz - s*srx*sry*srz)) * coeff.x+ (-s*crx*crz*pointOri.x - s*crx*srz*pointOri.y+ s*ty*crx*srz + s*tx*crx*crz) * coeff.y+ ((s*cry*crz*srx - s*sry*srz)*pointOri.x + (s*crz*sry + s*cry*srx*srz)*pointOri.y+ tx*(s*sry*srz - s*cry*crz*srx) - ty*(s*crz*sry + s*cry*srx*srz)) * coeff.z;float atx = -s*(cry*crz - srx*sry*srz) * coeff.x + s*crx*srz * coeff.y - s*(crz*sry + cry*srx*srz) * coeff.z;float aty = -s*(cry*srz + crz*srx*sry) * coeff.x - s*crx*crz * coeff.y - s*(sry*srz - cry*crz*srx) * coeff.z;float atz = s*crx*sry * coeff.x - s*srx * coeff.y - s*crx*cry * coeff.z;float d2 = coeff.intensity;matA.at<float>(i, 0) = arx;matA.at<float>(i, 1) = ary;matA.at<float>(i, 2) = arz;matA.at<float>(i, 3) = atx;matA.at<float>(i, 4) = aty;matA.at<float>(i, 5) = atz;matB.at<float>(i, 0) = -0.05 * d2;}// 2.最小二乘法计算(QR分解)cv::transpose(matA, matAt);matAtA = matAt * matA;matAtB = matAt * matB;//求解matAtA * matX = matAtBcv::solve(matAtA, matAtB, matX, cv::DECOMP_QR);// 3.出现退化用预测矩阵Pif (iterCount == 0) {//特征值1*6矩阵cv::Mat matE(1, 6, CV_32F, cv::Scalar::all(0));//特征向量6*6矩阵cv::Mat matV(6, 6, CV_32F, cv::Scalar::all(0));cv::Mat matV2(6, 6, CV_32F, cv::Scalar::all(0));//求解特征值/特征向量cv::eigen(matAtA, matE, matV);matV.copyTo(matV2);isDegenerate = false;//特征值取值门槛float eignThre[6] = {10, 10, 10, 10, 10, 10};for (int i = 5; i >= 0; i--) {//从小到大查找if (matE.at<float>(0, i) < eignThre[i]) {//特征值太小,则认为处在兼并环境中,发生了退化for (int j = 0; j < 6; j++) {//对应的特征向量置为0matV2.at<float>(i, j) = 0;}isDegenerate = true;} else {break;}}//计算P矩阵matP = matV.inv() * matV2;}if (isDegenerate) {//如果发生退化,只使用预测矩阵P计算cv::Mat matX2(6, 1, CV_32F, cv::Scalar::all(0));matX.copyTo(matX2);matX = matP * matX2;}//累加每次迭代的旋转平移量transform[0] += matX.at<float>(0, 0);transform[1] += matX.at<float>(1, 0);transform[2] += matX.at<float>(2, 0);transform[3] += matX.at<float>(3, 0);transform[4] += matX.at<float>(4, 0);transform[5] += matX.at<float>(5, 0);for(int i=0; i<6; i++){if(isnan(transform[i]))//判断是否非数字transform[i]=0;}//计算旋转平移量,如果很小就停止迭代float deltaR = sqrt(pow(rad2deg(matX.at<float>(0, 0)), 2) +pow(rad2deg(matX.at<float>(1, 0)), 2) +pow(rad2deg(matX.at<float>(2, 0)), 2));float deltaT = sqrt(pow(matX.at<float>(3, 0) * 100, 2) +pow(matX.at<float>(4, 0) * 100, 2) +pow(matX.at<float>(5, 0) * 100, 2));if (deltaR < 0.1 && deltaT < 0.1) {//迭代终止条件break;}}}

4、坐标转换

求解的是点云间的相对运动,但他们是在这两帧点云的局部坐标系下的,我们需要把它转换到世界坐标系下,因此需要进行转换。

  1. 局部坐标系转移到全局坐标系
  2. 根据IMU修正旋转量,插入imu旋转,更新位姿
  3. 欧拉角转换成四元数,再发布出去四元数和平移量
  4. 对k+1时刻的less特征点(边缘+平面)转移至k+1时刻的sweep的结束位置处的雷达坐标系下
  5. 更新,畸变校正之后的点作为last点保存等下个点云进来进行匹配
  6. 按照跳帧数publich边沿点,平面点以及全部点给laserMapping(每隔一帧发一次)

1.局部坐标系转移到全局坐标系
分为两步骤,先把旋转累积量全局化,再把平移量全局化。

// 1.局部坐标系转移到全局坐标系float rx, ry, rz, tx, ty, tz;// 1)旋转角累计变化量相对于原点rx,ry,rzAccumulateRotation(transformSum[0], transformSum[1], transformSum[2], -transform[0], -transform[1] * 1.05, -transform[2], rx, ry, rz);float x1 = cos(rz) * (transform[3] - imuShiftFromStartX) - sin(rz) * (transform[4] - imuShiftFromStartY);float y1 = sin(rz) * (transform[3] - imuShiftFromStartX) + cos(rz) * (transform[4] - imuShiftFromStartY);float z1 = transform[5] * 1.05 - imuShiftFromStartZ;float x2 = x1;float y2 = cos(rx) * y1 - sin(rx) * z1;float z2 = sin(rx) * y1 + cos(rx) * z1;// 2)平移量相对于原点tx,ty,tztx = transformSum[3] - (cos(ry) * x2 + sin(ry) * z2);ty = transformSum[4] - y2;tz = transformSum[5] - (-sin(ry) * x2 + cos(ry) * z2);

其中涉及到的旋转累积量函数。
AccumulateRotation()
相对于第一个点云即原点,积累旋转量.

//相对于第一个点云即原点,积累旋转量
void AccumulateRotation(float cx, float cy, float cz, float lx, float ly, float lz, float &ox, float &oy, float &oz)
{float srx = cos(lx)*cos(cx)*sin(ly)*sin(cz) - cos(cx)*cos(cz)*sin(lx) - cos(lx)*cos(ly)*sin(cx);ox = -asin(srx);float srycrx = sin(lx)*(cos(cy)*sin(cz) - cos(cz)*sin(cx)*sin(cy)) + cos(lx)*sin(ly)*(cos(cy)*cos(cz) + sin(cx)*sin(cy)*sin(cz)) + cos(lx)*cos(ly)*cos(cx)*sin(cy);float crycrx = cos(lx)*cos(ly)*cos(cx)*cos(cy) - cos(lx)*sin(ly)*(cos(cz)*sin(cy) - cos(cy)*sin(cx)*sin(cz)) - sin(lx)*(sin(cy)*sin(cz) + cos(cy)*cos(cz)*sin(cx));oy = atan2(srycrx / cos(ox), crycrx / cos(ox));float srzcrx = sin(cx)*(cos(lz)*sin(ly) - cos(ly)*sin(lx)*sin(lz)) + cos(cx)*sin(cz)*(cos(ly)*cos(lz) + sin(lx)*sin(ly)*sin(lz)) + cos(lx)*cos(cx)*cos(cz)*sin(lz);float crzcrx = cos(lx)*cos(lz)*cos(cx)*cos(cz) - cos(cx)*sin(cz)*(cos(ly)*sin(lz) - cos(lz)*sin(lx)*sin(ly)) - sin(cx)*(sin(ly)*sin(lz) + cos(ly)*cos(lz)*sin(lx));oz = atan2(srzcrx / cos(ox), crzcrx / cos(ox));
}

2.根据IMU修正旋转量,插入imu旋转,更新位姿

 PluginIMURotation(rx, ry, rz, imuPitchStart, imuYawStart, imuRollStart, imuPitchLast, imuYawLast, imuRollLast, rx, ry, rz);// 得到世界坐标系下的转移矩阵TtransformSum[0] = rx;transformSum[1] = ry;transformSum[2] = rz;transformSum[3] = tx;transformSum[4] = ty;transformSum[5] = tz;

其中涉及到的IMU修正函数。
PluginIMURotation()
利用IMU修正旋转量,根据起始欧拉角,当前点云的欧拉角修正

void PluginIMURotation(float bcx, float bcy, float bcz, float blx, float bly, float blz, float alx, float aly, float alz, float &acx, float &acy, float &acz)
{float sbcx = sin(bcx);float cbcx = cos(bcx);float sbcy = sin(bcy);float cbcy = cos(bcy);float sbcz = sin(bcz);float cbcz = cos(bcz);float sblx = sin(blx);float cblx = cos(blx);float sbly = sin(bly);float cbly = cos(bly);float sblz = sin(blz);float cblz = cos(blz);float salx = sin(alx);float calx = cos(alx);float saly = sin(aly);float caly = cos(aly);float salz = sin(alz);float calz = cos(alz);float srx = -sbcx*(salx*sblx + calx*caly*cblx*cbly + calx*cblx*saly*sbly) - cbcx*cbcz*(calx*saly*(cbly*sblz - cblz*sblx*sbly) - calx*caly*(sbly*sblz + cbly*cblz*sblx) + cblx*cblz*salx) - cbcx*sbcz*(calx*caly*(cblz*sbly - cbly*sblx*sblz) - calx*saly*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sblz);acx = -asin(srx);float srycrx = (cbcy*sbcz - cbcz*sbcx*sbcy)*(calx*saly*(cbly*sblz - cblz*sblx*sbly) - calx*caly*(sbly*sblz + cbly*cblz*sblx) + cblx*cblz*salx) - (cbcy*cbcz + sbcx*sbcy*sbcz)*(calx*caly*(cblz*sbly - cbly*sblx*sblz) - calx*saly*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sblz) + cbcx*sbcy*(salx*sblx + calx*caly*cblx*cbly + calx*cblx*saly*sbly);float crycrx = (cbcz*sbcy - cbcy*sbcx*sbcz)*(calx*caly*(cblz*sbly - cbly*sblx*sblz) - calx*saly*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sblz) - (sbcy*sbcz + cbcy*cbcz*sbcx)*(calx*saly*(cbly*sblz - cblz*sblx*sbly) - calx*caly*(sbly*sblz + cbly*cblz*sblx) + cblx*cblz*salx) + cbcx*cbcy*(salx*sblx + calx*caly*cblx*cbly + calx*cblx*saly*sbly);acy = atan2(srycrx / cos(acx), crycrx / cos(acx));float srzcrx = sbcx*(cblx*cbly*(calz*saly - caly*salx*salz) - cblx*sbly*(caly*calz + salx*saly*salz) + calx*salz*sblx) - cbcx*cbcz*((caly*calz + salx*saly*salz)*(cbly*sblz - cblz*sblx*sbly) + (calz*saly - caly*salx*salz)*(sbly*sblz + cbly*cblz*sblx) - calx*cblx*cblz*salz) + cbcx*sbcz*((caly*calz + salx*saly*salz)*(cbly*cblz + sblx*sbly*sblz) + (calz*saly - caly*salx*salz)*(cblz*sbly - cbly*sblx*sblz) + calx*cblx*salz*sblz);float crzcrx = sbcx*(cblx*sbly*(caly*salz - calz*salx*saly) - cblx*cbly*(saly*salz + caly*calz*salx) + calx*calz*sblx) + cbcx*cbcz*((saly*salz + caly*calz*salx)*(sbly*sblz + cbly*cblz*sblx) + (caly*salz - calz*salx*saly)*(cbly*sblz - cblz*sblx*sbly) + calx*calz*cblx*cblz) - cbcx*sbcz*((saly*salz + caly*calz*salx)*(cblz*sbly - cbly*sblx*sblz) + (caly*salz - calz*salx*saly)*(cbly*cblz + sblx*sbly*sblz) - calx*calz*cblx*sblz);acz = atan2(srzcrx / cos(acx), crzcrx / cos(acx));
}

3.欧拉角转换成四元数,再发布出去四元数和平移量

geometry_msgs::Quaternion geoQuat = tf::createQuaternionMsgFromRollPitchYaw(rz, -rx, -ry);laserOdometry.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);laserOdometry.pose.pose.orientation.x = -geoQuat.y;laserOdometry.pose.pose.orientation.y = -geoQuat.z;laserOdometry.pose.pose.orientation.z = geoQuat.x;laserOdometry.pose.pose.orientation.w = geoQuat.w;laserOdometry.pose.pose.position.x = tx;laserOdometry.pose.pose.position.y = ty;laserOdometry.pose.pose.position.z = tz;pubLaserOdometry.publish(laserOdometry);// tf广播新的平移旋转之后的坐标系(rviz)laserOdometryTrans.stamp_ = ros::Time().fromSec(timeSurfPointsLessFlat);laserOdometryTrans.setRotation(tf::Quaternion(-geoQuat.y, -geoQuat.z, geoQuat.x, geoQuat.w));laserOdometryTrans.setOrigin(tf::Vector3(tx, ty, tz));tfBroadcaster.sendTransform(laserOdometryTrans);

4.对k+1时刻的less特征点(边缘+平面)转移至k+1时刻的sweep的结束位置处的雷达坐标系下

int cornerPointsLessSharpNum = cornerPointsLessSharp->points.size();for (int i = 0; i < cornerPointsLessSharpNum; i++) {TransformToEnd(&cornerPointsLessSharp->points[i], &cornerPointsLessSharp->points[i]);}int surfPointsLessFlatNum = surfPointsLessFlat->points.size();for (int i = 0; i < surfPointsLessFlatNum; i++) {TransformToEnd(&surfPointsLessFlat->points[i], &surfPointsLessFlat->points[i]);}frameCount++;// 点云全部点,每间隔一个点云数据相对点云最后一个点进行畸变校正if (frameCount >= skipFrameNum + 1) {int laserCloudFullResNum = laserCloudFullRes->points.size();for (int i = 0; i < laserCloudFullResNum; i++) {TransformToEnd(&laserCloudFullRes->points[i], &laserCloudFullRes->points[i]);}}

其中,涉及到将当前时刻特征点投影到sweep结束位置的雷达坐标系TransformToEnd()。这里其实一起来讲,有当前帧点云P(k+1) TransformToStart()和上一帧点云P(k) TransformToEnd()两个函数,为了将两帧点云去除畸变,统一到同一坐标系下计算。

TransformToStart()
当前点云中的点相对第一个点去除因匀速运动产生的畸变,效果相当于得到在点云扫描开始位置静止扫描得到的点云

void TransformToStart(PointType const * const pi, PointType * const po)
{//插值系数计算,云中每个点的相对时间/点云周期10float s = 10 * (pi->intensity - int(pi->intensity));//线性插值:根据每个点在点云中的相对位置关系,乘以相应的旋转平移系数float rx = s * transform[0];float ry = s * transform[1];float rz = s * transform[2];float tx = s * transform[3];float ty = s * transform[4];float tz = s * transform[5];//平移后绕z轴旋转(-rz)float x1 = cos(rz) * (pi->x - tx) + sin(rz) * (pi->y - ty);float y1 = -sin(rz) * (pi->x - tx) + cos(rz) * (pi->y - ty);float z1 = (pi->z - tz);//绕x轴旋转(-rx)float x2 = x1;float y2 = cos(rx) * y1 + sin(rx) * z1;float z2 = -sin(rx) * y1 + cos(rx) * z1;//绕y轴旋转(-ry)po->x = cos(ry) * x2 - sin(ry) * z2;po->y = y2;po->z = sin(ry) * x2 + cos(ry) * z2;po->intensity = pi->intensity;
}

TransformToEnd()
当前点云中的点相对第一个点去除因匀速运动产生的畸变,效果相当于得到在点云扫描结束位置静止扫描得到的点云

void TransformToEnd(PointType const * const pi, PointType * const po)
{//插值系数计算float s = 10 * (pi->intensity - int(pi->intensity));float rx = s * transform[0];float ry = s * transform[1];float rz = s * transform[2];float tx = s * transform[3];float ty = s * transform[4];float tz = s * transform[5];//平移后绕z轴旋转(-rz)float x1 = cos(rz) * (pi->x - tx) + sin(rz) * (pi->y - ty);float y1 = -sin(rz) * (pi->x - tx) + cos(rz) * (pi->y - ty);float z1 = (pi->z - tz);//绕x轴旋转(-rx)float x2 = x1;float y2 = cos(rx) * y1 + sin(rx) * z1;float z2 = -sin(rx) * y1 + cos(rx) * z1;//绕y轴旋转(-ry)float x3 = cos(ry) * x2 - sin(ry) * z2;float y3 = y2;float z3 = sin(ry) * x2 + cos(ry) * z2;//求出了相对于起始点校正的坐标rx = transform[0];ry = transform[1];rz = transform[2];tx = transform[3];ty = transform[4];tz = transform[5];//绕y轴旋转(ry)float x4 = cos(ry) * x3 + sin(ry) * z3;float y4 = y3;float z4 = -sin(ry) * x3 + cos(ry) * z3;//绕x轴旋转(rx)float x5 = x4;float y5 = cos(rx) * y4 - sin(rx) * z4;float z5 = sin(rx) * y4 + cos(rx) * z4;//绕z轴旋转(rz),再平移float x6 = cos(rz) * x5 - sin(rz) * y5 + tx;float y6 = sin(rz) * x5 + cos(rz) * y5 + ty;float z6 = z5 + tz;//平移后绕z轴旋转(imuRollStart)float x7 = cos(imuRollStart) * (x6 - imuShiftFromStartX) - sin(imuRollStart) * (y6 - imuShiftFromStartY);float y7 = sin(imuRollStart) * (x6 - imuShiftFromStartX) + cos(imuRollStart) * (y6 - imuShiftFromStartY);float z7 = z6 - imuShiftFromStartZ;//绕x轴旋转(imuPitchStart)float x8 = x7;float y8 = cos(imuPitchStart) * y7 - sin(imuPitchStart) * z7;float z8 = sin(imuPitchStart) * y7 + cos(imuPitchStart) * z7;//绕y轴旋转(imuYawStart)float x9 = cos(imuYawStart) * x8 + sin(imuYawStart) * z8;float y9 = y8;float z9 = -sin(imuYawStart) * x8 + cos(imuYawStart) * z8;//绕y轴旋转(-imuYawLast)float x10 = cos(imuYawLast) * x9 - sin(imuYawLast) * z9;float y10 = y9;float z10 = sin(imuYawLast) * x9 + cos(imuYawLast) * z9;//绕x轴旋转(-imuPitchLast)float x11 = x10;float y11 = cos(imuPitchLast) * y10 + sin(imuPitchLast) * z10;float z11 = -sin(imuPitchLast) * y10 + cos(imuPitchLast) * z10;//绕z轴旋转(-imuRollLast)po->x = cos(imuRollLast) * x11 + sin(imuRollLast) * y11;po->y = -sin(imuRollLast) * x11 + cos(imuRollLast) * y11;po->z = z11;//只保留线号po->intensity = int(pi->intensity);
}

5.更新,畸变校正之后的点作为last点保存等下个点云进来进行匹配

pcl::PointCloud<PointType>::Ptr laserCloudTemp = cornerPointsLessSharp;cornerPointsLessSharp = laserCloudCornerLast;laserCloudCornerLast = laserCloudTemp;laserCloudTemp = surfPointsLessFlat;surfPointsLessFlat = laserCloudSurfLast;laserCloudSurfLast = laserCloudTemp;laserCloudCornerLastNum = laserCloudCornerLast->points.size();laserCloudSurfLastNum = laserCloudSurfLast->points.size();// 点足够多就构建kd-tree,否则弃用此帧,沿用上一帧数据的kd-treeif (laserCloudCornerLastNum > 10 && laserCloudSurfLastNum > 100) {kdtreeCornerLast->setInputCloud(laserCloudCornerLast);kdtreeSurfLast->setInputCloud(laserCloudSurfLast);}

6.按照跳帧数publich边沿点,平面点以及全部点给laserMapping(每隔一帧发一次)

 if (frameCount >= skipFrameNum + 1) {frameCount = 0;sensor_msgs::PointCloud2 laserCloudCornerLast2;pcl::toROSMsg(*laserCloudCornerLast, laserCloudCornerLast2);laserCloudCornerLast2.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);laserCloudCornerLast2.header.frame_id = "/camera";pubLaserCloudCornerLast.publish(laserCloudCornerLast2);sensor_msgs::PointCloud2 laserCloudSurfLast2;pcl::toROSMsg(*laserCloudSurfLast, laserCloudSurfLast2);laserCloudSurfLast2.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);laserCloudSurfLast2.header.frame_id = "/camera";pubLaserCloudSurfLast.publish(laserCloudSurfLast2);sensor_msgs::PointCloud2 laserCloudFullRes3;pcl::toROSMsg(*laserCloudFullRes, laserCloudFullRes3);laserCloudFullRes3.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);laserCloudFullRes3.header.frame_id = "/camera";pubLaserCloudFullRes.publish(laserCloudFullRes3);}}status = ros::ok();rate.sleep();

LOAM源码解析2——laserOdometry相关推荐

  1. loam源码解析5 : laserOdometry(三)

    transformMaintenance.cpp解析 八.位姿估计 1. 雅可比计算 2. 矩阵求解 3. 退化问题分析 4. 姿态更新 5. 坐标转换 loam源码地址: https://githu ...

  2. loam源码解析1 : scanRegistration(一)

    scanRegistration.cpp解析 一.概述 二.变量说明 三.主函数 四.IMU回调函数laserCloudHandler 1 接受IMU的角度和加速度信息 2 AccumulateIMU ...

  3. LOAM源码解析1一scanRegistration

    鉴于工作和学习需要,学习了激光salm算法loam,并阅读了作者的原版论文,现将学习过程中的理解与一些源码剖析记录整理下来,也是对于学习slam的阶段性总结!!! 一.综述 LOAM这篇论文是发表于2 ...

  4. LOAM源码结合论文解析(二)laserOdometry

    中文注释版本.本文大多注释来自 --- https://github.com/daobilige-su/loam_velodyne laserOdometry节点接收scanResgistraion传 ...

  5. A-LOAM源码解析

    声明:本文是笔者在学习SLAM时发现的好文,与诸君分享 转载自:https://www.cnblogs.com/wellp/p/8877990.html 导读 下面是我对LOAM论文的理解以及对A-L ...

  6. Tightly Coupled LiDAR Inertial Odometry and Mapping源码解析(一)

    Tightly Coupled LiDAR Inertial Odometry and Mapping源码解析(一) 1. LiDAR inertial odometry and mapping简介 ...

  7. 谷歌BERT预训练源码解析(二):模型构建

    版权声明:本文为博主原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明. 本文链接:https://blog.csdn.net/weixin_39470744/arti ...

  8. 谷歌BERT预训练源码解析(三):训练过程

    目录 前言 源码解析 主函数 自定义模型 遮蔽词预测 下一句预测 规范化数据集 前言 本部分介绍BERT训练过程,BERT模型训练过程是在自己的TPU上进行的,这部分我没做过研究所以不做深入探讨.BE ...

  9. 谷歌BERT预训练源码解析(一):训练数据生成

    目录 预训练源码结构简介 输入输出 源码解析 参数 主函数 创建训练实例 下一句预测&实例生成 随机遮蔽 输出 结果一览 预训练源码结构简介 关于BERT,简单来说,它是一个基于Transfo ...

最新文章

  1. 如何在OSCOMMERCE中安装中文语言包
  2. Linux编写一个C程序HelloWorld
  3. windows聚焦壁纸不更新_技术编辑示范win10系统锁屏壁纸聚焦不更新的处理教程
  4. Linux下创建与解压zip, tar, tar.gz和tar.bz2文件及该文件压缩对比
  5. yunyang1994 tensorflow_yolov3训练报错:IndexError: index 68 is out of bounds for axis 1 with size 68 数据清洗
  6. jQuery Ajax – Servlets集成:构建完整的应用程序
  7. 敏捷结果30天之第十二天:效率角色-你是启动者还是完成者
  8. C# async 和 await 理解
  9. Java学习笔记2.1.3 Java基本语法 - Java关键字与标识符
  10. VSCode远程链接Could not establish connection to “hz.matpool.com”
  11. 在线CSV转JSON工具
  12. 预备作业02 1501 李俊
  13. linux轮训创建文件夹,Linux文件和目录管理相关命令(三)
  14. 揭密 Vue 的双向绑定
  15. CF 354E DFS
  16. java emf 转jpg_JAVA读取EMF文件并转化为PNG,JPG,GIF格式
  17. MySQL 5.7详细下载安装配置教程
  18. 计算机系统无法启动 错误恢复怎么办,win7系统无法启动 安全模式也进入不了怎么办-win7启动失败,win7错误恢复无法开机...
  19. http请求状态码有哪些?分别代表什么意思?
  20. 电商营销活动的优惠金额精度问题

热门文章

  1. jitter单位_Jitter知识
  2. 微服务多网卡部署(eureka显示IP不为服务IP的地址)解决办法
  3. 大疆机甲大师Python开发: 两只老虎
  4. Python Diary - Day 15 模块、异常和文件
  5. 5G NR Spec Introduction
  6. linux应用程序注册表,如何打开 Linux 中 Windows 程序的注册表编辑器
  7. 我们都是代码接盘侠,请做一位好前任!
  8. Win10微软输入法打不出汉字?
  9. Javaweb开发了解前端知识七、Servlet(一)
  10. android hawk 保存map对象,Android Hawk数据库 github开源项目