#include "utility.h" #include "lio_sam/cloud_info.h" struct smoothness_t{ float value; size_t ind; }; struct by_value{ bool operator()(smoothness_t const &left, smoothness_t const &right) { return left.value < right.value; } }; class FeatureExtraction : public ParamServer { public: ros::Subscriber subLaserCloudInfo; ros::Publisher pubLaserCloudInfo; ros::Publisher pubCornerPoints; ros::Publisher pubSurfacePoints; pcl::PointCloud<PointType>::Ptr extractedCloud; pcl::PointCloud<PointType>::Ptr cornerCloud; pcl::PointCloud<PointType>::Ptr cornerCloudDS; pcl::PointCloud<PointType>::Ptr surfaceCloud; pcl::PointCloud<PointType>::Ptr surfaceCloudDS; pcl::VoxelGrid<PointType> downSizeFilterSimple; pcl::VoxelGrid<PointType> downSizeFilterCorner; pcl::VoxelGrid<PointType> downSizeFilterSurf; lio_sam::cloud_info cloudInfo; std_msgs::Header cloudHeader; std::vector<smoothness_t> cloudSmoothness; float *cloudCurvature; int *cloudNeighborPicked; int *cloudLabel; FeatureExtraction() { subLaserCloudInfo = nh.subscribe<lio_sam::cloud_info>("lio_sam/deskew/cloud_info", 10, &FeatureExtraction::laserCloudInfoHandler, this, ros::TransportHints().tcpNoDelay()); pubLaserCloudInfo = nh.advertise<lio_sam::cloud_info> ("lio_sam/feature/cloud_info", 10); pubCornerPoints = nh.advertise<sensor_msgs::PointCloud2>("lio_sam/feature/cloud_corner", 1); pubSurfacePoints = nh.advertise<sensor_msgs::PointCloud2>("lio_sam/feature/cloud_surface", 1); initializationValue(); } void initializationValue() { cloudSmoothness.resize(N_SCAN*Horizon_SCAN); downSizeFilterSimple.setLeafSize(0.2, 0.2, 0.2); downSizeFilterCorner.setLeafSize(mappingCornerLeafSize, mappingCornerLeafSize, mappingCornerLeafSize); downSizeFilterSurf.setLeafSize(mappingSurfLeafSize, mappingSurfLeafSize, mappingSurfLeafSize); extractedCloud.reset(new pcl::PointCloud<PointType>()); cornerCloud.reset(new pcl::PointCloud<PointType>()); cornerCloudDS.reset(new pcl::PointCloud<PointType>()); surfaceCloud.reset(new pcl::PointCloud<PointType>()); surfaceCloudDS.reset(new pcl::PointCloud<PointType>()); cloudCurvature = new float[N_SCAN*Horizon_SCAN]; cloudNeighborPicked = new int[N_SCAN*Horizon_SCAN]; cloudLabel = new int[N_SCAN*Horizon_SCAN]; } void laserCloudInfoHandler(const lio_sam::cloud_infoConstPtr& msgIn) { cloudInfo = *msgIn; // new cloud info cloudHeader = msgIn->header; // new cloud header static double timeLastProcessing = -1; if (cloudHeader.stamp.toSec() - timeLastProcessing >= mappingProcessInterval) timeLastProcessing = cloudHeader.stamp.toSec(); else return; pcl::fromROSMsg(msgIn->cloud_deskewed, *extractedCloud); // new cloud for extraction calculateSmoothness(); markOccludedPoints(); extractFeatures(); publishFeatureCloud(); } void calculateSmoothness() { int cloudSize = extractedCloud->points.size(); for (int i = 5; i < cloudSize - 5; i++) { float diffRange = cloudInfo.pointRange[i-5] + cloudInfo.pointRange[i-4] + cloudInfo.pointRange[i-3] + cloudInfo.pointRange[i-2] + cloudInfo.pointRange[i-1] - cloudInfo.pointRange[i] * 10 + cloudInfo.pointRange[i+1] + cloudInfo.pointRange[i+2] + cloudInfo.pointRange[i+3] + cloudInfo.pointRange[i+4] + cloudInfo.pointRange[i+5]; cloudCurvature[i] = diffRange*diffRange;//diffX * diffX + diffY * diffY + diffZ * diffZ; cloudNeighborPicked[i] = 0; cloudLabel[i] = 0; // cloudSmoothness for sorting cloudSmoothness[i].value = cloudCurvature[i]; cloudSmoothness[i].ind = i; } } void markOccludedPoints() { int cloudSize = extractedCloud->points.size(); // mark occluded points and parallel beam points for (int i = 5; i < cloudSize - 6; ++i) { // occluded points float depth1 = cloudInfo.pointRange[i]; float depth2 = cloudInfo.pointRange[i+1]; int columnDiff = std::abs(int(cloudInfo.pointColInd[i+1] - cloudInfo.pointColInd[i])); if (columnDiff < 10){ // 10 pixel diff in range image if (depth1 - depth2 > 0.3){ cloudNeighborPicked[i - 5] = 1; cloudNeighborPicked[i - 4] = 1; cloudNeighborPicked[i - 3] = 1; cloudNeighborPicked[i - 2] = 1; cloudNeighborPicked[i - 1] = 1; cloudNeighborPicked[i] = 1; }else if (depth2 - depth1 > 0.3){ cloudNeighborPicked[i + 1] = 1; cloudNeighborPicked[i + 2] = 1; cloudNeighborPicked[i + 3] = 1; cloudNeighborPicked[i + 4] = 1; cloudNeighborPicked[i + 5] = 1; cloudNeighborPicked[i + 6] = 1; } } // parallel beam float diff1 = std::abs(float(cloudInfo.pointRange[i-1] - cloudInfo.pointRange[i])); float diff2 = std::abs(float(cloudInfo.pointRange[i+1] - cloudInfo.pointRange[i])); if (diff1 > 0.02 * cloudInfo.pointRange[i] && diff2 > 0.02 * cloudInfo.pointRange[i]) cloudNeighborPicked[i] = 1; } } void extractFeatures() { cornerCloud->clear(); surfaceCloud->clear(); pcl::PointCloud<PointType>::Ptr surfaceCloudScan(new pcl::PointCloud<PointType>()); pcl::PointCloud<PointType>::Ptr surfaceCloudScanDS(new pcl::PointCloud<PointType>()); for (int i = 0; i < N_SCAN; i++) { surfaceCloudScan->clear(); for (int j = 0; j < 6; j++) { int sp = (cloudInfo.startRingIndex[i] * (6 - j) + cloudInfo.endRingIndex[i] * j) / 6; int ep = (cloudInfo.startRingIndex[i] * (5 - j) + cloudInfo.endRingIndex[i] * (j + 1)) / 6 - 1; if (sp >= ep) continue; std::sort(cloudSmoothness.begin()+sp, cloudSmoothness.begin()+ep, by_value()); int largestPickedNum = 0; for (int k = ep; k >= sp; k--) { int ind = cloudSmoothness[k].ind; if (cloudNeighborPicked[ind] == 0 && cloudCurvature[ind] > edgeThreshold) { largestPickedNum++; if (largestPickedNum <= 20){ cloudLabel[ind] = 1; cornerCloud->push_back(extractedCloud->points[ind]); } else { break; } cloudNeighborPicked[ind] = 1; for (int l = 1; l <= 5; l++) { int columnDiff = std::abs(int(cloudInfo.pointColInd[ind + l] - cloudInfo.pointColInd[ind + l - 1])); if (columnDiff > 10) break; cloudNeighborPicked[ind + l] = 1; } for (int l = -1; l >= -5; l--) { int columnDiff = std::abs(int(cloudInfo.pointColInd[ind + l] - cloudInfo.pointColInd[ind + l + 1])); if (columnDiff > 10) break; cloudNeighborPicked[ind + l] = 1; } } } for (int k = sp; k <= ep; k++) { int ind = cloudSmoothness[k].ind; if (cloudNeighborPicked[ind] == 0 && cloudCurvature[ind] < surfThreshold) { cloudLabel[ind] = -1; cloudNeighborPicked[ind] = 1; for (int l = 1; l <= 5; l++) { int columnDiff = std::abs(int(cloudInfo.pointColInd[ind + l] - cloudInfo.pointColInd[ind + l - 1])); if (columnDiff > 10) break; cloudNeighborPicked[ind + l] = 1; } for (int l = -1; l >= -5; l--) { int columnDiff = std::abs(int(cloudInfo.pointColInd[ind + l] - cloudInfo.pointColInd[ind + l + 1])); if (columnDiff > 10) break; cloudNeighborPicked[ind + l] = 1; } } } for (int k = sp; k <= ep; k++) { if (cloudLabel[k] <= 0){ surfaceCloudScan->push_back(extractedCloud->points[k]); } } } surfaceCloudScanDS->clear(); downSizeFilterSimple.setInputCloud(surfaceCloudScan); downSizeFilterSimple.filter(*surfaceCloudScanDS); *surfaceCloud += *surfaceCloudScanDS; } } void freeCloudInfoMemory() { cloudInfo.startRingIndex.clear(); cloudInfo.endRingIndex.clear(); cloudInfo.pointColInd.clear(); cloudInfo.pointRange.clear(); } void publishFeatureCloud() { // free cloud info memory freeCloudInfoMemory(); // downsample features cornerCloudDS->clear(); downSizeFilterCorner.setInputCloud(cornerCloud); downSizeFilterCorner.filter(*cornerCloudDS); surfaceCloudDS->clear(); downSizeFilterSurf.setInputCloud(surfaceCloud); downSizeFilterSurf.filter(*surfaceCloudDS); // save newly extracted features cloudInfo.cloud_corner = publishCloud(&pubCornerPoints, cornerCloudDS, cloudHeader.stamp, "base_link"); cloudInfo.cloud_surface = publishCloud(&pubSurfacePoints, surfaceCloudDS, cloudHeader.stamp, "base_link"); // publish to mapOptimization pubLaserCloudInfo.publish(cloudInfo); } }; int main(int argc, char** argv) { ros::init(argc, argv, "lio_sam"); FeatureExtraction FE; ROS_INFO("\033[1;32m----> Feature Extraction Started.\033[0m"); ros::spin(); return 0; }