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

#include <velodyne_convert_component.h>

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

Public 成员函数

bool Init () override
 
bool Proc (const std::shared_ptr< VelodyneScan > &scan_msg) 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_
 

详细描述

在文件 velodyne_convert_component.h42 行定义.

成员函数说明

◆ Init()

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

实现了 apollo::cyber::ComponentBase.

在文件 velodyne_convert_component.cc29 行定义.

29 {
30 Config velodyne_config;
31 if (!GetProtoConfig(&velodyne_config)) {
32 AWARN << "Load config failed, config file" << config_file_path_;
33 return false;
34 }
35
36 conv_.reset(new Convert());
37 conv_->init(velodyne_config);
38 writer_ =
39 node_->CreateWriter<PointCloud>(velodyne_config.convert_channel_name());
40 point_cloud_pool_.reset(new CCObjectPool<PointCloud>(pool_size_));
41 point_cloud_pool_->ConstructAll();
42 for (int i = 0; i < pool_size_; i++) {
43 auto point_cloud = point_cloud_pool_->GetObject();
44 if (point_cloud == nullptr) {
45 AERROR << "fail to getobject, i: " << i;
46 return false;
47 }
48 point_cloud->mutable_point()->Reserve(140000);
49 }
50 AINFO << "Point cloud comp convert init success";
51 return true;
52}
bool GetProtoConfig(T *config) const
std::shared_ptr< Node > node_
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43

◆ Proc()

bool apollo::drivers::velodyne::VelodyneConvertComponent::Proc ( const std::shared_ptr< VelodyneScan > &  scan_msg)
override

在文件 velodyne_convert_component.cc54 行定义.

55 {
56 std::shared_ptr<PointCloud> point_cloud_out = point_cloud_pool_->GetObject();
57 if (point_cloud_out == nullptr) {
58 AWARN << "poin cloud pool return nullptr, will be create new.";
59 point_cloud_out = std::make_shared<PointCloud>();
60 point_cloud_out->mutable_point()->Reserve(140000);
61 }
62 if (point_cloud_out == nullptr) {
63 AWARN << "point cloud out is nullptr";
64 return false;
65 }
66 point_cloud_out->Clear();
67 conv_->ConvertPacketsToPointcloud(scan_msg, point_cloud_out);
68
69 if (point_cloud_out == nullptr || point_cloud_out->point().empty()) {
70 AWARN << "point_cloud_out convert is empty.";
71 return false;
72 }
73 writer_->Write(point_cloud_out);
74 return true;
75}

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