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

#include <convert.h>

apollo::drivers::velodyne::Convert 的协作图:

Public 成员函数

 Convert ()=default
 
virtual ~Convert ()=default
 
void init (const Config &velodyne_config)
 
void ConvertPacketsToPointcloud (const std::shared_ptr< VelodyneScan > &scan_msg, std::shared_ptr< PointCloud > point_cloud_out)
 Callback for raw scan messages.
 

详细描述

在文件 convert.h35 行定义.

构造及析构函数说明

◆ Convert()

apollo::drivers::velodyne::Convert::Convert ( )
default

◆ ~Convert()

virtual apollo::drivers::velodyne::Convert::~Convert ( )
virtualdefault

成员函数说明

◆ ConvertPacketsToPointcloud()

void apollo::drivers::velodyne::Convert::ConvertPacketsToPointcloud ( const std::shared_ptr< VelodyneScan > &  scan_msg,
std::shared_ptr< PointCloud point_cloud_out 
)

Callback for raw scan messages.

在文件 convert.cc39 行定义.

41 {
42 ADEBUG << "Convert scan msg seq " << scan_msg->header().sequence_num();
43
44 parser_->GeneratePointcloud(scan_msg, point_cloud);
45
46 if (point_cloud == nullptr || point_cloud->point().empty()) {
47 AERROR << "point cloud has no point";
48 return;
49 }
50
51 if (config_.organized()) {
52 parser_->Order(point_cloud);
53 point_cloud->set_is_dense(false);
54 } else {
55 point_cloud->set_is_dense(true);
56 }
57}
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ init()

void apollo::drivers::velodyne::Convert::init ( const Config velodyne_config)

在文件 convert.cc26 行定义.

26 {
27 config_ = velodyne_config;
28 // we use Beijing time by default
29
30 parser_.reset(VelodyneParserFactory::CreateParser(config_));
31 if (parser_.get() == nullptr) {
32 AFATAL << "Create parser failed.";
33 return;
34 }
35 parser_->setup();
36}
static VelodyneParser * CreateParser(Config config)
#define AFATAL
Definition log.h:45

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