LOAM SLAM代码解析之一:scanRegistration.cpp 点云及IMU数据处理节点

前言

       LOAM的源码有好几个版本,对应于不同的硬件设备。由于大多数三维激光使用velodyne,所以我主要看的是Velodyne16线程激光的这个版本。并且KITTI里也有Velodyne16线程的激光数据,可以用来对程序进行测试。代码的结构和论文讲的一致,主要分为四个.cpp 文件分别对应下图中的四个部分。今天先看一下Point Cloud Regisration这部分的源码,也就是scanRegistration.cpp这个文件里的代码。

LOAM SLAM代码解析之一:scanRegistration.cpp 点云及IMU数据处理节点_第1张图片

      先说一下这个节点的流程,主要做了什么;然后结合代码一步一步分析。这个节点一共接收两个话题消息并发布六个话题消息。接收的两个话题分布是激光点云消息和IMU数据消息分别对应两个回调函数laserCloudHandler和imuHandler。建议读者先从imuHandler()函数看起,因为laserCloudHandler()函数会用到这个函数的结果。

main函数

       首先从main函数看起,这个main函数很简单,都是一些ros里面定义话题订阅器和发布器。这个节点一共订阅了两个话题的消息,发布六个话题的消息,没有什么难点,如果看不懂的读者需要首先复习一下ros的基本知识了。

int main(int argc, char** argv)
{
  ros::init(argc, argv, "scanRegistration");
  ros::NodeHandle nh;

  ros::Subscriber subLaserCloud = nh.subscribe 
                                  ("/velodyne_points", 2, laserCloudHandler);

  ros::Subscriber subImu = nh.subscribe ("/imu/data", 50, imuHandler);

  pubLaserCloud = nh.advertise
                                 ("/velodyne_cloud_2", 2);

  pubCornerPointsSharp = nh.advertise
                                        ("/laser_cloud_sharp", 2);

  pubCornerPointsLessSharp = nh.advertise
                                            ("/laser_cloud_less_sharp", 2);

  pubSurfPointsFlat = nh.advertise
                                       ("/laser_cloud_flat", 2);

  pubSurfPointsLessFlat = nh.advertise
                                           ("/laser_cloud_less_flat", 2);

  pubImuTrans = nh.advertise ("/imu_trans", 5);

  ros::spin();

  return 0;
}

imuHandler()函数

       我们先总体说一下imuHandler()函数做了些什么。首先为什么要用IMU?可能很多人认为IMU的作用类似于cartographer中提供位姿的先验信息。但LOAM中并没有使用IMU提供下一时刻位姿的先验信息,而是利用IMU去除激光传感器在运动过程中非匀速(加减速)部分造成的误差(运动畸变)。为什么这样做呢?因为LOAM是基于匀速运动的假设,但实际中激光传感器的运动肯定不是匀速的,因此使用IMU来去除非匀速运动部分造成的误差,以满足匀速运动的假设。

       那么imuHandler()函数具体做了些什么呢?我们知道IMU的数据可以提供给我们IMU坐标系三个轴相对于世界坐标系的欧拉角和三个轴上的加速度。但由于加速度受到重力的影响所以首先得去除重力影响。在去除重力影响后我们想要获得IMU在世界坐标系下的运动,因此根据欧拉角就可以将IMU三轴上的加速度转换到世界坐标系下的加速度。 然后根据加速度利用 公式s1 = s2+ vt + 1/2at*t来计算位移。因此我们可以求出每一帧IMU数据在世界坐标系下对应的位移和速度。 至此imuHandler()函数就完成了它的使命。

//接收imu消息,imu坐标系为x轴向前,y轴向右,z轴向上的右手坐标系
void imuHandler(const sensor_msgs::Imu::ConstPtr& imuIn)
{
  double roll, pitch, yaw;
  //定义四元数
  tf::Quaternion orientation;
  //将IMU数据中的四元数转换到定义的四元数中
  tf::quaternionMsgToTF(imuIn->orientation, orientation);
  //由四元数获得欧拉角
  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();
}

AccumulateIMUShift()函数主要用于获取每一帧IMU数据对应IMU在全局坐标系下的位移和速度。

void AccumulateIMUShift()
{
  //获得由IMUHandler函数得到该帧IMU数据的欧拉角和三轴角加速度
  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)角,转换得到世界
  //坐标系下的加速度值(右手法则)
  //绕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;
  }
}

laserCloudHandler()函数

这个函数是这个节点的主要内容了,这部分主要完成了三个功能:

一、从话题/velodyne_points中获得sensor_msgs::PointCloud2消息的点云数据,并将这些点云中的点按照其空间中与Z轴成的角度将其分类到16根激光线束中并记录线束号和获取的相对时间(也就是代码中的intensity,这个不是强度);

二、就是提前特征,遍历每个线束 上的点,求该点的曲率,通过曲率将点进行特征点分类;

三、根据IMU获得的数据去除激光传感器加减速造成的误差(也就是运动畸变)。 

函数的开头有这样的一段代码,作用就是延时,为了确保有IMU数据 后再进行点云数据的处理

if (!systemInited) {//丢弃前20个点云数据
    systemInitCount++;
    if (systemInitCount >= systemDelay) {
      systemInited = true;
    }
    return;
  }

       接下来先对点云数据进行滤波,滤除无效点。接下来记录点云的起始位置和终止位置的角度,用于计算点云数据中的每一个点在这帧点云数据中的相对位置,结合点云获取时的时间和扫描周期就可以得到每一个点获取时的时间,为后面使用IMU数据进行插值做准备。

 //记录每个scan有曲率的点的开始和结束索引
  std::vector scanStartInd(N_SCANS, 0);
  std::vector scanEndInd(N_SCANS, 0);
  
  //当前点云时间
  double timeScanCur = laserCloudMsg->header.stamp.toSec();
  pcl::PointCloud laserCloudIn;
  //消息转换成pcl数据存放
  pcl::fromROSMsg(*laserCloudMsg, laserCloudIn);
  std::vector 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;

  //结束方位角与开始方位角差值控制在(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;
  }

接下来就将点云中的点归类到16根激光线束中。这里需要注意线束号是怎么确定的。

//lidar扫描线是否旋转过半
  bool halfPassed = false;
  int count = cloudSize;
  PointType point;
  std::vector > laserCloudScans(N_SCANS);
  for (int i = 0; i < cloudSize; i++) {
    //这里需要注意!LOAM中的坐标系和velodyne激光雷达坐标系不一样需要坐标轴转换,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;
      }

      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;
      } 
    }

这里就开始使用IMU数据进行插值计算点云的中点的位置,消除由于非匀速运动造成的运动畸变。

//-0.5 < relTime < 1.5(点旋转的角度与整个周期旋转角度的比率, 即点云中点的相对时间)
    float relTime = (ori - startOri) / (endOri - startOri);
    //点强度=线号+点相对时间(即一个整数+一个小数,整数部分是线号,小数部分是该点的相对时间),匀
    //速扫描:根据当前扫描的角度和扫描周期计算相对扫描起始位置的时间
    point.intensity = scanID + scanPeriod * relTime;

    //点时间=点云时间+周期时间
    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);//将每个补偿矫正的点放入对应线号的容器
  }

       按照代码的流程我们来看函数ShiftToStartIMU(pointTime)具体做了些什么。我们已经知道了每个点在世界坐标系下的位置,而我们想要求的是这一帧数据中该点相对于起始点由于加减速造成的运动畸变。因此我们首先要求出世界坐标系下的加减速造成的运动畸变,然后将运动畸变值经过绕y、x、z轴旋转后得到起始点坐标系下的运动畸变。这里的坐标系一定要搞清楚为什么要放的起始点的坐标系下。

//计算局部坐标系下点云中的点相对第一个开始点的由于加减速运动产生的位移畸变
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;
}

       接下来就是VeloToStartIMU()函数,这个函数流程和上一个函数大致相同。它的作用就是求当前点的速度相对于点云起始点的速度畸变,先计算全局坐标系下的然后再转换到起始点的坐标系中。 

//计算局部坐标系下点云中的点相对第一个开始点由于加减速产生的的速度畸变(增量)
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;
}

       接下来就是TransformToStartIMU(PointType *p)函数作用是将当前点先转换到世界坐标系下然后再由世界坐标转换到点云起始点坐标系下。 然后减去加减速造成的非匀速畸变的值。

//去除点云加减速产生的位移畸变
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;
}

到这里就完成了点云数据中非匀速造成的运动畸变的去除。

       接下来就是进行特征点提取了。怎么提取特征点呢,论文了提出了用曲率的方法,但代码中没有使用论文中的公式,只是使用当前点的前后5个点差值的平方来计算曲率。

  //获得有效范围内的点的数量
  cloudSize = count;

  pcl::PointCloud::Ptr laserCloud(new pcl::PointCloud());
  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;

       接下来就要去除不和要求的点了,先看看论文中对不合要求点的要求:第一种点首先是不能与激光线接近于平行的点,为什么呢,因为这些点在这一帧数据 中可以看到,但是下一帧数据可能就看不到了 也就没有 办法匹配了。第二种是可能会遮挡的点同样这些点可能也会在下一帧数据中看不到。因此这两类点都必须要去除掉。

LOAM SLAM代码解析之一:scanRegistration.cpp 点云及IMU数据处理节点_第2张图片

 

       代码中首先是去除第二类的点,也就是可能会遮挡的点。去除的方法也很简单就是计算相邻两点的深度差,差的多的就可能是发生遮挡的点了,然后再计算两点间的角度,角度小于设定阈值则认为是可能发生遮挡的点,然后再把深度大的点的一侧五个点设为处理过的点,也就是认为这些点中不存在特征点。  

  //挑选点,排除容易被斜面挡住的点以及离群点,有些点容易被斜面挡住,而离群点可能出现带有偶然性,这些情况都可能导致前后两次扫描不能被同时看到
  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;
    }

接下来开始按曲率对特征点进行排序

  pcl::PointCloud cornerPointsSharp;
  pcl::PointCloud cornerPointsLessSharp;
  pcl::PointCloud surfPointsFlat;
  pcl::PointCloud surfPointsLessFlat;

  //将每条线上的点分入相应的类别:边沿点和平面点
  for (int i = 0; i < N_SCANS; i++) {
    pcl::PointCloud::Ptr surfPointsLessFlatScan(new pcl::PointCloud);
    //将每个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;
          }
        }
      }

接下来开始对特征点进行分类

          //将曲率比较大的点的前后各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 surfPointsLessFlatScanDS;
    pcl::VoxelGrid downSizeFilter;
    downSizeFilter.setInputCloud(surfPointsLessFlatScan);
    downSizeFilter.setLeafSize(0.2, 0.2, 0.2);
    downSizeFilter.filter(surfPointsLessFlatScanDS);

    //less flat点汇总
    surfPointsLessFlat += surfPointsLessFlatScanDS;
  }

之后就是将不同的特征点打包成消息发送出去。

//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 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);
}

到此这个节点所有的代码就介绍完了。

你可能感兴趣的:(LOAM SLAM代码解析之一:scanRegistration.cpp 点云及IMU数据处理节点)