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

#include <laneline_calibrator.h>

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

Public 成员函数

 LaneLineCalibrator ()=default
 
virtual ~LaneLineCalibrator ()=default
 
bool Init (const CalibratorInitOptions &options=CalibratorInitOptions()) override
 
bool Calibrate (const CalibratorOptions &options, float *pitch_angle) override
 
std::string Name () const override
 
float GetTimeDiff () const
 
float GetYawRate () const
 
float GetVelocity () const
 
float GetVanishingRow () const
 
- Public 成员函数 继承自 apollo::perception::camera::BaseCalibrator
 BaseCalibrator ()=default
 
virtual ~BaseCalibrator ()=default
 
 DISALLOW_COPY_AND_ASSIGN (BaseCalibrator)
 

详细描述

在文件 laneline_calibrator.h29 行定义.

构造及析构函数说明

◆ LaneLineCalibrator()

apollo::perception::camera::LaneLineCalibrator::LaneLineCalibrator ( )
default

◆ ~LaneLineCalibrator()

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

成员函数说明

◆ Calibrate()

bool apollo::perception::camera::LaneLineCalibrator::Calibrate ( const CalibratorOptions options,
float *  pitch_angle 
)
overridevirtual

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

在文件 laneline_calibrator.cc36 行定义.

37 {
38 if (pitch_angle == nullptr) {
39 AERROR << "pitch_angle is not available";
40 return false;
41 }
42 EgoLane ego_lane;
43 if (!LoadEgoLaneline(*options.lane_objects, &ego_lane)) {
44 AINFO << "Failed to get the ego lane.";
45 return false;
46 }
47
48 double cam_ori[4] = {0};
49 cam_ori[3] = 1.0;
50
51 // Camera to world pose
52 Eigen::Affine3d c2w = *options.camera2world_pose;
53
54 double p2w[12] = {
55 c2w(0, 0), c2w(0, 1), c2w(0, 2), c2w(0, 3), c2w(1, 0), c2w(1, 1),
56 c2w(1, 2), c2w(1, 3), c2w(2, 0), c2w(2, 1), c2w(2, 2), c2w(2, 3),
57 };
58
59 ADEBUG << "c2w transform this frame:\n"
60 << p2w[0] << ", " << p2w[1] << ", " << p2w[2] << ", " << p2w[3] << "\n"
61 << p2w[4] << ", " << p2w[5] << ", " << p2w[6] << ", " << p2w[7] << "\n"
62 << p2w[8] << ", " << p2w[9] << ", " << p2w[10] << ", " << p2w[11];
63
64 algorithm::IMultAx3x4(p2w, cam_ori, cam_coord_cur_);
65 time_diff_ = kTimeDiffDefault;
66 yaw_rate_ = kYawRateDefault;
67 velocity_ = kVelocityDefault;
68
69 timestamp_cur_ = *options.timestamp;
70 if (!is_first_frame_) {
71 time_diff_ = fabsf(static_cast<float>(timestamp_cur_ - timestamp_pre_));
72 ADEBUG << timestamp_cur_ << " " << timestamp_pre_ << std::endl;
73 camera::GetYawVelocityInfo(time_diff_, cam_coord_cur_, cam_coord_pre_,
74 cam_coord_pre_pre_, &yaw_rate_, &velocity_);
75 std::string timediff_yawrate_velocity_text =
76 absl::StrCat("time_diff_: ", std::to_string(time_diff_).substr(0, 4),
77 " | yaw_rate_: ", std::to_string(yaw_rate_).substr(0, 4),
78 " | velocity_: ", std::to_string(velocity_).substr(0, 4));
79 ADEBUG << timediff_yawrate_velocity_text << std::endl;
80 }
81
82 bool updated =
83 calibrator_.Process(ego_lane, velocity_, yaw_rate_, time_diff_);
84 if (updated) {
85 *pitch_angle = calibrator_.get_pitch_estimation();
86 float vanishing_row = calibrator_.get_vanishing_row();
87 AINFO << "#updated pitch angle: " << *pitch_angle;
88 AINFO << "#vanishing row: " << vanishing_row;
89 }
90
91 if (!is_first_frame_) {
92 memcpy(cam_coord_pre_pre_, cam_coord_pre_, sizeof(double) * 3);
93 }
94 is_first_frame_ = false;
95 memcpy(cam_coord_pre_, cam_coord_cur_, sizeof(double) * 3);
96 timestamp_pre_ = timestamp_cur_;
97 return updated;
98}
bool Process(const EgoLane &lane, const float &velocity, const float &yaw_rate, const float &time_diff)
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
void IMultAx3x4(const T A[12], const T x[4], T Ax[3])
Definition i_blas.h:4380
void GetYawVelocityInfo(const float &time_diff, const double cam_coord_cur[3], const double cam_coord_pre[3], const double cam_coord_pre_pre[3], float *yaw_rate, float *velocity)

◆ GetTimeDiff()

float apollo::perception::camera::LaneLineCalibrator::GetTimeDiff ( ) const
inline

在文件 laneline_calibrator.h45 行定义.

45{ return time_diff_; }

◆ GetVanishingRow()

float apollo::perception::camera::LaneLineCalibrator::GetVanishingRow ( ) const
inline

在文件 laneline_calibrator.h48 行定义.

48 {
49 return calibrator_.get_vanishing_row();
50 }

◆ GetVelocity()

float apollo::perception::camera::LaneLineCalibrator::GetVelocity ( ) const
inline

在文件 laneline_calibrator.h47 行定义.

47{ return velocity_; }

◆ GetYawRate()

float apollo::perception::camera::LaneLineCalibrator::GetYawRate ( ) const
inline

在文件 laneline_calibrator.h46 行定义.

46{ return yaw_rate_; }

◆ Init()

bool apollo::perception::camera::LaneLineCalibrator::Init ( const CalibratorInitOptions options = CalibratorInitOptions())
overridevirtual

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

在文件 laneline_calibrator.cc24 行定义.

24 {
25 LocalCalibratorInitOptions local_options;
26 local_options.cx = options.cx;
27 local_options.cy = options.cy;
28 local_options.focal_x = options.focal_x;
29 local_options.focal_y = options.focal_y;
30 image_width_ = local_options.image_width = options.image_width;
31 image_height_ = local_options.image_height = options.image_height;
32 calibrator_.Init(local_options);
33 return true;
34}
void Init(const LocalCalibratorInitOptions &options, const CalibratorParams *params=nullptr)

◆ Name()

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

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

在文件 laneline_calibrator.h43 行定义.

43{ return "LaneLineCalibrator"; }

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