Apollo  6.0
Open source self driving car software
ncut_segmentation.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2019 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 #ifdef DEBUG_NCUT
23 #include "pcl/visualization/pcl_visualizer.h"
24 #endif
25 
33 #include "modules/perception/lidar/lib/detector/ncut_segmentation/proto/ncut_param.pb.h"
34 
35 namespace apollo {
36 namespace perception {
37 namespace lidar {
38 
39 using base::ObjectPtr;
40 
42  public:
43  NCutSegmentation() = default;
44  virtual ~NCutSegmentation() = 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 "NCutSegmentation"; }
52 
54  remove_roi_ = false;
55  remove_ground_ = false;
56  }
57 
58  private:
59  bool Configure(std::string model_name);
60 
61  void PartitionConnectedComponents(
62  const base::PointFCloudPtr& in_cloud, float cell_size,
63  std::vector<base::PointFCloudPtr>* out_clouds);
64 
65  void ObstacleFilter(const base::PointFCloudPtr& in_cloud, float cell_size,
66  bool filter_pedestrian_only,
67  base::PointFCloudPtr* out_cloud,
68  std::vector<base::ObjectPtr>* segments);
69 
70  bool IsOutlier(const base::PointFCloudPtr& in_cloud);
71 
72  bool GetConfigs(std::string* ncut_file);
73 
74  base::ObjectType Label2Type(const std::string& label);
75 
76  // ground detector for background segmentation
77  BaseGroundDetector* ground_detector_;
78  // roi filter for background segmentation
79  BaseROIFilter* roi_filter_;
80 
81  // reference pointer of lidar frame
82  LidarFrame* lidar_frame_ref_ = nullptr;
83  std::shared_ptr<base::AttributePointCloud<base::PointF>> original_cloud_;
84  std::shared_ptr<base::AttributePointCloud<base::PointD>>
85  original_world_cloud_;
86  std::shared_ptr<base::AttributePointCloud<base::PointF>> roi_cloud_;
87  std::shared_ptr<base::AttributePointCloud<base::PointD>> roi_world_cloud_;
88  // thread worker
89  lib::ThreadWorker worker_;
90 
91  std::vector<std::shared_ptr<NCut>> _segmentors;
92  // for outliers, must be "unknown"
93  std::unique_ptr<std::vector<ObjectPtr>> _outliers;
94  float grid_radius_ = 100.0f;
95  float height_threshold_ = 2.5f;
96  float partition_cell_size_ = 1.0f;
97  float vehicle_filter_cell_size_ = 1.0f;
98  float pedestrian_filter_cell_size_ = 0.05f;
99  float outlier_length_ = 0.3f;
100  float outlier_width_ = 0.3f;
101  float outlier_height_ = 0.3f;
102  int outlier_min_num_points_ = 10;
103  bool remove_ground_ = true;
104  bool remove_roi_ = true;
105  bool do_classification_ = true;
106  std::string ground_detector_str_;
107  std::string roi_filter_str_;
108  NCutParam ncut_param_;
109 
110 #ifdef DEBUG_NCUT
111  pcl::visualization::PCLVisualizer::Ptr _viewer;
112  CPointCloudPtr _rgb_cloud;
113  char _viewer_id[128];
114  int _viewer_count;
115  void VisualizePointCloud(const base::PointFCloudPtr& cloud);
116  void VisualizeSegments(const std::vector<base::ObjectPtr>& segments);
117  void VisualizeComponents(
118  const base::PointFCloudPtr& cloud,
119  const std::vector<std::vector<int>>& component_points);
120 #endif
121 }; // class NCutSegmentation
122 
123 } // namespace lidar
124 } // namespace perception
125 } // namespace apollo
Definition: ncut_segmentation.h:41
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
pcl::PointCloud< CPoint >::Ptr CPointCloudPtr
Definition: pcl_util.h:33
Definition: base_lidar_detector.h:34
void ByPassROIService()
Definition: ncut_segmentation.h:53
Definition: base_ground_detector.h:32
bool Detect(const LidarDetectorOptions &options, LidarFrame *frame) override
Definition: thread_worker.h:27
bool Init(const LidarDetectorInitOptions &options=LidarDetectorInitOptions()) override
Definition: lidar_frame.h:33
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:482
Definition: base_lidar_detector.h:28
Definition: base_lidar_detector.h:32
ObjectType
Definition: object_types.h:26
std::string Name() const override
Definition: ncut_segmentation.h:51
std::shared_ptr< Object > ObjectPtr
Definition: object.h:123