Apollo 10.0
自动驾驶开放平台
apollo::drivers::velodyne::Calibration类 参考

Calibration class storing entire configuration for the Velodyne 更多...

#include <calibration.h>

apollo::drivers::velodyne::Calibration 的协作图:

Public 成员函数

 Calibration ()
 
 Calibration (const std::string &calibration_file)
 
void read (const std::string &calibration_file)
 
void write (const std::string &calibration_file)
 

Public 属性

std::map< int, LaserCorrectionlaser_corrections_
 
int num_lasers_
 
bool initialized_
 

详细描述

Calibration class storing entire configuration for the Velodyne

在文件 calibration.h68 行定义.

构造及析构函数说明

◆ Calibration() [1/2]

apollo::drivers::velodyne::Calibration::Calibration ( )
inline

在文件 calibration.h75 行定义.

◆ Calibration() [2/2]

apollo::drivers::velodyne::Calibration::Calibration ( const std::string &  calibration_file)
inlineexplicit

在文件 calibration.h76 行定义.

76 {
77 read(calibration_file);
78 }
void read(const std::string &calibration_file)

成员函数说明

◆ read()

void apollo::drivers::velodyne::Calibration::read ( const std::string &  calibration_file)

在文件 calibration.cc207 行定义.

207 {
208 std::ifstream fin(calibration_file.c_str());
209
210 if (!fin.is_open()) {
211 initialized_ = false;
212 return;
213 }
214
215 initialized_ = true;
216
217 try {
218 YAML::Node doc;
219 fin.close();
220 doc = YAML::LoadFile(calibration_file);
221 doc >> *this;
222 } catch (YAML::Exception& e) {
223 std::cerr << "YAML Exception: " << e.what() << std::endl;
224 initialized_ = false;
225 }
226
227 fin.close();
228}

◆ write()

void apollo::drivers::velodyne::Calibration::write ( const std::string &  calibration_file)

在文件 calibration.cc230 行定义.

230 {
231 std::ofstream fout(calibration_file.c_str());
232 YAML::Emitter out;
233 out << *this;
234 fout << out.c_str();
235 fout.close();
236}

类成员变量说明

◆ initialized_

bool apollo::drivers::velodyne::Calibration::initialized_

在文件 calibration.h72 行定义.

◆ laser_corrections_

std::map<int, LaserCorrection> apollo::drivers::velodyne::Calibration::laser_corrections_

在文件 calibration.h70 行定义.

◆ num_lasers_

int apollo::drivers::velodyne::Calibration::num_lasers_

在文件 calibration.h71 行定义.


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