1 scanRegistration.cpp
代码:https://github.com/cuitaixiang/LOAM_NOTED
根据VLP16的激光扫描模型, 对单帧点云(paper中称为一个Sweep)进行分线束(分为16束), 每束称为一个Scan, 并记录每个点所属线束和每个点在此帧点云内的相对扫描时间(相对于本帧第一个点)。
针对单个Scan提取特征点, 而相对时间会用于插值计算非匀速运动畸变补偿。每帧点云,输出角点和面点的四种特征点云, 给下一个节点laserOdometry。
在对代码进行阅读之前,需要先了解坐标系的设置:
- imu为x轴向前,y轴向左,z轴向上的右手坐标系
- velodyne lidar为x轴向前,y轴向左,z轴向上的右手坐标系
- scanRegistration会把两者通过交换坐标轴,都统一到z轴向前,x轴向左,y轴向上的右手坐标系 ,这是J. Zhang的论文里面使用的坐标系
scanRegistration.cpp
1)对应节点:/scanRegistration
2)功能:
1.点云处理 (点云回调函数)
1.1 计算点的线号与点到该帧初始点的时间;
1.2 去除点云加速度产生的畸变
1.3 计算所有点的曲率
1.4 去除平行点与遮挡点
1.5 提取面点与角点
1.6 发布面点、角点以及IMU消息
2.imu处理(imu回调函数)
2.1 提取姿态角 (imu坐标系x轴向前,y轴向左,z轴向上,roll,pitch,yaw)
加速度(imu坐标系转换到z轴向前,x轴向左,y轴向上的坐标系)
2.2 根据上面的加速度,转换得到世界坐标系下的加速度值,使用匀加速模型得出当前时刻车辆在世界坐标系下的速度与位移
3)代码分析:
订阅话题2个:
/velodyne_points
点云数据
/imu/data
IMU数据
发布话题6个:
/imu_trans
发布IMU信息
/velodyne_cloud_2
消除非匀速运动畸变后的点
/laser_cloud_sharp(flat)、/laser_cloud_less_sharp(flat)
消除非匀速运动畸变后的平面点和边沿点
从main函数开始:
int main(int argc, char** argv)
{
ros::init(argc, argv, "scanRegistration");
/*
* NodeHandle 是节点同ROS系统交流的主要接口
* NodeHandle 在构造的时候会完整地初始化本节点
* NodeHandle 析构的时候会关闭此节点
*/
ros::NodeHandle nh;
/*
* 参数1:话题名称
* 参数2:信息队列长度
* 参数3:回调函数,每当一个信息到来的时候,这个函数会被调用
* 返回一个ros::Subscriber类的对象,当此对象的所有引用都被销毁时,本节点将不再是该话题的订阅者
*/
// 订阅了velodyne_points和imu/data
ros::Subscriber subLaserCloud = nh.subscribe<sensor_msgs::PointCloud2>
("/velodyne_points", 2, laserCloudHandler);
ros::Subscriber subImu = nh.subscribe<sensor_msgs::Imu> ("/imu/data", 50, imuHandler);
/*
* 我们通过advertise() 函数指定我们如何在给定的topic上发布信息
* 它会触发对ROS master的调用,master会记录话题发布者和订阅者
* 在advertise()函数执行之后,master会通知每一个订阅此话题的节点
* 两节点间由此可以建立直接的联系
* advertise()会返回一个Publisher对象,使用这个对象的publish方法我们就可以在此话题上发布信息
* 当返回的Publisher对象的所有引用都被销毁的时候,本节点将不再是该话题的发布者
* 此函数是一个带模板的函数,需要传入具体的类型进行实例化
* 传入的类型就是要发布的信息的类型,在这里是String
* 第一个参数是话题名称
* 第二个参数是信息队列的长度,相当于信息的一个缓冲区
* 在我们发布信息的速度大于处理信息的速度时
* 信息会被缓存在先进先出的信息队列里
*/
// 发布了6个话题:velodyne_cloud_2、laser_cloud_sharp、laser_cloud_flat、laser_cloud_less_flat、laser_cloud_less_sharp、imu_trans
pubLaserCloud = nh.advertise<sensor_msgs::PointCloud2>
("/velodyne_cloud_2", 2);
pubCornerPointsSharp = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_sharp", 2);
pubCornerPointsLessSharp = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_less_sharp", 2);
pubSurfPointsFlat = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_flat", 2);
pubSurfPointsLessFlat = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_less_flat", 2);
pubImuTrans = nh.advertise<sensor_msgs::PointCloud2> ("/imu_trans", 5);
/**
* 它可以保证你指定的回调函数会被调用
* 程序执行到spin()后就不调用其他语句了
*/
ros::spin();
return 0;
}
laserCloudHandler
main函数主要是订阅前一个节点发布的点云topic,一旦接受到一帧点云就执行一次回调函数laserCloudHandler:
接收点云处理:
//接收点云数据,velodyne雷达坐标系安装为x轴向前,y轴向左,z轴向上的右手坐标系
void laserCloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg)
{
if (!systemInited) {//丢弃前20帧点云数据,systemInited初始为false
systemInitCount++;
if (systemInitCount >= systemDelay) {
systemInited = true;
}
return;
}
//记录每个scan有曲率的点的开始和结束索引
std::vector<int> scanStartInd(N_SCANS, 0);
std::vector<int> scanEndInd(N_SCANS, 0);
//当前点云时间
double timeScanCur = laserCloudMsg->header.stamp.toSec();
pcl::PointCloud<pcl::PointXYZ> laserCloudIn;
//消息转换成pcl数据存放
pcl::fromROSMsg(*laserCloudMsg, laserCloudIn);
std::vector<int> indices;
//移除空点
pcl::removeNaNFromPointCloud(laserCloudIn, laserCloudIn, indices);
//点云点的数量
int cloudSize = laserCloudIn.points.size();
//lidar scan开始点的旋转角,atan2范围(-pi,+pi],计算旋转角时取负号是因为velodyne是顺时针旋转
float startOri = -atan2(laserCloudIn.points[0].y, laserCloudIn.points[0].x);
//lidar scan结束点的旋转角,加2*pi使点云旋转周期为2*pi
float endOri = -atan2(laserCloudIn.points[cloudSize - 1].y,
laserCloudIn.points[cloudSize - 1].x) + 2 * M_PI; //加2 * M_PI在于,若结束点在x轴附近,几度/-几度
//结束方位角与开始方位角差值控制在(PI,3*PI)范围,允许lidar不是一个圆周扫描
//正常情况下在这个范围内:pi < endOri - startOri < 3*pi,异常则修正
if (endOri - startOri > 3 * M_PI) {
endOri -= 2 * M_PI;
} else if (endOri - startOri < M_PI) {
endOri += 2 * M_PI;
}
计算每个点线号与每个点相对该帧初始时刻的时间
point.x=laserCloudIn.points[i].y; point.y=laserCloudIn.points[i].z; point.z=laserCloudIn.points[I].x
;
将坐标系转化为z向前,x向左,y向上的右手坐标系
(原作标系x向前,y向左,z向上)
//lidar扫描线是否旋转过半
bool halfPassed = false;
int count = cloudSize;
PointType point;
std::vector<pcl::PointCloud<PointType> > laserCloudScans(N_SCANS);
for (int i = 0; i < cloudSize; i++) {
//坐标轴交换,velodyne lidar的坐标系也转换到z轴向前,x轴向左的右手坐标系
point.x = laserCloudIn.points[i].y;
point.y = laserCloudIn.points[i].z;
point.z = laserCloudIn.points[i].x;
//计算点的仰角(根据lidar文档垂直角计算公式),根据仰角排列激光线号,velodyne每两个scan之间间隔2度
float angle = atan(point.y / sqrt(point.x * point.x + point.z * point.z)) * 180 / M_PI;
int scanID;
//仰角四舍五入(加减0.5截断效果等于四舍五入)
int roundedAngle = int(angle + (angle<0.0?-0.5:+0.5));
if (roundedAngle > 0){
scanID = roundedAngle;
}
else {
scanID = roundedAngle + (N_SCANS - 1);
}
//过滤点,只挑选[-15度,+15度]范围内的点,scanID属于[0,15]
if (scanID > (N_SCANS - 1) || scanID < 0 ){
count--;
continue;
}
//该点的旋转角
float ori = -atan2(point.x, point.z);
if (!halfPassed) {//根据扫描线是否旋转过半选择与起始位置还是终止位置进行差值计算,从而进行补偿
//确保-pi/2 < ori - startOri < 3*pi/2
if (ori < startOri - M_PI / 2) {
ori += 2 * M_PI;
} else if (ori > startOri + M_PI * 3 / 2) {
ori -= 2 * M_PI;
}
//ori: 0-2pi?
if (ori - startOri > M_PI) {
halfPassed = true;
}
} else {
ori += 2 * M_PI;
//确保-3*pi/2 < ori - endOri < pi/2
if (ori < endOri - M_PI * 3 / 2) {
ori += 2 * M_PI;
} else if (ori > endOri + M_PI / 2) {
ori -= 2 * M_PI;
}
}
//-0.5 < relTime < 1.5(点旋转的角度与整个周期旋转角度的比率, 即点云中点的相对时间)
float relTime = (ori - startOri) / (endOri - startOri);
//点强度=线号+点相对时间(即一个整数+一个小数,整数部分是线号,小数部分是该点的相对时间),匀速扫描:根据当前扫描的角度和扫描周期计算相对扫描起始位置的时间
point.intensity = scanID + scanPeriod * relTime;
使用imu数据进行插值去除车辆非匀速运动造成的畸变,最后将每个补偿畸变的点放入对应线号的容器:
下面的代码实现了:
1.imu时间戳恰好大于点云时间戳的位置,该点必处于imuPointerBack和imuPointerFront之间,据此线性插值,计算点云点的速度,位移和欧拉角
2.如果没有,以当前收到的最新的IMU的速度,位移,欧拉角作为当前点的速度,位移,欧拉角使用;
3.记录此sweep中的第一个点的位置、位移和欧拉角;
4.计算之后每个点相对于第一个点的由于加减速非匀速运动产生的位移速度畸变,并对点云中的每个点位置信息重新补偿矫正(即采用三个全局函数进行处理
ShiftToStartIMU(pointTime);,VeloToStartIMU();,TransformToStartIMU(&point);
//点时间=点云时间+周期时间
if (imuPointerLast >= 0) {//如果收到IMU数据,使用IMU矫正点云畸变
float pointTime = relTime * scanPeriod;//计算点的周期时间
//寻找是否有点云的时间戳小于IMU的时间戳的IMU位置:imuPointerFront
while (imuPointerFront != imuPointerLast) {
if (timeScanCur + pointTime < imuTime[imuPointerFront]) {
break;
}
imuPointerFront = (imuPointerFront + 1) % imuQueLength;
}
if (timeScanCur + pointTime > imuTime[imuPointerFront]) {//没找到,此时imuPointerFront==imtPointerLast,只能以当前收到的最新的IMU的速度,位移,欧拉角作为当前点的速度,位移,欧拉角使用
imuRollCur = imuRoll[imuPointerFront];
imuPitchCur = imuPitch[imuPointerFront];
imuYawCur = imuYaw[imuPointerFront];
imuVeloXCur = imuVeloX[imuPointerFront];
imuVeloYCur = imuVeloY[imuPointerFront];
imuVeloZCur = imuVeloZ[imuPointerFront];
imuShiftXCur = imuShiftX[imuPointerFront];
imuShiftYCur = imuShiftY[imuPointerFront];
imuShiftZCur = imuShiftZ[imuPointerFront];
} else {//找到了点云时间戳小于IMU时间戳的IMU位置,则该点必处于imuPointerBack和imuPointerFront之间,据此线性插值,计算点云点的速度,位移和欧拉角
int imuPointerBack = (imuPointerFront + imuQueLength - 1) % imuQueLength;
//按时间距离计算权重分配比率,也即线性插值
float ratioFront = (timeScanCur + pointTime - imuTime[imuPointerBack])
/ (imuTime[imuPointerFront] - imuTime[imuPointerBack]);
float ratioBack = (imuTime[imuPointerFront] - timeScanCur - pointTime)
/ (imuTime[imuPointerFront] - imuTime[imuPointerBack]);
imuRollCur = imuRoll[imuPointerFront] * ratioFront + imuRoll[imuPointerBack] * ratioBack;
imuPitchCur = imuPitch[imuPointerFront] * ratioFront + imuPitch[imuPointerBack] * ratioBack;
if (imuYaw[imuPointerFront] - imuYaw[imuPointerBack] > M_PI) {
imuYawCur = imuYaw[imuPointerFront] * ratioFront + (imuYaw[imuPointerBack] + 2 * M_PI) * ratioBack;
} else if (imuYaw[imuPointerFront] - imuYaw[imuPointerBack] < -M_PI) {
imuYawCur = imuYaw[imuPointerFront] * ratioFront + (imuYaw[imuPointerBack] - 2 * M_PI) * ratioBack;
} else {
imuYawCur = imuYaw[imuPointerFront] * ratioFront + imuYaw[imuPointerBack] * ratioBack;
}
//本质:imuVeloXCur = imuVeloX[imuPointerback] + (imuVelX[imuPointerFront]-imuVelX[imuPoniterBack])*ratioFront
imuVeloXCur = imuVeloX[imuPointerFront] * ratioFront + imuVeloX[imuPointerBack] * ratioBack;
imuVeloYCur = imuVeloY[imuPointerFront] * ratioFront + imuVeloY[imuPointerBack] * ratioBack;
imuVeloZCur = imuVeloZ[imuPointerFront] * ratioFront + imuVeloZ[imuPointerBack] * ratioBack;
imuShiftXCur = imuShiftX[imuPointerFront] * ratioFront + imuShiftX[imuPointerBack] * ratioBack;
imuShiftYCur = imuShiftY[imuPointerFront] * ratioFront + imuShiftY[imuPointerBack] * ratioBack;
imuShiftZCur = imuShiftZ[imuPointerFront] * ratioFront + imuShiftZ[imuPointerBack] * ratioBack;
}
if (i == 0) {//如果是第一个点,记住点云起始位置的速度,位移,欧拉角 //一帧执行一次
imuRollStart = imuRollCur;
imuPitchStart = imuPitchCur;
imuYawStart = imuYawCur;
imuVeloXStart = imuVeloXCur;
imuVeloYStart = imuVeloYCur;
imuVeloZStart = imuVeloZCur;
imuShiftXStart = imuShiftXCur;
imuShiftYStart = imuShiftYCur;
imuShiftZStart = imuShiftZCur;
} else {//计算之后每个点相对于第一个点的由于加减速非匀速运动产生的位移速度畸变,并对点云中的每个点位置信息重新补偿矫正
ShiftToStartIMU(pointTime);
VeloToStartIMU();
TransformToStartIMU(&point);//去除加速度产生的畸变
}
}
laserCloudScans[scanID].push_back(point);//将每个补偿矫正的点放入对应线号的容器
}
1).
ShiftToStartIMU(float pointTime)
我们已经知道了每个点对应的车辆在世界坐标系下的位置,而我们想要求的是这一帧数据中该点相对于起始点由于加减速造成的运动畸变。因此我们首先要求出世界坐标系下的加减速造成的运动畸变,然后将运动畸变值经过绕y、x、z轴旋转后得到该sweep起始点坐标系下的运动畸变。
需要理解:为什么只有旋转变换而没有位移变换?因为imu的旋转信息是与imu全局坐标系的变换关系,所以可以只旋转。
//计算sweep起始坐标系下点云中的点相对第一个开始点的由于加减速运动产生的位移畸变
void ShiftToStartIMU(float pointTime)
{
//计算相对于第一个点由于加减速产生的畸变位移(全局坐标系下畸变位移量delta_Tg)
//imuShiftFromStartCur = imuShiftCur - (imuShiftStart + imuVeloStart * pointTime)
imuShiftFromStartXCur = imuShiftXCur - imuShiftXStart - imuVeloXStart * pointTime;
imuShiftFromStartYCur = imuShiftYCur - imuShiftYStart - imuVeloYStart * pointTime;
imuShiftFromStartZCur = imuShiftZCur - imuShiftZStart - imuVeloZStart * pointTime;
/********************************************************************************
Rz(pitch).inverse * Rx(pitch).inverse * Ry(yaw).inverse * delta_Tg
transfrom from the global frame to the local frame
*********************************************************************************/
//绕y轴旋转(-imuYawStart),即Ry(yaw).inverse
float x1 = cos(imuYawStart) * imuShiftFromStartXCur - sin(imuYawStart) * imuShiftFromStartZCur;
float y1 = imuShiftFromStartYCur;
float z1 = sin(imuYawStart) * imuShiftFromStartXCur + cos(imuYawStart) * imuShiftFromStartZCur;
//绕x轴旋转(-imuPitchStart),即Rx(pitch).inverse
float x2 = x1;
float y2 = cos(imuPitchStart) * y1 + sin(imuPitchStart) * z1;
float z2 = -sin(imuPitchStart) * y1 + cos(imuPitchStart) * z1;
//绕z轴旋转(-imuRollStart),即Rz(pitch).inverse
imuShiftFromStartXCur = cos(imuRollStart) * x2 + sin(imuRollStart) * y2;
imuShiftFromStartYCur = -sin(imuRollStart) * x2 + cos(imuRollStart) * y2;
imuShiftFromStartZCur = z2;
}
2).
void VeloToStartIMU()
作用是求当前点对应的车辆速度相对于sweep起始点的速度畸变,先计算全局坐标系下的然后再转换到起始点的坐标系中。
//计算sweep起始坐标系下点云中的点相对第一个开始点由于加减速产生的的速度畸变(增量)
void VeloToStartIMU()
{
//计算相对于第一个点由于加减速产生的畸变速度(全局坐标系下畸变速度增量delta_Vg)
imuVeloFromStartXCur = imuVeloXCur - imuVeloXStart;
imuVeloFromStartYCur = imuVeloYCur - imuVeloYStart;
imuVeloFromStartZCur = imuVeloZCur - imuVeloZStart;
/********************************************************************************
Rz(pitch).inverse * Rx(pitch).inverse * Ry(yaw).inverse * delta_Vg
transfrom from the global frame to the local frame
*********************************************************************************/
//绕y轴旋转(-imuYawStart),即Ry(yaw).inverse
float x1 = cos(imuYawStart) * imuVeloFromStartXCur - sin(imuYawStart) * imuVeloFromStartZCur;
float y1 = imuVeloFromStartYCur;
float z1 = sin(imuYawStart) * imuVeloFromStartXCur + cos(imuYawStart) * imuVeloFromStartZCur;
//绕x轴旋转(-imuPitchStart),即Rx(pitch).inverse
float x2 = x1;
float y2 = cos(imuPitchStart) * y1 + sin(imuPitchStart) * z1;
float z2 = -sin(imuPitchStart) * y1 + cos(imuPitchStart) * z1;
//绕z轴旋转(-imuRollStart),即Rz(pitch).inverse
imuVeloFromStartXCur = cos(imuRollStart) * x2 + sin(imuRollStart) * y2;
imuVeloFromStartYCur = -sin(imuRollStart) * x2 + cos(imuRollStart) * y2;
imuVeloFromStartZCur = z2;
}
3).
void TransformToStartIMU(PointType *p)
作用是将当前点先转换到世界坐标系下然后再由世界坐标转换到sweep起始点坐标系下。
然后减去(代码中是加上)加减速造成的非匀速畸变的值。
//去除点云加减速产生的位移畸变
void TransformToStartIMU(PointType *p)
{
/********************************************************************************
Ry*Rx*Rz*Pl, transform point to the global frame
*********************************************************************************/
//绕z轴旋转(imuRollCur)
float x1 = cos(imuRollCur) * p->x - sin(imuRollCur) * p->y;
float y1 = sin(imuRollCur) * p->x + cos(imuRollCur) * p->y;
float z1 = p->z;
//绕x轴旋转(imuPitchCur)
float x2 = x1;
float y2 = cos(imuPitchCur) * y1 - sin(imuPitchCur) * z1;
float z2 = sin(imuPitchCur) * y1 + cos(imuPitchCur) * z1;
//绕y轴旋转(imuYawCur)
float x3 = cos(imuYawCur) * x2 + sin(imuYawCur) * z2;
float y3 = y2;
float z3 = -sin(imuYawCur) * x2 + cos(imuYawCur) * z2;
/********************************************************************************
Rz(pitch).inverse * Rx(pitch).inverse * Ry(yaw).inverse * Pg
transfrom global points to the local frame
*********************************************************************************/
//绕y轴旋转(-imuYawStart)
float x4 = cos(imuYawStart) * x3 - sin(imuYawStart) * z3;
float y4 = y3;
float z4 = sin(imuYawStart) * x3 + cos(imuYawStart) * z3;
//绕x轴旋转(-imuPitchStart)
float x5 = x4;
float y5 = cos(imuPitchStart) * y4 + sin(imuPitchStart) * z4;
float z5 = -sin(imuPitchStart) * y4 + cos(imuPitchStart) * z4;
//绕z轴旋转(-imuRollStart),然后叠加平移量
p->x = cos(imuRollStart) * x5 + sin(imuRollStart) * y5 + imuShiftFromStartXCur;
p->y = -sin(imuRollStart) * x5 + cos(imuRollStart) * y5 + imuShiftFromStartYCur;
p->z = z5 + imuShiftFromStartZCur;
}
下面计算所有点的曲率,并记录每一条线开始点与结束点在所有点中的索引:
//获得有效范围内的点的数量
cloudSize = count;
pcl::PointCloud<PointType>::Ptr laserCloud(new pcl::PointCloud<PointType>());
for (int i = 0; i < N_SCANS; i++) {//将所有的点按照线号从小到大放入一个容器
*laserCloud += laserCloudScans[i];
}
int scanCount = -1;
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;
//初始化为less flat点
cloudLabel[i] = 0;
//每个scan,只有第一个符合的点会进来,因为每个scan的点都在一起存放
if (int(laserCloud->points[i].intensity) != scanCount) {
scanCount = int(laserCloud->points[i].intensity);//控制每个scan只进入第一个点
//曲率只取同一个scan计算出来的,跨scan计算的曲率非法,排除,也即排除每个scan的前后五个点
if (scanCount > 0 && scanCount < N_SCANS) {
scanStartInd[scanCount] = i + 5;
scanEndInd[scanCount - 1] = i - 5;
}
}
}
//第一个scan曲率点有效点序从第5个开始,最后一个激光线结束点序size-5
scanStartInd[0] = 5;
scanEndInd.back() = cloudSize - 5;
不选取以下两种类型的点作为特征点:
a.与激光束平行的平面上的面点;
b.遮挡处不选取作为边界点(尽管曲率较大).
//挑选点,排除容易被斜面挡住的点以及离群点,有些点容易被斜面挡住,而离群点可能出现带有偶然性,这些情况都可能导致前后两次扫描不能被同时看到
for (int i = 5; i < cloudSize - 6; i++) {//与后一个点差值,所以减6
float diffX = laserCloud->points[i + 1].x - laserCloud->points[i].x;
float diffY = laserCloud->points[i + 1].y - laserCloud->points[i].y;
float diffZ = laserCloud->points[i + 1].z - laserCloud->points[i].z;
//计算有效曲率点与后一个点之间的距离平方和
float diff = diffX * diffX + diffY * diffY + diffZ * diffZ;
if (diff > 0.1) {//前提:两个点之间距离要大于0.1
//点的深度
float depth1 = sqrt(laserCloud->points[i].x * laserCloud->points[i].x +
laserCloud->points[i].y * laserCloud->points[i].y +
laserCloud->points[i].z * laserCloud->points[i].z);
//后一个点的深度
float depth2 = sqrt(laserCloud->points[i + 1].x * laserCloud->points[i + 1].x +
laserCloud->points[i + 1].y * laserCloud->points[i + 1].y +
laserCloud->points[i + 1].z * laserCloud->points[i + 1].z);
//按照两点的深度的比例,将深度较大的点拉回后计算距离
if (depth1 > depth2) {
diffX = laserCloud->points[i + 1].x - laserCloud->points[i].x * depth2 / depth1;
diffY = laserCloud->points[i + 1].y - laserCloud->points[i].y * depth2 / depth1;
diffZ = laserCloud->points[i + 1].z - laserCloud->points[i].z * depth2 / depth1;
//边长比也即是弧度值,若小于0.1,说明夹角比较小,斜面比较陡峭,点深度变化比较剧烈,点处在近似与激光束平行的斜面上
if (sqrt(diffX * diffX + diffY * diffY + diffZ * diffZ) / depth2 < 0.1) {//排除容易被斜面挡住的点
//该点及前面五个点(大致都在斜面上)全部置为筛选过
cloudNeighborPicked[i - 5] = 1;
cloudNeighborPicked[i - 4] = 1;
cloudNeighborPicked[i - 3] = 1;
cloudNeighborPicked[i - 2] = 1;
cloudNeighborPicked[i - 1] = 1;
cloudNeighborPicked[i] = 1;
}
} else {
diffX = laserCloud->points[i + 1].x * depth1 / depth2 - laserCloud->points[i].x;
diffY = laserCloud->points[i + 1].y * depth1 / depth2 - laserCloud->points[i].y;
diffZ = laserCloud->points[i + 1].z * depth1 / depth2 - laserCloud->points[i].z;
if (sqrt(diffX * diffX + diffY * diffY + diffZ * diffZ) / depth1 < 0.1) {
cloudNeighborPicked[i + 1] = 1;
cloudNeighborPicked[i + 2] = 1;
cloudNeighborPicked[i + 3] = 1;
cloudNeighborPicked[i + 4] = 1;
cloudNeighborPicked[i + 5] = 1;
cloudNeighborPicked[i + 6] = 1;
}
}
}
float diffX2 = laserCloud->points[i].x - laserCloud->points[i - 1].x;
float diffY2 = laserCloud->points[i].y - laserCloud->points[i - 1].y;
float diffZ2 = laserCloud->points[i].z - laserCloud->points[i - 1].z;
//与前一个点的距离平方和
float diff2 = diffX2 * diffX2 + diffY2 * diffY2 + diffZ2 * diffZ2;
//点深度的平方和
float dis = laserCloud->points[i].x * laserCloud->points[i].x
+ laserCloud->points[i].y * laserCloud->points[i].y
+ laserCloud->points[i].z * laserCloud->points[i].z;
//与前后点的平方和都大于深度平方和的万分之二,这些点视为离群点,包括陡斜面上的点,强烈凸凹点和空旷区域中的某些点,置为筛选过,弃用
if (diff > 0.0002 * dis && diff2 > 0.0002 * dis) {
cloudNeighborPicked[i] = 1;
}
}
然后提取平面点和角点,16条线,每条线分六段,每段中根据曲率提取2个sharp, 20个lesssharp; 4个flat,剩余的点都归入less flat,由于less flat 点数量较多,每条线执行一次体素滤波:
pcl::PointCloud<PointType> cornerPointsSharp;
pcl::PointCloud<PointType> cornerPointsLessSharp;
pcl::PointCloud<PointType> surfPointsFlat;
pcl::PointCloud<PointType> surfPointsLessFlat;
//将每条线上的点分入相应的类别:边沿点和平面点
for (int i = 0; i < N_SCANS; i++) {
pcl::PointCloud<PointType>::Ptr surfPointsLessFlatScan(new pcl::PointCloud<PointType>);
//将每个scan的曲率点分成6等份处理,确保周围都有点被选作特征点
for (int j = 0; j < 6; j++) {
//六等份起点:sp = scanStartInd + (scanEndInd - scanStartInd)*j/6
int sp = (scanStartInd[i] * (6 - j) + scanEndInd[i] * j) / 6;
//六等份终点:ep = scanStartInd - 1 + (scanEndInd - scanStartInd)*(j+1)/6
int ep = (scanStartInd[i] * (5 - j) + scanEndInd[i] * (j + 1)) / 6 - 1;
//按曲率从小到大冒泡排序
for (int k = sp + 1; k <= ep; k++) {
for (int l = k; l >= sp + 1; l--) {
//如果后面曲率点小于前面,则交换 (每段后面曲率大,前面曲率小)
if (cloudCurvature[cloudSortInd[l]] < cloudCurvature[cloudSortInd[l - 1]]) {
int temp = cloudSortInd[l - 1];
cloudSortInd[l - 1] = cloudSortInd[l];
cloudSortInd[l] = temp;
}
}
}
//挑选每个分段的曲率很大和比较大的点
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) {//挑选曲率最大的前2个点放入sharp点集合
cloudLabel[ind] = 2;//2代表点曲率很大
cornerPointsSharp.push_back(laserCloud->points[ind]);
cornerPointsLessSharp.push_back(laserCloud->points[ind]);
} else if (largestPickedNum <= 20) {//挑选曲率最大的前20个点放入less sharp点集合
cloudLabel[ind] = 1;//1代表点曲率比较尖锐
cornerPointsLessSharp.push_back(laserCloud->points[ind]);
} else {
break;
}
cloudNeighborPicked[ind] = 1;//筛选标志置位
//将曲率比较大的点的前后各5个连续距离比较近的点筛选出去,防止特征点聚集,使得特征点在每个方向上尽量分布均匀
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;//-1代表曲率很小的点
surfPointsFlat.push_back(laserCloud->points[ind]);
smallestPickedNum++;
if (smallestPickedNum >= 4) {//只选最小的四个,剩下的Label==0,就都是曲率比较小的
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;
}
}
}
//将剩余的点(包括之前被排除的点)全部归入平面点中less flat类别中
for (int k = sp; k <= ep; k++) {
if (cloudLabel[k] <= 0) {
surfPointsLessFlatScan->push_back(laserCloud->points[k]);
}
}
}
//由于less flat点最多,对每个分段less flat的点进行体素栅格滤波
pcl::PointCloud<PointType> surfPointsLessFlatScanDS;
pcl::VoxelGrid<PointType> downSizeFilter;
downSizeFilter.setInputCloud(surfPointsLessFlatScan);
downSizeFilter.setLeafSize(0.2, 0.2, 0.2);
downSizeFilter.filter(surfPointsLessFlatScanDS);
//less flat点汇总
surfPointsLessFlat += surfPointsLessFlatScanDS;
}
发布去除非匀速运动畸变后的整帧点云,四种特征点的消息,以及imu得到的起始点欧拉角、sweep最后一个点的欧拉角、sweep最后一个点相对于第一个点的畸变位移和速度
//publich消除非匀速运动畸变后的所有的点
sensor_msgs::PointCloud2 laserCloudOutMsg;
pcl::toROSMsg(*laserCloud, laserCloudOutMsg);
laserCloudOutMsg.header.stamp = laserCloudMsg->header.stamp;
laserCloudOutMsg.header.frame_id = "/camera";
pubLaserCloud.publish(laserCloudOutMsg);
//publich消除非匀速运动畸变后的平面点和边沿点
sensor_msgs::PointCloud2 cornerPointsSharpMsg;
pcl::toROSMsg(cornerPointsSharp, cornerPointsSharpMsg);
cornerPointsSharpMsg.header.stamp = laserCloudMsg->header.stamp;
cornerPointsSharpMsg.header.frame_id = "/camera";
pubCornerPointsSharp.publish(cornerPointsSharpMsg);
sensor_msgs::PointCloud2 cornerPointsLessSharpMsg;
pcl::toROSMsg(cornerPointsLessSharp, cornerPointsLessSharpMsg);
cornerPointsLessSharpMsg.header.stamp = laserCloudMsg->header.stamp;
cornerPointsLessSharpMsg.header.frame_id = "/camera";
pubCornerPointsLessSharp.publish(cornerPointsLessSharpMsg);
sensor_msgs::PointCloud2 surfPointsFlat2;
pcl::toROSMsg(surfPointsFlat, surfPointsFlat2);
surfPointsFlat2.header.stamp = laserCloudMsg->header.stamp;
surfPointsFlat2.header.frame_id = "/camera";
pubSurfPointsFlat.publish(surfPointsFlat2);
sensor_msgs::PointCloud2 surfPointsLessFlat2;
pcl::toROSMsg(surfPointsLessFlat, surfPointsLessFlat2);
surfPointsLessFlat2.header.stamp = laserCloudMsg->header.stamp;
surfPointsLessFlat2.header.frame_id = "/camera";
pubSurfPointsLessFlat.publish(surfPointsLessFlat2);
//publich IMU消息,由于循环到了最后,因此是Cur都是代表最后一个点,即最后一个点的欧拉角,畸变位移及一个点云周期增加的速度
pcl::PointCloud<pcl::PointXYZ> imuTrans(4, 1);
//起始点欧拉角
imuTrans.points[0].x = imuPitchStart;
imuTrans.points[0].y = imuYawStart;
imuTrans.points[0].z = imuRollStart;
//最后一个点的欧拉角
imuTrans.points[1].x = imuPitchCur;
imuTrans.points[1].y = imuYawCur;
imuTrans.points[1].z = imuRollCur;
//最后一个点相对于第一个点的畸变位移和速度
imuTrans.points[2].x = imuShiftFromStartXCur;
imuTrans.points[2].y = imuShiftFromStartYCur;
imuTrans.points[2].z = imuShiftFromStartZCur;
imuTrans.points[3].x = imuVeloFromStartXCur;
imuTrans.points[3].y = imuVeloFromStartYCur;
imuTrans.points[3].z = imuVeloFromStartZCur;
sensor_msgs::PointCloud2 imuTransMsg;
pcl::toROSMsg(imuTrans, imuTransMsg);
imuTransMsg.header.stamp = laserCloudMsg->header.stamp;
imuTransMsg.header.frame_id = "/camera";
pubImuTrans.publish(imuTransMsg);
imuHandler
我们先总体说一下imuHandler()函数做了些什么。首先为什么要用IMU?可能很多人认为IMU的作用类似于cartographer中提供位姿的先验信息。但LOAM中并没有使用IMU提供下一时刻位姿的先验信息,而是利用IMU去除激光传感器在运动过程中非匀速(加减速)部分造成的误差(运动畸变)。为什么这样做呢?因为LOAM是基于匀速运动的假设,但实际中激光传感器的运动肯定不是匀速的,因此使用IMU来去除非匀速运动部分造成的误差,以满足匀速运动的假设。
那么imuHandler()函数具体做了些什么呢?我们知道IMU的数据可以提供给我们IMU坐标系三个轴相对于世界坐标系的欧拉角和三个轴上的加速度。但由于加速度受到重力的影响所以首先得去除重力影响。在去除重力影响后我们想要获得IMU在世界坐标系下的运动,因此根据欧拉角就可以将IMU三轴上的加速度转换到世界坐标系下的加速度。 然后根据加速度利用 公式s1 = s2+ vt + 1/2at*t来计算位移。因此我们可以求出每一帧IMU数据在世界坐标系下对应的位移和速度。 至此imuHandler()函数就完成了它的使命。
接收imu信息,执行imuHandler回调函数:
//接收imu消息,imu坐标系为x轴向前,y轴向左,z轴向上的右手坐标系
void imuHandler(const sensor_msgs::Imu::ConstPtr& imuIn)
{
double roll, pitch, yaw;
tf::Quaternion orientation;
//convert Quaternion msg to Quaternion
tf::quaternionMsgToTF(imuIn->orientation, orientation);
//This will get the roll pitch and yaw from the matrix about fixed axes X, Y, Z respectively.
//That's R = Rz(yaw)*Ry(pitch)*Rx(roll).
//Here roll pitch yaw is in the global frame
tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
//减去重力的影响,求出xyz方向的加速度实际值,并进行坐标轴交换,统一到z轴向前,x轴向左的右手坐标系, 交换过后RPY对应fixed axes ZXY(RPY---ZXY)。Now R = Ry(yaw)*Rx(pitch)*Rz(roll).
float accX = imuIn->linear_acceleration.y - sin(roll) * cos(pitch) * 9.81;
float accY = imuIn->linear_acceleration.z - cos(roll) * cos(pitch) * 9.81;
float accZ = imuIn->linear_acceleration.x + sin(pitch) * 9.81;
//循环移位效果,形成环形数组
imuPointerLast = (imuPointerLast + 1) % imuQueLength;
imuTime[imuPointerLast] = imuIn->header.stamp.toSec();
imuRoll[imuPointerLast] = roll;
imuPitch[imuPointerLast] = pitch;
imuYaw[imuPointerLast] = yaw;
imuAccX[imuPointerLast] = accX;
imuAccY[imuPointerLast] = accY;
imuAccZ[imuPointerLast] = accZ;
AccumulateIMUShift();
}
imu传感器得到的角速度、加速度为载体系相对于惯性系(世界坐标系)的角速度、加速度在载体系下的投影(坐标)
1) 将sensor_msgs::Imu信息中的四元数信息转存为tf中的四元数信息,然后再使用getRPY得到imu坐标系下roll、pitch&yaw信息
2)消除重力影响,并将IMU坐标系(x前y左z上)下数据转化到 z前x左y上坐标系
imu坐标系下旋转矩阵:
R = Rz(yaw)*Ry(pitch)*Rx(roll)
.
重力的在imu中读数
[0,0,9.8]
(自由落体读数为0)
去除重力即加上
[0,0,-9.8]
,
其在原坐标系下分量为
[0,0,−9.8] = R∗[x,y,z](即 RT ∗ [ 0, 0, − 9.8] = [x,y,z])
可以得到在x前,y左,z上的右手系下 x , y , z 的加速度
[x,y,z]=[9.8sinβ,−9.8sinαcosβ,−9.8cosβcosα]
其中 α = roll, β=pitch
最后交换坐标系z前x左y上:x变为z,y变为x,z变为y,减去重力得各个轴加速度 :
float accX = imuIn->linear_acceleration.y - sin(roll) * cos(pitch) * 9.81;
float accY = imuIn->linear_acceleration.z - cos(roll) * cos(pitch) * 9.81;
float accZ = imuIn->linear_acceleration.x + sin(pitch) * 9.81;
3)保存每一帧imu数据的信息(时间,IMU坐标系下的旋转角度roll,pitch,yaw,IMU下变换坐标系后的加速度,最后调用
AccumulateIMUShift()
计算一帧imu数据在世界坐标系下的位移和速度)
4)
AccumulateIMUShift()
:这个函数作用就是将加速度转换到世界坐标系下,假设每帧IMU之间匀加速直线运动,计算当前时刻车在世界坐标系下的位置、速度。
(因为坐标系已经转化与世界坐标系一致,所以角度就代表当前位置坐标系到世界坐标系下的旋转)
//积分速度与位移
void AccumulateIMUShift()
{
float roll = imuRoll[imuPointerLast];
float pitch = imuPitch[imuPointerLast];
float yaw = imuYaw[imuPointerLast];
float accX = imuAccX[imuPointerLast];
float accY = imuAccY[imuPointerLast];
float accZ = imuAccZ[imuPointerLast];
//将当前时刻的加速度值绕交换过的ZXY固定轴(原XYZ)分别旋转(roll, pitch, yaw)角,转换得到世界坐标系下的加速度值(right hand rule)
//绕z轴旋转(roll)
float x1 = cos(roll) * accX - sin(roll) * accY;
float y1 = sin(roll) * accX + cos(roll) * accY;
float z1 = accZ;
//绕x轴旋转(pitch)
float x2 = x1;
float y2 = cos(pitch) * y1 - sin(pitch) * z1;
float z2 = sin(pitch) * y1 + cos(pitch) * z1;
//绕y轴旋转(yaw)
accX = cos(yaw) * x2 + sin(yaw) * z2;
accY = y2;
accZ = -sin(yaw) * x2 + cos(yaw) * z2;
//上一个imu点
int imuPointerBack = (imuPointerLast + imuQueLength - 1) % imuQueLength;
//上一个点到当前点所经历的时间,即计算imu测量周期
double timeDiff = imuTime[imuPointerLast] - imuTime[imuPointerBack];
//要求imu的频率至少比lidar高,这样的imu信息才使用,后面校正也才有意义
if (timeDiff < scanPeriod) {//(隐含从静止开始运动)
//求每个imu时间点的位移与速度,两点之间视为匀加速直线运动
// 推算当前时刻的位置信息
imuShiftX[imuPointerLast] = imuShiftX[imuPointerBack] + imuVeloX[imuPointerBack] * timeDiff
+ accX * timeDiff * timeDiff / 2;
imuShiftY[imuPointerLast] = imuShiftY[imuPointerBack] + imuVeloY[imuPointerBack] * timeDiff
+ accY * timeDiff * timeDiff / 2;
imuShiftZ[imuPointerLast] = imuShiftZ[imuPointerBack] + imuVeloZ[imuPointerBack] * timeDiff
+ accZ * timeDiff * timeDiff / 2;
// 推算当前时刻的速度信息
imuVeloX[imuPointerLast] = imuVeloX[imuPointerBack] + accX * timeDiff;
imuVeloY[imuPointerLast] = imuVeloY[imuPointerBack] + accY * timeDiff;
imuVeloZ[imuPointerLast] = imuVeloZ[imuPointerBack] + accZ * timeDiff;
}
}
该节点结束.