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

#include <driver.h>

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

静态 Public 成员函数

static VelodyneDriverCreateDriver (const std::shared_ptr<::apollo::cyber::Node > &node, const Config &config)
 

详细描述

在文件 driver.h101 行定义.

成员函数说明

◆ CreateDriver()

VelodyneDriver * apollo::drivers::velodyne::VelodyneDriverFactory::CreateDriver ( const std::shared_ptr<::apollo::cyber::Node > &  node,
const Config config 
)
static

在文件 driver.cc232 行定义.

233 {
234 auto new_config = config;
235 if (new_config.prefix_angle() > 35900 || new_config.prefix_angle() < 100) {
236 AWARN << "invalid prefix angle, prefix_angle must be between 100 and 35900";
237 if (new_config.prefix_angle() > 35900) {
238 new_config.set_prefix_angle(35900);
239 } else if (new_config.prefix_angle() < 100) {
240 new_config.set_prefix_angle(100);
241 }
242 }
243 VelodyneDriver* driver = nullptr;
244 switch (config.model()) {
245 case HDL64E_S2: {
246 driver = new Velodyne64Driver(node, config);
247 driver->SetPacketRate(PACKET_RATE_HDL64E_S2);
248 break;
249 }
250 case HDL64E_S3S: {
251 driver = new Velodyne64Driver(node, config);
252 driver->SetPacketRate(PACKET_RATE_HDL64E_S3S);
253 break;
254 }
255 case HDL64E_S3D: {
256 driver = new Velodyne64Driver(node, config);
257 driver->SetPacketRate(PACKET_RATE_HDL64E_S3D);
258 break;
259 }
260 case HDL32E: {
261 driver = new VelodyneDriver(node, config);
262 driver->SetPacketRate(PACKET_RATE_HDL32E);
263 break;
264 }
265 case VLP32C: {
266 driver = new VelodyneDriver(node, config);
267 driver->SetPacketRate(PACKET_RATE_VLP32C);
268 break;
269 }
270 case VLP16: {
271 driver = new VelodyneDriver(node, config);
272 driver->SetPacketRate(PACKET_RATE_VLP16);
273 break;
274 }
275 case VLS128: {
276 driver = new VelodyneDriver(node, config);
277 driver->SetPacketRate(PACKET_RATE_VLS128);
278 break;
279 }
280 default:
281 AERROR << "invalid model, must be 64E_S2|64E_S3S"
282 << "|64E_S3D|VLP16|HDL32E|VLS128";
283 break;
284 }
285 return driver;
286}
#define AERROR
Definition log.h:44
#define AWARN
Definition log.h:43
constexpr double PACKET_RATE_HDL64E_S2
Definition driver.h:38
constexpr double PACKET_RATE_HDL64E_S3D
Definition driver.h:40
constexpr double PACKET_RATE_VLP16
Definition driver.h:36
constexpr double PACKET_RATE_HDL32E
Definition driver.h:37
constexpr double PACKET_RATE_HDL64E_S3S
Definition driver.h:39
constexpr double PACKET_RATE_VLP32C
Definition driver.h:42
constexpr double PACKET_RATE_VLS128
Definition driver.h:41

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