【多传感器融合定位】【代码阅读】【A_LOAM及详细注释】
- 0 前言
- 1 概述介绍
-
- 2 代码演示
-
- 2.1 kittiHelper.cpp
- 2.2 laserMapping.cpp
- 2.3 laserOdometry.cpp
- 2.4 lidarFactor.hpp
- 2.5 scanRegistration.cpp
- 3 运行结果
0 前言
- 去掉了和IMU相关的部分
- 使用Eigen(四元数)做位姿转换,简化了代码
- 使用ceres做位姿优化,简化了代码,但降低了效率
- A_LOAM代码:https://github.com/HKUST-Aerial-Robotics/A-LOAM
- A_LOAM_NOTED代码注释版:https://github.com/cgbcgb/A-LOAM-NOTED
- 注释参考:A-LOAM源码解读
- A_LOAM代码带我的注释自取:链接:链接:https://pan.baidu.com/s/1lXvtkuyiavHAEBWjoxGWBQ
提取码:iusz ,将所得工程包放入catkin/src
路径下,参考A_LOAM_NOTED的编译方法
- nsh_indoor_outdoor.bag:链接:https://pan.baidu.com/s/19I66agf-xb8edHJ1c9y8oQ 提取码:r4mw
catkin_makesource ~/catkin_ws/devel/setup.bash
1 概述介绍
1.1 各模块说明
-
scanRegistration.cpp
scanRegistration.cpp
的功能是对激光点云预处理,包括移除空点和近点、计算每个点的水平和垂直角度并分成不同的scan、然后就是最重要的曲率计算、将每条激光线分成6个扇区然后根据曲率提取出特征点(极大边线点sharp、less sharp次极大边线点、flat极小平面点、less flat次极小平面点),对于得到的less flat进行滤波处理,最后把四种特征点,和含有intensity(scanID和对应时间)的点云发布出来;
-
laserOdometry.cpp
laserOdometry.cpp
的功能是通过求解最小二乘问题进行点云匹配,从而得到状态估计,包括畸变补偿(上面是用IMU补偿)、查找最近的对应特征点、计算点到直线和点到平面的距离、求雅克比矩阵、迭代解最小二乘问题、最后发布估计的状态里程计和path、以及上一帧的边线点、平面点并且重新把点云原封不动地发布出去。
-
laserMapping.cpp
laserMapping.cpp
的功能是不断拼接每帧点云建立地图,包括对点云坐标变换、然后还是求雅克比矩阵和解最小二乘问题这一套、最后把环境地图发布出来就不管了;这里是把地图分成很多个cube,然后进行管理,基于地图和上一帧的角点和边点匹配优化位姿,将局部地图发布、发布全局地图、优化后位姿的点云、优化后的位姿,是世界坐标系下当前帧的位姿、高频位姿、路径
2 代码演示
2.1 kittiHelper.cpp
- 其代码主要功能是将kitti数据集读取并数据发布,可选择是否生成对应的bag包
2.2 laserMapping.cpp
2.3 laserOdometry.cpp
- 参考:五.激光SLAM框架学习之A-LOAM框架—项目工程代码介绍—3.laserOdometry.cpp–前端雷达里程计和位姿粗估计
#include <cmath>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <geometry_msgs/PoseStamped.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl_conversions/pcl_conversions.h>
#include <ros/ros.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>
#include <eigen3/Eigen/Dense>
#include <mutex>
#include <queue>#include "aloam_velodyne/common.h"
#include "aloam_velodyne/tic_toc.h"
#include "lidarFactor.hpp"#define DISTORTION 0int corner_correspondence = 0, plane_correspondence = 0;constexpr double SCAN_PERIOD = 0.1;
constexpr double DISTANCE_SQ_THRESHOLD = 25;
constexpr double NEARBY_SCAN = 2.5;int skipFrameNum = 5;
bool systemInited = false;double timeCornerPointsSharp = 0;
double timeCornerPointsLessSharp = 0;
double timeSurfPointsFlat = 0;
double timeSurfPointsLessFlat = 0;
double timeLaserCloudFullRes = 0;pcl::KdTreeFLANN<pcl::PointXYZI>::Ptr kdtreeCornerLast(new pcl::KdTreeFLANN<pcl::PointXYZI>());
pcl::KdTreeFLANN<pcl::PointXYZI>::Ptr kdtreeSurfLast(new pcl::KdTreeFLANN<pcl::PointXYZI>());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 laserCloudFullRes(new pcl::PointCloud<PointType>());int laserCloudCornerLastNum = 0;
int laserCloudSurfLastNum = 0;
Eigen::Quaterniond q_w_curr(1, 0, 0, 0);
Eigen::Vector3d t_w_curr(0, 0, 0);
double para_q[4] = {0, 0, 0, 1};
double para_t[3] = {0, 0, 0};
Eigen::Map<Eigen::Quaterniond> q_last_curr(para_q);
Eigen::Map<Eigen::Vector3d> t_last_curr(para_t);
std::queue<sensor_msgs::PointCloud2ConstPtr> cornerSharpBuf;
std::queue<sensor_msgs::PointCloud2ConstPtr> cornerLessSharpBuf;
std::queue<sensor_msgs::PointCloud2ConstPtr> surfFlatBuf;
std::queue<sensor_msgs::PointCloud2ConstPtr> surfLessFlatBuf;
std::queue<sensor_msgs::PointCloud2ConstPtr> fullPointsBuf;
std::mutex mBuf;
void TransformToStart(PointType const *const pi, PointType *const po)
{double s;if (DISTORTION)s = (pi->intensity - int(pi->intensity)) / SCAN_PERIOD;elses = 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;
}
void TransformToEnd(PointType const *const pi, PointType *const po)
{pcl::PointXYZI un_point_tmp;TransformToStart(pi, &un_point_tmp);Eigen::Vector3d un_point(un_point_tmp.x, un_point_tmp.y, un_point_tmp.z);Eigen::Vector3d point_end = q_last_curr.inverse() * (un_point - t_last_curr);po->x = point_end.x();po->y = point_end.y();po->z = point_end.z();po->intensity = int(pi->intensity);
}
void laserCloudSharpHandler(const sensor_msgs::PointCloud2ConstPtr &cornerPointsSharp2)
{mBuf.lock();cornerSharpBuf.push(cornerPointsSharp2);mBuf.unlock();
}void laserCloudLessSharpHandler(const sensor_msgs::PointCloud2ConstPtr &cornerPointsLessSharp2)
{mBuf.lock();cornerLessSharpBuf.push(cornerPointsLessSharp2);mBuf.unlock();
}void laserCloudFlatHandler(const sensor_msgs::PointCloud2ConstPtr &surfPointsFlat2)
{mBuf.lock();surfFlatBuf.push(surfPointsFlat2);mBuf.unlock();
}void laserCloudLessFlatHandler(const sensor_msgs::PointCloud2ConstPtr &surfPointsLessFlat2)
{mBuf.lock();surfLessFlatBuf.push(surfPointsLessFlat2);mBuf.unlock();
}
void laserCloudFullResHandler(const sensor_msgs::PointCloud2ConstPtr &laserCloudFullRes2)
{mBuf.lock();fullPointsBuf.push(laserCloudFullRes2);mBuf.unlock();
}
int main(int argc, char **argv)
{ros::init(argc, argv, "laserOdometry");ros::NodeHandle nh;nh.param<int>("mapping_skip_frame", skipFrameNum, 2);printf("Mapping %d Hz \n", 10 / skipFrameNum);ros::Subscriber subCornerPointsSharp = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_sharp", 100, laserCloudSharpHandler);ros::Subscriber subCornerPointsLessSharp = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_less_sharp", 100, laserCloudLessSharpHandler);ros::Subscriber subSurfPointsFlat = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_flat", 100, laserCloudFlatHandler);ros::Subscriber subSurfPointsLessFlat = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_less_flat", 100, laserCloudLessFlatHandler);ros::Subscriber subLaserCloudFullRes = nh.subscribe<sensor_msgs::PointCloud2>("/velodyne_cloud_2", 100, laserCloudFullResHandler);ros::Publisher pubLaserCloudCornerLast = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_corner_last", 100);ros::Publisher pubLaserCloudSurfLast = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_surf_last", 100);ros::Publisher pubLaserCloudFullRes = nh.advertise<sensor_msgs::PointCloud2>("/velodyne_cloud_3", 100);ros::Publisher pubLaserOdometry = nh.advertise<nav_msgs::Odometry>("/laser_odom_to_init", 100);ros::Publisher pubLaserPath = nh.advertise<nav_msgs::Path>("/laser_odom_path", 100);nav_msgs::Path laserPath;int frameCount = 0;ros::Rate rate(100);
while (ros::ok()){ros::spinOnce();if (!cornerSharpBuf.empty() && !cornerLessSharpBuf.empty() &&!surfFlatBuf.empty() && !surfLessFlatBuf.empty() &&!fullPointsBuf.empty()){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();}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();TicToc t_whole;if (!systemInited){systemInited = true;std::cout << "Initialization finished \n";}else{int cornerPointsSharpNum = cornerPointsSharp->points.size();int surfPointsFlatNum = surfPointsFlat->points.size();TicToc t_opt;for (size_t opti_counter = 0; opti_counter < 2; ++opti_counter){corner_correspondence = 0;plane_correspondence = 0;ceres::LossFunction *loss_function = new ceres::HuberLoss(0.1);ceres::LocalParameterization *q_parameterization =new ceres::EigenQuaternionParameterization();ceres::Problem::Options problem_options;ceres::Problem problem(problem_options);problem.AddParameterBlock(para_q, 4, q_parameterization);problem.AddParameterBlock(para_t, 3);pcl::PointXYZI pointSel;std::vector<int> pointSearchInd;std::vector<float> pointSearchSqDis;TicToc t_data;for (int i = 0; i < cornerPointsSharpNum; ++i){TransformToStart(&(cornerPointsSharp->points[i]), &pointSel);kdtreeCornerLast->nearestKSearch(pointSel, 1, pointSearchInd, pointSearchSqDis);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;}}}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;elses = 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++;}}for (int i = 0; i < surfPointsFlatNum; ++i){TransformToStart(&(surfPointsFlat->points[i]), &pointSel);kdtreeSurfLast->nearestKSearch(pointSel, 1, pointSearchInd, pointSearchSqDis);int closestPointInd = -1, minPointInd2 = -1, minPointInd3 = -1;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;}}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;elses = 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++;}}}printf("data association time %f ms \n", t_data.toc());if ((corner_correspondence + plane_correspondence) < 10){printf("less correspondence! *************************************************\n");}TicToc t_solver;ceres::Solver::Options options;options.linear_solver_type = ceres::DENSE_QR;options.max_num_iterations = 4;options.minimizer_progress_to_stdout = false;ceres::Solver::Summary summary;ceres::Solve(options, &problem, &summary);printf("solver time %f ms \n", t_solver.toc());}printf("optimization twice time %f \n", t_opt.toc());t_w_curr = t_w_curr + q_w_curr * t_last_curr;q_w_curr = q_w_curr * q_last_curr;}TicToc t_pub;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);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);if (0){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]);}int laserCloudFullResNum = laserCloudFullRes->points.size();for (int i = 0; i < laserCloudFullResNum; i++){TransformToEnd(&laserCloudFullRes->points[i], &laserCloudFullRes->points[i]);}}pcl::PointCloud<PointType>::Ptr laserCloudTemp = cornerPointsLessSharp;cornerPointsLessSharp = laserCloudCornerLast;laserCloudCornerLast = laserCloudTemp;laserCloudTemp = surfPointsLessFlat;surfPointsLessFlat = laserCloudSurfLast;laserCloudSurfLast = laserCloudTemp;laserCloudCornerLastNum = laserCloudCornerLast->points.size();laserCloudSurfLastNum = laserCloudSurfLast->points.size();kdtreeCornerLast->setInputCloud(laserCloudCornerLast);kdtreeSurfLast->setInputCloud(laserCloudSurfLast);if (frameCount % skipFrameNum == 0){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);}printf("publication time %f ms \n", t_pub.toc());printf("whole laserOdometry time %f ms \n \n", t_whole.toc());if(t_whole.toc() > 100)ROS_WARN("odometry process over 100ms");frameCount++;}rate.sleep();}return 0;
}
2.4 lidarFactor.hpp
#include <ceres/ceres.h>
#include <ceres/rotation.h>
#include <eigen3/Eigen/Dense>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl_conversions/pcl_conversions.h>
struct LidarEdgeFactor
{LidarEdgeFactor(Eigen::Vector3d curr_point_, Eigen::Vector3d last_point_a_,Eigen::Vector3d last_point_b_, double s_): curr_point(curr_point_), last_point_a(last_point_a_), last_point_b(last_point_b_), s(s_) {}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;}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_)));}Eigen::Vector3d curr_point, last_point_a, last_point_b;double s;
};
struct LidarPlaneFactor
{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();}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;}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_)));}Eigen::Vector3d curr_point, last_point_j, last_point_l, last_point_m;Eigen::Vector3d ljm_norm;double s;
};struct LidarPlaneNormFactor
{LidarPlaneNormFactor(Eigen::Vector3d curr_point_, Eigen::Vector3d plane_unit_norm_,double negative_OA_dot_norm_) : curr_point(curr_point_), plane_unit_norm(plane_unit_norm_),negative_OA_dot_norm(negative_OA_dot_norm_) {}template <typename T>bool operator()(const T *q, const T *t, T *residual) const{Eigen::Quaternion<T> q_w_curr{q[3], q[0], q[1], q[2]};Eigen::Matrix<T, 3, 1> t_w_curr{t[0], t[1], t[2]};Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};Eigen::Matrix<T, 3, 1> point_w;point_w = q_w_curr * cp + t_w_curr;Eigen::Matrix<T, 3, 1> norm(T(plane_unit_norm.x()), T(plane_unit_norm.y()), T(plane_unit_norm.z()));residual[0] = norm.dot(point_w) + T(negative_OA_dot_norm);return true;}static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_, const Eigen::Vector3d plane_unit_norm_,const double negative_OA_dot_norm_){return (new ceres::AutoDiffCostFunction<LidarPlaneNormFactor, 1, 4, 3>(new LidarPlaneNormFactor(curr_point_, plane_unit_norm_, negative_OA_dot_norm_)));}Eigen::Vector3d curr_point;Eigen::Vector3d plane_unit_norm;double negative_OA_dot_norm;
};struct LidarDistanceFactor
{LidarDistanceFactor(Eigen::Vector3d curr_point_, Eigen::Vector3d closed_point_) : curr_point(curr_point_), closed_point(closed_point_){}template <typename T>bool operator()(const T *q, const T *t, T *residual) const{Eigen::Quaternion<T> q_w_curr{q[3], q[0], q[1], q[2]};Eigen::Matrix<T, 3, 1> t_w_curr{t[0], t[1], t[2]};Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};Eigen::Matrix<T, 3, 1> point_w;point_w = q_w_curr * cp + t_w_curr;residual[0] = point_w.x() - T(closed_point.x());residual[1] = point_w.y() - T(closed_point.y());residual[2] = point_w.z() - T(closed_point.z());return true;}static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_, const Eigen::Vector3d closed_point_){return (new ceres::AutoDiffCostFunction<LidarDistanceFactor, 3, 4, 3>(new LidarDistanceFactor(curr_point_, closed_point_)));}Eigen::Vector3d curr_point;Eigen::Vector3d closed_point;
};
2.5 scanRegistration.cpp
- 前端雷达处理和特征提取
- 参考:四.激光SLAM框架学习之A-LOAM框架—项目工程代码介绍—2.scanRegistration.cpp–前端雷达处理和特征提取
#include <cmath>
#include <vector>
#include <string>
#include "aloam_velodyne/common.h"
#include "aloam_velodyne/tic_toc.h"
#include <nav_msgs/Odometry.h>
#include <opencv/cv.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <ros/ros.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>using std::atan2;
using std::cos;
using std::sin;const double scanPeriod = 0.1;const int systemDelay = 0;
int systemInitCount = 0;
bool systemInited = false;
int N_SCANS = 0;
float cloudCurvature[400000];
int cloudSortInd[400000];
int cloudNeighborPicked[400000];
int cloudLabel[400000];
bool comp (int i,int j) { return (cloudCurvature[i]<cloudCurvature[j]); }ros::Publisher pubLaserCloud;
ros::Publisher pubCornerPointsSharp;
ros::Publisher pubCornerPointsLessSharp;
ros::Publisher pubSurfPointsFlat;
ros::Publisher pubSurfPointsLessFlat;
ros::Publisher pubRemovePoints;
std::vector<ros::Publisher> pubEachScan;bool PUB_EACH_LINE = false;double MINIMUM_RANGE = 0.1;
template <typename PointT>
void removeClosedPointCloud(const pcl::PointCloud<PointT> &cloud_in,pcl::PointCloud<PointT> &cloud_out, float thres)
{if (&cloud_in != &cloud_out){cloud_out.header = cloud_in.header;cloud_out.points.resize(cloud_in.points.size());}size_t j = 0;for (size_t i = 0; i < cloud_in.points.size(); ++i){if (cloud_in.points[i].x * cloud_in.points[i].x + cloud_in.points[i].y * cloud_in.points[i].y + cloud_in.points[i].z * cloud_in.points[i].z < thres * thres)continue;cloud_out.points[j] = cloud_in.points[i];j++;}if (j != cloud_in.points.size()){cloud_out.points.resize(j);}cloud_out.height = 1;cloud_out.width = static_cast<uint32_t>(j);cloud_out.is_dense = true;
}
void laserCloudHandler(const sensor_msgs::PointCloud2ConstPtr &laserCloudMsg)
{if (!systemInited){ systemInitCount++;if (systemInitCount >= systemDelay){systemInited = true;}elsereturn;}TicToc t_whole;TicToc t_prepare;std::vector<int> scanStartInd(N_SCANS, 0);std::vector<int> scanEndInd(N_SCANS, 0);pcl::PointCloud<pcl::PointXYZ> laserCloudIn;pcl::fromROSMsg(*laserCloudMsg, laserCloudIn);std::vector<int> indices;pcl::removeNaNFromPointCloud(laserCloudIn, laserCloudIn, indices);removeClosedPointCloud(laserCloudIn, laserCloudIn, MINIMUM_RANGE);int cloudSize = laserCloudIn.points.size();float startOri = -atan2(laserCloudIn.points[0].y, laserCloudIn.points[0].x);float endOri = -atan2(laserCloudIn.points[cloudSize - 1].y, laserCloudIn.points[cloudSize - 1].x) +2 * M_PI;if (endOri - startOri > 3 * M_PI){endOri -= 2 * M_PI;}else if (endOri - startOri < M_PI){endOri += 2 * M_PI;}bool halfPassed = false;int count = cloudSize; PointType point;std::vector<pcl::PointCloud<PointType>> laserCloudScans(N_SCANS);for (int i = 0; i < cloudSize; i++){point.x = laserCloudIn.points[i].x;point.y = laserCloudIn.points[i].y;point.z = laserCloudIn.points[i].z;float angle = atan(point.z / sqrt(point.x * point.x + point.y * point.y)) * 180 / M_PI;int scanID = 0;if (N_SCANS == 16){scanID = int((angle + 15) / 2 + 0.5);if (scanID > (N_SCANS - 1) || scanID < 0){count--;continue;}}else if (N_SCANS == 32){scanID = int((angle + 92.0/3.0) * 3.0 / 4.0);if (scanID > (N_SCANS - 1) || scanID < 0){count--;continue;}}else if (N_SCANS == 64){ if (angle >= -8.83)scanID = int((2 - angle) * 3.0 + 0.5);elsescanID = N_SCANS / 2 + int((-8.83 - angle) * 2.0 + 0.5);if (angle > 2 || angle < -24.33 || scanID > 50 || scanID < 0){count--;continue;}}else{printf("wrong scan number\n");ROS_BREAK();}float ori = -atan2(point.y, point.x);if (!halfPassed) { if (ori < startOri - M_PI / 2){ori += 2 * M_PI;}else if (ori > startOri + M_PI * 3 / 2){ori -= 2 * M_PI;}if (ori - startOri > M_PI){halfPassed = true;}}else{ori += 2 * M_PI;if (ori < endOri - M_PI * 3 / 2){ori += 2 * M_PI;}else if (ori > endOri + M_PI / 2){ori -= 2 * M_PI;}}float relTime = (ori - startOri) / (endOri - startOri);point.intensity = scanID + scanPeriod * relTime;laserCloudScans[scanID].push_back(point); }cloudSize = count;printf("points size %d \n", cloudSize);pcl::PointCloud<PointType>::Ptr laserCloud(new pcl::PointCloud<PointType>());for (int i = 0; i < N_SCANS; i++){ scanStartInd[i] = laserCloud->size() + 5;*laserCloud += laserCloudScans[i];scanEndInd[i] = laserCloud->size() - 6;}printf("prepare time %f \n", t_prepare.toc());for (int i = 5; i < cloudSize - 5; i++){ float diffX = laserCloud->points[i - 5].x + laserCloud->points[i - 4].x + laserCloud->points[i - 3].x + laserCloud->points[i - 2].x + laserCloud->points[i - 1].x - 10 * laserCloud->points[i].x + laserCloud->points[i + 1].x + laserCloud->points[i + 2].x + laserCloud->points[i + 3].x + laserCloud->points[i + 4].x + laserCloud->points[i + 5].x;float diffY = laserCloud->points[i - 5].y + laserCloud->points[i - 4].y + laserCloud->points[i - 3].y + laserCloud->points[i - 2].y + laserCloud->points[i - 1].y - 10 * laserCloud->points[i].y + laserCloud->points[i + 1].y + laserCloud->points[i + 2].y + laserCloud->points[i + 3].y + laserCloud->points[i + 4].y + laserCloud->points[i + 5].y;float diffZ = laserCloud->points[i - 5].z + laserCloud->points[i - 4].z + laserCloud->points[i - 3].z + laserCloud->points[i - 2].z + laserCloud->points[i - 1].z - 10 * laserCloud->points[i].z + laserCloud->points[i + 1].z + laserCloud->points[i + 2].z + laserCloud->points[i + 3].z + laserCloud->points[i + 4].z + laserCloud->points[i + 5].z;cloudCurvature[i] = diffX * diffX + diffY * diffY + diffZ * diffZ;cloudSortInd[i] = i;cloudNeighborPicked[i] = 0;cloudLabel[i] = 0;}TicToc t_pts;pcl::PointCloud<PointType> cornerPointsSharp;pcl::PointCloud<PointType> cornerPointsLessSharp;pcl::PointCloud<PointType> surfPointsFlat;pcl::PointCloud<PointType> surfPointsLessFlat;float t_q_sort = 0;for (int i = 0; i < N_SCANS; i++){if( scanEndInd[i] - scanStartInd[i] < 6)continue;pcl::PointCloud<PointType>::Ptr surfPointsLessFlatScan(new pcl::PointCloud<PointType>);for (int j = 0; j < 6; j++){int sp = scanStartInd[i] + (scanEndInd[i] - scanStartInd[i]) * j / 6;int ep = scanStartInd[i] + (scanEndInd[i] - scanStartInd[i]) * (j + 1) / 6 - 1;TicToc t_tmp;std::sort (cloudSortInd + sp, cloudSortInd + ep + 1, comp);t_q_sort += t_tmp.toc();int largestPickedNum = 0;for (int k = ep; k >= sp; k--){int ind = cloudSortInd[k]; if (cloudNeighborPicked[ind] == 0 &&cloudCurvature[ind] > 0.1){largestPickedNum++;if (largestPickedNum <= 2){ cloudLabel[ind] = 2;cornerPointsSharp.push_back(laserCloud->points[ind]);cornerPointsLessSharp.push_back(laserCloud->points[ind]);}else if (largestPickedNum <= 20){ cloudLabel[ind] = 1; cornerPointsLessSharp.push_back(laserCloud->points[ind]);}else{break;}cloudNeighborPicked[ind] = 1;for (int l = 1; l <= 5; l++){float diffX = laserCloud->points[ind + l].x - laserCloud->points[ind + l - 1].x;float diffY = laserCloud->points[ind + l].y - laserCloud->points[ind + l - 1].y;float diffZ = laserCloud->points[ind + l].z - laserCloud->points[ind + l - 1].z;if (diffX * diffX + diffY * diffY + diffZ * diffZ > 0.05){break;}cloudNeighborPicked[ind + l] = 1;}for (int l = -1; l >= -5; l--){float diffX = laserCloud->points[ind + l].x - laserCloud->points[ind + l + 1].x;float diffY = laserCloud->points[ind + l].y - laserCloud->points[ind + l + 1].y;float diffZ = laserCloud->points[ind + l].z - laserCloud->points[ind + l + 1].z;if (diffX * diffX + diffY * diffY + diffZ * diffZ > 0.05){break;}cloudNeighborPicked[ind + l] = 1;}}}int smallestPickedNum = 0;for (int k = sp; k <= ep; k++) {int ind = cloudSortInd[k];if (cloudNeighborPicked[ind] == 0 &&cloudCurvature[ind] < 0.1){cloudLabel[ind] = -1; surfPointsFlat.push_back(laserCloud->points[ind]);smallestPickedNum++;if (smallestPickedNum >= 4){ break;}cloudNeighborPicked[ind] = 1;for (int l = 1; l <= 5; l++){ float diffX = laserCloud->points[ind + l].x - laserCloud->points[ind + l - 1].x;float diffY = laserCloud->points[ind + l].y - laserCloud->points[ind + l - 1].y;float diffZ = laserCloud->points[ind + l].z - laserCloud->points[ind + l - 1].z;if (diffX * diffX + diffY * diffY + diffZ * diffZ > 0.05){break;}cloudNeighborPicked[ind + l] = 1;}for (int l = -1; l >= -5; l--){float diffX = laserCloud->points[ind + l].x - laserCloud->points[ind + l + 1].x;float diffY = laserCloud->points[ind + l].y - laserCloud->points[ind + l + 1].y;float diffZ = laserCloud->points[ind + l].z - laserCloud->points[ind + l + 1].z;if (diffX * diffX + diffY * diffY + diffZ * diffZ > 0.05){break;}cloudNeighborPicked[ind + l] = 1;}}}for (int k = sp; k <= ep; k++){if (cloudLabel[k] <= 0){surfPointsLessFlatScan->push_back(laserCloud->points[k]);}}}pcl::PointCloud<PointType> surfPointsLessFlatScanDS;pcl::VoxelGrid<PointType> downSizeFilter;downSizeFilter.setInputCloud(surfPointsLessFlatScan);downSizeFilter.setLeafSize(0.2, 0.2, 0.2);downSizeFilter.filter(surfPointsLessFlatScanDS);surfPointsLessFlat += surfPointsLessFlatScanDS;}printf("sort q time %f \n", t_q_sort);printf("seperate points time %f \n", t_pts.toc());sensor_msgs::PointCloud2 laserCloudOutMsg;pcl::toROSMsg(*laserCloud, laserCloudOutMsg);laserCloudOutMsg.header.stamp = laserCloudMsg->header.stamp;laserCloudOutMsg.header.frame_id = "/camera_init"; pubLaserCloud.publish(laserCloudOutMsg);sensor_msgs::PointCloud2 cornerPointsSharpMsg;pcl::toROSMsg(cornerPointsSharp, cornerPointsSharpMsg);cornerPointsSharpMsg.header.stamp = laserCloudMsg->header.stamp;cornerPointsSharpMsg.header.frame_id = "/camera_init";pubCornerPointsSharp.publish(cornerPointsSharpMsg);sensor_msgs::PointCloud2 cornerPointsLessSharpMsg;pcl::toROSMsg(cornerPointsLessSharp, cornerPointsLessSharpMsg);cornerPointsLessSharpMsg.header.stamp = laserCloudMsg->header.stamp;cornerPointsLessSharpMsg.header.frame_id = "/camera_init";pubCornerPointsLessSharp.publish(cornerPointsLessSharpMsg);sensor_msgs::PointCloud2 surfPointsFlat2;pcl::toROSMsg(surfPointsFlat, surfPointsFlat2);surfPointsFlat2.header.stamp = laserCloudMsg->header.stamp;surfPointsFlat2.header.frame_id = "/camera_init";pubSurfPointsFlat.publish(surfPointsFlat2);sensor_msgs::PointCloud2 surfPointsLessFlat2;pcl::toROSMsg(surfPointsLessFlat, surfPointsLessFlat2);surfPointsLessFlat2.header.stamp = laserCloudMsg->header.stamp;surfPointsLessFlat2.header.frame_id = "/camera_init";pubSurfPointsLessFlat.publish(surfPointsLessFlat2);if(PUB_EACH_LINE){for(int i = 0; i< N_SCANS; i++){sensor_msgs::PointCloud2 scanMsg;pcl::toROSMsg(laserCloudScans[i], scanMsg);scanMsg.header.stamp = laserCloudMsg->header.stamp;scanMsg.header.frame_id = "/camera_init";pubEachScan[i].publish(scanMsg);}}printf("scan registration time %f ms *************\n", t_whole.toc());if(t_whole.toc() > 100)ROS_WARN("scan registration process over 100ms");
}int main(int argc, char **argv)
{ros::init(argc, argv, "scanRegistration"); ros::NodeHandle nh; nh.param<int>("scan_line", N_SCANS, 16);nh.param<double>("minimum_range", MINIMUM_RANGE, 0.1);printf("scan line number %d \n", N_SCANS);if(N_SCANS != 16 && N_SCANS != 32 && N_SCANS != 64){printf("only support velodyne with 16, 32 or 64 scan line!");return 0;}ros::Subscriber subLaserCloud = nh.subscribe<sensor_msgs::PointCloud2>("/velodyne_points", 100, laserCloudHandler);pubLaserCloud = nh.advertise<sensor_msgs::PointCloud2>("/velodyne_cloud_2", 100);pubCornerPointsSharp = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_sharp", 100);pubCornerPointsLessSharp = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_less_sharp", 100);pubSurfPointsFlat = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_flat", 100);pubSurfPointsLessFlat = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_less_flat", 100);pubRemovePoints = nh.advertise<sensor_msgs::PointCloud2>("/laser_remove_points", 100);if(PUB_EACH_LINE){for(int i = 0; i < N_SCANS; i++){ros::Publisher tmp = nh.advertise<sensor_msgs::PointCloud2>("/laser_scanid_" + std::to_string(i), 100);pubEachScan.push_back(tmp);}}ros::spin();return 0;
}
3 运行结果
roslaunch aloam_velodyne aloam_velodyne_VLP_16.launch
rosbag play YOUR_DATASET_FOLDER/nsh_indoor_outdoor.bag
