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