Apollo  6.0
Open source self driving car software
base_calibrator.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 
24 
26 
27 namespace apollo {
28 namespace perception {
29 namespace camera {
30 
32  int image_width = 0;
33  int image_height = 0;
34  float focal_x = 0.0f;
35  float focal_y = 0.0f;
36  float cx = 0.0f;
37  float cy = 0.0f;
38 };
39 
41  std::shared_ptr<std::vector<base::LaneLine>> lane_objects;
42  std::shared_ptr<Eigen::Affine3d> camera2world_pose;
43  double *timestamp = nullptr;
44 };
45 
47  public:
48  BaseCalibrator() = default;
49 
50  virtual ~BaseCalibrator() = default;
51 
52  virtual bool Init(
53  const CalibratorInitOptions &options = CalibratorInitOptions()) = 0;
54 
55  // @brief: refine 3D location of detected obstacles.
56  // @param [in]: options
57  // @param [in/out]: pitch_angle
58  virtual bool Calibrate(const CalibratorOptions &options,
59  float *pitch_angle) = 0;
60 
61  virtual std::string Name() const = 0;
62 
63  BaseCalibrator(const BaseCalibrator &) = delete;
64  BaseCalibrator &operator=(const BaseCalibrator &) = delete;
65 }; // class BaseCalibrator
66 
68 #define REGISTER_CALIBRATOR(name) \
69  PERCEPTION_REGISTER_CLASS(BaseCalibrator, name)
70 
71 } // namespace camera
72 } // namespace perception
73 } // namespace apollo
PERCEPTION_REGISTER_REGISTERER(BaseCalibrationService)
Definition: base_init_options.h:24
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
float focal_x
Definition: base_calibrator.h:34
float cy
Definition: base_calibrator.h:37
Definition: base_calibrator.h:40
float cx
Definition: base_calibrator.h:36
Definition: base_calibrator.h:46
std::shared_ptr< std::vector< base::LaneLine > > lane_objects
Definition: base_calibrator.h:41
float focal_y
Definition: base_calibrator.h:35
bool Init(const char *binary_name)
int image_height
Definition: base_calibrator.h:33
int image_width
Definition: base_calibrator.h:32
std::shared_ptr< Eigen::Affine3d > camera2world_pose
Definition: base_calibrator.h:42