15 #ifndef APOLLO_LIDAR_SEGMENTATION__FEATURE_GENERATOR_HPP_
16 #define APOLLO_LIDAR_SEGMENTATION__FEATURE_GENERATOR_HPP_
18 #include <pcl/io/pcd_io.h>
19 #include <pcl/point_types.h>
20 #include <sensor_msgs/msg/point_cloud2.hpp>
32 namespace segmentation
34 namespace apollo_lidar_segmentation
43 const bool8_t use_intensity_feature_;
44 const bool8_t use_constant_feature_;
47 std::shared_ptr<FeatureMapInterface> map_ptr_;
59 int32_t width, int32_t height, int32_t range,
bool8_t use_intensity_feature,
65 std::shared_ptr<FeatureMapInterface> generate(
66 const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & pc_ptr);
72 #endif // APOLLO_LIDAR_SEGMENTATION__FEATURE_GENERATOR_HPP_