Apollo  6.0
Open source self driving car software
lidar_obstacle_detection.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2021 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 <string>
19 #include <memory>
20 
27 
28 namespace apollo {
29 namespace perception {
30 namespace lidar {
31 
33  public:
34  LidarObstacleDetection() = default;
35  virtual ~LidarObstacleDetection() = default;
36 
37  bool Init(const LidarObstacleDetectionInitOptions& options =
39 
41  const LidarObstacleDetectionOptions& options,
42  const std::shared_ptr<apollo::drivers::PointCloud const>& message,
43  LidarFrame* frame) override;
44 
46  LidarFrame* frame) override;
47 
48  std::string Name() const override { return "LidarObstacleDetection"; }
49 
50  private:
51  LidarProcessResult ProcessCommon(const LidarObstacleDetectionOptions& options,
52  LidarFrame* frame);
53 
54  private:
55  std::shared_ptr<BasePointCloudPreprocessor> cloud_preprocessor_;
56  std::shared_ptr<BaseLidarDetector> detector_;
57  MapManager map_manager_;
58  ObjectBuilder builder_;
59  ObjectFilterBank filter_bank_;
60  // params
61  bool use_map_manager_ = true;
62  bool use_object_filter_bank_ = true;
63  bool use_object_builder_ = true;
64 }; // class LidarObstacleDetection
65 
66 } // namespace lidar
67 } // namespace perception
68 } // namespace apollo
Definition: base_lidar_obstacle_detection.h:38
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::string Name() const override
Definition: lidar_obstacle_detection.h:48
bool Init(const LidarObstacleDetectionInitOptions &options=LidarObstacleDetectionInitOptions()) override
Definition: object_builder.h:38
LidarProcessResult Process(const LidarObstacleDetectionOptions &options, const std::shared_ptr< apollo::drivers::PointCloud const > &message, LidarFrame *frame) override
Definition: lidar_obstacle_detection.h:32
Definition: base_lidar_obstacle_detection.h:45
Definition: lidar_frame.h:33
Definition: map_manager.h:34
Definition: object_filter_bank.h:28
Definition: lidar_error_code.h:36
Definition: base_lidar_obstacle_detection.h:33