imageProjection.cpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546
  1. // Copyright 2013, Ji Zhang, Carnegie Mellon University
  2. // Further contributions copyright (c) 2016, Southwest Research Institute
  3. // All rights reserved.
  4. //
  5. // Redistribution and use in source and binary forms, with or without
  6. // modification, are permitted provided that the following conditions are met:
  7. //
  8. // 1. Redistributions of source code must retain the above copyright notice,
  9. // this list of conditions and the following disclaimer.
  10. // 2. Redistributions in binary form must reproduce the above copyright notice,
  11. // this list of conditions and the following disclaimer in the documentation
  12. // and/or other materials provided with the distribution.
  13. // 3. Neither the name of the copyright holder nor the names of its
  14. // contributors may be used to endorse or promote products derived from this
  15. // software without specific prior written permission.
  16. //
  17. // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
  18. // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  19. // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
  20. // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
  21. // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
  22. // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
  23. // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
  24. // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
  25. // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
  26. // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  27. // POSSIBILITY OF SUCH DAMAGE.
  28. //
  29. // This is an implementation of the algorithm described in the following papers:
  30. // J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time.
  31. // Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014.
  32. // T. Shan and B. Englot. LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain
  33. // IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). October 2018.
  34. #include "utility.h"
  35. namespace iv {
  36. struct SegInfo
  37. {
  38. int startRingIndex[N_SCAN];
  39. int endRingIndex[N_SCAN];
  40. float startOrientation;
  41. float endOrientation;
  42. float orientationDiff;
  43. bool segmentedCloudGroundFlag[N_SCAN*Horizon_SCAN]; // true - ground point, false - other points
  44. unsigned int segmentedCloudColInd[N_SCAN*Horizon_SCAN]; // point column index in range image
  45. float segmentedCloudRange[N_SCAN*Horizon_SCAN]; // point range
  46. };
  47. }
  48. class ImageProjection{
  49. private:
  50. // ros::NodeHandle nh;
  51. // ros::Subscriber subLaserCloud;
  52. // ros::Publisher pubFullCloud;
  53. // ros::Publisher pubFullInfoCloud;
  54. // ros::Publisher pubGroundCloud;
  55. // ros::Publisher pubSegmentedCloud;
  56. // ros::Publisher pubSegmentedCloudPure;
  57. // ros::Publisher pubSegmentedCloudInfo;
  58. // ros::Publisher pubOutlierCloud;
  59. pcl::PointCloud<PointType>::Ptr laserCloudIn;
  60. pcl::PointCloud<PointXYZIR>::Ptr laserCloudInRing;
  61. pcl::PointCloud<PointType>::Ptr fullCloud; // projected velodyne raw cloud, but saved in the form of 1-D matrix
  62. pcl::PointCloud<PointType>::Ptr fullInfoCloud; // same as fullCloud, but with intensity - range
  63. pcl::PointCloud<PointType>::Ptr groundCloud;
  64. pcl::PointCloud<PointType>::Ptr segmentedCloud;
  65. pcl::PointCloud<PointType>::Ptr segmentedCloudPure;
  66. pcl::PointCloud<PointType>::Ptr outlierCloud;
  67. PointType nanPoint; // fill in fullCloud at each iteration
  68. cv::Mat rangeMat; // range matrix for range image
  69. cv::Mat labelMat; // label matrix for segmentaiton marking
  70. cv::Mat groundMat; // ground matrix for ground cloud marking
  71. int labelCount;
  72. float startOrientation;
  73. float endOrientation;
  74. iv::SegInfo segMsg;
  75. // cloud_msgs::cloud_info segMsg; // info of segmented cloud
  76. // std_msgs::Header cloudHeader;
  77. std::vector<std::pair<int8_t, int8_t> > neighborIterator; // neighbor iterator for segmentaiton process
  78. uint16_t *allPushedIndX; // array for tracking points of a segmented object
  79. uint16_t *allPushedIndY;
  80. uint16_t *queueIndX; // array for breadth-first search process of segmentation, for speed
  81. uint16_t *queueIndY;
  82. public:
  83. ImageProjection()
  84. {
  85. // ImageProjection():
  86. // nh("~"){
  87. // subLaserCloud = nh.subscribe<sensor_msgs::PointCloud2>(pointCloudTopic, 1, &ImageProjection::cloudHandler, this);
  88. // pubFullCloud = nh.advertise<sensor_msgs::PointCloud2> ("/full_cloud_projected", 1);
  89. // pubFullInfoCloud = nh.advertise<sensor_msgs::PointCloud2> ("/full_cloud_info", 1);
  90. // pubGroundCloud = nh.advertise<sensor_msgs::PointCloud2> ("/ground_cloud", 1);
  91. // pubSegmentedCloud = nh.advertise<sensor_msgs::PointCloud2> ("/segmented_cloud", 1);
  92. // pubSegmentedCloudPure = nh.advertise<sensor_msgs::PointCloud2> ("/segmented_cloud_pure", 1);
  93. // pubSegmentedCloudInfo = nh.advertise<cloud_msgs::cloud_info> ("/segmented_cloud_info", 1);
  94. // pubOutlierCloud = nh.advertise<sensor_msgs::PointCloud2> ("/outlier_cloud", 1);
  95. nanPoint.x = std::numeric_limits<float>::quiet_NaN();
  96. nanPoint.y = std::numeric_limits<float>::quiet_NaN();
  97. nanPoint.z = std::numeric_limits<float>::quiet_NaN();
  98. nanPoint.intensity = -1;
  99. allocateMemory();
  100. resetParameters();
  101. }
  102. void allocateMemory(){
  103. laserCloudIn.reset(new pcl::PointCloud<PointType>());
  104. laserCloudInRing.reset(new pcl::PointCloud<PointXYZIR>());
  105. fullCloud.reset(new pcl::PointCloud<PointType>());
  106. fullInfoCloud.reset(new pcl::PointCloud<PointType>());
  107. groundCloud.reset(new pcl::PointCloud<PointType>());
  108. segmentedCloud.reset(new pcl::PointCloud<PointType>());
  109. segmentedCloudPure.reset(new pcl::PointCloud<PointType>());
  110. outlierCloud.reset(new pcl::PointCloud<PointType>());
  111. fullCloud->points.resize(N_SCAN*Horizon_SCAN);
  112. fullInfoCloud->points.resize(N_SCAN*Horizon_SCAN);
  113. // segMsg.startRingIndex.assign(N_SCAN, 0);
  114. // segMsg.endRingIndex.assign(N_SCAN, 0);
  115. // segMsg.segmentedCloudGroundFlag.assign(N_SCAN*Horizon_SCAN, false);
  116. // segMsg.segmentedCloudColInd.assign(N_SCAN*Horizon_SCAN, 0);
  117. // segMsg.segmentedCloudRange.assign(N_SCAN*Horizon_SCAN, 0);
  118. std::pair<int8_t, int8_t> neighbor;
  119. neighbor.first = -1; neighbor.second = 0; neighborIterator.push_back(neighbor);
  120. neighbor.first = 0; neighbor.second = 1; neighborIterator.push_back(neighbor);
  121. neighbor.first = 0; neighbor.second = -1; neighborIterator.push_back(neighbor);
  122. neighbor.first = 1; neighbor.second = 0; neighborIterator.push_back(neighbor);
  123. allPushedIndX = new uint16_t[N_SCAN*Horizon_SCAN];
  124. allPushedIndY = new uint16_t[N_SCAN*Horizon_SCAN];
  125. queueIndX = new uint16_t[N_SCAN*Horizon_SCAN];
  126. queueIndY = new uint16_t[N_SCAN*Horizon_SCAN];
  127. }
  128. void resetParameters(){
  129. laserCloudIn->clear();
  130. groundCloud->clear();
  131. segmentedCloud->clear();
  132. segmentedCloudPure->clear();
  133. outlierCloud->clear();
  134. rangeMat = cv::Mat(N_SCAN, Horizon_SCAN, CV_32F, cv::Scalar::all(FLT_MAX));
  135. groundMat = cv::Mat(N_SCAN, Horizon_SCAN, CV_8S, cv::Scalar::all(0));
  136. labelMat = cv::Mat(N_SCAN, Horizon_SCAN, CV_32S, cv::Scalar::all(0));
  137. labelCount = 1;
  138. std::fill(fullCloud->points.begin(), fullCloud->points.end(), nanPoint);
  139. std::fill(fullInfoCloud->points.begin(), fullInfoCloud->points.end(), nanPoint);
  140. }
  141. ~ImageProjection(){}
  142. // void copyPointCloud(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){
  143. // cloudHeader = laserCloudMsg->header;
  144. // // cloudHeader.stamp = ros::Time::now(); // Ouster lidar users may need to uncomment this line
  145. // pcl::fromROSMsg(*laserCloudMsg, *laserCloudIn);
  146. // // Remove Nan points
  147. // std::vector<int> indices;
  148. // pcl::removeNaNFromPointCloud(*laserCloudIn, *laserCloudIn, indices);
  149. // // have "ring" channel in the cloud
  150. // if (useCloudRing == true){
  151. // pcl::fromROSMsg(*laserCloudMsg, *laserCloudInRing);
  152. // if (laserCloudInRing->is_dense == false) {
  153. // ROS_ERROR("Point cloud is not in dense format, please remove NaN points first!");
  154. // ros::shutdown();
  155. // }
  156. // }
  157. // }
  158. // void cloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){
  159. void cloudHandler(){
  160. // 1. Convert ros message to pcl point cloud
  161. // copyPointCloud(laserCloudMsg);
  162. // 2. Start and end angle of a scan
  163. // findStartEndAngle();
  164. // 3. Range image projection
  165. projectPointCloud();
  166. // 4. Mark ground points
  167. groundRemoval();
  168. // 5. Point cloud segmentation
  169. cloudSegmentation();
  170. // 6. Publish all clouds
  171. // publishCloud();
  172. // 7. Reset parameters for next iteration
  173. resetParameters();
  174. }
  175. // void findStartEndAngle(){
  176. // // start and end orientation of this cloud
  177. // segMsg.startOrientation = -atan2(laserCloudIn->points[0].y, laserCloudIn->points[0].x);
  178. // segMsg.endOrientation = -atan2(laserCloudIn->points[laserCloudIn->points.size() - 1].y,
  179. // laserCloudIn->points[laserCloudIn->points.size() - 1].x) + 2 * M_PI;
  180. // if (segMsg.endOrientation - segMsg.startOrientation > 3 * M_PI) {
  181. // segMsg.endOrientation -= 2 * M_PI;
  182. // } else if (segMsg.endOrientation - segMsg.startOrientation < M_PI)
  183. // segMsg.endOrientation += 2 * M_PI;
  184. // segMsg.orientationDiff = segMsg.endOrientation - segMsg.startOrientation;
  185. // }
  186. void projectPointCloud(){
  187. // range image projection
  188. float verticalAngle, horizonAngle, range;
  189. size_t rowIdn, columnIdn, index, cloudSize;
  190. PointType thisPoint;
  191. cloudSize = laserCloudIn->points.size();
  192. for (size_t i = 0; i < cloudSize; ++i){
  193. thisPoint.x = laserCloudIn->points[i].x;
  194. thisPoint.y = laserCloudIn->points[i].y;
  195. thisPoint.z = laserCloudIn->points[i].z;
  196. // find the row and column index in the iamge for this point
  197. if (useCloudRing == true){
  198. rowIdn = laserCloudInRing->points[i].ring;
  199. }
  200. else{
  201. verticalAngle = atan2(thisPoint.z, sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y)) * 180 / M_PI;
  202. rowIdn = (verticalAngle + ang_bottom) / ang_res_y;
  203. }
  204. if (rowIdn < 0 || rowIdn >= N_SCAN)
  205. continue;
  206. horizonAngle = atan2(thisPoint.x, thisPoint.y) * 180 / M_PI;
  207. columnIdn = -round((horizonAngle-90.0)/ang_res_x) + Horizon_SCAN/2;
  208. if (columnIdn >= Horizon_SCAN)
  209. columnIdn -= Horizon_SCAN;
  210. if (columnIdn < 0 || columnIdn >= Horizon_SCAN)
  211. continue;
  212. range = sqrt(thisPoint.x * thisPoint.x + thisPoint.y * thisPoint.y + thisPoint.z * thisPoint.z);
  213. if (range < sensorMinimumRange)
  214. continue;
  215. rangeMat.at<float>(rowIdn, columnIdn) = range;
  216. thisPoint.intensity = (float)rowIdn + (float)columnIdn / 10000.0;
  217. index = columnIdn + rowIdn * Horizon_SCAN;
  218. fullCloud->points[index] = thisPoint;
  219. fullInfoCloud->points[index] = thisPoint;
  220. fullInfoCloud->points[index].intensity = range; // the corresponding range of a point is saved as "intensity"
  221. }
  222. }
  223. void groundRemoval(){
  224. size_t lowerInd, upperInd;
  225. float diffX, diffY, diffZ, angle;
  226. // groundMat
  227. // -1, no valid info to check if ground of not
  228. // 0, initial value, after validation, means not ground
  229. // 1, ground
  230. for (size_t j = 0; j < Horizon_SCAN; ++j){
  231. for (size_t i = 0; i < groundScanInd; ++i){
  232. lowerInd = j + ( i )*Horizon_SCAN;
  233. upperInd = j + (i+1)*Horizon_SCAN;
  234. if (fullCloud->points[lowerInd].intensity == -1 ||
  235. fullCloud->points[upperInd].intensity == -1){
  236. // no info to check, invalid points
  237. groundMat.at<int8_t>(i,j) = -1;
  238. continue;
  239. }
  240. diffX = fullCloud->points[upperInd].x - fullCloud->points[lowerInd].x;
  241. diffY = fullCloud->points[upperInd].y - fullCloud->points[lowerInd].y;
  242. diffZ = fullCloud->points[upperInd].z - fullCloud->points[lowerInd].z;
  243. angle = atan2(diffZ, sqrt(diffX*diffX + diffY*diffY) ) * 180 / M_PI;
  244. if (abs(angle - sensorMountAngle) <= 10){
  245. groundMat.at<int8_t>(i,j) = 1;
  246. groundMat.at<int8_t>(i+1,j) = 1;
  247. }
  248. }
  249. }
  250. // extract ground cloud (groundMat == 1)
  251. // mark entry that doesn't need to label (ground and invalid point) for segmentation
  252. // note that ground remove is from 0~N_SCAN-1, need rangeMat for mark label matrix for the 16th scan
  253. for (size_t i = 0; i < N_SCAN; ++i){
  254. for (size_t j = 0; j < Horizon_SCAN; ++j){
  255. if (groundMat.at<int8_t>(i,j) == 1 || rangeMat.at<float>(i,j) == FLT_MAX){
  256. labelMat.at<int>(i,j) = -1;
  257. }
  258. }
  259. }
  260. // if (pubGroundCloud.getNumSubscribers() != 0){
  261. // for (size_t i = 0; i <= groundScanInd; ++i){
  262. // for (size_t j = 0; j < Horizon_SCAN; ++j){
  263. // if (groundMat.at<int8_t>(i,j) == 1)
  264. // groundCloud->push_back(fullCloud->points[j + i*Horizon_SCAN]);
  265. // }
  266. // }
  267. // }
  268. }
  269. void cloudSegmentation(){
  270. // segmentation process
  271. for (size_t i = 0; i < N_SCAN; ++i)
  272. for (size_t j = 0; j < Horizon_SCAN; ++j)
  273. if (labelMat.at<int>(i,j) == 0)
  274. labelComponents(i, j);
  275. int sizeOfSegCloud = 0;
  276. // extract segmented cloud for lidar odometry
  277. for (size_t i = 0; i < N_SCAN; ++i) {
  278. segMsg.startRingIndex[i] = sizeOfSegCloud-1 + 5;
  279. for (size_t j = 0; j < Horizon_SCAN; ++j) {
  280. if (labelMat.at<int>(i,j) > 0 || groundMat.at<int8_t>(i,j) == 1){
  281. // outliers that will not be used for optimization (always continue)
  282. if (labelMat.at<int>(i,j) == 999999){
  283. if (i > groundScanInd && j % 5 == 0){
  284. outlierCloud->push_back(fullCloud->points[j + i*Horizon_SCAN]);
  285. continue;
  286. }else{
  287. continue;
  288. }
  289. }
  290. // majority of ground points are skipped
  291. if (groundMat.at<int8_t>(i,j) == 1){
  292. if (j%5!=0 && j>5 && j<Horizon_SCAN-5)
  293. continue;
  294. }
  295. // mark ground points so they will not be considered as edge features later
  296. segMsg.segmentedCloudGroundFlag[sizeOfSegCloud] = (groundMat.at<int8_t>(i,j) == 1);
  297. // mark the points' column index for marking occlusion later
  298. segMsg.segmentedCloudColInd[sizeOfSegCloud] = j;
  299. // save range info
  300. segMsg.segmentedCloudRange[sizeOfSegCloud] = rangeMat.at<float>(i,j);
  301. // save seg cloud
  302. segmentedCloud->push_back(fullCloud->points[j + i*Horizon_SCAN]);
  303. // size of seg cloud
  304. ++sizeOfSegCloud;
  305. }
  306. }
  307. segMsg.endRingIndex[i] = sizeOfSegCloud-1 - 5;
  308. }
  309. // extract segmented cloud for visualization
  310. // if (pubSegmentedCloudPure.getNumSubscribers() != 0){
  311. // for (size_t i = 0; i < N_SCAN; ++i){
  312. // for (size_t j = 0; j < Horizon_SCAN; ++j){
  313. // if (labelMat.at<int>(i,j) > 0 && labelMat.at<int>(i,j) != 999999){
  314. // segmentedCloudPure->push_back(fullCloud->points[j + i*Horizon_SCAN]);
  315. // segmentedCloudPure->points.back().intensity = labelMat.at<int>(i,j);
  316. // }
  317. // }
  318. // }
  319. // }
  320. }
  321. void labelComponents(int row, int col){
  322. // use std::queue std::vector std::deque will slow the program down greatly
  323. float d1, d2, alpha, angle;
  324. int fromIndX, fromIndY, thisIndX, thisIndY;
  325. bool lineCountFlag[N_SCAN] = {false};
  326. queueIndX[0] = row;
  327. queueIndY[0] = col;
  328. int queueSize = 1;
  329. int queueStartInd = 0;
  330. int queueEndInd = 1;
  331. allPushedIndX[0] = row;
  332. allPushedIndY[0] = col;
  333. int allPushedIndSize = 1;
  334. while(queueSize > 0){
  335. // Pop point
  336. fromIndX = queueIndX[queueStartInd];
  337. fromIndY = queueIndY[queueStartInd];
  338. --queueSize;
  339. ++queueStartInd;
  340. // Mark popped point
  341. labelMat.at<int>(fromIndX, fromIndY) = labelCount;
  342. // Loop through all the neighboring grids of popped grid
  343. for (auto iter = neighborIterator.begin(); iter != neighborIterator.end(); ++iter){
  344. // new index
  345. thisIndX = fromIndX + (*iter).first;
  346. thisIndY = fromIndY + (*iter).second;
  347. // index should be within the boundary
  348. if (thisIndX < 0 || thisIndX >= N_SCAN)
  349. continue;
  350. // at range image margin (left or right side)
  351. if (thisIndY < 0)
  352. thisIndY = Horizon_SCAN - 1;
  353. if (thisIndY >= Horizon_SCAN)
  354. thisIndY = 0;
  355. // prevent infinite loop (caused by put already examined point back)
  356. if (labelMat.at<int>(thisIndX, thisIndY) != 0)
  357. continue;
  358. d1 = std::max(rangeMat.at<float>(fromIndX, fromIndY),
  359. rangeMat.at<float>(thisIndX, thisIndY));
  360. d2 = std::min(rangeMat.at<float>(fromIndX, fromIndY),
  361. rangeMat.at<float>(thisIndX, thisIndY));
  362. if ((*iter).first == 0)
  363. alpha = segmentAlphaX;
  364. else
  365. alpha = segmentAlphaY;
  366. angle = atan2(d2*sin(alpha), (d1 -d2*cos(alpha)));
  367. if (angle > segmentTheta){
  368. queueIndX[queueEndInd] = thisIndX;
  369. queueIndY[queueEndInd] = thisIndY;
  370. ++queueSize;
  371. ++queueEndInd;
  372. labelMat.at<int>(thisIndX, thisIndY) = labelCount;
  373. lineCountFlag[thisIndX] = true;
  374. allPushedIndX[allPushedIndSize] = thisIndX;
  375. allPushedIndY[allPushedIndSize] = thisIndY;
  376. ++allPushedIndSize;
  377. }
  378. }
  379. }
  380. // check if this segment is valid
  381. bool feasibleSegment = false;
  382. if (allPushedIndSize >= 30)
  383. feasibleSegment = true;
  384. else if (allPushedIndSize >= segmentValidPointNum){
  385. int lineCount = 0;
  386. for (size_t i = 0; i < N_SCAN; ++i)
  387. if (lineCountFlag[i] == true)
  388. ++lineCount;
  389. if (lineCount >= segmentValidLineNum)
  390. feasibleSegment = true;
  391. }
  392. // segment is valid, mark these points
  393. if (feasibleSegment == true){
  394. ++labelCount;
  395. }else{ // segment is invalid, mark these points
  396. for (size_t i = 0; i < allPushedIndSize; ++i){
  397. labelMat.at<int>(allPushedIndX[i], allPushedIndY[i]) = 999999;
  398. }
  399. }
  400. }
  401. // void publishCloud(){
  402. // // 1. Publish Seg Cloud Info
  403. // segMsg.header = cloudHeader;
  404. // pubSegmentedCloudInfo.publish(segMsg);
  405. // // 2. Publish clouds
  406. // sensor_msgs::PointCloud2 laserCloudTemp;
  407. // pcl::toROSMsg(*outlierCloud, laserCloudTemp);
  408. // laserCloudTemp.header.stamp = cloudHeader.stamp;
  409. // laserCloudTemp.header.frame_id = "base_link";
  410. // pubOutlierCloud.publish(laserCloudTemp);
  411. // // segmented cloud with ground
  412. // pcl::toROSMsg(*segmentedCloud, laserCloudTemp);
  413. // laserCloudTemp.header.stamp = cloudHeader.stamp;
  414. // laserCloudTemp.header.frame_id = "base_link";
  415. // pubSegmentedCloud.publish(laserCloudTemp);
  416. // // projected full cloud
  417. // if (pubFullCloud.getNumSubscribers() != 0){
  418. // pcl::toROSMsg(*fullCloud, laserCloudTemp);
  419. // laserCloudTemp.header.stamp = cloudHeader.stamp;
  420. // laserCloudTemp.header.frame_id = "base_link";
  421. // pubFullCloud.publish(laserCloudTemp);
  422. // }
  423. // // original dense ground cloud
  424. // if (pubGroundCloud.getNumSubscribers() != 0){
  425. // pcl::toROSMsg(*groundCloud, laserCloudTemp);
  426. // laserCloudTemp.header.stamp = cloudHeader.stamp;
  427. // laserCloudTemp.header.frame_id = "base_link";
  428. // pubGroundCloud.publish(laserCloudTemp);
  429. // }
  430. // // segmented cloud without ground
  431. // if (pubSegmentedCloudPure.getNumSubscribers() != 0){
  432. // pcl::toROSMsg(*segmentedCloudPure, laserCloudTemp);
  433. // laserCloudTemp.header.stamp = cloudHeader.stamp;
  434. // laserCloudTemp.header.frame_id = "base_link";
  435. // pubSegmentedCloudPure.publish(laserCloudTemp);
  436. // }
  437. // // projected full cloud info
  438. // if (pubFullInfoCloud.getNumSubscribers() != 0){
  439. // pcl::toROSMsg(*fullInfoCloud, laserCloudTemp);
  440. // laserCloudTemp.header.stamp = cloudHeader.stamp;
  441. // laserCloudTemp.header.frame_id = "base_link";
  442. // pubFullInfoCloud.publish(laserCloudTemp);
  443. // }
  444. // }
  445. };
  446. //int main(int argc, char** argv){
  447. // ros::init(argc, argv, "lego_loam");
  448. // ImageProjection IP;
  449. // ROS_INFO("\033[1;32m---->\033[0m Image Projection Started.");
  450. // ros::spin();
  451. // return 0;
  452. //}