22 #include "gtest/gtest_prod.h" 24 #include "modules/perception/lidar/lib/detector/cnn_segmentation/proto/cnnseg_param.pb.h" 25 #include "modules/perception/lidar/lib/detector/cnn_segmentation/proto/spp_engine_config.pb.h" 38 namespace perception {
51 std::string
Name()
const override {
return "CNNSegmentation"; }
54 bool GetConfigs(std::string* param_file, std::string* proto_file,
55 std::string* weight_file, std::string* engine_file);
57 bool InitClusterAndBackgroundSegmentation();
59 void GetObjectsFromSppEngine(
60 std::vector<std::shared_ptr<base::Object>>* objects);
65 CNNSegParam cnnseg_param_;
66 std::shared_ptr<inference::Inference> inference_;
67 std::shared_ptr<FeatureGenerator> feature_generator_;
70 std::shared_ptr<base::Blob<float>> instance_pt_blob_;
71 std::shared_ptr<base::Blob<float>> category_pt_blob_;
72 std::shared_ptr<base::Blob<float>> confidence_pt_blob_;
73 std::shared_ptr<base::Blob<float>> classify_pt_blob_;
74 std::shared_ptr<base::Blob<float>> heading_pt_blob_;
75 std::shared_ptr<base::Blob<float>> height_pt_blob_;
77 std::shared_ptr<base::Blob<float>> feature_blob_;
83 float min_height_ = 0.f;
84 float max_height_ = 0.f;
87 std::vector<int> point2grid_;
99 SppEngineConfig spp_engine_config_;
103 std::shared_ptr<base::AttributePointCloud<base::PointF>> original_cloud_;
104 std::shared_ptr<base::AttributePointCloud<base::PointD>>
105 original_world_cloud_;
106 std::shared_ptr<base::AttributePointCloud<base::PointF>> roi_cloud_;
107 std::shared_ptr<base::AttributePointCloud<base::PointD>> roi_world_cloud_;
111 double mapping_time_ = 0.0;
112 double feature_time_ = 0.0;
113 double infer_time_ = 0.0;
114 double join_time_ = 0.0;
115 double fg_seg_time_ = 0.0;
116 double collect_time_ = 0.0;
117 double roi_filter_time_ = 0.0;
118 double ground_detector_time_ = 0.0;
121 std::string sensor_name_;
125 std::shared_ptr<BaseLidarDetector> secondary_segmentor;
128 const int kDefaultPointCloudSize = 120000;
130 FRIEND_TEST(CNNSegmentationTest, cnn_segmentation_sequence_test);
131 FRIEND_TEST(CNNSegmentationTest, cnn_segmentation_test);
virtual ~CNNSegmentation()=default
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: base_roi_filter.h:32
Definition: base_lidar_detector.h:34
std::string Name() const override
Definition: cnn_segmentation.h:51
CNNSegmentation()=default
Definition: point_cloud.h:264
Definition: base_ground_detector.h:32
Definition: cnn_segmentation.h:41
Definition: thread_worker.h:27
Definition: lidar_frame.h:33
bool Init(const LidarDetectorInitOptions &options=LidarDetectorInitOptions()) override
Definition: base_lidar_detector.h:28
Definition: base_lidar_detector.h:32
Definition: spp_engine.h:33
bool Detect(const LidarDetectorOptions &options, LidarFrame *frame) override