Apollo  6.0
Open source self driving car software
base_radar_obstacle_perception.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 // SAMPLE CODE:
17 //
18 // class DefaultRadarObstaclePerception : public BaseRadarObstaclePerception {
19 // public:
20 // DefaultRadarObstaclePerception() : BaseRadarObstaclePerception() {}
21 // virtual ~DefaultRadarObstaclePerception() {}
22 //
23 // virtual bool Init() override {
24 // // Do something.
25 // return true;
26 // }
27 //
28 // virtual bool Perceive(
29 // const drivers::ContiRadar& corrected_obstacles,
30 // const RadarPerceptionOptions& options,
31 // std::vector<base::ObjectPtr>* objects) override {
32 // // Do something.
33 // return true;
34 // }
35 //
36 // virtual std::string Name() const override {
37 // return "DefaultRadarObstaclePerception";
38 // }
39 //
40 // };
41 //
42 // // Register plugin.
43 // PERCEPTION_REGISTER_RADAR_OBSTACLE_PERCEPTION(DefaultRadarObstaclePerception);
45 // USING CODE:
46 //
47 // BaseRadarObstaclePerception* radar_perception =
48 // BaseRadarObstaclePerceptionRegisterer::GetInstanceByName("DefaultRadarObstaclePerception");
49 // using radar_perception to do somethings.
50 // ////////////////////////////////////////////////////
51 
52 #pragma once
53 
54 #include <string>
55 #include <vector>
56 
61 
62 namespace apollo {
63 namespace perception {
64 namespace radar {
69  std::string sensor_name;
70 };
72  public:
73  BaseRadarObstaclePerception() = default;
74  virtual ~BaseRadarObstaclePerception() = default;
75  virtual bool Init(const std::string& pipeline_name) = 0;
76  virtual bool Perceive(const drivers::ContiRadar& corrected_obstacles,
77  const RadarPerceptionOptions& options,
78  std::vector<base::ObjectPtr>* objects) = 0;
79  virtual std::string Name() const = 0;
80 };
81 
83 #define PERCEPTION_REGISTER_RADAR_OBSTACLE_PERCEPTION(name) \
84  PERCEPTION_REGISTER_CLASS(BaseRadarObstaclePerception, name)
85 
86 } // namespace radar
87 } // namespace perception
88 } // namespace apollo
Definition: base_detector.h:72
Definition: base_roi_filter.h:69
Definition: base_radar_obstacle_perception.h:71
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
PERCEPTION_REGISTER_REGISTERER(BaseDetector)
TrackerOptions track_options
Definition: base_radar_obstacle_perception.h:68
Definition: base_radar_obstacle_perception.h:65
Definition: base_tracker.h:67
bool Init(const char *binary_name)
DetectorOptions detector_options
Definition: base_radar_obstacle_perception.h:66
RoiFilterOptions roi_filter_options
Definition: base_radar_obstacle_perception.h:67
std::string sensor_name
Definition: base_radar_obstacle_perception.h:69