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