1. 程式人生 > 其它 >LOAM學習-程式碼解析(三)特徵點運動估計 laserOdometry

LOAM學習-程式碼解析(三)特徵點運動估計 laserOdometry

技術標籤:SLAMloamslam

LOAM學習-程式碼解析(三)特徵點運動估計 laserOdometry


前言

前兩篇文章LOAM學習-程式碼解析(一)點雲資料配準LOAM學習-程式碼解析(二)點雲資料配準 scanRegistration,對點雲資料配準的原始碼進行詳細完整的即系,這裡繼續LOAM的程式碼解析工作。

LOAM程式碼(帶中文註釋)的地址:https://github.com/cuitaixiang/LOAM_NOTED

LOAM程式碼(帶中文註釋)的百度網盤連結:https://pan.baidu.com/s/1tVSNBxNQrxKJyd5c9mWFWw 提取碼: wwxr

LOAM論文的百度網盤連結: https://pan.baidu.com/s/10ahqg8O3G2-xOt9QZ1GuEQ 提取碼: hnri

LOAM流程:
在這裡插入圖片描述
從LOAM流程圖上可一看出,完成點雲配準之後,需要進行鐳射雷達里程計的計算。


一、初始化

設定點雲週期,lidar從特徵點中估計運動頻率為10Hz,因此點雲週期為0.1s。

const float scanPeriod = 0.1;

傳送資料給laser Mapping的頻率為 1HZ,因此設定資料傳送週期為1s。

const int skipFrameNum = 1;
bool systemInited = false;

設定時間戳資訊

double timeCornerPointsSharp = 0;
double timeCornerPointsLessSharp = 0;
double timeSurfPointsFlat = 0;
double timeSurfPointsLessFlat = 0;
double timeLaserCloudFullRes = 0;
double timeImuTrans = 0;

設定訊息接收標誌

bool newCornerPointsSharp = false;
bool newCornerPointsLessSharp = false; bool newSurfPointsFlat = false; bool newSurfPointsLessFlat = false; bool newLaserCloudFullRes = false; bool newImuTrans = false;

接收scanRegistration的資訊

//獲得尖銳點
pcl::PointCloud<PointType>::Ptr cornerPointsSharp(new pcl::PointCloud<PointType>());
//獲得較少的尖銳點
pcl::PointCloud<PointType>::Ptr cornerPointsLessSharp(new pcl::PointCloud<PointType>());
//獲得平面點
pcl::PointCloud<PointType>::Ptr surfPointsFlat(new pcl::PointCloud<PointType>());
//獲得更少的平面點 
pcl::PointCloud<PointType>::Ptr surfPointsLessFlat(new pcl::PointCloud<PointType>());
//最後一幀的尖銳點
pcl::PointCloud<PointType>::Ptr laserCloudCornerLast(new pcl::PointCloud<PointType>());
//最後一幀的平面點
pcl::PointCloud<PointType>::Ptr laserCloudSurfLast(new pcl::PointCloud<PointType>());
//儲存前一個節點發過來的未經處理過的特徵點
pcl::PointCloud<PointType>::Ptr laserCloudOri(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr coeffSel(new pcl::PointCloud<PointType>());
//獲得所有點
pcl::PointCloud<PointType>::Ptr laserCloudFullRes(new pcl::PointCloud<PointType>());
//接收imu資訊
pcl::PointCloud<pcl::PointXYZ>::Ptr imuTrans(new pcl::PointCloud<pcl::PointXYZ>());
//用最後一幀的較少尖銳點建立kd樹
pcl::KdTreeFLANN<PointType>::Ptr kdtreeCornerLast(new pcl::KdTreeFLANN<PointType>());
//用最後一幀較少的平面點建立kd樹
pcl::KdTreeFLANN<PointType>::Ptr kdtreeSurfLast(new pcl::KdTreeFLANN<PointType>());

設定計數標誌

int laserCloudCornerLastNum;
int laserCloudSurfLastNum;

設定角點和平面點變數

//unused
int pointSelCornerInd[40000];
//儲存搜尋到的2個角點索引
float pointSearchCornerInd1[40000];
float pointSearchCornerInd2[40000];

//unused
int pointSelSurfInd[40000];
//儲存搜尋到的3個平面點索引
float pointSearchSurfInd1[40000];
float pointSearchSurfInd2[40000];
float pointSearchSurfInd3[40000];

設定狀態轉移量

//當前幀相對上一幀的狀態轉移量,in the local frame
float transform[6] = {0};
//當前幀相對於第一幀的狀態轉移量,in the global frame
float transformSum[6] = {0};

設定點雲的尤拉角、畸變位移、畸變速度

//點雲第一個點的RPY
float imuRollStart = 0, imuPitchStart = 0, imuYawStart = 0;
//點雲最後一個點的RPY
float imuRollLast = 0, imuPitchLast = 0, imuYawLast = 0;
//點雲最後一個點相對於第一個點由於加減速產生的畸變位移
float imuShiftFromStartX = 0, imuShiftFromStartY = 0, imuShiftFromStartZ = 0;
//點雲最後一個點相對於第一個點由於加減速產生的畸變速度
float imuVeloFromStartX = 0, imuVeloFromStartY = 0, imuVeloFromStartZ = 0;

二、去除位移畸變 TransformToStart TransformToEnd

將當前幀點雲TransformToStart和將上一幀點雲TransformToEnd的作用:去除畸變,並將兩幀點雲資料統一到同一個座標系下計算。

當前點雲中的點相對第一個點去除因勻速運動產生的畸變,效果相當於得到在點雲掃描開始位置靜止掃描得到的點雲。

在這一部分中,要回顧scanRegistration.cpp中intensity的計算程式碼,是由scanID和scanPeriod * relTime兩部分組成。而relTime是點旋轉的角度與整個週期旋轉角度的比率, 即點雲中點的相對時間。

// scanRegistration.cpp 371-374
//-0.5 < relTime < 1.5(點旋轉的角度與整個週期旋轉角度的比率, 即點雲中點的相對時間)
float relTime = (ori - startOri) / (endOri - startOri);
//點強度=線號+點相對時間(即一個整數+一個小數,整數部分是線號,小數部分是該點的相對時間),勻速掃描:根據當前掃描的角度和掃描週期計算相對掃描起始位置的時間
//掃描週期, velodyne頻率10Hz,週期0.1s,scanPeriod=0.1
point.intensity = scanID + scanPeriod * relTime;

插值係數的計算公式如下,感覺作者這裡寫的很比較繞,實際上計算的就是點旋轉的角度與整個週期旋轉角度的比率,即點的相對時間。
s = F p e r i o d ∗ ( I p o i n t − i n t ( I p o i n t ) ) = F p e r i o d ∗ T p e r i o d ∗ T r e l = T r e l s = F_{period}*(I_{point}-int(I_{point})) =F_{period}*T_{period}*T_{rel}=T_{rel} s=Fperiod(Ipointint(Ipoint))=FperiodTperiodTrel=Trel

s = T r e l = O r i − O r i s t a r t O r i e n d − O r i s t a r t s = T_{rel}=\frac{Ori-Ori_{start}}{Ori_{end}-Ori_{start}} s=Trel=OriendOristartOriOristart

這裡需要重新瞭解旋轉矩陣,由區域性座標系轉換到世界座標系。

[ x y z ] T = [ x p o i n t y p o i n t z p o i n t ] T R z ( γ ) R x ( α ) R y ( β ) \begin{bmatrix} x\\ y\\ z\end{bmatrix}^T=\begin{bmatrix} x_{point}\\ y_{point}\\ z_{point}\end{bmatrix}^TR_z(γ)R_x(α) R_y(β) xyzT=xpointypointzpointTRz(γ)Rx(α)Ry(β)

R y ( β ) = [ c o s β 0 s i n β 0 1 0 − s i n β 0 c o s β ] R_y(β) = \begin{bmatrix} cosβ & 0 & sinβ\\ 0 & 1 & 0\\ -sinβ & 0 & cosβ \end{bmatrix} Ry(β)=cosβ0sinβ010sinβ0cosβ

R x ( α ) = [ 1 0 0 0 c o s α − s i n α 0 s i n α c o s α ] R_x(α)=\begin{bmatrix} 1 & 0 & 0\\ 0 & cosα & -sinα\\ 0 & sinα& cosα \end{bmatrix} Rx(α)=1000cosαsinα0sinαcosα

R z ( γ ) = [ c o s γ − s i n γ 0 s i n γ c o s γ 0 0 0 1 ] R_z(γ)=\begin{bmatrix} cosγ & -sinγ & 0\\ sinγ & cosγ & 0\\ 0 & 0 & 1 \end{bmatrix} Rz(γ)=cosγsinγ0sinγcosγ0001

//當前點雲中的點相對第一個點去除因勻速運動產生的畸變,效果相當於得到在點雲掃描開始位置靜止掃描得到的點雲
void TransformToStart(PointType const * const pi, PointType * const po)
{
  //插值係數計算,雲中每個點的相對時間/點雲週期10
  float s = 10 * (pi->intensity - int(pi->intensity));

  //線性插值:根據每個點在點雲中的相對位置關係,乘以相應的旋轉平移係數
  float rx = s * transform[0];
  float ry = s * transform[1];
  float rz = s * transform[2];
  float tx = s * transform[3];
  float ty = s * transform[4];
  float tz = s * transform[5];

  //平移後繞z軸旋轉(-rz)
  float x1 = cos(rz) * (pi->x - tx) + sin(rz) * (pi->y - ty);
  float y1 = -sin(rz) * (pi->x - tx) + cos(rz) * (pi->y - ty);
  float z1 = (pi->z - tz);

  //繞x軸旋轉(-rx)
  float x2 = x1;
  float y2 = cos(rx) * y1 + sin(rx) * z1;
  float z2 = -sin(rx) * y1 + cos(rx) * z1;

  //繞y軸旋轉(-ry)
  po->x = cos(ry) * x2 - sin(ry) * z2;
  po->y = y2;
  po->z = sin(ry) * x2 + cos(ry) * z2;
  po->intensity = pi->intensity;
}

TransformToEnd函式中,需要將點在上一幀時刻區域性座標系轉換到世界座標系,再由世界座標系轉換到上一幀時刻區域性座標系。接著平移imu位移畸變值,再將在區域性座標系轉換到世界座標系,再由世界座標系轉換到區域性座標系。

這裡寫的程式碼實在是太繞了,我暫時不是很能理解,為什麼要進行四次轉換…

//將上一幀點雲中的點相對結束位置去除因勻速運動產生的畸變,效果相當於得到在點雲掃描結束位置靜止掃描得到的點雲
void TransformToEnd(PointType const * const pi, PointType * const po)
{
  //插值係數計算
  float s = 10 * (pi->intensity - int(pi->intensity));

  float rx = s * transform[0];
  float ry = s * transform[1];
  float rz = s * transform[2];
  float tx = s * transform[3];
  float ty = s * transform[4];
  float tz = s * transform[5];

  //平移後繞z軸旋轉(-rz)
  float x1 = cos(rz) * (pi->x - tx) + sin(rz) * (pi->y - ty);
  float y1 = -sin(rz) * (pi->x - tx) + cos(rz) * (pi->y - ty);
  float z1 = (pi->z - tz);

  //繞x軸旋轉(-rx)
  float x2 = x1;
  float y2 = cos(rx) * y1 + sin(rx) * z1;
  float z2 = -sin(rx) * y1 + cos(rx) * z1;

  //繞y軸旋轉(-ry)
  float x3 = cos(ry) * x2 - sin(ry) * z2;
  float y3 = y2;
  float z3 = sin(ry) * x2 + cos(ry) * z2;//求出了相對於起始點校正的座標

  rx = transform[0];
  ry = transform[1];
  rz = transform[2];
  tx = transform[3];
  ty = transform[4];
  tz = transform[5];

  //繞y軸旋轉(ry)
  float x4 = cos(ry) * x3 + sin(ry) * z3;
  float y4 = y3;
  float z4 = -sin(ry) * x3 + cos(ry) * z3;

  //繞x軸旋轉(rx)
  float x5 = x4;
  float y5 = cos(rx) * y4 - sin(rx) * z4;
  float z5 = sin(rx) * y4 + cos(rx) * z4;

  //繞z軸旋轉(rz),再平移
  float x6 = cos(rz) * x5 - sin(rz) * y5 + tx;
  float y6 = sin(rz) * x5 + cos(rz) * y5 + ty;
  float z6 = z5 + tz;

  //平移後繞z軸旋轉(imuRollStart)
  float x7 = cos(imuRollStart) * (x6 - imuShiftFromStartX) 
           - sin(imuRollStart) * (y6 - imuShiftFromStartY);
  float y7 = sin(imuRollStart) * (x6 - imuShiftFromStartX) 
           + cos(imuRollStart) * (y6 - imuShiftFromStartY);
  float z7 = z6 - imuShiftFromStartZ;

  //繞x軸旋轉(imuPitchStart)
  float x8 = x7;
  float y8 = cos(imuPitchStart) * y7 - sin(imuPitchStart) * z7;
  float z8 = sin(imuPitchStart) * y7 + cos(imuPitchStart) * z7;

  //繞y軸旋轉(imuYawStart)
  float x9 = cos(imuYawStart) * x8 + sin(imuYawStart) * z8;
  float y9 = y8;
  float z9 = -sin(imuYawStart) * x8 + cos(imuYawStart) * z8;

  //繞y軸旋轉(-imuYawLast)
  float x10 = cos(imuYawLast) * x9 - sin(imuYawLast) * z9;
  float y10 = y9;
  float z10 = sin(imuYawLast) * x9 + cos(imuYawLast) * z9;

  //繞x軸旋轉(-imuPitchLast)
  float x11 = x10;
  float y11 = cos(imuPitchLast) * y10 + sin(imuPitchLast) * z10;
  float z11 = -sin(imuPitchLast) * y10 + cos(imuPitchLast) * z10;

  //繞z軸旋轉(-imuRollLast)
  po->x = cos(imuRollLast) * x11 + sin(imuRollLast) * y11;
  po->y = -sin(imuRollLast) * x11 + cos(imuRollLast) * y11;
  po->z = z11;
  //只保留線號
  po->intensity = int(pi->intensity);
}

三、去除角度畸變

啊 這…
應該是使用旋轉矩陣進行角度畸變矯正,

//利用IMU修正旋轉量,根據起始尤拉角,當前點雲的尤拉角修正
void PluginIMURotation(float bcx, float bcy, float bcz, float blx, float bly, float blz, 
                       float alx, float aly, float alz, float &acx, float &acy, float &acz)
{
  float sbcx = sin(bcx);
  float cbcx = cos(bcx);
  float sbcy = sin(bcy);
  float cbcy = cos(bcy);
  float sbcz = sin(bcz);
  float cbcz = cos(bcz);

  float sblx = sin(blx);
  float cblx = cos(blx);
  float sbly = sin(bly);
  float cbly = cos(bly);
  float sblz = sin(blz);
  float cblz = cos(blz);

  float salx = sin(alx);
  float calx = cos(alx);
  float saly = sin(aly);
  float caly = cos(aly);
  float salz = sin(alz);
  float calz = cos(alz);

  float srx = -sbcx*(salx*sblx + calx*caly*cblx*cbly + calx*cblx*saly*sbly) 
            - cbcx*cbcz*(calx*saly*(cbly*sblz - cblz*sblx*sbly) 
            - calx*caly*(sbly*sblz + cbly*cblz*sblx) + cblx*cblz*salx) 
            - cbcx*sbcz*(calx*caly*(cblz*sbly - cbly*sblx*sblz) 
            - calx*saly*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sblz);
  acx = -asin(srx);

  float srycrx = (cbcy*sbcz - cbcz*sbcx*sbcy)*(calx*saly*(cbly*sblz - cblz*sblx*sbly) 
               - calx*caly*(sbly*sblz + cbly*cblz*sblx) + cblx*cblz*salx) 
               - (cbcy*cbcz + sbcx*sbcy*sbcz)*(calx*caly*(cblz*sbly - cbly*sblx*sblz) 
               - calx*saly*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sblz) 
               + cbcx*sbcy*(salx*sblx + calx*caly*cblx*cbly + calx*cblx*saly*sbly);
  float crycrx = (cbcz*sbcy - cbcy*sbcx*sbcz)*(calx*caly*(cblz*sbly - cbly*sblx*sblz) 
               - calx*saly*(cbly*cblz + sblx*sbly*sblz) + cblx*salx*sblz) 
               - (sbcy*sbcz + cbcy*cbcz*sbcx)*(calx*saly*(cbly*sblz - cblz*sblx*sbly) 
               - calx*caly*(sbly*sblz + cbly*cblz*sblx) + cblx*cblz*salx) 
               + cbcx*cbcy*(salx*sblx + calx*caly*cblx*cbly + calx*cblx*saly*sbly);
  acy = atan2(srycrx / cos(acx), crycrx / cos(acx));
  
  float srzcrx = sbcx*(cblx*cbly*(calz*saly - caly*salx*salz) 
               - cblx*sbly*(caly*calz + salx*saly*salz) + calx*salz*sblx) 
               - cbcx*cbcz*((caly*calz + salx*saly*salz)*(cbly*sblz - cblz*sblx*sbly) 
               + (calz*saly - caly*salx*salz)*(sbly*sblz + cbly*cblz*sblx) 
               - calx*cblx*cblz*salz) + cbcx*sbcz*((caly*calz + salx*saly*salz)*(cbly*cblz 
               + sblx*sbly*sblz) + (calz*saly - caly*salx*salz)*(cblz*sbly - cbly*sblx*sblz) 
               + calx*cblx*salz*sblz);
  float crzcrx = sbcx*(cblx*sbly*(caly*salz - calz*salx*saly) 
               - cblx*cbly*(saly*salz + caly*calz*salx) + calx*calz*sblx) 
               + cbcx*cbcz*((saly*salz + caly*calz*salx)*(sbly*sblz + cbly*cblz*sblx) 
               + (caly*salz - calz*salx*saly)*(cbly*sblz - cblz*sblx*sbly) 
               + calx*calz*cblx*cblz) - cbcx*sbcz*((saly*salz + caly*calz*salx)*(cblz*sbly 
               - cbly*sblx*sblz) + (caly*salz - calz*salx*saly)*(cbly*cblz + sblx*sbly*sblz) 
               - calx*calz*cblx*sblz);
  acz = atan2(srzcrx / cos(acx), crzcrx / cos(acx));
}

四、積累旋轉量

看不明白…

//相對於第一個點雲即原點,積累旋轉量
void AccumulateRotation(float cx, float cy, float cz, float lx, float ly, float lz, 
                        float &ox, float &oy, float &oz)
{
  float srx = cos(lx)*cos(cx)*sin(ly)*sin(cz) - cos(cx)*cos(cz)*sin(lx) - cos(lx)*cos(ly)*sin(cx);
  ox = -asin(srx);

  float srycrx = sin(lx)*(cos(cy)*sin(cz) - cos(cz)*sin(cx)*sin(cy)) + cos(lx)*sin(ly)*(cos(cy)*cos(cz) 
               + sin(cx)*sin(cy)*sin(cz)) + cos(lx)*cos(ly)*cos(cx)*sin(cy);
  float crycrx = cos(lx)*cos(ly)*cos(cx)*cos(cy) - cos(lx)*sin(ly)*(cos(cz)*sin(cy) 
               - cos(cy)*sin(cx)*sin(cz)) - sin(lx)*(sin(cy)*sin(cz) + cos(cy)*cos(cz)*sin(cx));
  oy = atan2(srycrx / cos(ox), crycrx / cos(ox));

  float srzcrx = sin(cx)*(cos(lz)*sin(ly) - cos(ly)*sin(lx)*sin(lz)) + cos(cx)*sin(cz)*(cos(ly)*cos(lz) 
               + sin(lx)*sin(ly)*sin(lz)) + cos(lx)*cos(cx)*cos(cz)*sin(lz);
  float crzcrx = cos(lx)*cos(lz)*cos(cx)*cos(cz) - cos(cx)*sin(cz)*(cos(ly)*sin(lz) 
               - cos(lz)*sin(lx)*sin(ly)) - sin(cx)*(sin(ly)*sin(lz) + cos(ly)*cos(lz)*sin(lx));
  oz = atan2(srzcrx / cos(ox), crzcrx / cos(ox));
}

五、資料處理器

這裡設定了laserCloudSharp、laserCloudLessSharp、laserCloudFlat、laserCloudLessFlat、laserCloudFullResHandler、imuTransHandler、等資料處理器(Handler)。

//資料處理器
void laserCloudSharpHandler(const sensor_msgs::PointCloud2ConstPtr& cornerPointsSharp2)
{
  timeCornerPointsSharp = cornerPointsSharp2->header.stamp.toSec();

  cornerPointsSharp->clear();
  pcl::fromROSMsg(*cornerPointsSharp2, *cornerPointsSharp);
  std::vector<int> indices;
  pcl::removeNaNFromPointCloud(*cornerPointsSharp,*cornerPointsSharp, indices);
  newCornerPointsSharp = true;
}

void laserCloudLessSharpHandler(const sensor_msgs::PointCloud2ConstPtr& cornerPointsLessSharp2)
{
  timeCornerPointsLessSharp = cornerPointsLessSharp2->header.stamp.toSec();

  cornerPointsLessSharp->clear();
  pcl::fromROSMsg(*cornerPointsLessSharp2, *cornerPointsLessSharp);
  std::vector<int> indices;
  pcl::removeNaNFromPointCloud(*cornerPointsLessSharp,*cornerPointsLessSharp, indices);
  newCornerPointsLessSharp = true;
}

void laserCloudFlatHandler(const sensor_msgs::PointCloud2ConstPtr& surfPointsFlat2)
{
  timeSurfPointsFlat = surfPointsFlat2->header.stamp.toSec();

  surfPointsFlat->clear();
  pcl::fromROSMsg(*surfPointsFlat2, *surfPointsFlat);
  std::vector<int> indices;
  pcl::removeNaNFromPointCloud(*surfPointsFlat,*surfPointsFlat, indices);
  newSurfPointsFlat = true;
}

void laserCloudLessFlatHandler(const sensor_msgs::PointCloud2ConstPtr& surfPointsLessFlat2)
{
  timeSurfPointsLessFlat = surfPointsLessFlat2->header.stamp.toSec();

  surfPointsLessFlat->clear();
  pcl::fromROSMsg(*surfPointsLessFlat2, *surfPointsLessFlat);
  std::vector<int> indices;
  pcl::removeNaNFromPointCloud(*surfPointsLessFlat,*surfPointsLessFlat, indices);
  newSurfPointsLessFlat = true;
}

//接收全部點
void laserCloudFullResHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudFullRes2)
{
  timeLaserCloudFullRes = laserCloudFullRes2->header.stamp.toSec();

  laserCloudFullRes->clear();
  pcl::fromROSMsg(*laserCloudFullRes2, *laserCloudFullRes);
  std::vector<int> indices;
  pcl::removeNaNFromPointCloud(*laserCloudFullRes,*laserCloudFullRes, indices);
  newLaserCloudFullRes = true;
}

//接收imu訊息
void imuTransHandler(const sensor_msgs::PointCloud2ConstPtr& imuTrans2)
{
  timeImuTrans = imuTrans2->header.stamp.toSec();

  imuTrans->clear();
  pcl::fromROSMsg(*imuTrans2, *imuTrans);

  //根據發來的訊息提取imu資訊
  imuPitchStart = imuTrans->points[0].x;
  imuYawStart = imuTrans->points[0].y;
  imuRollStart = imuTrans->points[0].z;

  imuPitchLast = imuTrans->points[1].x;
  imuYawLast = imuTrans->points[1].y;
  imuRollLast = imuTrans->points[1].z;

  imuShiftFromStartX = imuTrans->points[2].x;
  imuShiftFromStartY = imuTrans->points[2].y;
  imuShiftFromStartZ = imuTrans->points[2].z;

  imuVeloFromStartX = imuTrans->points[3].x;
  imuVeloFromStartY = imuTrans->points[3].y;
  imuVeloFromStartZ = imuTrans->points[3].z;

  newImuTrans = true;
}

六、主函式

這裡的程式碼非常長,我留到下一章再繼續解析吧。

結語

至此,已經把laserOdometry.cpp函式的內容解析一半了。上述內容還有幾處不太理解的,如果有人能夠解答,就請給我留言吧,十分感謝。

如果你看到這裡,說明你已經下定決心要學習loam了,學習新知識的過程總是痛苦的,與君共勉吧!