LOAM源码结合论文解析(二)laserOdometry
中文注釋版本。本文大多注釋來自 --- https://github.com/daobilige-su/loam_velodyne
laserOdometry節(jié)點接收scanResgistraion傳過來的點云,進(jìn)行點云匹配來估計位姿,并發(fā)布里程計以及去畸變的點云給mapping節(jié)點。下面先大體分析下算法原理。
目錄
算法概要分析
laserCloudXXXHandler()
TransformToStart()
TransformToEnd()
核心代碼
點線匹配
點面匹配
最小二乘問題構(gòu)建
遺留問題
算法概要分析
算法流程:
具體如何操作,在下面結(jié)合相關(guān)代碼進(jìn)行細(xì)致說明。
laserCloudXXXHandler()
訂閱句柄的操作都相似,獲取數(shù)據(jù)。
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; }TransformToStart()
功能:當(dāng)前點云中的點相對第一個點去除因勻速運動產(chǎn)生的畸變(加速度畸變在上一個節(jié)點中補(bǔ)償過了),效果相當(dāng)于得到在點云掃描開始位置靜止掃描得到的點云(就是算法流程中的第二步)。
論文中上述公式對應(yīng)代碼,一個點云周期0.1s,上下同乘10。T用transform[6]來表示,代表上一幀到這一幀的變換,包含旋轉(zhuǎn)向量和三維平移量。
?對各個點進(jìn)行補(bǔ)償,注意要先平移再旋轉(zhuǎn),而且這里是從當(dāng)前幀變換到上一幀,旋轉(zhuǎn)矩陣是求個逆的。具體代碼如下。
void TransformToStart(PointType const * const pi, PointType * const po) {//插值系數(shù)計算,云中每個點的相對時間/點云周期10float s = 10 * (pi->intensity - int(pi->intensity));//線性插值:根據(jù)每個點在點云中的相對位置關(guān)系,乘以相應(yīng)的旋轉(zhuǎn)平移系數(shù)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];//變換到start時刻//平移后繞z軸旋轉(zhuǎn)(-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軸旋轉(zhuǎn)(-rx)float x2 = x1;float y2 = cos(rx) * y1 + sin(rx) * z1;float z2 = -sin(rx) * y1 + cos(rx) * z1;//繞y軸旋轉(zhuǎn)(-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()
功能:對點云向后補(bǔ)償(算法流程第一步)。
思路:先把當(dāng)前各點向前補(bǔ)償,如TransformToStart(),流程一樣的,再用transform整體向后補(bǔ)償(transform正好是從上一幀到當(dāng)前幀的變換)。具體看注釋。
void TransformToEnd(PointType const * const pi, PointType * const po) {//插值系數(shù)計算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];//先向前補(bǔ)償//平移后繞z軸旋轉(zhuǎn)(-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軸旋轉(zhuǎn)(-rx)float x2 = x1;float y2 = cos(rx) * y1 + sin(rx) * z1;float z2 = -sin(rx) * y1 + cos(rx) * z1;//繞y軸旋轉(zhuǎn)(-ry)float x3 = cos(ry) * x2 - sin(ry) * z2;float y3 = y2;float z3 = sin(ry) * x2 + cos(ry) * z2;//求出了相對于起始點校正的坐標(biāo)//整體向后補(bǔ)償rx = transform[0];ry = transform[1];rz = transform[2];tx = transform[3];ty = transform[4];tz = transform[5];//繞y軸旋轉(zhuǎn)(ry)float x4 = cos(ry) * x3 + sin(ry) * z3;float y4 = y3;float z4 = -sin(ry) * x3 + cos(ry) * z3;//繞x軸旋轉(zhuǎn)(rx)float x5 = x4;float y5 = cos(rx) * y4 - sin(rx) * z4;float z5 = sin(rx) * y4 + cos(rx) * z4;//繞z軸旋轉(zhuǎn)(rz),再平移float x6 = cos(rz) * x5 - sin(rz) * y5 + tx;float y6 = sin(rz) * x5 + cos(rz) * y5 + ty;float z6 = z5 + tz;// 我認(rèn)為到這里其實就已經(jīng)完成了補(bǔ)償(局部坐標(biāo)系下),下面還有兩次變換好像換到了世界坐標(biāo)系了?// 不是很懂了,歡迎各位下方留言為小弟解惑//----------------------------//平移后繞z軸旋轉(zhuǎn)(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軸旋轉(zhuǎn)(imuPitchStart)float x8 = x7;float y8 = cos(imuPitchStart) * y7 - sin(imuPitchStart) * z7;float z8 = sin(imuPitchStart) * y7 + cos(imuPitchStart) * z7;//繞y軸旋轉(zhuǎn)(imuYawStart)float x9 = cos(imuYawStart) * x8 + sin(imuYawStart) * z8;float y9 = y8;float z9 = -sin(imuYawStart) * x8 + cos(imuYawStart) * z8;//繞y軸旋轉(zhuǎn)(-imuYawLast)float x10 = cos(imuYawLast) * x9 - sin(imuYawLast) * z9;float y10 = y9;float z10 = sin(imuYawLast) * x9 + cos(imuYawLast) * z9;//繞x軸旋轉(zhuǎn)(-imuPitchLast)float x11 = x10;float y11 = cos(imuPitchLast) * y10 + sin(imuPitchLast) * z10;float z11 = -sin(imuPitchLast) * y10 + cos(imuPitchLast) * z10;//繞z軸旋轉(zhuǎn)(-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); }核心代碼
下面進(jìn)入主題。
先看看點線匹配、點面匹配的理論部分,說明一下論文和代碼的對應(yīng)部分。
點線匹配
正如之前所說的那樣,我們在點云中找匹配子,特征點表示為i,用kdtree查找第一個距離i最近點,記為點j;在j附近scan中查找另一個距離i最近的點,記為l。保證點j、l不在同一scan中,這樣可以避免出現(xiàn)3點處于同一scan。
?根據(jù)上式計算點到線的距離,通化優(yōu)化transform來使d值最小。這個式子分子部分為兩個向量(ij 和 il )叉乘的模,在幾何意義上來說就是以這兩向量為鄰邊圍成平行四邊形的面積,分子為向量jl的模,也就是低,高 = 面積/低。(圖畫得有點丑...)
?代碼具體注釋看下方。
void edgeCor(){//處理當(dāng)前點云中的曲率最大的特征點,從上個點云中曲率比較大的特征點中找兩個最近距離點,一個點使用kd-tree查找,另一個根據(jù)找到的點在其相鄰線找另外一個最近距離的點for (int i = 0; i < cornerPointsSharpNum; i++) {TransformToStart(&cornerPointsSharp->points[i], &pointSel);//每迭代五次,重新查找最近點if (iterCount % 5 == 0) {std::vector<int> indices;pcl::removeNaNFromPointCloud(*laserCloudCornerLast,*laserCloudCornerLast, indices);//kd-tree查找一個最近距離點,邊沿點未經(jīng)過體素柵格濾波,一般邊沿點本來就比較少,不做濾波kdtreeCornerLast->nearestKSearch(pointSel, 1, pointSearchInd, pointSearchSqDis);int closestPointInd = -1, minPointInd2 = -1;//尋找相鄰線距離目標(biāo)點距離最小的點//再次提醒:velodyne是2度一線,scanID相鄰并不代表線號相鄰,相鄰線度數(shù)相差2度,也即線號scanID相差2if (pointSearchSqDis[0] < 25) {//找到的最近點距離的確很近的話closestPointInd = pointSearchInd[0];//提取最近點線號int closestPointScan = int(laserCloudCornerLast->points[closestPointInd].intensity);float pointSqDis, minPointSqDis2 = 25;//初始門檻值5米,可大致過濾掉scanID相鄰,但實際線不相鄰的值//尋找距離目標(biāo)點最近距離的平方和最小的點for (int j = closestPointInd + 1; j < cornerPointsSharpNum; j++) {//向scanID增大的方向查找if (int(laserCloudCornerLast->points[j].intensity) > closestPointScan + 2.5) {//非相鄰線break;}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 (int(laserCloudCornerLast->points[j].intensity) > closestPointScan) {//確保兩個點不在同一條scan上(相鄰線查找應(yīng)該可以用scanID == closestPointScan +/- 1 來做)if (pointSqDis < minPointSqDis2) {//距離更近,要小于初始值5米//更新最小距離與點序minPointSqDis2 = pointSqDis;minPointInd2 = j;}}}//同理for (int j = closestPointInd - 1; j >= 0; j--) {//向scanID減小的方向查找if (int(laserCloudCornerLast->points[j].intensity) < closestPointScan - 2.5) {break;}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 (int(laserCloudCornerLast->points[j].intensity) < closestPointScan) {if (pointSqDis < minPointSqDis2) {minPointSqDis2 = pointSqDis;minPointInd2 = j;}}}}//記住組成線的點序pointSearchCornerInd1[i] = closestPointInd;//kd-tree最近距離點,-1表示未找到滿足的點pointSearchCornerInd2[i] = minPointInd2;//另一個最近的,-1表示未找到滿足的點}if (pointSearchCornerInd2[i] >= 0) {//大于等于0,不等于-1,說明兩個點都找到了tripod1 = laserCloudCornerLast->points[pointSearchCornerInd1[i]];tripod2 = laserCloudCornerLast->points[pointSearchCornerInd2[i]];//選擇的特征點記為O,kd-tree最近距離點記為A,另一個最近距離點記為Bfloat x0 = pointSel.x;float y0 = pointSel.y;float z0 = pointSel.z;float x1 = tripod1.x;float y1 = tripod1.y;float z1 = tripod1.z;float x2 = tripod2.x;float y2 = tripod2.y;float z2 = tripod2.z;//向量OA = (x0 - x1, y0 - y1, z0 - z1), 向量OB = (x0 - x2, y0 - y2, z0 - z2),向量AB = (x1 - x2, y1 - y2, z1 - z2)//向量OA OB的向量積(即叉乘)為://| i j k |//|x0-x1 y0-y1 z0-z1|//|x0-x2 y0-y2 z0-z2|//模為:float a012 = sqrt(((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))* ((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) + ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))* ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1)) + ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))* ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1)));//兩個最近距離點之間的距離,即向量AB的模float l12 = sqrt((x1 - x2)*(x1 - x2) + (y1 - y2)*(y1 - y2) + (z1 - z2)*(z1 - z2));//AB方向的單位向量與OAB平面的單位法向量的向量積在各軸上的分量(d的方向)//x軸分量ifloat la = ((y1 - y2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) + (z1 - z2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))) / a012 / l12;//y軸分量jfloat lb = -((x1 - x2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) - (z1 - z2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;//z軸分量kfloat lc = -((x1 - x2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1)) + (y1 - y2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;//點到線的距離,d = |向量OA 叉乘 向量OB|/|AB|float ld2 = a012 / l12;//unusedpointProj = pointSel;pointProj.x -= la * ld2;pointProj.y -= lb * ld2;pointProj.z -= lc * ld2;//權(quán)重計算,距離越大權(quán)重越小,距離越小權(quán)重越大,得到的權(quán)重范圍<=1float s = 1;if (iterCount >= 5) {//5次迭代之后開始增加權(quán)重因素s = 1 - 1.8 * fabs(ld2);}//考慮權(quán)重coeff.x = s * la;coeff.y = s * lb;coeff.z = s * lc;coeff.intensity = s * ld2;if (s > 0.1 && ld2 != 0) {//只保留權(quán)重大的,也即距離比較小的點,同時也舍棄距離為零的laserCloudOri->push_back(cornerPointsSharp->points[i]);coeffSel->push_back(coeff);}}} }點面匹配
(這里注意點m、l 兩個點中要有一個同j scan,另一個點不同,為了避免三點共線而導(dǎo)致沒有平面的情況)
點到平面距離公式如上,分子是 的模,幾何意義為點i j l m四點在空間中所圍立方體的體積,分母還是那個四邊形面積。那么距離 = 體積/面積。
代碼如下:
void surfCor(){ //對本次接收到的曲率最小的點,從上次接收到的點云曲率比較小的點中找三點組成平面,一個使用kd-tree查找,另外一個在同一線上查找滿足要求的,第三個在不同線上查找滿足要求的 for (int i = 0; i < surfPointsFlatNum; i++) {TransformToStart(&surfPointsFlat->points[i], &pointSel);if (iterCount % 5 == 0) {//kd-tree最近點查找,在經(jīng)過體素柵格濾波之后的平面點中查找,一般平面點太多,濾波后最近點查找數(shù)據(jù)量小kdtreeSurfLast->nearestKSearch(pointSel, 1, pointSearchInd, pointSearchSqDis);int closestPointInd = -1, minPointInd2 = -1, minPointInd3 = -1;if (pointSearchSqDis[0] < 25) {closestPointInd = pointSearchInd[0];int closestPointScan = int(laserCloudSurfLast->points[closestPointInd].intensity);float pointSqDis, minPointSqDis2 = 25, minPointSqDis3 = 25;for (int j = closestPointInd + 1; j < surfPointsFlatNum; j++) {if (int(laserCloudSurfLast->points[j].intensity) > closestPointScan + 2.5) {break;}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) <= closestPointScan) {//如果點的線號小于等于最近點的線號(應(yīng)該最多取等,也即同一線上的點)if (pointSqDis < minPointSqDis2) {minPointSqDis2 = pointSqDis;minPointInd2 = j;}} else {//如果點處在大于該線上if (pointSqDis < minPointSqDis3) {minPointSqDis3 = pointSqDis;minPointInd3 = j;}}}//同理for (int j = closestPointInd - 1; j >= 0; j--) {if (int(laserCloudSurfLast->points[j].intensity) < closestPointScan - 2.5) {break;}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) >= closestPointScan) {if (pointSqDis < minPointSqDis2) {minPointSqDis2 = pointSqDis;minPointInd2 = j;}} else {if (pointSqDis < minPointSqDis3) {minPointSqDis3 = pointSqDis;minPointInd3 = j;}}}}pointSearchSurfInd1[i] = closestPointInd;//kd-tree最近距離點,-1表示未找到滿足要求的點pointSearchSurfInd2[i] = minPointInd2;//同一線號上的距離最近的點,-1表示未找到滿足要求的點pointSearchSurfInd3[i] = minPointInd3;//不同線號上的距離最近的點,-1表示未找到滿足要求的點}if (pointSearchSurfInd2[i] >= 0 && pointSearchSurfInd3[i] >= 0) {//找到了三個點tripod1 = laserCloudSurfLast->points[pointSearchSurfInd1[i]];//A點tripod2 = laserCloudSurfLast->points[pointSearchSurfInd2[i]];//B點tripod3 = laserCloudSurfLast->points[pointSearchSurfInd3[i]];//C點//向量AB = (tripod2.x - tripod1.x, tripod2.y - tripod1.y, tripod2.z - tripod1.z)//向量AC = (tripod3.x - tripod1.x, tripod3.y - tripod1.y, tripod3.z - tripod1.z)//向量AB AC的向量積(即叉乘),得到的是法向量//x軸方向分向量ifloat pa = (tripod2.y - tripod1.y) * (tripod3.z - tripod1.z) - (tripod3.y - tripod1.y) * (tripod2.z - tripod1.z);//y軸方向分向量jfloat pb = (tripod2.z - tripod1.z) * (tripod3.x - tripod1.x) - (tripod3.z - tripod1.z) * (tripod2.x - tripod1.x);//z軸方向分向量kfloat pc = (tripod2.x - tripod1.x) * (tripod3.y - tripod1.y) - (tripod3.x - tripod1.x) * (tripod2.y - tripod1.y);float pd = -(pa * tripod1.x + pb * tripod1.y + pc * tripod1.z);//法向量的模float ps = sqrt(pa * pa + pb * pb + pc * pc);//pa pb pc為法向量各方向上的單位向量pa /= ps;pb /= ps;pc /= ps;pd /= ps;//點到面的距離:向量OA與與法向量的點積除以法向量的模float pd2 = pa * pointSel.x + pb * pointSel.y + pc * pointSel.z + pd;//unusedpointProj = pointSel;pointProj.x -= pa * pd2;pointProj.y -= pb * pd2;pointProj.z -= pc * pd2;//同理計算權(quán)重float s = 1;if (iterCount >= 5) {s = 1 - 1.8 * fabs(pd2) / sqrt(sqrt(pointSel.x * pointSel.x+ pointSel.y * pointSel.y + pointSel.z * pointSel.z));}//考慮權(quán)重coeff.x = s * pa;coeff.y = s * pb;coeff.z = s * pc;coeff.intensity = s * pd2;if (s > 0.1 && pd2 != 0) {//保存原始點與相應(yīng)的系數(shù)laserCloudOri->push_back(surfPointsFlat->points[i]);coeffSel->push_back(coeff);}} }最小二乘問題構(gòu)建
建立最小二乘問題進(jìn)行優(yōu)化。
代碼中MatA表示雅可比矩陣,MatB表示非線性方程。建立方程如下:
也就是matAtA * matX = matAtB,迭代法求matX。這里還是牛頓法。
{cv::Mat matA(pointSelNum, 6, CV_32F, cv::Scalar::all(0));cv::Mat matAt(6, pointSelNum, CV_32F, cv::Scalar::all(0));cv::Mat matAtA(6, 6, CV_32F, cv::Scalar::all(0));cv::Mat matB(pointSelNum, 1, CV_32F, cv::Scalar::all(0));cv::Mat matAtB(6, 1, CV_32F, cv::Scalar::all(0));cv::Mat matX(6, 1, CV_32F, cv::Scalar::all(0));//計算matA,matB矩陣for (int i = 0; i < pointSelNum; i++) {pointOri = laserCloudOri->points[i];coeff = coeffSel->points[i];float s = 1;float srx = sin(s * transform[0]);float crx = cos(s * transform[0]);float sry = sin(s * transform[1]);float cry = cos(s * transform[1]);float srz = sin(s * transform[2]);float crz = cos(s * transform[2]);float tx = s * transform[3];float ty = s * transform[4];float tz = s * transform[5];//求解雅可比矩陣//小弟不才,這里已經(jīng)窒息了,雅各比各參數(shù)應(yīng)該f(x)對尋優(yōu)參數(shù)的一階導(dǎo)數(shù)(可以參考視覺slam14講)float arx = (-s*crx*sry*srz*pointOri.x + s*crx*crz*sry*pointOri.y + s*srx*sry*pointOri.z + s*tx*crx*sry*srz - s*ty*crx*crz*sry - s*tz*srx*sry) * coeff.x+ (s*srx*srz*pointOri.x - s*crz*srx*pointOri.y + s*crx*pointOri.z+ s*ty*crz*srx - s*tz*crx - s*tx*srx*srz) * coeff.y+ (s*crx*cry*srz*pointOri.x - s*crx*cry*crz*pointOri.y - s*cry*srx*pointOri.z+ s*tz*cry*srx + s*ty*crx*cry*crz - s*tx*crx*cry*srz) * coeff.z;float ary = ((-s*crz*sry - s*cry*srx*srz)*pointOri.x + (s*cry*crz*srx - s*sry*srz)*pointOri.y - s*crx*cry*pointOri.z + tx*(s*crz*sry + s*cry*srx*srz) + ty*(s*sry*srz - s*cry*crz*srx) + s*tz*crx*cry) * coeff.x+ ((s*cry*crz - s*srx*sry*srz)*pointOri.x + (s*cry*srz + s*crz*srx*sry)*pointOri.y - s*crx*sry*pointOri.z+ s*tz*crx*sry - ty*(s*cry*srz + s*crz*srx*sry) - tx*(s*cry*crz - s*srx*sry*srz)) * coeff.z;float arz = ((-s*cry*srz - s*crz*srx*sry)*pointOri.x + (s*cry*crz - s*srx*sry*srz)*pointOri.y+ tx*(s*cry*srz + s*crz*srx*sry) - ty*(s*cry*crz - s*srx*sry*srz)) * coeff.x+ (-s*crx*crz*pointOri.x - s*crx*srz*pointOri.y+ s*ty*crx*srz + s*tx*crx*crz) * coeff.y+ ((s*cry*crz*srx - s*sry*srz)*pointOri.x + (s*crz*sry + s*cry*srx*srz)*pointOri.y+ tx*(s*sry*srz - s*cry*crz*srx) - ty*(s*crz*sry + s*cry*srx*srz)) * coeff.z;float atx = -s*(cry*crz - srx*sry*srz) * coeff.x + s*crx*srz * coeff.y - s*(crz*sry + cry*srx*srz) * coeff.z;float aty = -s*(cry*srz + crz*srx*sry) * coeff.x - s*crx*crz * coeff.y - s*(sry*srz - cry*crz*srx) * coeff.z;float atz = s*crx*sry * coeff.x - s*srx * coeff.y - s*crx*cry * coeff.z;float d2 = coeff.intensity;matA.at<float>(i, 0) = arx;matA.at<float>(i, 1) = ary;matA.at<float>(i, 2) = arz;matA.at<float>(i, 3) = atx;matA.at<float>(i, 4) = aty;matA.at<float>(i, 5) = atz;matB.at<float>(i, 0) = -0.05 * d2;}cv::transpose(matA, matAt);matAtA = matAt * matA;matAtB = matAt * matB;//求解matAtA * matX = matAtBcv::solve(matAtA, matAtB, matX, cv::DECOMP_QR);if (iterCount == 0) {//特征值1*6矩陣cv::Mat matE(1, 6, CV_32F, cv::Scalar::all(0));//特征向量6*6矩陣cv::Mat matV(6, 6, CV_32F, cv::Scalar::all(0));cv::Mat matV2(6, 6, CV_32F, cv::Scalar::all(0));//求解特征值/特征向量cv::eigen(matAtA, matE, matV);matV.copyTo(matV2);isDegenerate = false;//特征值取值門檻float eignThre[6] = {10, 10, 10, 10, 10, 10};for (int i = 5; i >= 0; i--) {//從小到大查找if (matE.at<float>(0, i) < eignThre[i]) {//特征值太小,則認(rèn)為處在兼并環(huán)境中,發(fā)生了退化for (int j = 0; j < 6; j++) {//對應(yīng)的特征向量置為0matV2.at<float>(i, j) = 0;}isDegenerate = true;} else {break;}}//計算P矩陣matP = matV.inv() * matV2;}if (isDegenerate) {//如果發(fā)生退化,只使用預(yù)測矩陣P計算cv::Mat matX2(6, 1, CV_32F, cv::Scalar::all(0));matX.copyTo(matX2);matX = matP * matX2;}//累加每次迭代的旋轉(zhuǎn)平移量transform[0] += matX.at<float>(0, 0);transform[1] += matX.at<float>(1, 0);transform[2] += matX.at<float>(2, 0);transform[3] += matX.at<float>(3, 0);transform[4] += matX.at<float>(4, 0);transform[5] += matX.at<float>(5, 0);for(int i=0; i<6; i++){if(isnan(transform[i]))//判斷是否非數(shù)字transform[i]=0;}//計算旋轉(zhuǎn)平移量,如果很小就停止迭代float deltaR = sqrt(pow(rad2deg(matX.at<float>(0, 0)), 2) +pow(rad2deg(matX.at<float>(1, 0)), 2) +pow(rad2deg(matX.at<float>(2, 0)), 2));float deltaT = sqrt(pow(matX.at<float>(3, 0) * 100, 2) +pow(matX.at<float>(4, 0) * 100, 2) +pow(matX.at<float>(5, 0) * 100, 2));if (deltaR < 0.1 && deltaT < 0.1) {//迭代終止條件break;} }下面放上完整的代碼注解
int main(int argc, char** argv) {ros::init(argc, argv, "laserOdometry");ros::NodeHandle nh;ros::Subscriber subCornerPointsSharp = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_sharp", 2, laserCloudSharpHandler);ros::Subscriber subCornerPointsLessSharp = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_less_sharp", 2, laserCloudLessSharpHandler);ros::Subscriber subSurfPointsFlat = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_flat", 2, laserCloudFlatHandler);ros::Subscriber subSurfPointsLessFlat = nh.subscribe<sensor_msgs::PointCloud2>("/laser_cloud_less_flat", 2, laserCloudLessFlatHandler);ros::Subscriber subLaserCloudFullRes = nh.subscribe<sensor_msgs::PointCloud2> ("/velodyne_cloud_2", 2, laserCloudFullResHandler);ros::Subscriber subImuTrans = nh.subscribe<sensor_msgs::PointCloud2> ("/imu_trans", 5, imuTransHandler);ros::Publisher pubLaserCloudCornerLast = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_corner_last", 2);ros::Publisher pubLaserCloudSurfLast = nh.advertise<sensor_msgs::PointCloud2>("/laser_cloud_surf_last", 2);ros::Publisher pubLaserCloudFullRes = nh.advertise<sensor_msgs::PointCloud2> ("/velodyne_cloud_3", 2);ros::Publisher pubLaserOdometry = nh.advertise<nav_msgs::Odometry> ("/laser_odom_to_init", 5);nav_msgs::Odometry laserOdometry;laserOdometry.header.frame_id = "/camera_init";laserOdometry.child_frame_id = "/laser_odom";tf::TransformBroadcaster tfBroadcaster;tf::StampedTransform laserOdometryTrans;laserOdometryTrans.frame_id_ = "/camera_init";laserOdometryTrans.child_frame_id_ = "/laser_odom";std::vector<int> pointSearchInd;//搜索到的點序std::vector<float> pointSearchSqDis;//搜索到的點平方距離PointType pointOri, pointSel/*選中的特征點*/, tripod1, tripod2, tripod3/*特征點的對應(yīng)點*/, pointProj/*unused*/, coeff;//退化標(biāo)志bool isDegenerate = false;//P矩陣,預(yù)測矩陣cv::Mat matP(6, 6, CV_32F, cv::Scalar::all(0));int frameCount = skipFrameNum;ros::Rate rate(100);bool status = ros::ok();while (status) {ros::spinOnce();if (newCornerPointsSharp && newCornerPointsLessSharp && newSurfPointsFlat && newSurfPointsLessFlat && newLaserCloudFullRes && newImuTrans &&fabs(timeCornerPointsSharp - timeSurfPointsLessFlat) < 0.005 &&fabs(timeCornerPointsLessSharp - timeSurfPointsLessFlat) < 0.005 &&fabs(timeSurfPointsFlat - timeSurfPointsLessFlat) < 0.005 &&fabs(timeLaserCloudFullRes - timeSurfPointsLessFlat) < 0.005 &&fabs(timeImuTrans - timeSurfPointsLessFlat) < 0.005) { //同步作用,確保同時收到同一個點云的特征點以及IMU信息才進(jìn)入newCornerPointsSharp = false;newCornerPointsLessSharp = false;newSurfPointsFlat = false;newSurfPointsLessFlat = false;newLaserCloudFullRes = false;newImuTrans = false;//將第一個點云數(shù)據(jù)集發(fā)送給laserMapping,從下一個點云數(shù)據(jù)開始處理,我們需要兩幀數(shù)據(jù)來進(jìn)行匹配。if (!systemInited) {//將cornerPointsLessSharp與laserCloudCornerLast交換,目的保存cornerPointsLessSharp的值下輪使用pcl::PointCloud<PointType>::Ptr laserCloudTemp = cornerPointsLessSharp;cornerPointsLessSharp = laserCloudCornerLast;laserCloudCornerLast = laserCloudTemp;//將surfPointLessFlat與laserCloudSurfLast交換,目的保存surfPointsLessFlat的值下輪使用laserCloudTemp = surfPointsLessFlat;surfPointsLessFlat = laserCloudSurfLast;laserCloudSurfLast = laserCloudTemp;//使用上一幀的特征點構(gòu)建kd-treekdtreeCornerLast->setInputCloud(laserCloudCornerLast);//所有的邊沿點集合kdtreeSurfLast->setInputCloud(laserCloudSurfLast);//所有的平面點集合//將cornerPointsLessSharp和surfPointLessFlat點也即邊沿點和平面點分別發(fā)送給laserMappingsensor_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);//記住原點的翻滾角和俯仰角transformSum[0] += imuPitchStart;transformSum[2] += imuRollStart;systemInited = true;continue;}//T平移量的初值賦值為加減速的位移量,為其梯度下降的方向(沿用上次轉(zhuǎn)換的T(一個sweep勻速模型),同時在其基礎(chǔ)上減去勻速運動位移,即只考慮加減速的位移量)transform[3] -= imuVeloFromStartX * scanPeriod;transform[4] -= imuVeloFromStartY * scanPeriod;transform[5] -= imuVeloFromStartZ * scanPeriod;if (laserCloudCornerLastNum > 10 && laserCloudSurfLastNum > 100) {std::vector<int> indices;pcl::removeNaNFromPointCloud(*cornerPointsSharp,*cornerPointsSharp, indices);int cornerPointsSharpNum = cornerPointsSharp->points.size();int surfPointsFlatNum = surfPointsFlat->points.size();//Levenberg-Marquardt算法(L-M method),非線性最小二乘算法,最優(yōu)化算法的一種//最多迭代25次for (int iterCount = 0; iterCount < 25; iterCount++) {laserCloudOri->clear();coeffSel->clear();//處理當(dāng)前點云中的曲率最大的特征點,從上個點云中曲率比較大的特征點中找兩個最近距離點,一個點使用kd-tree查找,另一個根據(jù)找到的點在其相鄰線找另外一個最近距離的點edgeCor();surfCor();cv::Mat matA(pointSelNum, 6, CV_32F, cv::Scalar::all(0));cv::Mat matAt(6, pointSelNum, CV_32F, cv::Scalar::all(0));cv::Mat matAtA(6, 6, CV_32F, cv::Scalar::all(0));cv::Mat matB(pointSelNum, 1, CV_32F, cv::Scalar::all(0));cv::Mat matAtB(6, 1, CV_32F, cv::Scalar::all(0));cv::Mat matX(6, 1, CV_32F, cv::Scalar::all(0));//計算matA,matB矩陣for (int i = 0; i < pointSelNum; i++) {pointOri = laserCloudOri->points[i];coeff = coeffSel->points[i];float s = 1;float srx = sin(s * transform[0]);float crx = cos(s * transform[0]);float sry = sin(s * transform[1]);float cry = cos(s * transform[1]);float srz = sin(s * transform[2]);float crz = cos(s * transform[2]);float tx = s * transform[3];float ty = s * transform[4];float tz = s * transform[5];//求解雅可比矩陣float arx = (-s*crx*sry*srz*pointOri.x + s*crx*crz*sry*pointOri.y + s*srx*sry*pointOri.z + s*tx*crx*sry*srz - s*ty*crx*crz*sry - s*tz*srx*sry) * coeff.x+ (s*srx*srz*pointOri.x - s*crz*srx*pointOri.y + s*crx*pointOri.z+ s*ty*crz*srx - s*tz*crx - s*tx*srx*srz) * coeff.y+ (s*crx*cry*srz*pointOri.x - s*crx*cry*crz*pointOri.y - s*cry*srx*pointOri.z+ s*tz*cry*srx + s*ty*crx*cry*crz - s*tx*crx*cry*srz) * coeff.z;float ary = ((-s*crz*sry - s*cry*srx*srz)*pointOri.x + (s*cry*crz*srx - s*sry*srz)*pointOri.y - s*crx*cry*pointOri.z + tx*(s*crz*sry + s*cry*srx*srz) + ty*(s*sry*srz - s*cry*crz*srx) + s*tz*crx*cry) * coeff.x+ ((s*cry*crz - s*srx*sry*srz)*pointOri.x + (s*cry*srz + s*crz*srx*sry)*pointOri.y - s*crx*sry*pointOri.z+ s*tz*crx*sry - ty*(s*cry*srz + s*crz*srx*sry) - tx*(s*cry*crz - s*srx*sry*srz)) * coeff.z;float arz = ((-s*cry*srz - s*crz*srx*sry)*pointOri.x + (s*cry*crz - s*srx*sry*srz)*pointOri.y+ tx*(s*cry*srz + s*crz*srx*sry) - ty*(s*cry*crz - s*srx*sry*srz)) * coeff.x+ (-s*crx*crz*pointOri.x - s*crx*srz*pointOri.y+ s*ty*crx*srz + s*tx*crx*crz) * coeff.y+ ((s*cry*crz*srx - s*sry*srz)*pointOri.x + (s*crz*sry + s*cry*srx*srz)*pointOri.y+ tx*(s*sry*srz - s*cry*crz*srx) - ty*(s*crz*sry + s*cry*srx*srz)) * coeff.z;float atx = -s*(cry*crz - srx*sry*srz) * coeff.x + s*crx*srz * coeff.y - s*(crz*sry + cry*srx*srz) * coeff.z;float aty = -s*(cry*srz + crz*srx*sry) * coeff.x - s*crx*crz * coeff.y - s*(sry*srz - cry*crz*srx) * coeff.z;float atz = s*crx*sry * coeff.x - s*srx * coeff.y - s*crx*cry * coeff.z;float d2 = coeff.intensity;matA.at<float>(i, 0) = arx;matA.at<float>(i, 1) = ary;matA.at<float>(i, 2) = arz;matA.at<float>(i, 3) = atx;matA.at<float>(i, 4) = aty;matA.at<float>(i, 5) = atz;matB.at<float>(i, 0) = -0.05 * d2;}cv::transpose(matA, matAt);matAtA = matAt * matA;matAtB = matAt * matB;//求解matAtA * matX = matAtBcv::solve(matAtA, matAtB, matX, cv::DECOMP_QR);if (iterCount == 0) {//特征值1*6矩陣cv::Mat matE(1, 6, CV_32F, cv::Scalar::all(0));//特征向量6*6矩陣cv::Mat matV(6, 6, CV_32F, cv::Scalar::all(0));cv::Mat matV2(6, 6, CV_32F, cv::Scalar::all(0));//求解特征值/特征向量cv::eigen(matAtA, matE, matV);matV.copyTo(matV2);isDegenerate = false;//特征值取值門檻float eignThre[6] = {10, 10, 10, 10, 10, 10};for (int i = 5; i >= 0; i--) {//從小到大查找if (matE.at<float>(0, i) < eignThre[i]) {//特征值太小,則認(rèn)為處在兼并環(huán)境中,發(fā)生了退化for (int j = 0; j < 6; j++) {//對應(yīng)的特征向量置為0matV2.at<float>(i, j) = 0;}isDegenerate = true;} else {break;}}//計算P矩陣matP = matV.inv() * matV2;}if (isDegenerate) {//如果發(fā)生退化,只使用預(yù)測矩陣P計算cv::Mat matX2(6, 1, CV_32F, cv::Scalar::all(0));matX.copyTo(matX2);matX = matP * matX2;}//累加每次迭代的旋轉(zhuǎn)平移量transform[0] += matX.at<float>(0, 0);transform[1] += matX.at<float>(1, 0);transform[2] += matX.at<float>(2, 0);transform[3] += matX.at<float>(3, 0);transform[4] += matX.at<float>(4, 0);transform[5] += matX.at<float>(5, 0);for(int i=0; i<6; i++){if(isnan(transform[i]))//判斷是否非數(shù)字transform[i]=0;}//計算旋轉(zhuǎn)平移量,如果很小就停止迭代float deltaR = sqrt(pow(rad2deg(matX.at<float>(0, 0)), 2) +pow(rad2deg(matX.at<float>(1, 0)), 2) +pow(rad2deg(matX.at<float>(2, 0)), 2));float deltaT = sqrt(pow(matX.at<float>(3, 0) * 100, 2) +pow(matX.at<float>(4, 0) * 100, 2) +pow(matX.at<float>(5, 0) * 100, 2));if (deltaR < 0.1 && deltaT < 0.1) {//迭代終止條件break;}}}float rx, ry, rz, tx, ty, tz;//求相對于原點的旋轉(zhuǎn)量,垂直方向上1.05倍修正?AccumulateRotation(transformSum[0], transformSum[1], transformSum[2], -transform[0], -transform[1] * 1.05, -transform[2], rx, ry, rz);float x1 = cos(rz) * (transform[3] - imuShiftFromStartX) - sin(rz) * (transform[4] - imuShiftFromStartY);float y1 = sin(rz) * (transform[3] - imuShiftFromStartX) + cos(rz) * (transform[4] - imuShiftFromStartY);float z1 = transform[5] * 1.05 - imuShiftFromStartZ;float x2 = x1;float y2 = cos(rx) * y1 - sin(rx) * z1;float z2 = sin(rx) * y1 + cos(rx) * z1;//求相對于原點的平移量tx = transformSum[3] - (cos(ry) * x2 + sin(ry) * z2);ty = transformSum[4] - y2;tz = transformSum[5] - (-sin(ry) * x2 + cos(ry) * z2);//根據(jù)IMU修正旋轉(zhuǎn)量PluginIMURotation(rx, ry, rz, imuPitchStart, imuYawStart, imuRollStart, imuPitchLast, imuYawLast, imuRollLast, rx, ry, rz);//得到世界坐標(biāo)系下的轉(zhuǎn)移矩陣transformSum[0] = rx;transformSum[1] = ry;transformSum[2] = rz;transformSum[3] = tx;transformSum[4] = ty;transformSum[5] = tz;//歐拉角轉(zhuǎn)換成四元數(shù)geometry_msgs::Quaternion geoQuat = tf::createQuaternionMsgFromRollPitchYaw(rz, -rx, -ry);//publish四元數(shù)和平移量laserOdometry.header.stamp = ros::Time().fromSec(timeSurfPointsLessFlat);laserOdometry.pose.pose.orientation.x = -geoQuat.y;laserOdometry.pose.pose.orientation.y = -geoQuat.z;laserOdometry.pose.pose.orientation.z = geoQuat.x;laserOdometry.pose.pose.orientation.w = geoQuat.w;laserOdometry.pose.pose.position.x = tx;laserOdometry.pose.pose.position.y = ty;laserOdometry.pose.pose.position.z = tz;pubLaserOdometry.publish(laserOdometry);//廣播新的平移旋轉(zhuǎn)之后的坐標(biāo)系(rviz)laserOdometryTrans.stamp_ = ros::Time().fromSec(timeSurfPointsLessFlat);laserOdometryTrans.setRotation(tf::Quaternion(-geoQuat.y, -geoQuat.z, geoQuat.x, geoQuat.w));laserOdometryTrans.setOrigin(tf::Vector3(tx, ty, tz));tfBroadcaster.sendTransform(laserOdometryTrans);//對點云的曲率比較大和比較小的點投影到掃描結(jié)束位置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]);}frameCount++;//點云全部點,每間隔一個點云數(shù)據(jù)相對點云最后一個點進(jìn)行畸變校正if (frameCount >= skipFrameNum + 1) {int laserCloudFullResNum = laserCloudFullRes->points.size();for (int i = 0; i < laserCloudFullResNum; i++) {TransformToEnd(&laserCloudFullRes->points[i], &laserCloudFullRes->points[i]);}}//畸變校正之后的點作為last點保存等下個點云進(jìn)來進(jìn)行匹配pcl::PointCloud<PointType>::Ptr laserCloudTemp = cornerPointsLessSharp;cornerPointsLessSharp = laserCloudCornerLast;laserCloudCornerLast = laserCloudTemp;laserCloudTemp = surfPointsLessFlat;surfPointsLessFlat = laserCloudSurfLast;laserCloudSurfLast = laserCloudTemp;laserCloudCornerLastNum = laserCloudCornerLast->points.size();laserCloudSurfLastNum = laserCloudSurfLast->points.size();//點足夠多就構(gòu)建kd-tree,否則棄用此幀,沿用上一幀數(shù)據(jù)的kd-treeif (laserCloudCornerLastNum > 10 && laserCloudSurfLastNum > 100) {kdtreeCornerLast->setInputCloud(laserCloudCornerLast);kdtreeSurfLast->setInputCloud(laserCloudSurfLast);}//按照跳幀數(shù)publich邊沿點,平面點以及全部點給laserMapping(每隔一幀發(fā)一次)if (frameCount >= skipFrameNum + 1) {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);}}status = ros::ok();rate.sleep();}return 0; }遺留問題
AccumulateRotation()、PluginIMURotation() 這兩個函數(shù),并沒有完全看懂,就不亂說了。
如有問題,歡迎評論留言交流或私信。
LOAM源碼解析(一)ScanRegistration
總結(jié)
以上是生活随笔為你收集整理的LOAM源码结合论文解析(二)laserOdometry的全部內(nèi)容,希望文章能夠幫你解決所遇到的問題。
- 上一篇: 寒门再难出贵子(很现实,很残酷,慎入)
- 下一篇: 成本会计【9】