Apollo 10.0
自动驾驶开放平台
apollo::localization::msf::LocalizationInteg类 参考

interface of msf localization 更多...

#include <localization_integ.h>

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

Public 成员函数

 LocalizationInteg ()
 
 ~LocalizationInteg ()
 
common::Status Init (const LocalizationIntegParam &params)
 
void PcdProcess (const drivers::PointCloud &message)
 
void RawImuProcessFlu (const drivers::gnss::Imu &imu_msg)
 
void RawImuProcessRfu (const drivers::gnss::Imu &imu_msg)
 
void RawObservationProcess (const drivers::gnss::EpochObservation &raw_obs_msg)
 
void RawEphemerisProcess (const drivers::gnss::GnssEphemeris &gnss_orbit_msg)
 
void GnssBestPoseProcess (const drivers::gnss::GnssBestPose &bestgnsspos_msg)
 
void GnssHeadingProcess (const drivers::gnss::Heading &gnss_heading_msg)
 
const LocalizationResultGetLastestLidarLocalization () const
 
const LocalizationResultGetLastestIntegLocalization () const
 
const LocalizationResultGetLastestGnssLocalization () const
 

Protected 成员函数

void TransferImuFlu (const drivers::gnss::Imu &imu_msg, ImuData *imu_data)
 
void TransferImuRfu (const drivers::gnss::Imu &imu_msg, ImuData *imu_rfu)
 

详细描述

interface of msf localization

在文件 localization_integ.h52 行定义.

构造及析构函数说明

◆ LocalizationInteg()

apollo::localization::msf::LocalizationInteg::LocalizationInteg ( )

在文件 localization_integ.cc31 行定义.

32 : localization_integ_impl_(new LocalizationIntegImpl()) {}

◆ ~LocalizationInteg()

apollo::localization::msf::LocalizationInteg::~LocalizationInteg ( )

在文件 localization_integ.cc34 行定义.

34 {
35 delete localization_integ_impl_;
36 localization_integ_impl_ = nullptr;
37}

成员函数说明

◆ GetLastestGnssLocalization()

const LocalizationResult & apollo::localization::msf::LocalizationInteg::GetLastestGnssLocalization ( ) const

在文件 localization_integ.cc92 行定义.

93 {
94 return localization_integ_impl_->GetLastestGnssLocalization();
95}
const LocalizationResult & GetLastestGnssLocalization() const

◆ GetLastestIntegLocalization()

const LocalizationResult & apollo::localization::msf::LocalizationInteg::GetLastestIntegLocalization ( ) const

在文件 localization_integ.cc87 行定义.

88 {
89 return localization_integ_impl_->GetLastestIntegLocalization();
90}
const LocalizationResult & GetLastestIntegLocalization() const

◆ GetLastestLidarLocalization()

const LocalizationResult & apollo::localization::msf::LocalizationInteg::GetLastestLidarLocalization ( ) const

在文件 localization_integ.cc82 行定义.

83 {
84 return localization_integ_impl_->GetLastestLidarLocalization();
85}
const LocalizationResult & GetLastestLidarLocalization() const

◆ GnssBestPoseProcess()

void apollo::localization::msf::LocalizationInteg::GnssBestPoseProcess ( const drivers::gnss::GnssBestPose bestgnsspos_msg)

在文件 localization_integ.cc72 行定义.

73 {
74 localization_integ_impl_->GnssBestPoseProcess(bestgnsspos_msg);
75}
void GnssBestPoseProcess(const drivers::gnss::GnssBestPose &bestgnsspos_msg)

◆ GnssHeadingProcess()

void apollo::localization::msf::LocalizationInteg::GnssHeadingProcess ( const drivers::gnss::Heading gnss_heading_msg)

在文件 localization_integ.cc77 行定义.

78 {
79 localization_integ_impl_->GnssHeadingProcess(gnssheading_msg);
80}
void GnssHeadingProcess(const drivers::gnss::Heading &gnssheading_msg)

◆ Init()

Status apollo::localization::msf::LocalizationInteg::Init ( const LocalizationIntegParam params)

在文件 localization_integ.cc39 行定义.

39 {
40 return localization_integ_impl_->Init(params);
41}
common::Status Init(const LocalizationIntegParam &params)

◆ PcdProcess()

void apollo::localization::msf::LocalizationInteg::PcdProcess ( const drivers::PointCloud message)

在文件 localization_integ.cc43 行定义.

43 {
44 LidarFrame lidar_frame;
45 LidarMsgTransfer transfer;
46 transfer.Transfer(message, &lidar_frame);
47 localization_integ_impl_->PcdProcess(lidar_frame);
48}

◆ RawEphemerisProcess()

void apollo::localization::msf::LocalizationInteg::RawEphemerisProcess ( const drivers::gnss::GnssEphemeris gnss_orbit_msg)

在文件 localization_integ.cc67 行定义.

68 {
69 localization_integ_impl_->RawEphemerisProcess(gnss_orbit_msg);
70}
void RawEphemerisProcess(const drivers::gnss::GnssEphemeris &gnss_orbit_msg)

◆ RawImuProcessFlu()

void apollo::localization::msf::LocalizationInteg::RawImuProcessFlu ( const drivers::gnss::Imu imu_msg)

在文件 localization_integ.cc50 行定义.

50 {
51 ImuData imu;
52 TransferImuFlu(imu_msg, &imu);
53 localization_integ_impl_->RawImuProcessRfu(imu);
54}
void TransferImuFlu(const drivers::gnss::Imu &imu_msg, ImuData *imu_data)

◆ RawImuProcessRfu()

void apollo::localization::msf::LocalizationInteg::RawImuProcessRfu ( const drivers::gnss::Imu imu_msg)

在文件 localization_integ.cc56 行定义.

56 {
57 ImuData imu;
58 TransferImuRfu(imu_msg, &imu);
59 localization_integ_impl_->RawImuProcessRfu(imu);
60}
void TransferImuRfu(const drivers::gnss::Imu &imu_msg, ImuData *imu_rfu)

◆ RawObservationProcess()

void apollo::localization::msf::LocalizationInteg::RawObservationProcess ( const drivers::gnss::EpochObservation raw_obs_msg)

在文件 localization_integ.cc62 行定义.

63 {
64 localization_integ_impl_->RawObservationProcess(raw_obs_msg);
65}
void RawObservationProcess(const drivers::gnss::EpochObservation &raw_obs_msg)

◆ TransferImuFlu()

void apollo::localization::msf::LocalizationInteg::TransferImuFlu ( const drivers::gnss::Imu imu_msg,
ImuData *  imu_data 
)
protected

在文件 localization_integ.cc112 行定义.

113 {
114 CHECK_NOTNULL(imu_flu);
115
116 double measurement_time = TimeUtil::Gps2Unix(imu_msg.measurement_time());
117 imu_flu->measurement_time = measurement_time;
118 imu_flu->fb[0] = -imu_msg.linear_acceleration().y() * FLAGS_imu_rate;
119 imu_flu->fb[1] = imu_msg.linear_acceleration().x() * FLAGS_imu_rate;
120 imu_flu->fb[2] = imu_msg.linear_acceleration().z() * FLAGS_imu_rate;
121
122 imu_flu->wibb[0] = -imu_msg.angular_velocity().y() * FLAGS_imu_rate;
123 imu_flu->wibb[1] = imu_msg.angular_velocity().x() * FLAGS_imu_rate;
124 imu_flu->wibb[2] = imu_msg.angular_velocity().z() * FLAGS_imu_rate;
125}
static double Gps2Unix(double gps_time)
Definition time_util.h:37

◆ TransferImuRfu()

void apollo::localization::msf::LocalizationInteg::TransferImuRfu ( const drivers::gnss::Imu imu_msg,
ImuData *  imu_rfu 
)
protected

在文件 localization_integ.cc97 行定义.

98 {
99 CHECK_NOTNULL(imu_rfu);
100
101 double measurement_time = TimeUtil::Gps2Unix(imu_msg.measurement_time());
102 imu_rfu->measurement_time = measurement_time;
103 imu_rfu->fb[0] = imu_msg.linear_acceleration().x() * FLAGS_imu_rate;
104 imu_rfu->fb[1] = imu_msg.linear_acceleration().y() * FLAGS_imu_rate;
105 imu_rfu->fb[2] = imu_msg.linear_acceleration().z() * FLAGS_imu_rate;
106
107 imu_rfu->wibb[0] = imu_msg.angular_velocity().x() * FLAGS_imu_rate;
108 imu_rfu->wibb[1] = imu_msg.angular_velocity().y() * FLAGS_imu_rate;
109 imu_rfu->wibb[2] = imu_msg.angular_velocity().z() * FLAGS_imu_rate;
110}

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