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

#include <online_localization_expert.h>

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

Public 成员函数

 OnlineLocalizationExpert ()=default
 
 ~OnlineLocalizationExpert ()=default
 
bool Init (const LocalizationIntegParam &param)
 
void AddImu (const ImuData &data)
 
void AddFusionLocalization (const LocalizationEstimate &data)
 
void AddLidarLocalization (const LocalizationEstimate &data)
 
void AddGnssBestPose (const drivers::gnss::GnssBestPose &msg, const MeasureData &data)
 
void GetFusionStatus (MsfStatus *msf_status, MsfSensorMsgStatus *sensor_status, LocalizationIntegStatus *integstatus)
 
void GetGnssStatus (MsfStatus *msf_status)
 

详细描述

在文件 online_localization_expert.h33 行定义.

构造及析构函数说明

◆ OnlineLocalizationExpert()

apollo::localization::msf::OnlineLocalizationExpert::OnlineLocalizationExpert ( )
default

◆ ~OnlineLocalizationExpert()

apollo::localization::msf::OnlineLocalizationExpert::~OnlineLocalizationExpert ( )
default

成员函数说明

◆ AddFusionLocalization()

void apollo::localization::msf::OnlineLocalizationExpert::AddFusionLocalization ( const LocalizationEstimate data)

在文件 online_localization_expert.cc62 行定义.

63 {
64 SetLocalizationStatus(data);
65}

◆ AddGnssBestPose()

void apollo::localization::msf::OnlineLocalizationExpert::AddGnssBestPose ( const drivers::gnss::GnssBestPose msg,
const MeasureData &  data 
)

在文件 online_localization_expert.cc78 行定义.

79 {
80 int gnss_solution_status = static_cast<int>(msg.sol_status());
81 int gnss_position_type = static_cast<int>(msg.sol_type());
82
83 int gnss_status = 0;
84 if (gnss_solution_status != 0) {
85 gnss_status = 93;
86 } else {
87 gnss_status = gnss_position_type;
88 }
89
90 msf_status_mutex_.lock();
91 msf_status_.set_gnsspos_position_type(
92 static_cast<apollo::localization::GnssPositionType>(gnss_status));
93 msf_status_mutex_.unlock();
94
95 latest_gnsspos_timestamp_mutex_.lock();
96 latest_gnsspos_timestamp_ = data.time;
97 latest_gnsspos_timestamp_mutex_.unlock();
98}

◆ AddImu()

void apollo::localization::msf::OnlineLocalizationExpert::AddImu ( const ImuData &  data)

在文件 online_localization_expert.cc55 行定义.

55 {
56 double cur_imu_time = data.measurement_time;
57 CheckImuDelayStatus(cur_imu_time);
58 CheckImuMissingStatus(cur_imu_time);
59 CheckGnssLidarMsfStatus(cur_imu_time);
60}

◆ AddLidarLocalization()

void apollo::localization::msf::OnlineLocalizationExpert::AddLidarLocalization ( const LocalizationEstimate data)

在文件 online_localization_expert.cc67 行定义.

68 {
69 msf_status_mutex_.lock();
70 msf_status_.set_local_lidar_status(data.msf_status().local_lidar_status());
71 msf_status_.set_local_lidar_quality(data.msf_status().local_lidar_quality());
72 msf_status_mutex_.unlock();
73 latest_lidar_timestamp_mutex_.lock();
74 latest_lidar_timestamp_ = data.measurement_time();
75 latest_lidar_timestamp_mutex_.unlock();
76}

◆ GetFusionStatus()

void apollo::localization::msf::OnlineLocalizationExpert::GetFusionStatus ( MsfStatus msf_status,
MsfSensorMsgStatus sensor_status,
LocalizationIntegStatus integstatus 
)

在文件 online_localization_expert.cc427 行定义.

429 {
430 {
431 std::unique_lock<std::mutex> lock(msf_status_mutex_);
432 msf_status->set_local_lidar_consistency(
433 msf_status_.local_lidar_consistency());
434 msf_status->set_gnss_consistency(msf_status_.gnss_consistency());
435 msf_status->set_local_lidar_status(msf_status_.local_lidar_status());
436 msf_status->set_gnsspos_position_type(msf_status_.gnsspos_position_type());
437 msf_status->set_msf_running_status(msf_status_.msf_running_status());
438 msf_status->set_local_lidar_quality(msf_status_.local_lidar_quality());
439 }
440
441 sensor_status->set_imu_delay_status(sensor_status_.imu_delay_status());
442 sensor_status->set_imu_missing_status(sensor_status_.imu_missing_status());
443 sensor_status->set_imu_data_status(sensor_status_.imu_data_status());
444
445 *integ_status = integ_status_;
446}
optional LocalLidarQuality local_lidar_quality
optional LocalLidarConsistency local_lidar_consistency
optional GnssConsistency gnss_consistency
optional LocalLidarStatus local_lidar_status
optional MsfRunningStatus msf_running_status
optional GnssPositionType gnsspos_position_type

◆ GetGnssStatus()

void apollo::localization::msf::OnlineLocalizationExpert::GetGnssStatus ( MsfStatus msf_status)

在文件 online_localization_expert.cc448 行定义.

448 {
449 std::unique_lock<std::mutex> lock(msf_status_mutex_);
450 msf_status->set_gnsspos_position_type(msf_status_.gnsspos_position_type());
451}

◆ Init()

bool apollo::localization::msf::OnlineLocalizationExpert::Init ( const LocalizationIntegParam param)

在文件 online_localization_expert.cc27 行定义.

27 {
28 msf_status_.set_local_lidar_consistency(MSF_LOCAL_LIDAR_CONSISTENCY_03);
29 msf_status_.set_gnss_consistency(MSF_GNSS_CONSISTENCY_03);
30 msf_status_.set_local_lidar_status(MSF_LOCAL_LIDAR_UNDEFINED_STATUS);
31 msf_status_.set_gnsspos_position_type(NONE);
32 msf_status_.set_msf_running_status(MSF_RUNNING_INIT);
33 msf_status_.set_local_lidar_quality(MSF_LOCAL_LIDAR_BAD);
34
35 imu_delay_time_threshold_1_ = param.imu_delay_time_threshold_1;
36 imu_delay_time_threshold_2_ = param.imu_delay_time_threshold_2;
37 imu_delay_time_threshold_3_ = param.imu_delay_time_threshold_3;
38
39 imu_missing_time_threshold_1_ = param.imu_missing_time_threshold_1;
40 imu_missing_time_threshold_2_ = param.imu_missing_time_threshold_2;
41 imu_missing_time_threshold_3_ = param.imu_missing_time_threshold_3;
42
43 bestgnsspose_loss_time_threshold_ = param.bestgnsspose_loss_time_threshold;
44 lidar_loss_time_threshold_ = param.lidar_loss_time_threshold;
45
46 localization_std_x_threshold_1_ = param.localization_std_x_threshold_1;
47 localization_std_y_threshold_1_ = param.localization_std_y_threshold_1;
48
49 localization_std_x_threshold_2_ = param.localization_std_x_threshold_2;
50 localization_std_y_threshold_2_ = param.localization_std_y_threshold_2;
51
52 return true;
53}

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