Apollo  6.0
Open source self driving car software
cnn_segmentation.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "gtest/gtest_prod.h"
23 
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"
26 
36 
37 namespace apollo {
38 namespace perception {
39 namespace lidar {
40 
42  public:
43  CNNSegmentation() = default;
44  virtual ~CNNSegmentation() = default;
45 
46  bool Init(const LidarDetectorInitOptions& options =
47  LidarDetectorInitOptions()) override;
48 
49  bool Detect(const LidarDetectorOptions& options, LidarFrame* frame) override;
50 
51  std::string Name() const override { return "CNNSegmentation"; }
52 
53  private:
54  bool GetConfigs(std::string* param_file, std::string* proto_file,
55  std::string* weight_file, std::string* engine_file);
56 
57  bool InitClusterAndBackgroundSegmentation();
58 
59  void GetObjectsFromSppEngine(
60  std::vector<std::shared_ptr<base::Object>>* objects);
61 
62  void MapPointToGrid(
63  const std::shared_ptr<base::AttributePointCloud<base::PointF>>& pc_ptr);
64 
65  CNNSegParam cnnseg_param_;
66  std::shared_ptr<inference::Inference> inference_;
67  std::shared_ptr<FeatureGenerator> feature_generator_;
68 
69  // output blobs
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_;
76  // input blobs
77  std::shared_ptr<base::Blob<float>> feature_blob_;
78 
79  // feature parameters
80  float range_ = 0.f;
81  int width_ = 0;
82  int height_ = 0;
83  float min_height_ = 0.f;
84  float max_height_ = 0.f;
85 
86  // 1-d index in feature map of each point
87  std::vector<int> point2grid_;
88 
89  // ground detector for background segmentation
90  BaseGroundDetector* ground_detector_;
91  // roi filter for background segmentation
92  BaseROIFilter* roi_filter_;
93 
94  // thread worker
95  lib::ThreadWorker worker_;
96 
97  // spp engine
98  SppEngine spp_engine_;
99  SppEngineConfig spp_engine_config_;
100 
101  // reference pointer of lidar frame
102  LidarFrame* lidar_frame_ref_ = nullptr;
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_;
108  int gpu_id_ = -1;
109 
110  // time statistics
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;
119 
120  // sensor_name
121  std::string sensor_name_;
122 
123  // secondary segmentation to improve miss detection
124  // not found by neural networks !
125  std::shared_ptr<BaseLidarDetector> secondary_segmentor;
126 
127  private:
128  const int kDefaultPointCloudSize = 120000;
129 
130  FRIEND_TEST(CNNSegmentationTest, cnn_segmentation_sequence_test);
131  FRIEND_TEST(CNNSegmentationTest, cnn_segmentation_test);
132 }; // class CNNSegmentation
133 
134 } // namespace lidar
135 } // namespace perception
136 } // namespace apollo
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
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