V-LOAM源码解析(七)

转载请注明出处:本文转自zhch_pan的博客http://www.cnblogs.com/zhchp-blog/

 

本博客为本人之前做项目时做的源码阅读工作,po到网上希望帮助其他人更好的理解V-LOAM的工程实现,有些地方代码做了修改,可能和原工程有出入,但对于该工程的整体流程理解没有妨碍。

源码下载链接:https://github.com/Jinqiang/demo_lidar

 


 

节点:registerPointCloud

功能:根据最终的里程计信息将三维激光的点云加入到odom坐标系中,获得点云地图

  1 #include <math.h>
  2 #include <stdio.h>
  3 #include <stdlib.h>
  4 #include <ros/ros.h>
  5 
  6 #include <nav_msgs/Odometry.h>
  7 
  8 #include <tf/transform_datatypes.h>
  9 #include <tf/transform_listener.h>
 10 #include <tf/transform_broadcaster.h>
 11 
 12 #include<pcl/common/transforms.h>
 13 #include<pcl/common/eigen.h>
 14 
 15 #include "pointDefinition.h"
 16 
 17 const double PI = 3.1415926;
 18 
 19 const int keepVoDataNum = 30;
 20 double voDataTime[keepVoDataNum] = {0};
 21 double voRx[keepVoDataNum] = {0};
 22 double voRy[keepVoDataNum] = {0};
 23 double voRz[keepVoDataNum] = {0};
 24 double voTx[keepVoDataNum] = {0};
 25 double voTy[keepVoDataNum] = {0};
 26 double voTz[keepVoDataNum] = {0};
 27 int voDataInd = -1;
 28 int voRegInd = 0;
 29 
 30 pcl::PointCloud<pcl::PointXYZ>::Ptr surroundCloud(new pcl::PointCloud<pcl::PointXYZ>());
 31 pcl::PointCloud<pcl::PointXYZ>::Ptr syncCloud(new pcl::PointCloud<pcl::PointXYZ>());
 32 pcl::PointCloud<pcl::PointXYZ>::Ptr tempCloud(new pcl::PointCloud<pcl::PointXYZ>());
 33 
 34 int startCount = -1;
 35 const int startSkipNum = 5;
 36 
 37 int showCount = -1;
 38 const int showSkipNum = 15;
 39 const int downSizeMap = 10;
 40 
 41 ros::Publisher *surroundCloudPubPointer = NULL;
 42 
 43 void voDataHandler(const nav_msgs::Odometry::ConstPtr& voData)
 44 {
 45   /*
 46   //modified at 2018/01/18
 47   double time = voData->header.stamp.toSec();
 48   double rx, ry, rz;
 49   geometry_msgs::Quaternion geoQuat = voData->pose.pose.orientation;
 50   tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(rz, rx, ry);
 51   double tx = voData->pose.pose.position.x;
 52   double ty = voData->pose.pose.position.y;
 53   double tz = voData->pose.pose.position.z;
 54   voDataInd = (voDataInd + 1) % keepVoDataNum;
 55   voDataTime[voDataInd] = time;
 56   voRx[voDataInd] = rx;
 57   voRy[voDataInd] = ry;
 58   voRz[voDataInd] = rz;
 59   voTx[voDataInd] = tx;
 60   voTy[voDataInd] = ty;
 61   voTz[voDataInd] = tz;
 62   */
 63   double time = voData->header.stamp.toSec();
 64 
 65   double rx, ry, rz;
 66   geometry_msgs::Quaternion geoQuat = voData->pose.pose.orientation;
 67   //下面做点云转换的时候rx和ry取了个负号,因此这里先将rx和ry取为原来的负值
 68   tf::Matrix3x3(tf::Quaternion(-geoQuat.x, -geoQuat.y, geoQuat.z, geoQuat.w)).getRPY(rx, ry, rz);
 69 
 70   double tx = voData->pose.pose.position.x;
 71   double ty = voData->pose.pose.position.y;
 72   double tz = voData->pose.pose.position.z;
 73 
 74   voDataInd = (voDataInd + 1) % keepVoDataNum;
 75   voDataTime[voDataInd] = time;
 76   voRx[voDataInd] = rx;
 77   voRy[voDataInd] = ry;
 78   voRz[voDataInd] = rz;
 79   voTx[voDataInd] = tx;
 80   voTy[voDataInd] = ty;
 81   voTz[voDataInd] = tz;
 82 }
 83 
 84 void syncCloudHandler(const sensor_msgs::PointCloud2ConstPtr& syncCloud2)
 85 {
 86   if (startCount < startSkipNum) {
 87     startCount++;
 88     return;
 89   }
 90 
 91   showCount = (showCount + 1) % (showSkipNum + 1);
 92   if (showCount != showSkipNum) {
 93     return;
 94   }
 95   
 96   double time = syncCloud2->header.stamp.toSec();
 97 
 98   syncCloud->clear();
 99   tempCloud->clear();
100   //modified at 2018/01/18: translate point cloud into the frame that has the same direction with the original VLP coordinate
101   pcl::fromROSMsg(*syncCloud2, *tempCloud);
102   Eigen::Affine3f transf = pcl::getTransformation(0.0,0.0,0.0,-1.57,-3.14,-1.57);
103   pcl::transformPointCloud(*tempCloud, *syncCloud, transf);
104   tempCloud->clear();
105   /////////////////////////////////////////////
106   double scaleCur = 1;
107   double scaleLast = 0;
108   int voPreInd = keepVoDataNum - 1;
109   if (voDataInd >= 0) {
110     while (voDataTime[voRegInd] <= time && voRegInd != voDataInd) {
111       voRegInd = (voRegInd + 1) % keepVoDataNum;
112     }
113 
114     voPreInd = (voRegInd + keepVoDataNum - 1) % keepVoDataNum;
115     double voTimePre = voDataTime[voPreInd];
116     double voTimeReg = voDataTime[voRegInd];
117 
118     if (voTimeReg - voTimePre < 0.5) {
119       //modified at 2018/01/09
120       //double scaleLast =  (voTimeReg - time) / (voTimeReg - voTimePre);
121       //double scaleCur =  (time - voTimePre) / (voTimeReg - voTimePre);
122       scaleLast =  (voTimeReg - time) / (voTimeReg - voTimePre);
123       scaleCur =  (time - voTimePre) / (voTimeReg - voTimePre);
124       if (scaleLast > 1) {
125         scaleLast = 1;
126       } else if (scaleLast < 0) {
127         scaleLast = 0;
128       }
129       if (scaleCur > 1) {
130         scaleCur = 1;
131       } else if (scaleCur < 0) {
132         scaleCur = 0;
133       }
134     }
135   }
136 
137   double rx2 = voRx[voRegInd] * scaleCur + voRx[voPreInd] * scaleLast;
138   double ry2;
139   if (voRy[voRegInd] - voRy[voPreInd] > PI) {
140     ry2 = voRy[voRegInd] * scaleCur + (voRy[voPreInd] + 2 * PI) * scaleLast;
141   } else if (voRy[voRegInd] - voRy[voPreInd] < -PI) {
142     ry2 = voRy[voRegInd] * scaleCur + (voRy[voPreInd] - 2 * PI) * scaleLast;
143   } else {
144     ry2 = voRy[voRegInd] * scaleCur + voRy[voPreInd] * scaleLast;
145   }
146   double rz2 = voRz[voRegInd] * scaleCur + voRz[voPreInd] * scaleLast;
147 
148   double tx2 = voTx[voRegInd] * scaleCur + voTx[voPreInd] * scaleLast;
149   double ty2 = voTy[voRegInd] * scaleCur + voTy[voPreInd] * scaleLast;
150   double tz2 = voTz[voRegInd] * scaleCur + voTz[voPreInd] * scaleLast;
151 
152   double cosrx2 = cos(rx2);
153   double sinrx2 = sin(rx2);
154   double cosry2 = cos(ry2);
155   double sinry2 = sin(ry2);
156   double cosrz2 = cos(rz2);
157   double sinrz2 = sin(rz2);
158 
159   pcl::PointXYZ point;
160   int syncCloudNum = syncCloud->points.size();
161   for (int i = 0; i < syncCloudNum; i++) {
162     point = syncCloud->points[i];
163     double pointDis = sqrt(point.x * point.x + point.y * point.y + point.z * point.z);
164     //modified at 2018/01/11
165     if (/*pointDis > 0.3 && pointDis < 5*/pointDis > 0.3 && pointDis < 15) {
166       double x1 = cosrz2 * point.x - sinrz2 * point.y;
167       double y1 = sinrz2 * point.x + cosrz2 * point.y;
168       double z1 = point.z;
169 
170       double x2 = x1;
171       double y2 = cosrx2 * y1 + sinrx2 * z1;
172       double z2 = -sinrx2 * y1 + cosrx2 * z1;
173 
174       point.x = cosry2 * x2 - sinry2 * z2 + tx2;
175       point.y = y2 + ty2;
176       point.z = sinry2 * x2 + cosry2 * z2 + tz2;
177 
178       tempCloud->push_back(point); //modified at 2018/01/11
179     }
180   }
181 
182   syncCloud->clear();
183   pcl::VoxelGrid<pcl::PointXYZ> downSizeFilter;
184   downSizeFilter.setInputCloud(tempCloud);
185   downSizeFilter.setLeafSize(0.3, 0.3, 0.3);
186   downSizeFilter.filter(*syncCloud);
187   
188   for(int idx=0;idx<syncCloud->size();idx++){
189     surroundCloud->push_back(syncCloud->points[idx]);
190   }
191   
192   static int downSizeCount=0;
193   downSizeCount++;
194   
195   if(downSizeCount >= downSizeMap){
196     downSizeCount=0;
197     tempCloud->clear();
198     pcl::VoxelGrid<pcl::PointXYZ> downSizeMapFilter;
199     downSizeMapFilter.setInputCloud(surroundCloud);
200     downSizeMapFilter.setLeafSize(0.3,0.3,0.3);
201     downSizeMapFilter.filter(*tempCloud);
202     pcl::PointCloud<pcl::PointXYZ>::Ptr exchange=surroundCloud;
203     surroundCloud=tempCloud;
204     tempCloud=exchange;
205   }
206 
207   sensor_msgs::PointCloud2 surroundCloud2;
208   pcl::toROSMsg(*surroundCloud, surroundCloud2);
209   //modified at 2018/01/17
210   surroundCloud2.header.frame_id = "camera_init"; //remove the leading slash
211   surroundCloud2.header.stamp = syncCloud2->header.stamp;
212   surroundCloudPubPointer->publish(surroundCloud2);
213 }
214 
215 int main(int argc, char** argv)
216 {
217   ros::init(argc, argv, "registerPointCloud");
218   ros::NodeHandle nh;
219 
220   //modified at 2018/01/18
221   ros::Subscriber voDataSub = nh.subscribe<nav_msgs::Odometry> ("/odometry/filtered", 5, voDataHandler);
222 
223   ros::Subscriber syncCloudSub = nh.subscribe<sensor_msgs::PointCloud2>
224                                  ("/sync_scan_cloud_filtered", 5, syncCloudHandler);
225 
226   ros::Publisher surroundCloudPub = nh.advertise<sensor_msgs::PointCloud2> ("/surround_cloud", 1);
227   surroundCloudPubPointer = &surroundCloudPub;
228 
229   ros::spin();
230 
231   return 0;
232 }

 

posted on 2018-04-07 22:33  zhch_pan  阅读(1543)  评论(2编辑  收藏  举报

导航