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

#include <visualization_manager.h>

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

Public 成员函数

LocalizationMsg interpolate (const double scale, const LocalizationMsg &loc_msg)
 

Public 属性

double timestamp = 0.0
 
double x = 0
 
double y = 0
 
double z = 0
 
double qx = 0.0
 
double qy = 0.0
 
double qz = 0.0
 
double qw = 0.0
 
double std_x = 0
 
double std_y = 0
 
double std_z = 0
 

详细描述

在文件 visualization_manager.h47 行定义.

成员函数说明

◆ interpolate()

LocalizationMsg apollo::localization::msf::LocalizationMsg::interpolate ( const double  scale,
const LocalizationMsg loc_msg 
)
inline

在文件 visualization_manager.h62 行定义.

63 {
65 res.x = this->x * (1 - scale) + loc_msg.x * scale;
66 res.y = this->y * (1 - scale) + loc_msg.y * scale;
67 res.z = this->z * (1 - scale) + loc_msg.z * scale;
68
69 Eigen::Quaterniond quatd1(this->qw, this->qx, this->qy, this->qz);
70 Eigen::Quaterniond quatd2(loc_msg.qw, loc_msg.qx, loc_msg.qy, loc_msg.qz);
71 Eigen::Quaterniond res_quatd = quatd1.slerp(scale, quatd2);
72 res.qx = res_quatd.x();
73 res.qy = res_quatd.y();
74 res.qz = res_quatd.z();
75 res.qw = res_quatd.w();
76
77 res.std_x = this->std_x * (1 - scale) + loc_msg.std_x * scale;
78 res.std_y = this->std_y * (1 - scale) + loc_msg.std_y * scale;
79 res.std_z = this->std_z * (1 - scale) + loc_msg.std_z * scale;
80
81 return res;
82 }

类成员变量说明

◆ qw

double apollo::localization::msf::LocalizationMsg::qw = 0.0

在文件 visualization_manager.h56 行定义.

◆ qx

double apollo::localization::msf::LocalizationMsg::qx = 0.0

在文件 visualization_manager.h53 行定义.

◆ qy

double apollo::localization::msf::LocalizationMsg::qy = 0.0

在文件 visualization_manager.h54 行定义.

◆ qz

double apollo::localization::msf::LocalizationMsg::qz = 0.0

在文件 visualization_manager.h55 行定义.

◆ std_x

double apollo::localization::msf::LocalizationMsg::std_x = 0

在文件 visualization_manager.h58 行定义.

◆ std_y

double apollo::localization::msf::LocalizationMsg::std_y = 0

在文件 visualization_manager.h59 行定义.

◆ std_z

double apollo::localization::msf::LocalizationMsg::std_z = 0

在文件 visualization_manager.h60 行定义.

◆ timestamp

double apollo::localization::msf::LocalizationMsg::timestamp = 0.0

在文件 visualization_manager.h48 行定义.

◆ x

double apollo::localization::msf::LocalizationMsg::x = 0

在文件 visualization_manager.h49 行定义.

◆ y

double apollo::localization::msf::LocalizationMsg::y = 0

在文件 visualization_manager.h50 行定义.

◆ z

double apollo::localization::msf::LocalizationMsg::z = 0

在文件 visualization_manager.h51 行定义.


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