3D 激光SLAM通过角点和面点来进行匹配,求当前帧位姿
视觉SLAM是通过特征点的冲投影误差来求得当前的位姿
激光雷达畸变及运动补偿 运动畸变是由于扫描的过程中,车体运动导致一帧数据的数据原点不一致。因此需要去校正,将其校正到任何一个点上都可以
如何补偿 运动补偿的目的就是把所有的点云补偿到某一个时刻,这样就可以把本身在过去 100ms 内收集的点云统一到一个时间点上去
其中一个做法是补偿到起始时刻
因此运动补偿需要知道每个点该时刻对应的位姿$T_{start_current}$, 通常有几种做法
高频里程计,在短期内他的数据还是相对可靠
imu, imu可以计算每一个点相对起始点的旋转,imu出来的平移不靠谱,畸变影响最大的还是旋转
如果没有其他传感器,可以使用匀速模型假设,使用上一个帧间里程记的结果作为当前两帧之间的运动,同时假设当前帧也是匀速运动,也可以估计出每个点相对起始时刻的位姿
在A_LOAM中,使用的就是纯雷达的模式,下面看一下,他是如何通过匀速模型假设来完成运动畸变的补偿的
A-LOAM代码实现 假设q_last_curr 为上一帧到当前帧的坐标变换,用四元数表示。
现在假设机器人是匀速模型,所以假设上一帧的坐标变换也一样适用于从当前帧到下一帧。
之前我们计算了每一个点在一次scan中的相对时间,通过这个比例来计算当前帧下每一个点的位姿和平移。
1 2 Eigen::Quaterniond q_point_last = Eigen::Quaterniond::Identity ().slerp (s, q_last_curr); Eigen::Vector3d t_point_last = s * t_last_curr;
然后进行位姿的补偿,把他补偿到最开始的地方
1 Eigen::Vector3d un_point = q_point_last * point + t_point_last;
把算出来的位置,重新赋值到pi上。
全部代码:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 void TransformToStart (PointType const *const pi, PointType *const po) { double s; if (DISTORTION) s = (pi->intensity - int (pi->intensity)) / SCAN_PERIOD; else s = 1.0 ; Eigen::Quaterniond q_point_last = Eigen::Quaterniond::Identity ().slerp (s, q_last_curr); Eigen::Vector3d t_point_last = s * t_last_curr; Eigen::Vector3d point (pi->x, pi->y, pi->z) ; Eigen::Vector3d un_point = q_point_last * point + t_point_last; po->x = un_point.x (); po->y = un_point.y (); po->z = un_point.z (); po->intensity = pi->intensity; }
帧间里程计匹配 spinonce : 告诉所有的subscriber,把收到的消息执行一次
spin:来一个调一个
回调函数的处理 在laserOdometry.cpp文件中,声明了五个消息订阅这,注册了五个回调函数,
cornerSharpBuf 针对角点,曲率最大的点,存进一个cornerSharpBuf,类型为std::queue<sensor_msgs::PointCloud2ConstPtr>
1 2 3 4 5 6 void laserCloudSharpHandler (const sensor_msgs::PointCloud2ConstPtr &cornerPointsSharp2) { mBuf.lock (); cornerSharpBuf.push (cornerPointsSharp2); mBuf.unlock (); }
cornerLessSharpBuf 针对曲率比角点稍微小一点的点,存入cornerLessSharpBuf
1 2 3 4 5 6 void laserCloudLessSharpHandler (const sensor_msgs::PointCloud2ConstPtr &cornerPointsLessSharp2) { mBuf.lock (); cornerLessSharpBuf.push (cornerPointsLessSharp2); mBuf.unlock (); }
surfFlatBuf 曲率最小的点,存入surfFlatBuf
1 2 3 4 5 6 void laserCloudFlatHandler (const sensor_msgs::PointCloud2ConstPtr &surfPointsFlat2) { mBuf.lock (); surfFlatBuf.push (surfPointsFlat2); mBuf.unlock (); }
surfLessFlatBuf 曲率次小的点,存入surfLessFlatBuf
1 2 3 4 5 6 void laserCloudLessFlatHandler (const sensor_msgs::PointCloud2ConstPtr &surfPointsLessFlat2) { mBuf.lock (); surfLessFlatBuf.push (surfPointsLessFlat2); mBuf.unlock (); }
fullPointsBuf 原始点云,存入fullPointsBuf
1 2 3 4 5 6 void laserCloudFullResHandler (const sensor_msgs::PointCloud2ConstPtr &laserCloudFullRes2) { mBuf.lock (); fullPointsBuf.push (laserCloudFullRes2); mBuf.unlock (); }
数据队列消息处理 保证是同一帧数据 取出每一个队列的头数据的时间戳,并且和timeLaserCloudFullRes的时间做对比,不同则直接退出
1 2 3 4 5 6 7 8 9 10 11 12 13 14 timeCornerPointsSharp = cornerSharpBuf.front ()->header.stamp.toSec (); timeCornerPointsLessSharp = cornerLessSharpBuf.front ()->header.stamp.toSec (); timeSurfPointsFlat = surfFlatBuf.front ()->header.stamp.toSec (); timeSurfPointsLessFlat = surfLessFlatBuf.front ()->header.stamp.toSec (); timeLaserCloudFullRes = fullPointsBuf.front ()->header.stamp.toSec (); if (timeCornerPointsSharp != timeLaserCloudFullRes || timeCornerPointsLessSharp != timeLaserCloudFullRes || timeSurfPointsFlat != timeLaserCloudFullRes || timeSurfPointsLessFlat != timeLaserCloudFullRes) { printf ("unsync messeage!" ); ROS_BREAK (); }
这种情况基本不会发生,因为这个是同时被发出来的
转PCL 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 mBuf.lock (); cornerPointsSharp->clear (); pcl::fromROSMsg (*cornerSharpBuf.front (), *cornerPointsSharp); cornerSharpBuf.pop (); cornerPointsLessSharp->clear (); pcl::fromROSMsg (*cornerLessSharpBuf.front (), *cornerPointsLessSharp); cornerLessSharpBuf.pop (); surfPointsFlat->clear (); pcl::fromROSMsg (*surfFlatBuf.front (), *surfPointsFlat); surfFlatBuf.pop (); surfPointsLessFlat->clear (); pcl::fromROSMsg (*surfLessFlatBuf.front (), *surfPointsLessFlat); surfLessFlatBuf.pop (); laserCloudFullRes->clear (); pcl::fromROSMsg (*fullPointsBuf.front (), *laserCloudFullRes); fullPointsBuf.pop (); mBuf.unlock ();
计算取出当前帧的角点和面点的个数,即曲率最大和最小的点
1 2 int cornerPointsSharpNum = cornerPointsSharp->points.size ();int surfPointsFlatNum = surfPointsFlat->points.size ();
对每一个角点和面点我们都要形成一个约束
开始优化 定义核函数 当残差超过0.1之后,权重就变小。
1 ceres::LossFunction *loss_function = new ceres::HuberLoss(0.1);
添加参数块 告诉优化变量是什么,q_parameterization是告诉他加法怎么加了
1 2 problem.AddParameterBlock(para_q, 4, q_parameterization); problem.AddParameterBlock(para_t, 3);
寻找所有角点的对应点,并添加约束 畸变校准 将该点变换到此帧开始时刻的位姿,上一帧的角点们组成KDtree,寻找在KDtree中,距离当前角点最近的点
1 TransformToStart (&(cornerPointsSharp->points[i]), &pointSel);
KDTree找点 1 kdtreeCornerLast->nearestKSearch(pointSel, 1, pointSearchInd, pointSearchSqDis);
注意KDtree 不可以找两个点,这两个点不可以在同一个scan上,也不可以太远
寻找方式:暴力寻找上一帧的所有角点,但是以下情况忽略
和第一个点在同一个scan上,因为水平的线特征(两个特征点组成的线)不多,一般的线特征都是垂直的,比如拐角处的墙面,就需要来自不同的scan线束
不在附近的scan上
符合条件之后,计算距离,选择最近点
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 int closestPointInd = -1 , minPointInd2 = -1 ;if (pointSearchSqDis[0 ] < DISTANCE_SQ_THRESHOLD){ closestPointInd = pointSearchInd[0 ]; int closestPointScanID = int (laserCloudCornerLast->points[closestPointInd].intensity); double minPointSqDis2 = DISTANCE_SQ_THRESHOLD; for (int j = closestPointInd + 1 ; j < (int )laserCloudCornerLast->points.size (); ++j) { if (int (laserCloudCornerLast->points[j].intensity) <= closestPointScanID) continue ; if (int (laserCloudCornerLast->points[j].intensity) > (closestPointScanID + NEARBY_SCAN)) break ; double 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 (pointSqDis < minPointSqDis2) { minPointSqDis2 = pointSqDis; minPointInd2 = j; } } for (int j = closestPointInd - 1 ; j >= 0 ; --j) { if (int (laserCloudCornerLast->points[j].intensity) >= closestPointScanID) continue ; if (int (laserCloudCornerLast->points[j].intensity) < (closestPointScanID - NEARBY_SCAN)) break ; double 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 (pointSqDis < minPointSqDis2) { minPointSqDis2 = pointSqDis; minPointInd2 = j; } } }
添加点到线的约束 para_q 为优化变量,四元数旋转,para_t为优化变量,平移部分
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 if (minPointInd2 >= 0 ) { Eigen::Vector3d curr_point (cornerPointsSharp->points[i].x, cornerPointsSharp->points[i].y, cornerPointsSharp->points[i].z) ; Eigen::Vector3d last_point_a (laserCloudCornerLast->points[closestPointInd].x, laserCloudCornerLast->points[closestPointInd].y, laserCloudCornerLast->points[closestPointInd].z) ; Eigen::Vector3d last_point_b (laserCloudCornerLast->points[minPointInd2].x, laserCloudCornerLast->points[minPointInd2].y, laserCloudCornerLast->points[minPointInd2].z) ; double s; if (DISTORTION) s = (cornerPointsSharp->points[i].intensity - int (cornerPointsSharp->points[i].intensity)) / SCAN_PERIOD; else s = 1.0 ; ceres::CostFunction *cost_function = LidarEdgeFactor::Create (curr_point, last_point_a, last_point_b, s); problem.AddResidualBlock (cost_function, loss_function, para_q, para_t ); corner_correspondence++; }
具体优化内容:
把curr_point 转换到扫描开始处
curr_point到 由last_point_a 和 last_point_b连成的线的距离 为 残差。优化此残差为0
1 2 3 4 5 6 7 static ceres::CostFunction *Create (const Eigen::Vector3d curr_point_, const Eigen::Vector3d last_point_a_, const Eigen::Vector3d last_point_b_, const double s_) { return (new ceres::AutoDiffCostFunction< LidarEdgeFactor, 3 , 4 , 3 >( new LidarEdgeFactor (curr_point_, last_point_a_, last_point_b_, s_))); }
LidarEdgeFactor 定义的()函数内容如下
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 template <typename T>bool operator () (const T *q, const T *t, T *residual) const { Eigen::Matrix<T, 3 , 1 > cp{T (curr_point.x ()), T (curr_point.y ()), T (curr_point.z ())}; Eigen::Matrix<T, 3 , 1 > lpa{T (last_point_a.x ()), T (last_point_a.y ()), T (last_point_a.z ())}; Eigen::Matrix<T, 3 , 1 > lpb{T (last_point_b.x ()), T (last_point_b.y ()), T (last_point_b.z ())}; Eigen::Quaternion<T> q_last_curr{q[3 ], q[0 ], q[1 ], q[2 ]}; Eigen::Quaternion<T> q_identity{T (1 ), T (0 ), T (0 ), T (0 )}; q_last_curr = q_identity.slerp (T (s), q_last_curr); Eigen::Matrix<T, 3 , 1 > t_last_curr{T (s) * t[0 ], T (s) * t[1 ], T (s) * t[2 ]}; Eigen::Matrix<T, 3 , 1 > lp; lp = q_last_curr * cp + t_last_curr; Eigen::Matrix<T, 3 , 1 > nu = (lp - lpa).cross (lp - lpb); Eigen::Matrix<T, 3 , 1 > de = lpa - lpb; residual[0 ] = nu.x () / de.norm (); residual[1 ] = nu.y () / de.norm (); residual[2 ] = nu.z () / de.norm (); return true ; }
注意,优化的方向是,从K+1时刻到K时刻的变换 ,即优化变量q_last_curr, 扫描开始=q_last_curr*扫描结束 + t_last
寻找所有面点的对应点,并添加约束 畸变校正 1 TransformToStart (&(surfPointsFlat->points[i]), &pointSel);
寻找最近的三个点 使用KDTree找每一个点在上一帧中距离最近的三个特征点(面点)
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 if (pointSearchSqDis[0 ] < DISTANCE_SQ_THRESHOLD){ closestPointInd = pointSearchInd[0 ]; int closestPointScanID = int (laserCloudSurfLast->points[closestPointInd].intensity); double minPointSqDis2 = DISTANCE_SQ_THRESHOLD, minPointSqDis3 = DISTANCE_SQ_THRESHOLD; for (int j = closestPointInd + 1 ; j < (int )laserCloudSurfLast->points.size (); ++j) { if (int (laserCloudSurfLast->points[j].intensity) > (closestPointScanID + NEARBY_SCAN)) break ; double 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) <= closestPointScanID && pointSqDis < minPointSqDis2) { minPointSqDis2 = pointSqDis; minPointInd2 = j; } else if (int (laserCloudSurfLast->points[j].intensity) > closestPointScanID && pointSqDis < minPointSqDis3) { minPointSqDis3 = pointSqDis; minPointInd3 = j; } } for (int j = closestPointInd - 1 ; j >= 0 ; --j) { if (int (laserCloudSurfLast->points[j].intensity) < (closestPointScanID - NEARBY_SCAN)) break ; double 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) >= closestPointScanID && pointSqDis < minPointSqDis2) { minPointSqDis2 = pointSqDis; minPointInd2 = j; } else if (int (laserCloudSurfLast->points[j].intensity) < closestPointScanID && pointSqDis < minPointSqDis3) { minPointSqDis3 = pointSqDis; minPointInd3 = j; } }
添加点到面的约束 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 if (minPointInd2 >= 0 && minPointInd3 >= 0 ){ Eigen::Vector3d curr_point (surfPointsFlat->points[i].x, surfPointsFlat->points[i].y, surfPointsFlat->points[i].z) ; Eigen::Vector3d last_point_a (laserCloudSurfLast->points[closestPointInd].x, laserCloudSurfLast->points[closestPointInd].y, laserCloudSurfLast->points[closestPointInd].z) ; Eigen::Vector3d last_point_b (laserCloudSurfLast->points[minPointInd2].x, laserCloudSurfLast->points[minPointInd2].y, laserCloudSurfLast->points[minPointInd2].z) ; Eigen::Vector3d last_point_c (laserCloudSurfLast->points[minPointInd3].x, laserCloudSurfLast->points[minPointInd3].y, laserCloudSurfLast->points[minPointInd3].z) ; double s; if (DISTORTION) s = (surfPointsFlat->points[i].intensity - int (surfPointsFlat->points[i].intensity)) / SCAN_PERIOD; else s = 1.0 ; ceres::CostFunction *cost_function = LidarPlaneFactor::Create (curr_point, last_point_a, last_point_b, last_point_c, s); problem.AddResidualBlock (cost_function, loss_function, para_q, para_t ); plane_correspondence++; }
cost_function
1 2 3 4 5 6 7 8 static ceres::CostFunction *Create (const Eigen::Vector3d curr_point_, const Eigen::Vector3d last_point_j_, const Eigen::Vector3d last_point_l_, const Eigen::Vector3d last_point_m_, const double s_) { return (new ceres::AutoDiffCostFunction< LidarPlaneFactor, 1 , 4 , 3 >( new LidarPlaneFactor (curr_point_, last_point_j_, last_point_l_, last_point_m_, s_))); }
构造函数
1 2 3 4 5 6 7 8 LidarPlaneFactor (Eigen::Vector3d curr_point_, Eigen::Vector3d last_point_j_, Eigen::Vector3d last_point_l_, Eigen::Vector3d last_point_m_, double s_) : curr_point (curr_point_), last_point_j (last_point_j_), last_point_l (last_point_l_), last_point_m (last_point_m_), s (s_) { ljm_norm = (last_point_j - last_point_l).cross (last_point_j - last_point_m); ljm_norm.normalize (); }
()重载内容为
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 template <typename T>bool operator () (const T *q, const T *t, T *residual) const { Eigen::Matrix<T, 3 , 1 > cp{T (curr_point.x ()), T (curr_point.y ()), T (curr_point.z ())}; Eigen::Matrix<T, 3 , 1 > lpj{T (last_point_j.x ()), T (last_point_j.y ()), T (last_point_j.z ())}; Eigen::Matrix<T, 3 , 1 > ljm{T (ljm_norm.x ()), T (ljm_norm.y ()), T (ljm_norm.z ())}; Eigen::Quaternion<T> q_last_curr{q[3 ], q[0 ], q[1 ], q[2 ]}; Eigen::Quaternion<T> q_identity{T (1 ), T (0 ), T (0 ), T (0 )}; q_last_curr = q_identity.slerp (T (s), q_last_curr); Eigen::Matrix<T, 3 , 1 > t_last_curr{T (s) * t[0 ], T (s) * t[1 ], T (s) * t[2 ]}; Eigen::Matrix<T, 3 , 1 > lp; lp = q_last_curr * cp + t_last_curr; residual[0 ] = (lp - lpj).dot (ljm); return true ; }
点到面的距离:
其中,高向量 = 底边向量a $\times$ 底边向量b,注意是叉乘
更新优化的里程计 在ceres优化中,我们的优化方向为 扫描开始=q_last_curr*扫描结束 + t_last_curr, q_last_curr 和t_last_curr 组成的T 为从当前点到上一帧的变换$T_{now}^{last}$,从上一帧到当前帧的位移就是$T_{now}^{last}$中表示的位移,也就是雷达坐标系的位移
现在需要把它作用到之前的旋转和平移上,假设之前的从0到n-1时刻的位姿变换为$T_0^{n-1}$,那么$T_0^n$为
所以更新旋转的方式是
1 2 t_w_curr = t_w_curr + q_w_curr * t_last_curr; q_w_curr = q_w_curr * q_last_curr;
需要注意的是,此变换为$T{odom}^{laser}$,是odom -> laser的变换。可以通过$T {odom}^{laser} T_{laser}^{P}$ 计算出原本在laser下的点,通过坐标变换得到odom下的坐标点
发布里程计和路径 发布laser_odom_to_init 他表示目前当前时刻,激光雷达和odom之间的里程计
1 2 3 4 5 6 7 8 9 10 11 12 13 nav_msgs::Odometry laserOdometry; laserOdometry.header.frame_id = "camera_init" ; laserOdometry.child_frame_id = "/laser_odom" ; laserOdometry.header.stamp = ros::Time ().fromSec (timeSurfPointsLessFlat); laserOdometry.pose.pose.orientation.x = q_w_curr.x (); laserOdometry.pose.pose.orientation.y = q_w_curr.y (); laserOdometry.pose.pose.orientation.z = q_w_curr.z (); laserOdometry.pose.pose.orientation.w = q_w_curr.w (); laserOdometry.pose.pose.position.x = t_w_curr.x (); laserOdometry.pose.pose.position.y = t_w_curr.y (); laserOdometry.pose.pose.position.z = t_w_curr.z (); pubLaserOdometry.publish (laserOdometry);
发布laser_odom_path 发布里程计轨迹,路径
1 2 3 4 5 6 7 geometry_msgs::PoseStamped laserPose; laserPose.header = laserOdometry.header; laserPose.pose = laserOdometry.pose.pose; laserPath.header.stamp = laserOdometry.header.stamp; laserPath.poses.push_back(laserPose); laserPath.header.frame_id = "camera_init"; pubLaserPath.publish(laserPath);