00001 #include <math.h>
00002 #include <time.h>
00003 #include <stdio.h>
00004 #include <stdlib.h>
00005 #include <ros/ros.h>
00006
00007 #include <nav_msgs/Odometry.h>
00008 #include <sensor_msgs/Imu.h>
00009 #include <sensor_msgs/PointCloud2.h>
00010
00011 #include <tf/transform_datatypes.h>
00012 #include <tf/transform_broadcaster.h>
00013
00014 #include <opencv/cv.h>
00015 #include <opencv2/highgui/highgui.hpp>
00016
00017 #include <pcl/ros/conversions.h>
00018 #include <pcl/point_cloud.h>
00019 #include <pcl/point_types.h>
00020 #include <pcl/filters/voxel_grid.h>
00021 #include <pcl/kdtree/kdtree_flann.h>
00022
00023
00024 const double PI = 3.1415926;
00025 const double rad2deg = 180 / PI;
00026 const double deg2rad = PI / 180;
00027
00028 bool systemInited = false;
00029
00030 double initTime;
00031 double timeLasted;
00032 double timeLastedRec;
00033 double startTimeCur;
00034 double startTimeLast;
00035
00036 double timeLaserCloudExtreCur = 0;
00037 double timeLaserCloudLast = 0;
00038
00039 bool newLaserCloudExtreCur = false;
00040 bool newLaserCloudLast = false;
00041
00042 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudExtreCur(new pcl::PointCloud<pcl::PointXYZHSV>());
00043 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudExtreLast(new pcl::PointCloud<pcl::PointXYZHSV>());
00044 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudExtreOri(new pcl::PointCloud<pcl::PointXYZHSV>());
00045
00046
00047
00048 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudLast(new pcl::PointCloud<pcl::PointXYZHSV>());
00049 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCornerLast(new pcl::PointCloud<pcl::PointXYZHSV>());
00050 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurfLast(new pcl::PointCloud<pcl::PointXYZHSV>());
00051 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCornerLLast(new pcl::PointCloud<pcl::PointXYZHSV>());
00052 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurfLLast(new pcl::PointCloud<pcl::PointXYZHSV>());
00053
00054 pcl::PointCloud<pcl::PointXYZHSV>::Ptr coeffSel(new pcl::PointCloud<pcl::PointXYZHSV>());
00055 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeCornerLast(new pcl::KdTreeFLANN<pcl::PointXYZHSV>());
00056 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeSurfLast(new pcl::KdTreeFLANN<pcl::PointXYZHSV>());
00057 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeCornerLLast(new pcl::KdTreeFLANN<pcl::PointXYZHSV>());
00058 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeSurfLLast(new pcl::KdTreeFLANN<pcl::PointXYZHSV>());
00059
00060 float transform[6] = {0};
00061 float transformRec[6] = {0};
00062 float transformSum[6] = {0};
00063
00064 float imuRollStartCur = 0, imuPitchStartCur = 0, imuYawStartCur = 0;
00065 float imuRollCur = 0, imuPitchCur = 0, imuYawCur = 0;
00066 float imuShiftFromStartXCur = 0, imuShiftFromStartYCur = 0, imuShiftFromStartZCur = 0;
00067 float imuVeloFromStartXCur = 0, imuVeloFromStartYCur = 0, imuVeloFromStartZCur = 0;
00068
00069 float imuRollStartLast = 0, imuPitchStartLast = 0, imuYawStartLast = 0;
00070 float imuRollLast = 0, imuPitchLast = 0, imuYawLast = 0;
00071 float imuShiftFromStartXLast = 0, imuShiftFromStartYLast = 0, imuShiftFromStartZLast = 0;
00072 float imuVeloFromStartXLast = 0, imuVeloFromStartYLast = 0, imuVeloFromStartZLast = 0;
00073
00074 bool imuInited = false;
00075
00076 void TransformReset()
00077 {
00078 for (int i = 0; i < 6; i++) {
00079 transformRec[i] = transform[i];
00080 transform[i] = 0;
00081 }
00082
00083 transformRec[3] -= imuVeloFromStartXLast * (startTimeCur - startTimeLast);
00084 transformRec[4] -= imuVeloFromStartYLast * (startTimeCur - startTimeLast);
00085 transformRec[5] -= imuVeloFromStartZLast * (startTimeCur - startTimeLast);
00086 }
00087
00088 void TransformToStart(pcl::PointXYZHSV *pi, pcl::PointXYZHSV *po, double startTime, double endTime)
00089 {
00090 float s = (pi->h - startTime) / (endTime - startTime);
00091
00092 float rx = s * transform[0];
00093 float ry = s * transform[1];
00094 float rz = s * transform[2];
00095 float tx = s * transform[3];
00096 float ty = s * transform[4];
00097 float tz = s * transform[5];
00098
00099 float x1 = cos(rz) * (pi->x - tx) + sin(rz) * (pi->y - ty);
00100 float y1 = -sin(rz) * (pi->x - tx) + cos(rz) * (pi->y - ty);
00101 float z1 = (pi->z - tz);
00102
00103 float x2 = x1;
00104 float y2 = cos(rx) * y1 + sin(rx) * z1;
00105 float z2 = -sin(rx) * y1 + cos(rx) * z1;
00106
00107 po->x = cos(ry) * x2 - sin(ry) * z2;
00108 po->y = y2;
00109 po->z = sin(ry) * x2 + cos(ry) * z2;
00110 po->h = pi->h;
00111 po->s = pi->s;
00112 po->v = pi->v;
00113 }
00114
00115 void TransformToEnd(pcl::PointXYZHSV *pi, pcl::PointXYZHSV *po, double startTime, double endTime)
00116 {
00117 float s = (pi->h - startTime) / (endTime - startTime);
00118
00119 float rx = s * transform[0];
00120 float ry = s * transform[1];
00121 float rz = s * transform[2];
00122 float tx = s * transform[3];
00123 float ty = s * transform[4];
00124 float tz = s * transform[5];
00125
00126 float x1 = cos(rz) * (pi->x - tx) + sin(rz) * (pi->y - ty);
00127 float y1 = -sin(rz) * (pi->x - tx) + cos(rz) * (pi->y - ty);
00128 float z1 = (pi->z - tz);
00129
00130 float x2 = x1;
00131 float y2 = cos(rx) * y1 + sin(rx) * z1;
00132 float z2 = -sin(rx) * y1 + cos(rx) * z1;
00133
00134 float x3 = cos(ry) * x2 - sin(ry) * z2;
00135 float y3 = y2;
00136 float z3 = sin(ry) * x2 + cos(ry) * z2;
00137
00138 rx = transform[0];
00139 ry = transform[1];
00140 rz = transform[2];
00141 tx = transform[3];
00142 ty = transform[4];
00143 tz = transform[5];
00144
00145 float x4 = cos(ry) * x3 + sin(ry) * z3;
00146 float y4 = y3;
00147 float z4 = -sin(ry) * x3 + cos(ry) * z3;
00148
00149 float x5 = x4;
00150 float y5 = cos(rx) * y4 - sin(rx) * z4;
00151 float z5 = sin(rx) * y4 + cos(rx) * z4;
00152
00153 float x6 = cos(rz) * x5 - sin(rz) * y5 + tx;
00154 float y6 = sin(rz) * x5 + cos(rz) * y5 + ty;
00155 float z6 = z5 + tz;
00156
00157 float x7 = cos(imuRollStartLast) * (x6 - imuShiftFromStartXLast)
00158 - sin(imuRollStartLast) * (y6 - imuShiftFromStartYLast);
00159 float y7 = sin(imuRollStartLast) * (x6 - imuShiftFromStartXLast)
00160 + cos(imuRollStartLast) * (y6 - imuShiftFromStartYLast);
00161 float z7 = z6 - imuShiftFromStartZLast;
00162
00163 float x8 = x7;
00164 float y8 = cos(imuPitchStartLast) * y7 - sin(imuPitchStartLast) * z7;
00165 float z8 = sin(imuPitchStartLast) * y7 + cos(imuPitchStartLast) * z7;
00166
00167 float x9 = cos(imuYawStartLast) * x8 + sin(imuYawStartLast) * z8;
00168 float y9 = y8;
00169 float z9 = -sin(imuYawStartLast) * x8 + cos(imuYawStartLast) * z8;
00170
00171 float x10 = cos(imuYawLast) * x9 - sin(imuYawLast) * z9;
00172 float y10 = y9;
00173 float z10 = sin(imuYawLast) * x9 + cos(imuYawLast) * z9;
00174
00175 float x11 = x10;
00176 float y11 = cos(imuPitchLast) * y10 + sin(imuPitchLast) * z10;
00177 float z11 = -sin(imuPitchLast) * y10 + cos(imuPitchLast) * z10;
00178
00179 po->x = cos(imuRollLast) * x11 + sin(imuRollLast) * y11;
00180 po->y = -sin(imuRollLast) * x11 + cos(imuRollLast) * y11;
00181 po->z = z11;
00182 po->h = pi->h;
00183 po->s = pi->s;
00184 po->v = pi->v;
00185 }
00186
00187 void laserCloudExtreCurHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudExtreCur2)
00188 {
00189 if (!systemInited) {
00190 initTime = laserCloudExtreCur2->header.stamp.toSec();
00191 systemInited = true;
00192 }
00193 timeLaserCloudExtreCur = laserCloudExtreCur2->header.stamp.toSec();
00194 timeLasted = timeLaserCloudExtreCur - initTime;
00195
00196 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudExtreCur3(new pcl::PointCloud<pcl::PointXYZHSV>());
00197 pcl::fromROSMsg(*laserCloudExtreCur2, *laserCloudExtreCur3);
00198 int laserCloudExtreCur3Size = laserCloudExtreCur3->points.size();
00199
00200 laserCloudExtreCur->clear();
00201 for (int i = 0; i < laserCloudExtreCur3Size; i++) {
00202 if (fabs(laserCloudExtreCur3->points[i].v - 10) < 0.005) {
00203 imuPitchStartCur = laserCloudExtreCur3->points[i].x;
00204 imuYawStartCur = laserCloudExtreCur3->points[i].y;
00205 imuRollStartCur = laserCloudExtreCur3->points[i].z;
00206 } else if (fabs(laserCloudExtreCur3->points[i].v - 11) < 0.005) {
00207 imuPitchCur = laserCloudExtreCur3->points[i].x;
00208 imuYawCur = laserCloudExtreCur3->points[i].y;
00209 imuRollCur = laserCloudExtreCur3->points[i].z;
00210 } else if (fabs(laserCloudExtreCur3->points[i].v - 12) < 0.005) {
00211 imuShiftFromStartXCur = laserCloudExtreCur3->points[i].x;
00212 imuShiftFromStartYCur = laserCloudExtreCur3->points[i].y;
00213 imuShiftFromStartZCur = laserCloudExtreCur3->points[i].z;
00214 } else if (fabs(laserCloudExtreCur3->points[i].v - 13) < 0.005) {
00215 imuVeloFromStartXCur = laserCloudExtreCur3->points[i].x;
00216 imuVeloFromStartYCur = laserCloudExtreCur3->points[i].y;
00217 imuVeloFromStartZCur = laserCloudExtreCur3->points[i].z;
00218 } else {
00219 laserCloudExtreCur->push_back(laserCloudExtreCur3->points[i]);
00220 }
00221 }
00222 laserCloudExtreCur3->clear();
00223
00224 if (!imuInited) {
00225 transformSum[0] += imuPitchStartCur;
00226
00227 transformSum[2] += imuRollStartCur;
00228
00229 imuInited = true;
00230 }
00231
00232 if (timeLasted > 4.0) {
00233 newLaserCloudExtreCur = true;
00234 }
00235 }
00236
00237 void laserCloudLastHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudLast2)
00238 {
00239 if (laserCloudLast2->header.stamp.toSec() > timeLaserCloudLast + 0.005) {
00240 timeLaserCloudLast = laserCloudLast2->header.stamp.toSec();
00241 startTimeLast = startTimeCur;
00242 startTimeCur = timeLaserCloudLast - initTime;
00243
00244 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudPointer = laserCloudCornerLLast;
00245 laserCloudCornerLLast = laserCloudCornerLast;
00246 laserCloudCornerLast = laserCloudPointer;
00247
00248 laserCloudPointer = laserCloudSurfLLast;
00249 laserCloudSurfLLast = laserCloudSurfLast;
00250 laserCloudSurfLast = laserCloudPointer;
00251
00252 laserCloudLast->clear();
00253 pcl::fromROSMsg(*laserCloudLast2, *laserCloudLast);
00254 int laserCloudLastSize = laserCloudLast->points.size();
00255
00256 laserCloudExtreLast->clear();
00257 laserCloudCornerLast->clear();
00258 laserCloudSurfLast->clear();
00259 for (int i = 0; i < laserCloudLastSize; i++) {
00260 if (fabs(laserCloudLast->points[i].v - 2) < 0.005 || fabs(laserCloudLast->points[i].v + 1) < 0.005) {
00261 laserCloudExtreLast->push_back(laserCloudLast->points[i]);
00262 }
00263 if (fabs(laserCloudLast->points[i].v - 2) < 0.005 || fabs(laserCloudLast->points[i].v - 1) < 0.005) {
00264 laserCloudCornerLast->push_back(laserCloudLast->points[i]);
00265 }
00266 if (fabs(laserCloudLast->points[i].v) < 0.005 || fabs(laserCloudLast->points[i].v + 1) < 0.005) {
00267 laserCloudSurfLast->push_back(laserCloudLast->points[i]);
00268 }
00269 if (fabs(laserCloudLast->points[i].v - 10) < 0.005) {
00270 imuPitchStartLast = laserCloudLast->points[i].x;
00271 imuYawStartLast = laserCloudLast->points[i].y;
00272 imuRollStartLast = laserCloudLast->points[i].z;
00273 }
00274 if (fabs(laserCloudLast->points[i].v - 11) < 0.005) {
00275 imuPitchLast = laserCloudLast->points[i].x;
00276 imuYawLast = laserCloudLast->points[i].y;
00277 imuRollLast = laserCloudLast->points[i].z;
00278 }
00279 if (fabs(laserCloudLast->points[i].v - 12) < 0.005) {
00280 imuShiftFromStartXLast = laserCloudLast->points[i].x;
00281 imuShiftFromStartYLast = laserCloudLast->points[i].y;
00282 imuShiftFromStartZLast = laserCloudLast->points[i].z;
00283 }
00284 if (fabs(laserCloudLast->points[i].v - 13) < 0.005) {
00285 imuVeloFromStartXLast = laserCloudLast->points[i].x;
00286 imuVeloFromStartYLast = laserCloudLast->points[i].y;
00287 imuVeloFromStartZLast = laserCloudLast->points[i].z;
00288 }
00289 }
00290
00291 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreePointer = kdtreeCornerLLast;
00292 kdtreeCornerLLast = kdtreeCornerLast;
00293 kdtreeCornerLast = kdtreePointer;
00294 kdtreeCornerLast->setInputCloud(laserCloudCornerLast);
00295
00296 kdtreePointer = kdtreeSurfLLast;
00297 kdtreeSurfLLast = kdtreeSurfLast;
00298 kdtreeSurfLast = kdtreePointer;
00299 kdtreeSurfLast->setInputCloud(laserCloudSurfLast);
00300
00301 if (timeLasted > 4.0) {
00302 newLaserCloudLast = true;
00303 }
00304 }
00305 }
00306
00307 int main(int argc, char** argv)
00308 {
00309 ros::init(argc, argv, "laserOdometry");
00310 ros::NodeHandle nh;
00311
00312 ros::Subscriber subLaserCloudExtreCur = nh.subscribe<sensor_msgs::PointCloud2>
00313 ("/laser_cloud_extre_cur", 1, laserCloudExtreCurHandler);
00314
00315 ros::Subscriber subLaserCloudLast = nh.subscribe<sensor_msgs::PointCloud2>
00316 ("/laser_cloud_last", 1, laserCloudLastHandler);
00317
00318 ros::Publisher pubLaserCloudLast2 = nh.advertise<sensor_msgs::PointCloud2> ("/laser_cloud_last_2", 1);
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332 ros::Publisher pubLaserOdometry = nh.advertise<nav_msgs::Odometry> ("/cam_to_init", 1);
00333 nav_msgs::Odometry laserOdometry;
00334 laserOdometry.header.frame_id = "/camera_init";
00335 laserOdometry.child_frame_id = "/camera";
00336
00337 tf::TransformBroadcaster tfBroadcaster;
00338 tf::StampedTransform laserOdometryTrans;
00339 laserOdometryTrans.frame_id_ = "/camera_init";
00340 laserOdometryTrans.child_frame_id_ = "/camera";
00341
00342 std::vector<int> pointSearchInd;
00343 std::vector<float> pointSearchSqDis;
00344
00345 pcl::PointXYZHSV extreOri, extreSel, extreProj, tripod1, tripod2, tripod3, coeff;
00346
00347 bool status = ros::ok();
00348 while (status) {
00349 ros::spinOnce();
00350
00351 bool sweepEnd = false;
00352 bool newLaserPoints = false;
00353 bool sufficientPoints = false;
00354 double startTime, endTime;
00355 pcl::PointCloud<pcl::PointXYZHSV>::Ptr extrePointsPtr, laserCloudCornerPtr, laserCloudSurfPtr;
00356 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeCornerPtr, kdtreeSurfPtr;
00357 if (newLaserCloudExtreCur && newLaserCloudLast) {
00358
00359 startTime = startTimeLast;
00360 endTime = startTimeCur;
00361
00362 extrePointsPtr = laserCloudExtreLast;
00363 laserCloudCornerPtr = laserCloudCornerLLast;
00364 laserCloudSurfPtr = laserCloudSurfLLast;
00365 kdtreeCornerPtr = kdtreeCornerLLast;
00366 kdtreeSurfPtr = kdtreeSurfLLast;
00367
00368 laserOdometry.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00369 laserOdometryTrans.stamp_ = ros::Time().fromSec(timeLaserCloudLast);
00370
00371 sweepEnd = true;
00372 newLaserPoints = true;
00373
00374 if (laserCloudSurfLLast->points.size() >= 100) {
00375 sufficientPoints = true;
00376 }
00377
00378 } else if (newLaserCloudExtreCur) {
00379
00380 startTime = startTimeCur;
00381 endTime = timeLasted;
00382
00383 extrePointsPtr = laserCloudExtreCur;
00384 laserCloudCornerPtr = laserCloudCornerLast;
00385 laserCloudSurfPtr = laserCloudSurfLast;
00386 kdtreeCornerPtr = kdtreeCornerLast;
00387 kdtreeSurfPtr = kdtreeSurfLast;
00388
00389 laserOdometry.header.stamp = ros::Time().fromSec(timeLaserCloudExtreCur);
00390 laserOdometryTrans.stamp_ = ros::Time().fromSec(timeLaserCloudExtreCur);
00391
00392 float s = (timeLasted - timeLastedRec) / (startTimeCur - startTimeLast);
00393 for (int i = 0; i < 6; i++) {
00394 transform[i] += s * transformRec[i];
00395 }
00396 timeLastedRec = timeLasted;
00397
00398 newLaserPoints = true;
00399
00400 if (laserCloudSurfLast->points.size() >= 100) {
00401 sufficientPoints = true;
00402 }
00403 }
00404
00405 if (newLaserPoints && sufficientPoints) {
00406 newLaserCloudExtreCur = false;
00407 newLaserCloudLast = false;
00408
00409 int extrePointNum = extrePointsPtr->points.size();
00410 int laserCloudCornerNum = laserCloudCornerPtr->points.size();
00411 int laserCloudSurfNum = laserCloudSurfPtr->points.size();
00412
00413 float st = 1;
00414 if (!sweepEnd) {
00415 st = (timeLasted - startTime) / (startTimeCur - startTimeLast);
00416 }
00417 int iterNum = st * 50;
00418
00419 for (int iterCount = 0; iterCount < iterNum; iterCount++) {
00420
00421 laserCloudExtreOri->clear();
00422
00423
00424
00425
00426 coeffSel->clear();
00427
00428 for (int i = 0; i < extrePointNum; i++) {
00429
00430 extreOri = extrePointsPtr->points[i];
00431 TransformToStart(&extreOri, &extreSel, startTime, endTime);
00432 if (fabs(extreOri.v + 1) < 0.05) {
00433
00434 kdtreeSurfPtr->nearestKSearch(extreSel, 1, pointSearchInd, pointSearchSqDis);
00435 if (pointSearchSqDis[0] > 1.0) {
00436 continue;
00437 }
00438
00439 int closestPointInd = pointSearchInd[0];
00440 float closestPointTime = laserCloudSurfPtr->points[closestPointInd].h;
00441
00442 int minPointInd2 = -1, minPointInd3 = -1;
00443 float pointSqDis, minPointSqDis2 = 1, minPointSqDis3 = 1;
00444 for (int j = closestPointInd + 1; j < laserCloudSurfNum; j++) {
00445 if (laserCloudSurfPtr->points[j].h > closestPointTime + 0.07) {
00446 break;
00447 }
00448
00449 pointSqDis = (laserCloudSurfPtr->points[j].x - extreSel.x) *
00450 (laserCloudSurfPtr->points[j].x - extreSel.x) +
00451 (laserCloudSurfPtr->points[j].y - extreSel.y) *
00452 (laserCloudSurfPtr->points[j].y - extreSel.y) +
00453 (laserCloudSurfPtr->points[j].z - extreSel.z) *
00454 (laserCloudSurfPtr->points[j].z - extreSel.z);
00455
00456 if (laserCloudSurfPtr->points[j].h < closestPointTime + 0.005) {
00457 if (pointSqDis < minPointSqDis2) {
00458 minPointSqDis2 = pointSqDis;
00459 minPointInd2 = j;
00460 }
00461 } else {
00462 if (pointSqDis < minPointSqDis3) {
00463 minPointSqDis3 = pointSqDis;
00464 minPointInd3 = j;
00465 }
00466 }
00467 }
00468 for (int j = closestPointInd - 1; j >= 0; j--) {
00469 if (laserCloudSurfPtr->points[j].h < closestPointTime - 0.07) {
00470 break;
00471 }
00472
00473 pointSqDis = (laserCloudSurfPtr->points[j].x - extreSel.x) *
00474 (laserCloudSurfPtr->points[j].x - extreSel.x) +
00475 (laserCloudSurfPtr->points[j].y - extreSel.y) *
00476 (laserCloudSurfPtr->points[j].y - extreSel.y) +
00477 (laserCloudSurfPtr->points[j].z - extreSel.z) *
00478 (laserCloudSurfPtr->points[j].z - extreSel.z);
00479
00480 if (laserCloudSurfPtr->points[j].h > closestPointTime - 0.005) {
00481 if (pointSqDis < minPointSqDis2) {
00482 minPointSqDis2 = pointSqDis;
00483 minPointInd2 = j;
00484 }
00485 } else {
00486 if (pointSqDis < minPointSqDis3) {
00487 minPointSqDis3 = pointSqDis;
00488 minPointInd3 = j;
00489 }
00490 }
00491 }
00492
00493 if (minPointInd2 >= 0 && minPointInd3 >= 0) {
00494 tripod1 = laserCloudSurfPtr->points[closestPointInd];
00495 tripod2 = laserCloudSurfPtr->points[minPointInd2];
00496 tripod3 = laserCloudSurfPtr->points[minPointInd3];
00497
00498 float pa = (tripod2.y - tripod1.y) * (tripod3.z - tripod1.z)
00499 - (tripod3.y - tripod1.y) * (tripod2.z - tripod1.z);
00500 float pb = (tripod2.z - tripod1.z) * (tripod3.x - tripod1.x)
00501 - (tripod3.z - tripod1.z) * (tripod2.x - tripod1.x);
00502 float pc = (tripod2.x - tripod1.x) * (tripod3.y - tripod1.y)
00503 - (tripod3.x - tripod1.x) * (tripod2.y - tripod1.y);
00504 float pd = -(pa * tripod1.x + pb * tripod1.y + pc * tripod1.z);
00505
00506 float ps = sqrt(pa * pa + pb * pb + pc * pc);
00507 pa /= ps;
00508 pb /= ps;
00509 pc /= ps;
00510 pd /= ps;
00511
00512 float pd2 = pa * extreSel.x + pb * extreSel.y + pc * extreSel.z + pd;
00513
00514 extreProj = extreSel;
00515 extreProj.x -= pa * pd2;
00516 extreProj.y -= pb * pd2;
00517 extreProj.z -= pc * pd2;
00518
00519 float s = 1;
00520 if (iterCount >= 30) {
00521 s = 1 - 8 * fabs(pd2) / sqrt(sqrt(extreSel.x * extreSel.x
00522 + extreSel.y * extreSel.y + extreSel.z * extreSel.z));
00523 }
00524
00525 coeff.x = s * pa;
00526 coeff.y = s * pb;
00527 coeff.z = s * pc;
00528 coeff.h = s * pd2;
00529
00530 if (s > 0.2 || iterNum < 30) {
00531 laserCloudExtreOri->push_back(extreOri);
00532
00533
00534
00535
00536
00537 coeffSel->push_back(coeff);
00538 } else {
00539
00540 }
00541 }
00542 } else if (fabs(extreOri.v - 2) < 0.05) {
00543
00544 kdtreeCornerPtr->nearestKSearch(extreSel, 1, pointSearchInd, pointSearchSqDis);
00545 if (pointSearchSqDis[0] > 1.0) {
00546 continue;
00547 }
00548
00549 int closestPointInd = pointSearchInd[0];
00550 float closestPointTime = laserCloudCornerPtr->points[closestPointInd].h;
00551
00552 int minPointInd2 = -1;
00553 float pointSqDis, minPointSqDis2 = 1;
00554 for (int j = closestPointInd + 1; j < laserCloudCornerNum; j++) {
00555 if (laserCloudCornerPtr->points[j].h > closestPointTime + 0.07) {
00556 break;
00557 }
00558
00559 pointSqDis = (laserCloudCornerPtr->points[j].x - extreSel.x) *
00560 (laserCloudCornerPtr->points[j].x - extreSel.x) +
00561 (laserCloudCornerPtr->points[j].y - extreSel.y) *
00562 (laserCloudCornerPtr->points[j].y - extreSel.y) +
00563 (laserCloudCornerPtr->points[j].z - extreSel.z) *
00564 (laserCloudCornerPtr->points[j].z - extreSel.z);
00565
00566 if (laserCloudCornerPtr->points[j].h > closestPointTime + 0.005) {
00567 if (pointSqDis < minPointSqDis2) {
00568 minPointSqDis2 = pointSqDis;
00569 minPointInd2 = j;
00570 }
00571 }
00572 }
00573 for (int j = closestPointInd - 1; j >= 0; j--) {
00574 if (laserCloudCornerPtr->points[j].h < closestPointTime - 0.07) {
00575 break;
00576 }
00577
00578 pointSqDis = (laserCloudCornerPtr->points[j].x - extreSel.x) *
00579 (laserCloudCornerPtr->points[j].x - extreSel.x) +
00580 (laserCloudCornerPtr->points[j].y - extreSel.y) *
00581 (laserCloudCornerPtr->points[j].y - extreSel.y) +
00582 (laserCloudCornerPtr->points[j].z - extreSel.z) *
00583 (laserCloudCornerPtr->points[j].z - extreSel.z);
00584
00585 if (laserCloudCornerPtr->points[j].h < closestPointTime - 0.005) {
00586 if (pointSqDis < minPointSqDis2) {
00587 minPointSqDis2 = pointSqDis;
00588 minPointInd2 = j;
00589 }
00590 }
00591 }
00592
00593 if (minPointInd2 >= 0) {
00594 tripod1 = laserCloudCornerPtr->points[closestPointInd];
00595 tripod2 = laserCloudCornerPtr->points[minPointInd2];
00596
00597 float x0 = extreSel.x;
00598 float y0 = extreSel.y;
00599 float z0 = extreSel.z;
00600 float x1 = tripod1.x;
00601 float y1 = tripod1.y;
00602 float z1 = tripod1.z;
00603 float x2 = tripod2.x;
00604 float y2 = tripod2.y;
00605 float z2 = tripod2.z;
00606
00607 float a012 = sqrt(((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
00608 * ((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
00609 + ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))
00610 * ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))
00611 + ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))
00612 * ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1)));
00613
00614 float l12 = sqrt((x1 - x2)*(x1 - x2) + (y1 - y2)*(y1 - y2) + (z1 - z2)*(z1 - z2));
00615
00616 float la = ((y1 - y2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
00617 + (z1 - z2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))) / a012 / l12;
00618
00619 float lb = -((x1 - x2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
00620 - (z1 - z2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;
00621
00622 float lc = -((x1 - x2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))
00623 + (y1 - y2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;
00624
00625 float ld2 = a012 / l12;
00626
00627 extreProj = extreSel;
00628 extreProj.x -= la * ld2;
00629 extreProj.y -= lb * ld2;
00630 extreProj.z -= lc * ld2;
00631
00632 float s = 2 * (1 - 8 * fabs(ld2));
00633
00634 coeff.x = s * la;
00635 coeff.y = s * lb;
00636 coeff.z = s * lc;
00637 coeff.h = s * ld2;
00638
00639 if (s > 0.4) {
00640 laserCloudExtreOri->push_back(extreOri);
00641
00642
00643
00644
00645 coeffSel->push_back(coeff);
00646 } else {
00647
00648 }
00649 }
00650 }
00651 }
00652 int extrePointSelNum = laserCloudExtreOri->points.size();
00653
00654 if (extrePointSelNum < 10) {
00655 continue;
00656 }
00657
00658 cv::Mat matA(extrePointSelNum, 6, CV_32F, cv::Scalar::all(0));
00659 cv::Mat matAt(6, extrePointSelNum, CV_32F, cv::Scalar::all(0));
00660 cv::Mat matAtA(6, 6, CV_32F, cv::Scalar::all(0));
00661 cv::Mat matB(extrePointSelNum, 1, CV_32F, cv::Scalar::all(0));
00662 cv::Mat matAtB(6, 1, CV_32F, cv::Scalar::all(0));
00663 cv::Mat matX(6, 1, CV_32F, cv::Scalar::all(0));
00664 for (int i = 0; i < extrePointSelNum; i++) {
00665 extreOri = laserCloudExtreOri->points[i];
00666 coeff = coeffSel->points[i];
00667
00668 float s = (extreOri.h - startTime) / (endTime - startTime);
00669
00670 float srx = sin(s * transform[0]);
00671 float crx = cos(s * transform[0]);
00672 float sry = sin(s * transform[1]);
00673 float cry = cos(s * transform[1]);
00674 float srz = sin(s * transform[2]);
00675 float crz = cos(s * transform[2]);
00676 float tx = s * transform[3];
00677 float ty = s * transform[4];
00678 float tz = s * transform[5];
00679
00680 float arx = (-s*crx*sry*srz*extreOri.x + s*crx*crz*sry*extreOri.y + s*srx*sry*extreOri.z
00681 + s*tx*crx*sry*srz - s*ty*crx*crz*sry - s*tz*srx*sry) * coeff.x
00682 + (s*srx*srz*extreOri.x - s*crz*srx*extreOri.y + s*crx*extreOri.z
00683 + s*ty*crz*srx - s*tz*crx - s*tx*srx*srz) * coeff.y
00684 + (s*crx*cry*srz*extreOri.x - s*crx*cry*crz*extreOri.y - s*cry*srx*extreOri.z
00685 + s*tz*cry*srx + s*ty*crx*cry*crz - s*tx*crx*cry*srz) * coeff.z;
00686
00687 float ary = ((-s*crz*sry - s*cry*srx*srz)*extreOri.x
00688 + (s*cry*crz*srx - s*sry*srz)*extreOri.y - s*crx*cry*extreOri.z
00689 + tx*(s*crz*sry + s*cry*srx*srz) + ty*(s*sry*srz - s*cry*crz*srx)
00690 + s*tz*crx*cry) * coeff.x
00691 + ((s*cry*crz - s*srx*sry*srz)*extreOri.x
00692 + (s*cry*srz + s*crz*srx*sry)*extreOri.y - s*crx*sry*extreOri.z
00693 + s*tz*crx*sry - ty*(s*cry*srz + s*crz*srx*sry)
00694 - tx*(s*cry*crz - s*srx*sry*srz)) * coeff.z;
00695
00696 float arz = ((-s*cry*srz - s*crz*srx*sry)*extreOri.x + (s*cry*crz - s*srx*sry*srz)*extreOri.y
00697 + tx*(s*cry*srz + s*crz*srx*sry) - ty*(s*cry*crz - s*srx*sry*srz)) * coeff.x
00698 + (-s*crx*crz*extreOri.x - s*crx*srz*extreOri.y
00699 + s*ty*crx*srz + s*tx*crx*crz) * coeff.y
00700 + ((s*cry*crz*srx - s*sry*srz)*extreOri.x + (s*crz*sry + s*cry*srx*srz)*extreOri.y
00701 + tx*(s*sry*srz - s*cry*crz*srx) - ty*(s*crz*sry + s*cry*srx*srz)) * coeff.z;
00702
00703 float atx = -s*(cry*crz - srx*sry*srz) * coeff.x + s*crx*srz * coeff.y
00704 - s*(crz*sry + cry*srx*srz) * coeff.z;
00705
00706 float aty = -s*(cry*srz + crz*srx*sry) * coeff.x - s*crx*crz * coeff.y
00707 - s*(sry*srz - cry*crz*srx) * coeff.z;
00708
00709 float atz = s*crx*sry * coeff.x - s*srx * coeff.y - s*crx*cry * coeff.z;
00710
00711 float d2 = coeff.h;
00712
00713 matA.at<float>(i, 0) = arx;
00714 matA.at<float>(i, 1) = ary;
00715 matA.at<float>(i, 2) = arz;
00716 matA.at<float>(i, 3) = atx;
00717 matA.at<float>(i, 4) = aty;
00718 matA.at<float>(i, 5) = atz;
00719 matB.at<float>(i, 0) = -0.015 * st * d2;
00720 }
00721 cv::transpose(matA, matAt);
00722 matAtA = matAt * matA;
00723 matAtB = matAt * matB;
00724 cv::solve(matAtA, matAtB, matX, cv::DECOMP_QR);
00725
00726
00727 if (fabs(matX.at<float>(0, 0)) < 0.005 &&
00728 fabs(matX.at<float>(1, 0)) < 0.005 &&
00729 fabs(matX.at<float>(2, 0)) < 0.005 &&
00730 fabs(matX.at<float>(3, 0)) < 0.01 &&
00731 fabs(matX.at<float>(4, 0)) < 0.01 &&
00732 fabs(matX.at<float>(5, 0)) < 0.01) {
00733
00734
00735
00736
00737 transform[0] += 0.1 * matX.at<float>(0, 0);
00738 transform[1] += 0.1 * matX.at<float>(1, 0);
00739 transform[2] += 0.1 * matX.at<float>(2, 0);
00740 transform[3] += matX.at<float>(3, 0);
00741 transform[4] += matX.at<float>(4, 0);
00742 transform[5] += matX.at<float>(5, 0);
00743 } else {
00744
00745 }
00746 }
00747
00748
00749
00750
00751
00752
00753
00754
00755
00756
00757
00758
00759
00760
00761
00762
00763
00764
00765
00766
00767
00768
00769
00770
00771
00772
00773
00774
00775
00776
00777
00778
00779
00780
00781
00782
00783 }
00784
00785 if (newLaserPoints) {
00786 float rx, ry, rz, tx, ty, tz;
00787 if (sweepEnd) {
00788 rx = transformSum[0] - transform[0];
00789 ry = transformSum[1] - transform[1] * 1.05;
00790 rz = transformSum[2] - transform[2];
00791
00792 float x1 = cos(rz) * (transform[3] - imuShiftFromStartXLast)
00793 - sin(rz) * (transform[4] - imuShiftFromStartYLast);
00794 float y1 = sin(rz) * (transform[3] - imuShiftFromStartXLast)
00795 + cos(rz) * (transform[4] - imuShiftFromStartYLast);
00796 float z1 = transform[5] * 1.05 - imuShiftFromStartZLast;
00797
00798 float x2 = x1;
00799 float y2 = cos(rx) * y1 - sin(rx) * z1;
00800 float z2 = sin(rx) * y1 + cos(rx) * z1;
00801
00802 tx = transformSum[3] - (cos(ry) * x2 + sin(ry) * z2);
00803 ty = transformSum[4] - y2;
00804 tz = transformSum[5] - (-sin(ry) * x2 + cos(ry) * z2);
00805
00806 rx += imuPitchLast - imuPitchStartLast;
00807 ry += imuYawLast - imuYawStartLast;
00808 rz += imuRollLast - imuRollStartLast;
00809
00810 int laserCloudCornerLastNum = laserCloudCornerLast->points.size();
00811 for (int i = 0; i < laserCloudCornerLastNum; i++) {
00812 TransformToEnd(&laserCloudCornerLast->points[i], &laserCloudCornerLast->points[i],
00813 startTimeLast, startTimeCur);
00814 }
00815
00816 int laserCloudSurfLastNum = laserCloudSurfLast->points.size();
00817 for (int i = 0; i < laserCloudSurfLastNum; i++) {
00818 TransformToEnd(&laserCloudSurfLast->points[i], &laserCloudSurfLast->points[i],
00819 startTimeLast, startTimeCur);
00820 }
00821
00822 TransformReset();
00823
00824 transformSum[0] = rx;
00825 transformSum[1] = ry;
00826 transformSum[2] = rz;
00827 transformSum[3] = tx;
00828 transformSum[4] = ty;
00829 transformSum[5] = tz;
00830
00831 sensor_msgs::PointCloud2 laserCloudLast2;
00832 pcl::toROSMsg(*laserCloudCornerLast + *laserCloudSurfLast, laserCloudLast2);
00833 laserCloudLast2.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00834 laserCloudLast2.header.frame_id = "/camera";
00835 pubLaserCloudLast2.publish(laserCloudLast2);
00836
00837 } else {
00838 rx = transformSum[0] - transform[0];
00839 ry = transformSum[1] - transform[1] * 1.05;
00840 rz = transformSum[2] - transform[2];
00841
00842 float x1 = cos(rz) * (transform[3] - imuShiftFromStartXCur)
00843 - sin(rz) * (transform[4] - imuShiftFromStartYCur);
00844 float y1 = sin(rz) * (transform[3] - imuShiftFromStartXCur)
00845 + cos(rz) * (transform[4] - imuShiftFromStartYCur);
00846 float z1 = transform[5] * 1.05 - imuShiftFromStartZCur;
00847
00848 float x2 = x1;
00849 float y2 = cos(rx) * y1 - sin(rx) * z1;
00850 float z2 = sin(rx) * y1 + cos(rx) * z1;
00851
00852 tx = transformSum[3] - (cos(ry) * x2 + sin(ry) * z2);
00853 ty = transformSum[4] - y2;
00854 tz = transformSum[5] - (-sin(ry) * x2 + cos(ry) * z2);
00855
00856 rx += imuPitchCur - imuPitchStartCur;
00857 ry += imuYawCur - imuYawStartCur;
00858 rz += imuRollCur - imuRollStartCur;
00859 }
00860
00861 geometry_msgs::Quaternion geoQuat = tf::createQuaternionMsgFromRollPitchYaw(rz, -rx, -ry);
00862
00863 laserOdometry.pose.pose.orientation.x = -geoQuat.y;
00864 laserOdometry.pose.pose.orientation.y = -geoQuat.z;
00865 laserOdometry.pose.pose.orientation.z = geoQuat.x;
00866 laserOdometry.pose.pose.orientation.w = geoQuat.w;
00867 laserOdometry.pose.pose.position.x = tx;
00868 laserOdometry.pose.pose.position.y = ty;
00869 laserOdometry.pose.pose.position.z = tz;
00870 pubLaserOdometry.publish(laserOdometry);
00871
00872 laserOdometryTrans.setRotation(tf::Quaternion(-geoQuat.y, -geoQuat.z, geoQuat.x, geoQuat.w));
00873 laserOdometryTrans.setOrigin(tf::Vector3(tx, ty, tz));
00874 tfBroadcaster.sendTransform(laserOdometryTrans);
00875
00876
00877
00878 }
00879
00880 status = ros::ok();
00881 cvWaitKey(10);
00882 }
00883
00884 return 0;
00885 }