Apollo 10.0
自动驾驶开放平台
apollo::drivers::velodyne::PriSecFusionComponent类 参考

#include <pri_sec_fusion_component.h>

类 apollo::drivers::velodyne::PriSecFusionComponent 继承关系图:
apollo::drivers::velodyne::PriSecFusionComponent 的协作图:

Public 成员函数

bool Init () override
 
bool Proc (const std::shared_ptr< PointCloud > &point_cloud) override
 
- Public 成员函数 继承自 apollo::cyber::Component< M0, M1, M2, M3 >
 Component ()
 
 ~Component () override
 
bool Initialize (const ComponentConfig &config) override
 init the component by protobuf object.
 
bool Process (const std::shared_ptr< M0 > &msg0, const std::shared_ptr< M1 > &msg1, const std::shared_ptr< M2 > &msg2, const std::shared_ptr< M3 > &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_
 

详细描述

在文件 pri_sec_fusion_component.h46 行定义.

成员函数说明

◆ Init()

bool apollo::drivers::velodyne::PriSecFusionComponent::Init ( )
overridevirtual

实现了 apollo::cyber::ComponentBase.

在文件 pri_sec_fusion_component.cc28 行定义.

28 {
29 if (!GetProtoConfig(&conf_)) {
30 AWARN << "Load config failed, config file" << ConfigFilePath();
31 return false;
32 }
33 buffer_ptr_ = apollo::transform::Buffer::Instance();
34
35 fusion_writer_ = node_->CreateWriter<PointCloud>(conf_.fusion_channel());
36
37 for (const auto& channel : conf_.input_channel()) {
38 auto reader = node_->CreateReader<PointCloud>(channel);
39 readers_.emplace_back(reader);
40 }
41 return true;
42}
bool GetProtoConfig(T *config) const
const std::string & ConfigFilePath() const
std::shared_ptr< Node > node_
#define AWARN
Definition log.h:43

◆ Proc()

bool apollo::drivers::velodyne::PriSecFusionComponent::Proc ( const std::shared_ptr< PointCloud > &  point_cloud)
override

在文件 pri_sec_fusion_component.cc44 行定义.

45 {
46 auto target = std::make_shared<PointCloud>(*point_cloud);
47 auto fusion_readers = readers_;
48 auto start_time = Time::Now().ToSecond();
49 while ((Time::Now().ToSecond() - start_time) < conf_.wait_time_s() &&
50 fusion_readers.size() > 0) {
51 for (auto itr = fusion_readers.begin(); itr != fusion_readers.end();) {
52 (*itr)->Observe();
53 if (!(*itr)->Empty()) {
54 auto source = (*itr)->GetLatestObserved();
55 if (conf_.drop_expired_data() && IsExpired(target, source)) {
56 ++itr;
57 } else {
58 Fusion(target, source);
59 itr = fusion_readers.erase(itr);
60 }
61 } else {
62 ++itr;
63 }
64 }
65 std::this_thread::sleep_for(std::chrono::milliseconds(5));
66 }
67 auto diff = Time::Now().ToNanosecond() - target->header().lidar_timestamp();
68 AINFO << "Pointcloud fusion diff: " << diff / 1000000 << "ms";
69 fusion_writer_->Write(target);
70
71 return true;
72}
uint64_t ToNanosecond() const
convert time to nanosecond.
Definition time.cc:83
static Time Now()
get the current time.
Definition time.cc:57
double ToSecond() const
convert time to second.
Definition time.cc:77
#define AINFO
Definition log.h:42

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