18 #include <sensor_msgs/Imu.h>
19 #include <sensor_msgs/PointCloud2.h>
20 #include <nav_msgs/Odometry.h>
26 #include <pcl/point_cloud.h>
27 #include <pcl/point_types.h>
53 std::string points_topic =
"points";
54 std::string
frameId =
"base_link";
55 double vertical_angle = 2.0;
56 double horizontal_angle = 120.0;
57 double max_dis = 60.0;
59 double framerate = 30.0;
87 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>());
91 std::chrono::time_point<std::chrono::system_clock>
start, end;
92 start = std::chrono::system_clock::now();
95 pcl::PointCloud<pcl::PointXYZL>::Ptr edges(
new pcl::PointCloud<pcl::PointXYZL>());
96 pcl::PointCloud<pcl::PointNormal>::Ptr normals(
new pcl::PointCloud<pcl::PointNormal>());
101 std::vector <pcl::PointIndices> labelIndices;
104 end = std::chrono::system_clock::now();
105 std::chrono::duration<float> elapsed_seconds = end -
start;
110 float time_temp = elapsed_seconds.count() * 1000;
115 sensor_msgs::PointCloud2 edgePoints;
119 sensor_msgs::PointCloud2 surfacePoints;
123 edgePoints.header = points->header;
124 surfacePoints.header = points->header;