Apollo  6.0
Open source self driving car software
base_calibration_service.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 <map>
19 #include <string>
20 
24 
25 namespace apollo {
26 namespace perception {
27 namespace camera {
28 
30  int image_width = 0;
31  int image_height = 0;
32  double timestamp = 0;
34  std::string calibrator_method = "";
35  std::map<std::string, Eigen::Matrix3f> name_intrinsic_map;
36 };
37 
39 
41  public:
42  BaseCalibrationService() = default;
43 
44  virtual ~BaseCalibrationService() = default;
45 
46  virtual bool Init(const CalibrationServiceInitOptions &options =
48 
49  virtual bool BuildIndex() = 0;
50 
51  // @brief query camera to world pose with refinement if any
52  virtual bool QueryCameraToWorldPose(Eigen::Matrix4d *pose) const {
53  return false;
54  }
55 
56  // @brief query depth on ground plane given pixel coordinate
57  virtual bool QueryDepthOnGroundPlane(int x, int y, double *depth) const {
58  return false;
59  }
60 
61  // @brief query 3d point on ground plane given pixel coordinate
62  virtual bool QueryPoint3dOnGroundPlane(int x, int y,
63  Eigen::Vector3d *point3d) const {
64  return false;
65  }
66 
67  // @brief query ground plane in camera frame, parameterized as
68  // [n^T, d] with n^T*x+d=0
70  Eigen::Vector4d *plane_param) const {
71  return false;
72  }
73 
74  // @brief query camera to ground height and pitch angle
75  virtual bool QueryCameraToGroundHeightAndPitchAngle(float *height,
76  float *pitch) const {
77  return false;
78  }
79 
80  virtual float QueryCameraToGroundHeight() const { return 0.f; }
81 
82  virtual float QueryPitchAngle() const { return 0.f; }
83 
84  // @brief using calibrator to update pitch angle
85  virtual void Update(CameraFrame *frame) {
86  // do nothing
87  }
88 
89  // @brief set camera height, pitch and project matrix
91  const std::map<std::string, float> &name_camera_ground_height_map,
92  const std::map<std::string, float> &name_camera_pitch_angle_diff_map,
93  const float &pitch_angle_master_sensor) {
94  // do nothing
95  }
96 
97  virtual std::string Name() const = 0;
98 
100  BaseCalibrationService &operator=(const BaseCalibrationService &) = delete;
101 }; // class BaseCalibrationService
102 
104 #define REGISTER_CALIBRATION_SERVICE(name) \
105  PERCEPTION_REGISTER_CLASS(BaseCalibrationService, name)
106 
107 } // namespace camera
108 } // namespace perception
109 } // namespace apollo
PERCEPTION_REGISTER_REGISTERER(BaseCalibrationService)
int image_width
Definition: base_calibration_service.h:30
Definition: base_calibration_service.h:38
Definition: base_init_options.h:24
int image_height
Definition: base_calibration_service.h:31
Definition: camera_frame.h:33
std::string calibrator_working_sensor_name
Definition: base_calibration_service.h:33
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
virtual bool QueryGroundPlaneInCameraFrame(Eigen::Vector4d *plane_param) const
Definition: base_calibration_service.h:69
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
Eigen::Matrix4d Matrix4d
Definition: base_map_fwd.h:32
virtual bool QueryPoint3dOnGroundPlane(int x, int y, Eigen::Vector3d *point3d) const
Definition: base_calibration_service.h:62
virtual bool QueryCameraToWorldPose(Eigen::Matrix4d *pose) const
Definition: base_calibration_service.h:52
virtual bool QueryDepthOnGroundPlane(int x, int y, double *depth) const
Definition: base_calibration_service.h:57
double timestamp
Definition: base_calibration_service.h:32
Definition: base_calibration_service.h:40
std::string calibrator_method
Definition: base_calibration_service.h:34
virtual bool QueryCameraToGroundHeightAndPitchAngle(float *height, float *pitch) const
Definition: base_calibration_service.h:75
std::map< std::string, Eigen::Matrix3f > name_intrinsic_map
Definition: base_calibration_service.h:35
bool Init(const char *binary_name)
virtual float QueryCameraToGroundHeight() const
Definition: base_calibration_service.h:80
virtual void Update(CameraFrame *frame)
Definition: base_calibration_service.h:85
Definition: base_calibration_service.h:29
virtual void SetCameraHeightAndPitch(const std::map< std::string, float > &name_camera_ground_height_map, const std::map< std::string, float > &name_camera_pitch_angle_diff_map, const float &pitch_angle_master_sensor)
Definition: base_calibration_service.h:90
virtual float QueryPitchAngle() const
Definition: base_calibration_service.h:82