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

#include <msf_localization_component.h>

类 apollo::localization::MSFLocalizationComponent 继承关系图:
apollo::localization::MSFLocalizationComponent 的协作图:

Public 成员函数

 MSFLocalizationComponent ()
 
 ~MSFLocalizationComponent ()=default
 
bool Init () override
 
bool Proc (const std::shared_ptr< drivers::gnss::Imu > &imu_msg) override
 
- Public 成员函数 继承自 apollo::cyber::Component< drivers::gnss::Imu >
 Component ()
 
 ~Component () override
 
bool Initialize (const ComponentConfig &config) override
 init the component by protobuf object.
 
bool Process (const std::shared_ptr< drivers::gnss::Imu > &msg0, const std::shared_ptr< NullType > &msg1, const std::shared_ptr< NullType > &msg2, const std::shared_ptr< NullType > &msg3)
 
- Public 成员函数 继承自 apollo::cyber::ComponentBase
virtual ~ComponentBase ()
 
virtual bool Initialize (const TimerComponentConfig &config)
 
virtual void Shutdown ()
 
template<typename T >
bool GetProtoConfig (T *config) const
 

额外继承的成员函数

- Public 类型 继承自 apollo::cyber::ComponentBase
template<typename M >
using Reader = cyber::Reader< M >
 
- Protected 成员函数 继承自 apollo::cyber::ComponentBase
virtual void Clear ()
 
const std::string & ConfigFilePath () const
 
void LoadConfigFiles (const ComponentConfig &config)
 
void LoadConfigFiles (const TimerComponentConfig &config)
 
- Protected 属性 继承自 apollo::cyber::ComponentBase
std::atomic< bool > is_shutdown_ = {false}
 
std::shared_ptr< Nodenode_ = nullptr
 
std::string config_file_path_ = ""
 
std::vector< std::shared_ptr< ReaderBase > > readers_
 

详细描述

在文件 msf_localization_component.h41 行定义.

构造及析构函数说明

◆ MSFLocalizationComponent()

apollo::localization::MSFLocalizationComponent::MSFLocalizationComponent ( )

在文件 msf_localization_component.cc30 行定义.

30{}

◆ ~MSFLocalizationComponent()

apollo::localization::MSFLocalizationComponent::~MSFLocalizationComponent ( )
default

成员函数说明

◆ Init()

bool apollo::localization::MSFLocalizationComponent::Init ( )
overridevirtual

实现了 apollo::cyber::ComponentBase.

在文件 msf_localization_component.cc32 行定义.

32 {
33 publisher_.reset(new LocalizationMsgPublisher(this->node_));
34
35 if (!InitConfig()) {
36 AERROR << "Init Config failed.";
37 return false;
38 }
39
40 if (!InitIO()) {
41 AERROR << "Init IO failed.";
42 return false;
43 }
44
45 return true;
46}
std::shared_ptr< Node > node_
#define AERROR
Definition log.h:44

◆ Proc()

bool apollo::localization::MSFLocalizationComponent::Proc ( const std::shared_ptr< drivers::gnss::Imu > &  imu_msg)
override

在文件 msf_localization_component.cc103 行定义.

104 {
105 localization_.OnRawImuCache(imu_msg);
106 return true;
107}
void OnRawImuCache(const std::shared_ptr< drivers::gnss::Imu > &imu_msg)

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