Apollo  6.0
Open source self driving car software
base_lane_postprocessor.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 <string>
19 
22 
24 
25 namespace apollo {
26 namespace perception {
27 namespace camera {
28 
30  std::string detect_config_root;
31  std::string detect_config_name;
32 };
33 
35 
37  public:
38  BaseLanePostprocessor() = default;
39 
40  virtual ~BaseLanePostprocessor() = default;
41 
42  virtual bool Init(const LanePostprocessorInitOptions& options =
44 
45  // @brief: refine 3D location of detected lanes.
46  // @param [in]: options
47  // @param [in/out]: frame
48  // 3D information of lane should be filled, required.
49  virtual bool Process2D(const LanePostprocessorOptions& options,
50  CameraFrame* frame) = 0;
51 
52  virtual bool Process3D(const LanePostprocessorOptions& options,
53  CameraFrame* frame) = 0;
54 
55  virtual void SetIm2CarHomography(Eigen::Matrix3d homography_im2car) {
56  // do nothing
57  }
58 
59  virtual std::string Name() const = 0;
60 
62  BaseLanePostprocessor& operator=(const BaseLanePostprocessor&) = delete;
63 }; // class BaseLanePostprocessor
64 
66 #define REGISTER_LANE_POSTPROCESSOR(name) \
67  PERCEPTION_REGISTER_CLASS(BaseLanePostprocessor, name)
68 
69 } // namespace camera
70 } // namespace perception
71 } // namespace apollo
PERCEPTION_REGISTER_REGISTERER(BaseCalibrationService)
Definition: base_init_options.h:24
Definition: camera_frame.h:33
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::string detect_config_name
Definition: base_lane_postprocessor.h:31
virtual void SetIm2CarHomography(Eigen::Matrix3d homography_im2car)
Definition: base_lane_postprocessor.h:55
bool Init(const char *binary_name)
Definition: base_lane_postprocessor.h:36
std::string detect_config_root
Definition: base_lane_postprocessor.h:30
Definition: base_lane_postprocessor.h:34
Eigen::Matrix3d Matrix3d
Definition: base_map_fwd.h:33
Definition: base_lane_postprocessor.h:29