laserMapping.cpp
Go to the documentation of this file.
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 double timeLaserCloudLast;
00028 double timeLaserOdometry;
00029 
00030 bool newLaserCloudLast = false;
00031 bool newLaserOdometry = false;
00032 
00033 const int laserCloudCenWidth = 5;
00034 const int laserCloudCenHeight = 5;
00035 const int laserCloudCenDepth = 5;
00036 const int laserCloudWidth = 11;
00037 const int laserCloudHeight = 11;
00038 const int laserCloudDepth = 11;
00039 const int laserCloudNum = laserCloudWidth * laserCloudHeight * laserCloudDepth;
00040 
00041 int laserCloudValidInd[27];
00042 int laserCloudSurroundInd[27];
00043 
00044 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCorner(new pcl::PointCloud<pcl::PointXYZHSV>());
00045 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurf(new pcl::PointCloud<pcl::PointXYZHSV>());
00046 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCorner2(new pcl::PointCloud<pcl::PointXYZHSV>());
00047 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurf2(new pcl::PointCloud<pcl::PointXYZHSV>());
00048 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudLast(new pcl::PointCloud<pcl::PointXYZHSV>());
00049 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudOri(new pcl::PointCloud<pcl::PointXYZHSV>());
00050 //pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSel(new pcl::PointCloud<pcl::PointXYZHSV>());
00051 //pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCorr(new pcl::PointCloud<pcl::PointXYZHSV>());
00052 //pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudProj(new pcl::PointCloud<pcl::PointXYZHSV>());
00053 pcl::PointCloud<pcl::PointXYZHSV>::Ptr coeffSel(new pcl::PointCloud<pcl::PointXYZHSV>());
00054 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudFromMap(new pcl::PointCloud<pcl::PointXYZHSV>());
00055 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCornerFromMap(new pcl::PointCloud<pcl::PointXYZHSV>());
00056 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudSurfFromMap(new pcl::PointCloud<pcl::PointXYZHSV>());
00057 pcl::PointCloud<pcl::PointXYZI>::Ptr laserCloudSurround(new pcl::PointCloud<pcl::PointXYZI>());
00058 pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudArray[laserCloudNum];
00059 
00060 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeCornerFromMap(new pcl::KdTreeFLANN<pcl::PointXYZHSV>());
00061 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr kdtreeSurfFromMap(new pcl::KdTreeFLANN<pcl::PointXYZHSV>());
00062 
00063 float transformSum[6] = {0};
00064 float transformIncre[6] = {0};
00065 float transformTobeMapped[6] = {0};
00066 float transformBefMapped[6] = {0};
00067 float transformAftMapped[6] = {0};
00068 
00069 void transformAssociateToMap()
00070 {
00071   float x1 = cos(transformSum[2]) * (transformBefMapped[3] - transformSum[3]) 
00072            + sin(transformSum[2]) * (transformBefMapped[4] - transformSum[4]);
00073   float y1 = -sin(transformSum[2]) * (transformBefMapped[3] - transformSum[3])
00074            + cos(transformSum[2]) * (transformBefMapped[4] - transformSum[4]);
00075   float z1 = transformBefMapped[5] - transformSum[5];
00076 
00077   float x2 = x1;
00078   float y2 = cos(transformSum[0]) * y1 + sin(transformSum[0]) * z1;
00079   float z2 = -sin(transformSum[0]) * y1 + cos(transformSum[0]) * z1;
00080 
00081   transformIncre[3] = cos(transformSum[1]) * x1 - sin(transformSum[1]) * z1;
00082   transformIncre[4] = y2;
00083   transformIncre[5] = sin(transformSum[1]) * x1 + cos(transformSum[1]) * z1;
00084 
00085   transformIncre[0] = transformBefMapped[0] - transformSum[0];
00086   transformIncre[1] = transformBefMapped[1] - transformSum[1];
00087   transformIncre[2] = transformBefMapped[2] - transformSum[2];
00088 
00089   transformTobeMapped[0] = transformAftMapped[0] - transformIncre[0];
00090   transformTobeMapped[1] = transformAftMapped[1] - transformIncre[1];
00091   transformTobeMapped[2] = transformAftMapped[2] - transformIncre[2];
00092 
00093   x1 = cos(transformTobeMapped[1]) * transformIncre[3] 
00094      + sin(transformTobeMapped[1]) * transformIncre[5];
00095   y1 = transformIncre[4];
00096   z1 = -sin(transformTobeMapped[1]) * transformIncre[3] 
00097      + cos(transformTobeMapped[1]) * transformIncre[5];
00098 
00099   x2 = x1;
00100   y2 = cos(transformTobeMapped[0]) * y1 - sin(transformTobeMapped[0]) * z1;
00101   z2 = sin(transformTobeMapped[0]) * y1 + cos(transformTobeMapped[0]) * z1;
00102 
00103   transformTobeMapped[3] = transformAftMapped[3] 
00104                          - (cos(transformTobeMapped[2]) * x2 - sin(transformTobeMapped[2]) * y2);
00105   transformTobeMapped[4] = transformAftMapped[4] 
00106                          - (sin(transformTobeMapped[2]) * x2 + cos(transformTobeMapped[2]) * y2);
00107   transformTobeMapped[5] = transformAftMapped[5] - z2;
00108 }
00109 
00110 void transformUpdate()
00111 {
00112   //for (int i = 0; i < 3; i++) {
00113   //  transformTobeMapped[i] = (1 - 0.1) * transformTobeMapped[i] + 0.1 * transformSum[i];
00114   //}
00115 
00116   for (int i = 0; i < 6; i++) {
00117     transformBefMapped[i] = transformSum[i];
00118     transformAftMapped[i] = transformTobeMapped[i];
00119   }
00120 }
00121 
00122 void pointAssociateToMap(pcl::PointXYZHSV *pi, pcl::PointXYZHSV *po)
00123 {
00124   float x1 = cos(transformTobeMapped[2]) * pi->x
00125            - sin(transformTobeMapped[2]) * pi->y;
00126   float y1 = sin(transformTobeMapped[2]) * pi->x
00127            + cos(transformTobeMapped[2]) * pi->y;
00128   float z1 = pi->z;
00129 
00130   float x2 = x1;
00131   float y2 = cos(transformTobeMapped[0]) * y1 - sin(transformTobeMapped[0]) * z1;
00132   float z2 = sin(transformTobeMapped[0]) * y1 + cos(transformTobeMapped[0]) * z1;
00133 
00134   po->x = cos(transformTobeMapped[1]) * x2 + sin(transformTobeMapped[1]) * z2
00135         + transformTobeMapped[3];
00136   po->y = y2 + transformTobeMapped[4];
00137   po->z = -sin(transformTobeMapped[1]) * x2 + cos(transformTobeMapped[1]) * z2
00138         + transformTobeMapped[5];
00139   po->h = pi->h;
00140   po->s = pi->s;
00141   po->v = pi->v;
00142 }
00143 
00144 void laserCloudLastHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudLast2)
00145 {
00146   timeLaserCloudLast = laserCloudLast2->header.stamp.toSec();
00147 
00148   laserCloudLast->clear();
00149   pcl::fromROSMsg(*laserCloudLast2, *laserCloudLast);
00150 
00151   newLaserCloudLast = true;
00152 }
00153 
00154 void laserOdometryHandler(const nav_msgs::Odometry::ConstPtr& laserOdometry)
00155 {
00156   timeLaserOdometry = laserOdometry->header.stamp.toSec();
00157 
00158   double roll, pitch, yaw;
00159   geometry_msgs::Quaternion geoQuat = laserOdometry->pose.pose.orientation;
00160   tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(roll, pitch, yaw);
00161 
00162   transformSum[0] = -pitch;
00163   transformSum[1] = -yaw;
00164   transformSum[2] = roll;
00165 
00166   transformSum[3] = laserOdometry->pose.pose.position.x;
00167   transformSum[4] = laserOdometry->pose.pose.position.y;
00168   transformSum[5] = laserOdometry->pose.pose.position.z;
00169 
00170   newLaserOdometry = true;
00171 }
00172 
00173 int main(int argc, char** argv)
00174 {
00175   ros::init(argc, argv, "laserMapping");
00176   ros::NodeHandle nh;
00177 
00178   ros::Subscriber subLaserCloudLast2 = nh.subscribe<sensor_msgs::PointCloud2> 
00179                                        ("/laser_cloud_last_2", 1, laserCloudLastHandler);
00180 
00181   ros::Subscriber subLaserOdometry = nh.subscribe<nav_msgs::Odometry> 
00182                                      ("/cam_to_init", 1, laserOdometryHandler);
00183 
00184   ros::Publisher pubLaserCloudSurround = nh.advertise<sensor_msgs::PointCloud2> 
00185                                          ("/laser_cloud_surround", 1);
00186 
00187   //ros::Publisher pub1 = nh.advertise<sensor_msgs::PointCloud2> ("/pc1", 1);
00188 
00189   //ros::Publisher pub2 = nh.advertise<sensor_msgs::PointCloud2> ("/pc2", 1);
00190 
00191   //ros::Publisher pub3 = nh.advertise<sensor_msgs::PointCloud2> ("/pc3", 1);
00192 
00193   //ros::Publisher pub4 = nh.advertise<sensor_msgs::PointCloud2> ("/pc4", 1);
00194 
00195   ros::Publisher pubOdomBefMapped = nh.advertise<nav_msgs::Odometry> ("/bef_mapped_to_init_2", 1);
00196   nav_msgs::Odometry odomBefMapped;
00197   odomBefMapped.header.frame_id = "/camera_init_2";
00198   odomBefMapped.child_frame_id = "/bef_mapped";
00199 
00200   ros::Publisher pubOdomAftMapped = nh.advertise<nav_msgs::Odometry> ("/aft_mapped_to_init_2", 1);
00201   nav_msgs::Odometry odomAftMapped;
00202   odomAftMapped.header.frame_id = "/camera_init_2";
00203   odomAftMapped.child_frame_id = "/aft_mapped";
00204 
00205   std::vector<int> pointSearchInd;
00206   std::vector<float> pointSearchSqDis;
00207 
00208   pcl::PointXYZHSV pointOri, pointSel, pointProj, coeff;
00209   pcl::PointXYZI pointSurround;
00210 
00211   cv::Mat matA0(5, 3, CV_32F, cv::Scalar::all(0));
00212   cv::Mat matB0(5, 1, CV_32F, cv::Scalar::all(-1));
00213   cv::Mat matX0(3, 1, CV_32F, cv::Scalar::all(0));
00214 
00215   cv::Mat matA1(3, 3, CV_32F, cv::Scalar::all(0));
00216   cv::Mat matD1(1, 3, CV_32F, cv::Scalar::all(0));
00217   cv::Mat matV1(3, 3, CV_32F, cv::Scalar::all(0));
00218 
00219   for (int i = 0; i < laserCloudNum; i++) {
00220     laserCloudArray[i].reset(new pcl::PointCloud<pcl::PointXYZHSV>());
00221   }
00222 
00223   bool status = ros::ok();
00224   while (status) {
00225     ros::spinOnce();
00226 
00227     if (newLaserCloudLast && newLaserOdometry && fabs(timeLaserCloudLast - timeLaserOdometry) < 0.005) {
00228       newLaserCloudLast = false;
00229       newLaserOdometry = false;
00230 
00231       transformAssociateToMap();
00232 
00233       pcl::PointXYZHSV pointOnZAxis;
00234       pointOnZAxis.x = 0.0;
00235       pointOnZAxis.y = 0.0;
00236       pointOnZAxis.z = 10.0;
00237       pointAssociateToMap(&pointOnZAxis, &pointOnZAxis);        
00238 
00239       int centerCubeI = int((transformTobeMapped[3] + 10.0) / 20.0) + laserCloudCenWidth;
00240       int centerCubeJ = int((transformTobeMapped[4] + 10.0) / 20.0) + laserCloudCenHeight;
00241       int centerCubeK = int((transformTobeMapped[5] + 10.0) / 20.0) + laserCloudCenDepth;
00242       if (centerCubeI < 0 || centerCubeI >= laserCloudWidth || 
00243           centerCubeJ < 0 || centerCubeJ >= laserCloudHeight || 
00244           centerCubeK < 0 || centerCubeK >= laserCloudDepth) {
00245 
00246         transformUpdate();
00247         continue;
00248       }
00249 
00250       int laserCloudValidNum = 0;
00251       int laserCloudSurroundNum = 0;
00252       for (int i = centerCubeI - 1; i <= centerCubeI + 1; i++) {
00253         for (int j = centerCubeJ - 1; j <= centerCubeJ + 1; j++) {
00254           for (int k = centerCubeK - 1; k <= centerCubeK + 1; k++) {
00255             if (i >= 0 && i < laserCloudWidth && 
00256                 j >= 0 && j < laserCloudHeight && 
00257                 k >= 0 && k < laserCloudDepth) {
00258               
00259               float centerX = 20.0 * (i - laserCloudCenWidth);
00260               float centerY = 20.0 * (j - laserCloudCenHeight);
00261               float centerZ = 20.0 * (k - laserCloudCenDepth);
00262 
00263               bool isInLaserFOV = false;
00264               for (int ii = -1; ii <= 1; ii += 2) {
00265                 for (int jj = -1; jj <= 1; jj += 2) {
00266                   for (int kk = -1; kk <= 1; kk += 2) {
00267                     float cornerX = centerX + 10.0 * ii;
00268                     float cornerY = centerY + 10.0 * jj;
00269                     float cornerZ = centerZ + 10.0 * kk;
00270 
00271                     float check = 100.0 
00272                                 + (transformTobeMapped[3] - cornerX) * (transformTobeMapped[3] - cornerX) 
00273                                 + (transformTobeMapped[4] - cornerY) * (transformTobeMapped[4] - cornerY)
00274                                 + (transformTobeMapped[5] - cornerZ) * (transformTobeMapped[5] - cornerZ)
00275                                 - (pointOnZAxis.x - cornerX) * (pointOnZAxis.x - cornerX) 
00276                                 - (pointOnZAxis.y - cornerY) * (pointOnZAxis.y - cornerY)
00277                                 - (pointOnZAxis.z - cornerZ) * (pointOnZAxis.z - cornerZ);
00278 
00279                     if (check > 0) {
00280                       isInLaserFOV = true;
00281                     }
00282                   }
00283                 }
00284               }
00285 
00286               if (isInLaserFOV) {
00287                 laserCloudValidInd[laserCloudValidNum] = i + laserCloudWidth * j 
00288                                                        + laserCloudWidth * laserCloudHeight * k;
00289                 laserCloudValidNum++;
00290               }
00291               laserCloudSurroundInd[laserCloudSurroundNum] = i + laserCloudWidth * j 
00292                                                            + laserCloudWidth * laserCloudHeight * k;
00293               laserCloudSurroundNum++;
00294             }
00295           }
00296         }
00297       }
00298 
00299       laserCloudFromMap->clear();
00300       for (int i = 0; i < laserCloudValidNum; i++) {
00301         *laserCloudFromMap += *laserCloudArray[laserCloudValidInd[i]];
00302       }
00303       int laserCloudFromMapNum = laserCloudFromMap->points.size();
00304 
00305       laserCloudCornerFromMap->clear();
00306       laserCloudSurfFromMap->clear();
00307       for (int i = 0; i < laserCloudFromMapNum; i++) {
00308         if (fabs(laserCloudFromMap->points[i].v - 2) < 0.005 || 
00309             fabs(laserCloudFromMap->points[i].v - 1) < 0.005) {
00310           laserCloudCornerFromMap->push_back(laserCloudFromMap->points[i]);
00311         } else {
00312           laserCloudSurfFromMap->push_back(laserCloudFromMap->points[i]);
00313         }
00314       }
00315 
00316       laserCloudCorner->clear();
00317       laserCloudSurf->clear();
00318       int laserCloudLastNum = laserCloudLast->points.size();
00319       for (int i = 0; i < laserCloudLastNum; i++) {
00320         if (fabs(laserCloudLast->points[i].v - 2) < 0.005 || 
00321             fabs(laserCloudLast->points[i].v - 1) < 0.005) {
00322           laserCloudCorner->push_back(laserCloudLast->points[i]);
00323         } else {
00324           laserCloudSurf->push_back(laserCloudLast->points[i]);
00325         }
00326       }
00327 
00328       laserCloudCorner2->clear();
00329       pcl::VoxelGrid<pcl::PointXYZHSV> downSizeFilter;
00330       downSizeFilter.setInputCloud(laserCloudCorner);
00331       downSizeFilter.setLeafSize(0.05, 0.05, 0.05);
00332       downSizeFilter.filter(*laserCloudCorner2);
00333 
00334       laserCloudSurf2->clear();
00335       downSizeFilter.setInputCloud(laserCloudSurf);
00336       downSizeFilter.setLeafSize(0.1, 0.1, 0.1);
00337       downSizeFilter.filter(*laserCloudSurf2);
00338 
00339       laserCloudLast->clear();
00340       *laserCloudLast = *laserCloudCorner2 + *laserCloudSurf2;
00341       laserCloudLastNum = laserCloudLast->points.size();
00342 
00343       if (laserCloudSurfFromMap->points.size() > 500) {
00344 
00345         kdtreeCornerFromMap->setInputCloud(laserCloudCornerFromMap);
00346         kdtreeSurfFromMap->setInputCloud(laserCloudSurfFromMap);
00347 
00348         for (int iterCount = 0; iterCount < 10; iterCount++) {
00349           laserCloudOri->clear();
00350           //laserCloudSel->clear();
00351           //laserCloudCorr->clear();
00352           //laserCloudProj->clear();
00353           coeffSel->clear();
00354 
00355           for (int i = 0; i < laserCloudLastNum; i++) {
00356             if (fabs(laserCloudLast->points[i].x > 0.3) || fabs(laserCloudLast->points[i].y > 0.3) ||
00357                 fabs(laserCloudLast->points[i].z > 0.3)) {
00358 
00359               pointOri = laserCloudLast->points[i];
00360               pointAssociateToMap(&pointOri, &pointSel); 
00361               if (fabs(pointOri.v) < 0.05 || fabs(pointOri.v + 1) < 0.05) {
00362 
00363                 kdtreeSurfFromMap->nearestKSearch(pointSel, 5, pointSearchInd, pointSearchSqDis);
00364 
00365                 if (pointSearchSqDis[4] < 1.0) {
00366                   for (int j = 0; j < 5; j++) {
00367                     matA0.at<float>(j, 0) = laserCloudSurfFromMap->points[pointSearchInd[j]].x;
00368                     matA0.at<float>(j, 1) = laserCloudSurfFromMap->points[pointSearchInd[j]].y;
00369                     matA0.at<float>(j, 2) = laserCloudSurfFromMap->points[pointSearchInd[j]].z;
00370                   }
00371                   cv::solve(matA0, matB0, matX0, cv::DECOMP_QR);
00372 
00373                   float pa = matX0.at<float>(0, 0);
00374                   float pb = matX0.at<float>(1, 0);
00375                   float pc = matX0.at<float>(2, 0);
00376                   float pd = 1;
00377  
00378                   float ps = sqrt(pa * pa + pb * pb + pc * pc);
00379                   pa /= ps;
00380                   pb /= ps;
00381                   pc /= ps;
00382                   pd /= ps;
00383 
00384                   bool planeValid = true;
00385                   for (int j = 0; j < 5; j++) {
00386                     if (fabs(pa * laserCloudSurfFromMap->points[pointSearchInd[j]].x +
00387                         pb * laserCloudSurfFromMap->points[pointSearchInd[j]].y +
00388                         pc * laserCloudSurfFromMap->points[pointSearchInd[j]].z + pd) > 0.05) {
00389                       planeValid = false;
00390                       break;
00391                     }
00392                   }
00393 
00394                   if (planeValid) {
00395                     float pd2 = pa * pointSel.x + pb * pointSel.y + pc * pointSel.z + pd;
00396 
00397                     pointProj = pointSel;
00398                     pointProj.x -= pa * pd2;
00399                     pointProj.y -= pb * pd2;
00400                     pointProj.z -= pc * pd2;
00401 
00402                     float s = 1;
00403                     if (iterCount >= 6) {
00404                       s = 1 - 8 * fabs(pd2) / sqrt(sqrt(pointSel.x * pointSel.x
00405                         + pointSel.y * pointSel.y + pointSel.z * pointSel.z));
00406                     }
00407 
00408                     coeff.x = s * pa;
00409                     coeff.y = s * pb;
00410                     coeff.z = s * pc;
00411                     coeff.h = s * pd2;
00412 
00413                     if (s > 0.2) {
00414                       laserCloudOri->push_back(pointOri);
00415                       //laserCloudSel->push_back(pointSel);
00416                       //laserCloudProj->push_back(pointProj);
00417                       //laserCloudCorr->push_back(laserCloudSurfFromMap->points[pointSearchInd[0]]);
00418                       //laserCloudCorr->push_back(laserCloudSurfFromMap->points[pointSearchInd[1]]);
00419                       //laserCloudCorr->push_back(laserCloudSurfFromMap->points[pointSearchInd[2]]);
00420                       //laserCloudCorr->push_back(laserCloudSurfFromMap->points[pointSearchInd[3]]);
00421                       //laserCloudCorr->push_back(laserCloudSurfFromMap->points[pointSearchInd[4]]);
00422                       coeffSel->push_back(coeff);
00423                     }
00424                   }
00425                 }
00426               } else {
00427 
00428                 kdtreeCornerFromMap->nearestKSearch(pointSel, 5, pointSearchInd, pointSearchSqDis);
00429                 
00430                 if (pointSearchSqDis[4] < 1.0) {
00431                   float cx = 0;
00432                   float cy = 0; 
00433                   float cz = 0;
00434                   for (int j = 0; j < 5; j++) {
00435                     cx += laserCloudCornerFromMap->points[pointSearchInd[j]].x;
00436                     cy += laserCloudCornerFromMap->points[pointSearchInd[j]].y;
00437                     cz += laserCloudCornerFromMap->points[pointSearchInd[j]].z;
00438                   }
00439                   cx /= 5;
00440                   cy /= 5; 
00441                   cz /= 5;
00442 
00443                   float a11 = 0;
00444                   float a12 = 0; 
00445                   float a13 = 0;
00446                   float a22 = 0;
00447                   float a23 = 0; 
00448                   float a33 = 0;
00449                   for (int j = 0; j < 5; j++) {
00450                     float ax = laserCloudCornerFromMap->points[pointSearchInd[j]].x - cx;
00451                     float ay = laserCloudCornerFromMap->points[pointSearchInd[j]].y - cy;
00452                     float az = laserCloudCornerFromMap->points[pointSearchInd[j]].z - cz;
00453 
00454                     a11 += ax * ax;
00455                     a12 += ax * ay;
00456                     a13 += ax * az;
00457                     a22 += ay * ay;
00458                     a23 += ay * az;
00459                     a33 += az * az;
00460                   }
00461                   a11 /= 5;
00462                   a12 /= 5; 
00463                   a13 /= 5;
00464                   a22 /= 5;
00465                   a23 /= 5; 
00466                   a33 /= 5;
00467 
00468                   matA1.at<float>(0, 0) = a11;
00469                   matA1.at<float>(0, 1) = a12;
00470                   matA1.at<float>(0, 2) = a13;
00471                   matA1.at<float>(1, 0) = a12;
00472                   matA1.at<float>(1, 1) = a22;
00473                   matA1.at<float>(1, 2) = a23;
00474                   matA1.at<float>(2, 0) = a13;
00475                   matA1.at<float>(2, 1) = a23;
00476                   matA1.at<float>(2, 2) = a33;
00477 
00478                   cv::eigen(matA1, matD1, matV1);
00479 
00480                   if (matD1.at<float>(0, 0) > 3 * matD1.at<float>(0, 1)) {
00481 
00482                     float x0 = pointSel.x;
00483                     float y0 = pointSel.y;
00484                     float z0 = pointSel.z;
00485                     float x1 = cx + 0.1 * matV1.at<float>(0, 0);
00486                     float y1 = cy + 0.1 * matV1.at<float>(0, 1);
00487                     float z1 = cz + 0.1 * matV1.at<float>(0, 2);
00488                     float x2 = cx - 0.1 * matV1.at<float>(0, 0);
00489                     float y2 = cy - 0.1 * matV1.at<float>(0, 1);
00490                     float z2 = cz - 0.1 * matV1.at<float>(0, 2);
00491 
00492                     float a012 = sqrt(((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
00493                                * ((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) 
00494                                + ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))
00495                                * ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1)) 
00496                                + ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))
00497                                * ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1)));
00498 
00499                     float l12 = sqrt((x1 - x2)*(x1 - x2) + (y1 - y2)*(y1 - y2) + (z1 - z2)*(z1 - z2));
00500 
00501                     float la = ((y1 - y2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) 
00502                              + (z1 - z2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))) / a012 / l12;
00503 
00504                     float lb = -((x1 - x2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1)) 
00505                              - (z1 - z2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;
00506 
00507                     float lc = -((x1 - x2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1)) 
00508                              + (y1 - y2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;
00509 
00510                     float ld2 = a012 / l12;
00511 
00512                     pointProj = pointSel;
00513                     pointProj.x -= la * ld2;
00514                     pointProj.y -= lb * ld2;
00515                     pointProj.z -= lc * ld2;
00516 
00517                     float s = 2 * (1 - 8 * fabs(ld2));
00518 
00519                     coeff.x = s * la;
00520                     coeff.y = s * lb;
00521                     coeff.z = s * lc;
00522                     coeff.h = s * ld2;
00523 
00524                     if (s > 0.4) {
00525                       laserCloudOri->push_back(pointOri);
00526                       //laserCloudSel->push_back(pointSel);
00527                       //laserCloudProj->push_back(pointProj);
00528                       //laserCloudCorr->push_back(laserCloudCornerFromMap->points[pointSearchInd[0]]);
00529                       //laserCloudCorr->push_back(laserCloudCornerFromMap->points[pointSearchInd[1]]);
00530                       //laserCloudCorr->push_back(laserCloudCornerFromMap->points[pointSearchInd[2]]);
00531                       //laserCloudCorr->push_back(laserCloudCornerFromMap->points[pointSearchInd[3]]);
00532                       //laserCloudCorr->push_back(laserCloudCornerFromMap->points[pointSearchInd[4]]);
00533                       coeffSel->push_back(coeff);
00534                     }
00535                   }
00536                 }
00537               }
00538             }
00539           }
00540           int laserCloudSelNum = laserCloudOri->points.size();
00541 
00542           float srx = sin(transformTobeMapped[0]);
00543           float crx = cos(transformTobeMapped[0]);
00544           float sry = sin(transformTobeMapped[1]);
00545           float cry = cos(transformTobeMapped[1]);
00546           float srz = sin(transformTobeMapped[2]);
00547           float crz = cos(transformTobeMapped[2]);
00548 
00549           if (laserCloudSelNum < 50) {
00550             continue;
00551           }
00552 
00553           cv::Mat matA(laserCloudSelNum, 6, CV_32F, cv::Scalar::all(0));
00554           cv::Mat matAt(6, laserCloudSelNum, CV_32F, cv::Scalar::all(0));
00555           cv::Mat matAtA(6, 6, CV_32F, cv::Scalar::all(0));
00556           cv::Mat matB(laserCloudSelNum, 1, CV_32F, cv::Scalar::all(0));
00557           cv::Mat matAtB(6, 1, CV_32F, cv::Scalar::all(0));
00558           cv::Mat matX(6, 1, CV_32F, cv::Scalar::all(0));
00559           for (int i = 0; i < laserCloudSelNum; i++) {
00560             pointOri = laserCloudOri->points[i];
00561             coeff = coeffSel->points[i];
00562 
00563             float arx = (crx*sry*srz*pointOri.x + crx*crz*sry*pointOri.y - srx*sry*pointOri.z) * coeff.x
00564                       + (-srx*srz*pointOri.x - crz*srx*pointOri.y - crx*pointOri.z) * coeff.y
00565                       + (crx*cry*srz*pointOri.x + crx*cry*crz*pointOri.y - cry*srx*pointOri.z) * coeff.z;
00566 
00567             float ary = ((cry*srx*srz - crz*sry)*pointOri.x 
00568                       + (sry*srz + cry*crz*srx)*pointOri.y + crx*cry*pointOri.z) * coeff.x
00569                       + ((-cry*crz - srx*sry*srz)*pointOri.x 
00570                       + (cry*srz - crz*srx*sry)*pointOri.y - crx*sry*pointOri.z) * coeff.z;
00571 
00572             float arz = ((crz*srx*sry - cry*srz)*pointOri.x + (-cry*crz - srx*sry*srz)*pointOri.y)*coeff.x
00573                       + (crx*crz*pointOri.x - crx*srz*pointOri.y) * coeff.y
00574                       + ((sry*srz + cry*crz*srx)*pointOri.x + (crz*sry - cry*srx*srz)*pointOri.y)*coeff.z;
00575 
00576             matA.at<float>(i, 0) = arx;
00577             matA.at<float>(i, 1) = ary;
00578             matA.at<float>(i, 2) = arz;
00579             matA.at<float>(i, 3) = coeff.x;
00580             matA.at<float>(i, 4) = coeff.y;
00581             matA.at<float>(i, 5) = coeff.z;
00582             matB.at<float>(i, 0) = -coeff.h;
00583           }
00584           cv::transpose(matA, matAt);
00585           matAtA = matAt * matA;
00586           matAtB = matAt * matB;
00587           cv::solve(matAtA, matAtB, matX, cv::DECOMP_QR);
00588 
00589           if (fabs(matX.at<float>(0, 0)) < 0.5 &&
00590               fabs(matX.at<float>(1, 0)) < 0.5 &&
00591               fabs(matX.at<float>(2, 0)) < 0.5 &&
00592               fabs(matX.at<float>(3, 0)) < 1 &&
00593               fabs(matX.at<float>(4, 0)) < 1 &&
00594               fabs(matX.at<float>(5, 0)) < 1) {
00595 
00596             transformTobeMapped[0] += matX.at<float>(0, 0);
00597             transformTobeMapped[1] += matX.at<float>(1, 0);
00598             transformTobeMapped[2] += matX.at<float>(2, 0);
00599             transformTobeMapped[3] += matX.at<float>(3, 0);
00600             transformTobeMapped[4] += matX.at<float>(4, 0);
00601             transformTobeMapped[5] += matX.at<float>(5, 0);
00602           } else {
00603             //ROS_INFO ("Mapping update out of bound");
00604           }
00605         }
00606       }
00607 
00608       transformUpdate();
00609 
00610       for (int i = 0; i < laserCloudLastNum; i++) {
00611         if (fabs(laserCloudLast->points[i].x > 0.3) || fabs(laserCloudLast->points[i].y > 0.3) ||
00612             fabs(laserCloudLast->points[i].z > 0.3)) {
00613 
00614           pointAssociateToMap(&laserCloudLast->points[i], &pointSel);
00615 
00616           int cubeI = int((pointSel.x + 10.0) / 20.0) + laserCloudCenWidth;
00617           int cubeJ = int((pointSel.y + 10.0) / 20.0) + laserCloudCenHeight;
00618           int cubeK = int((pointSel.z + 10.0) / 20.0) + laserCloudCenDepth;
00619           int cubeInd = cubeI + laserCloudWidth * cubeJ + laserCloudWidth * laserCloudHeight * cubeK;
00620 
00621           laserCloudArray[cubeInd]->push_back(pointSel);
00622         }
00623       }
00624 
00625       for (int i = 0; i < laserCloudValidNum; i++) {
00626         laserCloudCorner->clear();
00627         laserCloudSurf->clear();
00628         pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCubePointer = 
00629                                                laserCloudArray[laserCloudValidInd[i]];
00630         int laserCloudCubeNum = laserCloudCubePointer->points.size();
00631         for (int j = 0; j < laserCloudCubeNum; j++) {
00632           if (fabs(laserCloudCubePointer->points[j].v - 2) < 0.005 || 
00633               fabs(laserCloudCubePointer->points[j].v - 1) < 0.005) {
00634             laserCloudCorner->push_back(laserCloudCubePointer->points[j]);
00635           } else {
00636             laserCloudSurf->push_back(laserCloudCubePointer->points[j]);
00637           }
00638         }
00639 
00640         laserCloudCorner2->clear();
00641         pcl::VoxelGrid<pcl::PointXYZHSV> downSizeFilter;
00642         downSizeFilter.setInputCloud(laserCloudCorner);
00643         downSizeFilter.setLeafSize(0.05, 0.05, 0.05);
00644         downSizeFilter.filter(*laserCloudCorner2);
00645 
00646         laserCloudSurf2->clear();
00647         downSizeFilter.setInputCloud(laserCloudSurf);
00648         downSizeFilter.setLeafSize(0.1, 0.1, 0.1);
00649         downSizeFilter.filter(*laserCloudSurf2);
00650 
00651         laserCloudCubePointer->clear();
00652         *laserCloudCubePointer = *laserCloudCorner2 + *laserCloudSurf2;
00653       }
00654 
00655       laserCloudSurround->clear();
00656       for (int i = 0; i < laserCloudSurroundNum; i++) {
00657          pcl::PointCloud<pcl::PointXYZHSV>::Ptr laserCloudCubePointer = 
00658                                                 laserCloudArray[laserCloudSurroundInd[i]];
00659          int laserCloudCubeNum = laserCloudCubePointer->points.size();
00660          for (int j = 0; j < laserCloudCubeNum; j++) {
00661            pointSurround.x = laserCloudCubePointer->points[j].x;
00662            pointSurround.y = laserCloudCubePointer->points[j].y;
00663            pointSurround.z = laserCloudCubePointer->points[j].z;
00664            pointSurround.intensity = laserCloudCubePointer->points[j].h;
00665            laserCloudSurround->push_back(pointSurround);
00666          }
00667       }
00668 
00669       sensor_msgs::PointCloud2 laserCloudSurround2;
00670       pcl::toROSMsg(*laserCloudSurround, laserCloudSurround2);
00671       laserCloudSurround2.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00672       laserCloudSurround2.header.frame_id = "/camera_init_2";
00673       pubLaserCloudSurround.publish(laserCloudSurround2);
00674 
00675       geometry_msgs::Quaternion geoQuat = tf::createQuaternionMsgFromRollPitchYaw
00676                      (transformBefMapped[2], -transformBefMapped[0], -transformBefMapped[1]);
00677 
00678       odomBefMapped.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00679       odomBefMapped.pose.pose.orientation.x = -geoQuat.y;
00680       odomBefMapped.pose.pose.orientation.y = -geoQuat.z;
00681       odomBefMapped.pose.pose.orientation.z = geoQuat.x;
00682       odomBefMapped.pose.pose.orientation.w = geoQuat.w;
00683       odomBefMapped.pose.pose.position.x = transformBefMapped[3];
00684       odomBefMapped.pose.pose.position.y = transformBefMapped[4];
00685       odomBefMapped.pose.pose.position.z = transformBefMapped[5];
00686       pubOdomBefMapped.publish(odomBefMapped);
00687 
00688       geoQuat = tf::createQuaternionMsgFromRollPitchYaw
00689                 (transformAftMapped[2], -transformAftMapped[0], -transformAftMapped[1]);
00690 
00691       odomAftMapped.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00692       odomAftMapped.pose.pose.orientation.x = -geoQuat.y;
00693       odomAftMapped.pose.pose.orientation.y = -geoQuat.z;
00694       odomAftMapped.pose.pose.orientation.z = geoQuat.x;
00695       odomAftMapped.pose.pose.orientation.w = geoQuat.w;
00696       odomAftMapped.pose.pose.position.x = transformAftMapped[3];
00697       odomAftMapped.pose.pose.position.y = transformAftMapped[4];
00698       odomAftMapped.pose.pose.position.z = transformAftMapped[5];
00699       pubOdomAftMapped.publish(odomAftMapped);
00700 
00701       /*sensor_msgs::PointCloud2 pc12;
00702       pcl::toROSMsg(*laserCloudCornerFromMap, pc12);
00703       pc12.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00704       pc12.header.frame_id = "/camera_init_2";
00705       pub1.publish(pc12);
00706 
00707       sensor_msgs::PointCloud2 pc22;
00708       pcl::toROSMsg(*laserCloudSel, pc22);
00709       pc22.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00710       pc22.header.frame_id = "/camera_init_2";
00711       pub2.publish(pc22);
00712 
00713       sensor_msgs::PointCloud2 pc32;
00714       pcl::toROSMsg(*laserCloudCorr, pc32);
00715       pc32.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00716       pc32.header.frame_id = "/camera_init_2";
00717       pub3.publish(pc32);
00718 
00719       sensor_msgs::PointCloud2 pc42;
00720       pcl::toROSMsg(*laserCloudProj, pc42);
00721       pc42.header.stamp = ros::Time().fromSec(timeLaserCloudLast);
00722       pc42.header.frame_id = "/camera_init_2";
00723       pub4.publish(pc42);*/
00724     }
00725 
00726     status = ros::ok();
00727     cvWaitKey(10);
00728   }
00729 
00730   return 0;
00731 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


loam_backAndForth
Author(s): Ji Zhang
autogenerated on Sun Oct 6 2013 11:47:42