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

#include <convert.h>

apollo::drivers::lslidar::parser::Convert 的协作图:

Public 成员函数

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

详细描述

在文件 convert.h38 行定义.

构造及析构函数说明

◆ Convert()

apollo::drivers::lslidar::parser::Convert::Convert ( )
default

◆ ~Convert()

virtual apollo::drivers::lslidar::parser::Convert::~Convert ( )
virtualdefault

成员函数说明

◆ ConvertPacketsToPointcloud()

void apollo::drivers::lslidar::parser::Convert::ConvertPacketsToPointcloud ( const std::shared_ptr< apollo::drivers::lslidar::LslidarScan > &  scan_msg,
std::shared_ptr< apollo::drivers::PointCloud point_cloud_out 
)

Callback for raw scan messages.

在文件 convert.cc41 行定义.

43 {
44 AINFO_EVERY(100) << "Converting scan msg seq "
45 << scan_msg->header().sequence_num();
46
47 parser_->GeneratePointcloud(scan_msg, point_cloud);
48
49 if (point_cloud == nullptr || point_cloud->point().empty()) {
50 AERROR << "point cloud has no point";
51 return;
52 }
53
54 parser_->Order(point_cloud);
55 point_cloud->set_is_dense(false);
56}
#define AINFO_EVERY(freq)
Definition log.h:82
#define AERROR
Definition log.h:44

◆ init()

void apollo::drivers::lslidar::parser::Convert::init ( const Config lslidar_config)

在文件 convert.cc27 行定义.

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

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