Apollo 10.0
自动驾驶开放平台
apollo::perception::camera::OnlineCalibrationService类 参考

#include <online_calibration_service.h>

类 apollo::perception::camera::OnlineCalibrationService 继承关系图:
apollo::perception::camera::OnlineCalibrationService 的协作图:

Public 成员函数

 OnlineCalibrationService ()=default
 
virtual ~OnlineCalibrationService ()=default
 
bool Init (const CalibrationServiceInitOptions &options=CalibrationServiceInitOptions()) override
 
bool BuildIndex () override
 
bool QueryDepthOnGroundPlane (int x, int y, double *depth) const override
 
bool QueryPoint3dOnGroundPlane (int x, int y, Eigen::Vector3d *point3d) const override
 
bool QueryGroundPlaneInCameraFrame (Eigen::Vector4d *plane_param) const override
 
bool QueryCameraToGroundHeightAndPitchAngle (float *height, float *pitch) const override
 
float QueryCameraToGroundHeight () const override
 
float QueryPitchAngle () const override
 
void Update (onboard::CameraFrame *frame) override
 
void Update (CameraFrame *frame) override
 
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) override
 
std::string Name () const override
 
- Public 成员函数 继承自 apollo::perception::camera::BaseCalibrationService
 BaseCalibrationService ()=default
 
virtual ~BaseCalibrationService ()=default
 
virtual bool QueryCameraToWorldPose (Eigen::Matrix4d *pose) const
 
 DISALLOW_COPY_AND_ASSIGN (BaseCalibrationService)
 

详细描述

在文件 online_calibration_service.h39 行定义.

构造及析构函数说明

◆ OnlineCalibrationService()

apollo::perception::camera::OnlineCalibrationService::OnlineCalibrationService ( )
default

◆ ~OnlineCalibrationService()

virtual apollo::perception::camera::OnlineCalibrationService::~OnlineCalibrationService ( )
virtualdefault

成员函数说明

◆ BuildIndex()

bool apollo::perception::camera::OnlineCalibrationService::BuildIndex ( )
overridevirtual

实现了 apollo::perception::camera::BaseCalibrationService.

在文件 online_calibration_service.cc68 行定义.

68 {
69 is_service_ready_ = HasSetIntrinsics() && HasSetGroundPlane();
70 return is_service_ready_;
71}

◆ Init()

bool apollo::perception::camera::OnlineCalibrationService::Init ( const CalibrationServiceInitOptions options = CalibrationServiceInitOptions())
overridevirtual

实现了 apollo::perception::camera::BaseCalibrationService.

在文件 online_calibration_service.cc28 行定义.

29 {
30 master_sensor_name_ = options.calibrator_working_sensor_name;
31 sensor_name_ = options.calibrator_working_sensor_name;
32 // Init k_matrix
33 auto &name_intrinsic_map = options.name_intrinsic_map;
34 ACHECK(name_intrinsic_map.find(master_sensor_name_) !=
35 name_intrinsic_map.end());
36 CameraStatus camera_status;
37 name_camera_status_map_.clear();
38 for (auto iter = name_intrinsic_map.begin(); iter != name_intrinsic_map.end();
39 ++iter) {
40 camera_status.k_matrix[0] = static_cast<double>(iter->second(0, 0));
41 camera_status.k_matrix[4] = static_cast<double>(iter->second(1, 1));
42 camera_status.k_matrix[2] = static_cast<double>(iter->second(0, 2));
43 camera_status.k_matrix[5] = static_cast<double>(iter->second(1, 2));
44 camera_status.k_matrix[8] = 1.0;
45 name_camera_status_map_.insert(
46 std::pair<std::string, CameraStatus>(iter->first, camera_status));
47 }
48 // Only init calibrator on master_sensor
49 CalibratorInitOptions calibrator_init_options;
50 calibrator_init_options.image_width = options.image_width;
51 calibrator_init_options.image_height = options.image_height;
52 calibrator_init_options.focal_x = static_cast<float>(
53 name_camera_status_map_[master_sensor_name_].k_matrix[0]);
54 calibrator_init_options.focal_y = static_cast<float>(
55 name_camera_status_map_[master_sensor_name_].k_matrix[4]);
56 calibrator_init_options.cx = static_cast<float>(
57 name_camera_status_map_[master_sensor_name_].k_matrix[2]);
58 calibrator_init_options.cy = static_cast<float>(
59 name_camera_status_map_[master_sensor_name_].k_matrix[5]);
60 calibrator_.reset(
61 BaseCalibratorRegisterer::GetInstanceByName(options.calibrator_method));
62 ACHECK(calibrator_ != nullptr);
63 ACHECK(calibrator_->Init(calibrator_init_options))
64 << "Failed to init " << options.calibrator_method;
65 return true;
66}
#define ACHECK(cond)
Definition log.h:80

◆ Name()

std::string apollo::perception::camera::OnlineCalibrationService::Name ( ) const
inlineoverridevirtual

实现了 apollo::perception::camera::BaseCalibrationService.

在文件 online_calibration_service.h94 行定义.

94{ return "OnlineCalibrationService"; }

◆ QueryCameraToGroundHeight()

float apollo::perception::camera::OnlineCalibrationService::QueryCameraToGroundHeight ( ) const
inlineoverridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.h66 行定义.

66 {
67 if (is_service_ready_) {
68 auto iter = name_camera_status_map_.find(sensor_name_);
69 return (iter->second).camera_ground_height;
70 }
71 return -1.f;
72 }

◆ QueryCameraToGroundHeightAndPitchAngle()

bool apollo::perception::camera::OnlineCalibrationService::QueryCameraToGroundHeightAndPitchAngle ( float *  height,
float *  pitch 
) const
overridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.cc137 行定义.

138 {
139 if (height == nullptr) {
140 AERROR << "height is nullptr";
141 return false;
142 }
143 if (pitch == nullptr) {
144 AERROR << "pitch is nullptr";
145 return false;
146 }
147 if (!is_service_ready_) {
148 *height = *pitch = 0.0;
149 return false;
150 }
151 auto iter = name_camera_status_map_.find(sensor_name_);
152 *height = iter->second.camera_ground_height;
153 *pitch = iter->second.pitch_angle;
154 return true;
155}
#define AERROR
Definition log.h:44
uint32_t height
Height of point cloud

◆ QueryDepthOnGroundPlane()

bool apollo::perception::camera::OnlineCalibrationService::QueryDepthOnGroundPlane ( int  x,
int  y,
double *  depth 
) const
overridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.cc73 行定义.

74 {
75 if (!is_service_ready_) {
76 return false;
77 }
78 ACHECK(depth != nullptr);
79 double pixel[2] = {static_cast<double>(x), static_cast<double>(y)};
80 double point[3] = {0};
81
82 auto iter = name_camera_status_map_.find(sensor_name_);
84 pixel, &(iter->second.k_matrix[0]), &(iter->second.ground_plane[0]),
85 point);
86 if (!success) {
87 *depth = 0.0;
88 return false;
89 }
90
91 *depth = point[2];
92 return true;
93}
bool IBackprojectPlaneIntersectionCanonical(const T *x, const T *K, const T *pi, T *X)
Definition i_util.h:197

◆ QueryGroundPlaneInCameraFrame()

bool apollo::perception::camera::OnlineCalibrationService::QueryGroundPlaneInCameraFrame ( Eigen::Vector4d *  plane_param) const
overridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.cc118 行定义.

119 {
120 if (plane_param == nullptr) {
121 AERROR << "plane_param is nullptr";
122 return false;
123 }
124 if (!is_service_ready_) {
125 (*plane_param)(0) = (*plane_param)(1) = (*plane_param)(2) =
126 (*plane_param)(3) = 0.0;
127 return false;
128 }
129 auto iter = name_camera_status_map_.find(sensor_name_);
130 (*plane_param)(0) = iter->second.ground_plane[0];
131 (*plane_param)(1) = iter->second.ground_plane[1];
132 (*plane_param)(2) = iter->second.ground_plane[2];
133 (*plane_param)(3) = iter->second.ground_plane[3];
134 return true;
135}

◆ QueryPitchAngle()

float apollo::perception::camera::OnlineCalibrationService::QueryPitchAngle ( ) const
inlineoverridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.h74 行定义.

74 {
75 if (is_service_ready_) {
76 auto iter = name_camera_status_map_.find(sensor_name_);
77 return (iter->second).pitch_angle;
78 }
79 return -1.f;
80 }

◆ QueryPoint3dOnGroundPlane()

bool apollo::perception::camera::OnlineCalibrationService::QueryPoint3dOnGroundPlane ( int  x,
int  y,
Eigen::Vector3d *  point3d 
) const
overridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.cc95 行定义.

96 {
97 if (!is_service_ready_) {
98 return false;
99 }
100 ACHECK(point3d != nullptr);
101 double pixel[2] = {static_cast<double>(x), static_cast<double>(y)};
102 double point[3] = {0};
103 auto iter = name_camera_status_map_.find(sensor_name_);
105 pixel, &(iter->second.k_matrix[0]), &(iter->second.ground_plane[0]),
106 point);
107 if (!success) {
108 (*point3d)(0) = (*point3d)(1) = (*point3d)(2) = 0.0;
109 return false;
110 }
111
112 (*point3d)(0) = point[0];
113 (*point3d)(1) = point[1];
114 (*point3d)(2) = point[2];
115 return true;
116}

◆ SetCameraHeightAndPitch()

void apollo::perception::camera::OnlineCalibrationService::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 
)
overridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.cc237 行定义.

240 {
241 name_camera_status_map_[master_sensor_name_].pitch_angle =
242 pitch_angle_master_sensor;
243 for (auto iter = name_camera_status_map_.begin();
244 iter != name_camera_status_map_.end(); ++iter) {
245 // get iters
246 auto iter_ground_height = name_camera_ground_height_map.find(iter->first);
247 auto iter_pitch_angle_diff =
248 name_camera_pitch_angle_diff_map.find(iter->first);
249 ACHECK(iter_ground_height != name_camera_ground_height_map.end());
250 ACHECK(iter_pitch_angle_diff != name_camera_pitch_angle_diff_map.end());
251 // set camera status
252 name_camera_status_map_[iter->first].camera_ground_height =
253 iter_ground_height->second;
254 name_camera_status_map_[iter->first].pitch_angle_diff =
255 iter_pitch_angle_diff->second;
256 name_camera_status_map_[iter->first].pitch_angle =
257 pitch_angle_master_sensor + iter_pitch_angle_diff->second;
258 name_camera_status_map_[iter->first].ground_plane[1] =
259 cos(name_camera_status_map_[iter->first].pitch_angle);
260 name_camera_status_map_[iter->first].ground_plane[2] =
261 -sin(name_camera_status_map_[iter->first].pitch_angle);
262 name_camera_status_map_[iter->first].ground_plane[3] =
263 -name_camera_status_map_[iter->first].camera_ground_height;
264 }
265}
float cos(Angle16 a)
Definition angle.cc:42
float sin(Angle16 a)
Definition angle.cc:25

◆ Update() [1/2]

void apollo::perception::camera::OnlineCalibrationService::Update ( CameraFrame frame)
overridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.cc197 行定义.

197 {
198 if (frame == nullptr) {
199 AERROR << "frame is nullptr";
200 return;
201 }
202 sensor_name_ = frame->data_provider->sensor_name();
203 if (sensor_name_ == master_sensor_name_) {
204 CalibratorOptions calibrator_options;
205
206 calibrator_options.lane_objects =
207 std::make_shared<std::vector<base::LaneLine>>(frame->lane_objects);
208 calibrator_options.camera2world_pose.reset(
209 new Eigen::Affine3d(frame->camera2world_pose));
210 calibrator_options.timestamp = &(frame->timestamp);
211 float pitch_angle = 0.f;
212 bool updated = calibrator_->Calibrate(calibrator_options, &pitch_angle);
213 // rebuild the service when updated
214 if (updated) {
215 name_camera_status_map_[master_sensor_name_].pitch_angle = pitch_angle;
216 for (auto iter = name_camera_status_map_.begin();
217 iter != name_camera_status_map_.end(); iter++) {
218 // update pitch angle
219 iter->second.pitch_angle =
220 iter->second.pitch_angle_diff +
221 name_camera_status_map_[master_sensor_name_].pitch_angle;
222 // update ground plane param
223 iter->second.ground_plane[1] = cos(iter->second.pitch_angle);
224 iter->second.ground_plane[2] = -sin(iter->second.pitch_angle);
225 }
226 }
227 }
228 auto iter = name_camera_status_map_.find(sensor_name_);
229 AINFO << "camera_ground_height: " << iter->second.camera_ground_height
230 << " meter.";
231 AINFO << "pitch_angle: " << iter->second.pitch_angle * 180.0 / M_PI
232 << " degree.";
233 // ACHECK(BuildIndex());
234 is_service_ready_ = true;
235}
#define AINFO
Definition log.h:42

◆ Update() [2/2]

void apollo::perception::camera::OnlineCalibrationService::Update ( onboard::CameraFrame frame)
overridevirtual

重载 apollo::perception::camera::BaseCalibrationService .

在文件 online_calibration_service.cc157 行定义.

157 {
158 if (frame == nullptr) {
159 AERROR << "frame is nullptr";
160 return;
161 }
162 sensor_name_ = frame->data_provider->sensor_name();
163 if (sensor_name_ == master_sensor_name_) {
164 CalibratorOptions calibrator_options;
165 // todo(daohu527) need complete
166 // calibrator_options.lane_objects =
167 // std::make_shared<std::vector<base::LaneLine>>(frame->lane_objects);
168 calibrator_options.camera2world_pose.reset(
169 new Eigen::Affine3d(frame->camera2world_pose));
170 calibrator_options.timestamp = &(frame->timestamp);
171 float pitch_angle = 0.f;
172 bool updated = calibrator_->Calibrate(calibrator_options, &pitch_angle);
173 // rebuild the service when updated
174 if (updated) {
175 name_camera_status_map_[master_sensor_name_].pitch_angle = pitch_angle;
176 for (auto iter = name_camera_status_map_.begin();
177 iter != name_camera_status_map_.end(); iter++) {
178 // update pitch angle
179 iter->second.pitch_angle =
180 iter->second.pitch_angle_diff +
181 name_camera_status_map_[master_sensor_name_].pitch_angle;
182 // update ground plane param
183 iter->second.ground_plane[1] = cos(iter->second.pitch_angle);
184 iter->second.ground_plane[2] = -sin(iter->second.pitch_angle);
185 }
186 }
187 }
188 auto iter = name_camera_status_map_.find(sensor_name_);
189 AINFO << "camera_ground_height: " << iter->second.camera_ground_height
190 << " meter.";
191 AINFO << "pitch_angle: " << iter->second.pitch_angle * 180.0 / M_PI
192 << " degree.";
193 // ACHECK(BuildIndex());
194 is_service_ready_ = true;
195}

该类的文档由以下文件生成: