Apollo 10.0
自动驾驶开放平台
apollo::localization::msf::LocalizatonInfo结构体 参考

The data structure to store info of a localization 更多...

#include <visualization_engine.h>

apollo::localization::msf::LocalizatonInfo 的协作图:

Public 成员函数

void set (const Eigen::Translation3d &location, const Eigen::Quaterniond &attitude, const Eigen::Vector3d &std_var, const std::string &description, const double timestamp, const unsigned int frame_id)
 
void set (const Eigen::Translation3d &location, const Eigen::Quaterniond &attitude, const std::string &description, const double timestamp, const unsigned int frame_id)
 
void set (const Eigen::Translation3d &location, const Eigen::Vector3d &std_var, const std::string &description, const double timestamp, const unsigned int frame_id)
 
void set (const Eigen::Translation3d &location, const std::string &description, const double timestamp, const unsigned int frame_id)
 

Public 属性

Eigen::Translation3d location
 
Eigen::Quaterniond attitude
 
Eigen::Affine3d pose
 
Eigen::Vector3d std_var = {0.01, 0.01, 0.01}
 
std::string description
 
double timestamp = 0
 
unsigned int frame_id = 0
 
bool is_valid = false
 
bool is_has_attitude = false
 
bool is_has_std = false
 

详细描述

The data structure to store info of a localization

在文件 visualization_engine.h42 行定义.

成员函数说明

◆ set() [1/4]

void apollo::localization::msf::LocalizatonInfo::set ( const Eigen::Translation3d &  location,
const Eigen::Quaterniond &  attitude,
const Eigen::Vector3d &  std_var,
const std::string &  description,
const double  timestamp,
const unsigned int  frame_id 
)
inline

在文件 visualization_engine.h43 行定义.

46 {
48 this->std_var = std_var;
49 is_has_std = true;
50 }
void set(const Eigen::Translation3d &location, const Eigen::Quaterniond &attitude, const Eigen::Vector3d &std_var, const std::string &description, const double timestamp, const unsigned int frame_id)

◆ set() [2/4]

void apollo::localization::msf::LocalizatonInfo::set ( const Eigen::Translation3d &  location,
const Eigen::Quaterniond &  attitude,
const std::string &  description,
const double  timestamp,
const unsigned int  frame_id 
)
inline

◆ set() [3/4]

void apollo::localization::msf::LocalizatonInfo::set ( const Eigen::Translation3d &  location,
const Eigen::Vector3d &  std_var,
const std::string &  description,
const double  timestamp,
const unsigned int  frame_id 
)
inline

在文件 visualization_engine.h61 行定义.

63 {
65 this->std_var = std_var;
66 is_has_std = true;
67 }

◆ set() [4/4]

void apollo::localization::msf::LocalizatonInfo::set ( const Eigen::Translation3d &  location,
const std::string &  description,
const double  timestamp,
const unsigned int  frame_id 
)
inline

在文件 visualization_engine.h69 行定义.

70 {
71 this->attitude = Eigen::Quaterniond::Identity();
72 this->location = location;
73 this->pose = location * attitude;
75 this->timestamp = timestamp;
76 this->frame_id = frame_id;
77 is_valid = true;
78 }

类成员变量说明

◆ attitude

Eigen::Quaterniond apollo::localization::msf::LocalizatonInfo::attitude

在文件 visualization_engine.h81 行定义.

◆ description

std::string apollo::localization::msf::LocalizatonInfo::description

在文件 visualization_engine.h84 行定义.

◆ frame_id

unsigned int apollo::localization::msf::LocalizatonInfo::frame_id = 0

在文件 visualization_engine.h86 行定义.

◆ is_has_attitude

bool apollo::localization::msf::LocalizatonInfo::is_has_attitude = false

在文件 visualization_engine.h88 行定义.

◆ is_has_std

bool apollo::localization::msf::LocalizatonInfo::is_has_std = false

在文件 visualization_engine.h89 行定义.

◆ is_valid

bool apollo::localization::msf::LocalizatonInfo::is_valid = false

在文件 visualization_engine.h87 行定义.

◆ location

Eigen::Translation3d apollo::localization::msf::LocalizatonInfo::location

在文件 visualization_engine.h80 行定义.

◆ pose

Eigen::Affine3d apollo::localization::msf::LocalizatonInfo::pose

在文件 visualization_engine.h82 行定义.

◆ std_var

Eigen::Vector3d apollo::localization::msf::LocalizatonInfo::std_var = {0.01, 0.01, 0.01}

在文件 visualization_engine.h83 行定义.

83{0.01, 0.01, 0.01};

◆ timestamp

double apollo::localization::msf::LocalizatonInfo::timestamp = 0

在文件 visualization_engine.h85 行定义.


该结构体的文档由以下文件生成: