17 #include <sensor_msgs/Imu.h>
18 #include <sensor_msgs/PointCloud2.h>
19 #include <nav_msgs/Odometry.h>
27 #include <pcl/point_cloud.h>
28 #include <pcl/point_types.h>
29 #include <pcl/filters/filter.h>
30 #include <pcl/filters/conditional_removal.h>
43 : m_tf2Listener(m_tf2Buffer)
57 std::string points_topic =
"points";
59 std::string
frameId =
"base_link";
61 double vertical_angle = 2.0;
62 double horizontal_angle = 360.0;
63 double scan_period= 0.1;
64 double max_dis = 60.0;
66 double edgeThreshold = 0.05;
69 double searchRadius = 0.25;
106 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWithNaN(
new pcl::PointCloud<pcl::PointXYZ>());
107 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudTransformed(
new pcl::PointCloud<pcl::PointXYZ>());
108 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>());
120 std::vector<int> indices;
122 pcl::removeNaNFromPointCloud(*cloudWithNaN, *cloud, indices);
125 std::chrono::time_point<std::chrono::system_clock>
start, end;
126 start = std::chrono::system_clock::now();
129 pcl::PointCloud<pcl::PointXYZL>::Ptr edgesAndSurfaces(
new pcl::PointCloud<pcl::PointXYZL>());
130 pcl::PointCloud<pcl::PointXYZL>::Ptr surfaces(
new pcl::PointCloud<pcl::PointXYZL>());
131 pcl::PointCloud<pcl::PointXYZL>::Ptr edges(
new pcl::PointCloud<pcl::PointXYZL>());
137 auto edge_cond = pcl::make_shared<floam::lidar::GenericCondition<pcl::PointXYZL>>(
138 [](
const pcl::PointXYZL & point) {
139 return point.label > 0;
143 auto surface_cond = pcl::make_shared<floam::lidar::GenericCondition<pcl::PointXYZL>>(
144 [](
const pcl::PointXYZL & point) {
145 return point.label == 0;
150 pcl::ConditionalRemoval<pcl::PointXYZL> surface_removal;
151 pcl::ConditionalRemoval<pcl::PointXYZL> edge_removal;
153 surface_removal.setCondition(edge_cond);
154 surface_removal.setInputCloud(edgesAndSurfaces);
155 surface_removal.filter(*edges);
157 edge_removal.setCondition(surface_cond);
158 edge_removal.setInputCloud(edgesAndSurfaces);
159 edge_removal.filter(*surfaces);
161 std::vector <pcl::PointIndices> labelIndices;
164 end = std::chrono::system_clock::now();
165 std::chrono::duration<float> elapsed_seconds = end -
start;
170 float time_temp = elapsed_seconds.count() * 1000;
176 sensor_msgs::PointCloud2 edgeMsg;
180 sensor_msgs::PointCloud2 surfaceMsg;
184 sensor_msgs::PointCloud2 edgeAndSurfaceMsg;
188 edgeMsg.header = points->header;
189 surfaceMsg.header = points->header;
190 edgeAndSurfaceMsg.header = points->header;
194 edgeMsg.header.frame_id = floamLidarFrame;
195 surfaceMsg.header.frame_id = floamLidarFrame;
196 edgeAndSurfaceMsg.header.frame_id = floamLidarFrame;