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

#include <velodyne_parser.h>

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

静态 Public 成员函数

static VelodyneParserCreateParser (Config config)
 

详细描述

在文件 velodyne_parser.h375 行定义.

成员函数说明

◆ CreateParser()

VelodyneParser * apollo::drivers::velodyne::VelodyneParserFactory::CreateParser ( Config  config)
static

在文件 velodyne_parser.cc203 行定义.

203 {
204 Config config = source_config;
205 if (config.model() == VLP16) {
206 config.set_calibration_online(false);
207 return new Velodyne16Parser(config);
208 } else if (config.model() == HDL32E || config.model() == VLP32C) {
209 config.set_calibration_online(false);
210 return new Velodyne32Parser(config);
211 } else if (config.model() == HDL64E_S3S || config.model() == HDL64E_S3D ||
212 config.model() == HDL64E_S2) {
213 return new Velodyne64Parser(config);
214 } else if (config.model() == VLS128) {
215 return new Velodyne128Parser(config);
216 } else {
217 AERROR << "invalid model, must be 64E_S2|64E_S3S"
218 << "|64E_S3D_STRONGEST|64E_S3D_LAST|64E_S3D_DUAL|HDL32E|VLP16";
219 return nullptr;
220 }
221}
#define AERROR
Definition log.h:44

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