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

#include <driver.h>

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

Public 成员函数

 Velodyne64Driver (const Config &config)
 
 Velodyne64Driver (const std::shared_ptr< cyber::Node > &node, const Config &config)
 
 ~Velodyne64Driver ()
 
bool Init () override
 Initialize the lidar driver.
 
bool Poll (const std::shared_ptr< VelodyneScan > &scan) override
 poll the device
 
void DevicePoll ()
 
- Public 成员函数 继承自 apollo::drivers::velodyne::VelodyneDriver
 VelodyneDriver ()
 
 VelodyneDriver (const Config &config)
 
 VelodyneDriver (const std::shared_ptr< cyber::Node > &node, const Config &config)
 
virtual ~VelodyneDriver ()
 
bool Init () override
 Initialize the lidar driver.
 
virtual void PollPositioningPacket ()
 
void SetPacketRate (const double packet_rate)
 
void DevicePoll ()
 
- Public 成员函数 继承自 apollo::drivers::lidar::LidarDriver
 LidarDriver ()
 Constructor
 
 LidarDriver (const std::shared_ptr<::apollo::cyber::Node > &node)
 
virtual ~LidarDriver ()=default
 Destructor
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::drivers::velodyne::VelodyneDriver
virtual int PollStandard (std::shared_ptr< VelodyneScan > scan)
 
bool SetBaseTime ()
 
void SetBaseTimeFromNmeaTime (NMEATimePtr nmea_time, uint64_t *basetime)
 
void UpdateGpsTopHour (uint32_t current_time)
 
- Protected 属性 继承自 apollo::drivers::velodyne::VelodyneDriver
std::thread poll_thread_
 
Config config_
 
std::shared_ptr< apollo::cyber::Writer< VelodyneScan > > writer_
 
std::unique_ptr< Inputinput_ = nullptr
 
std::unique_ptr< Inputpositioning_input_ = nullptr
 
std::string topic_
 
double packet_rate_ = 0.0
 
uint64_t basetime_ = 0
 
uint32_t last_gps_time_ = 0
 
uint64_t last_count_ = 0
 
std::thread positioning_thread_
 
- Protected 属性 继承自 apollo::drivers::lidar::LidarDriver
std::shared_ptr< cyber::Nodenode_
 
- 静态 Protected 属性 继承自 apollo::drivers::velodyne::VelodyneDriver
static uint64_t sync_counter = 0
 

详细描述

在文件 driver.h82 行定义.

构造及析构函数说明

◆ Velodyne64Driver() [1/2]

apollo::drivers::velodyne::Velodyne64Driver::Velodyne64Driver ( const Config config)
inlineexplicit

在文件 driver.h84 行定义.

◆ Velodyne64Driver() [2/2]

apollo::drivers::velodyne::Velodyne64Driver::Velodyne64Driver ( const std::shared_ptr< cyber::Node > &  node,
const Config config 
)
inline

在文件 driver.h85 行定义.

86 {
87 node_ = node;
88 config_ = config;
89 }
std::shared_ptr< cyber::Node > node_
Definition driver_base.h:66

◆ ~Velodyne64Driver()

apollo::drivers::velodyne::Velodyne64Driver::~Velodyne64Driver ( )

在文件 driver64.cc28 行定义.

28 {
29 if (poll_thread_.joinable()) {
30 poll_thread_.join();
31 }
32}

成员函数说明

◆ DevicePoll()

void apollo::drivers::velodyne::Velodyne64Driver::DevicePoll ( )

在文件 driver64.cc133 行定义.

133 {
134 while (!apollo::cyber::IsShutdown()) {
135 // poll device until end of file
136 std::shared_ptr<VelodyneScan> scan = std::make_shared<VelodyneScan>();
137 bool ret = Poll(scan);
138 if (ret) {
139 apollo::common::util::FillHeader("velodyne", scan.get());
140 writer_->Write(scan);
141 } else {
142 AWARN << "device poll failed";
143 }
144 }
145
146 AERROR << "CompVelodyneDriver thread exit";
147}
bool Poll(const std::shared_ptr< VelodyneScan > &scan) override
poll the device
Definition driver64.cc:58
std::shared_ptr< apollo::cyber::Writer< VelodyneScan > > writer_
Definition driver.h:64
#define AERROR
Definition log.h:44
#define AWARN
Definition log.h:43
bool IsShutdown()
Definition state.h:46

◆ Init()

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

Initialize the lidar driver.

返回
If the initialization is successful.

实现了 apollo::drivers::lidar::LidarDriver.

在文件 driver64.cc34 行定义.

34 {
35 const double frequency = config_.rpm() / 60.0; // expected Hz rate
36
37 // default number of packets for each scan is a single revolution
38 // (fractions rounded up)
39 config_.set_npackets(static_cast<int>(ceil(packet_rate_ / frequency)));
40 AINFO << "publishing " << config_.npackets() << " packets per scan";
41
42 input_.reset(new SocketInput());
44
45 if (node_ == NULL) {
46 AERROR << "node is NULL";
47 return false;
48 }
49 writer_ = node_->CreateWriter<VelodyneScan>(config_.scan_channel());
50 poll_thread_ = std::thread(&Velodyne64Driver::DevicePoll, this);
51 return true;
52}
std::unique_ptr< Input > input_
Definition driver.h:65
#define AINFO
Definition log.h:42

◆ Poll()

bool apollo::drivers::velodyne::Velodyne64Driver::Poll ( const std::shared_ptr< VelodyneScan > &  scan)
overridevirtual

poll the device

返回
true unless end of file reached

重载 apollo::drivers::velodyne::VelodyneDriver .

在文件 driver64.cc58 行定义.

58 {
59 // Allocate a new shared pointer for zero-copy sharing with other nodelets.
60 int poll_result =
61 config_.use_sensor_sync() ? PollStandardSync(scan) : PollStandard(scan);
62
63 if (poll_result == SOCKET_TIMEOUT || poll_result == RECEIVE_FAIL) {
64 return false; // poll again
65 }
66
67 if (scan->firing_pkts().empty()) {
68 AINFO << "Get an empty scan from port: " << config_.firing_data_port();
69 return false;
70 }
71
72 // publish message using time of last packet read
73 ADEBUG << "Publishing a full Velodyne scan.";
74 scan->mutable_header()->set_timestamp_sec(cyber::Time().Now().ToSecond());
75 scan->mutable_header()->set_frame_id(config_.frame_id());
76 scan->set_model(config_.model());
77 scan->set_mode(config_.mode());
78 scan->set_basetime(basetime_);
79
80 return true;
81}
virtual int PollStandard(std::shared_ptr< VelodyneScan > scan)
Definition driver.cc:144
#define ADEBUG
Definition log.h:41

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