22#include "modules/drivers/lidar/proto/config.pb.h"
23#include "modules/drivers/lidar/proto/velodyne.pb.h"
24#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
55 virtual bool Poll(
const std::shared_ptr<VelodyneScan> &scan);
64 std::shared_ptr<apollo::cyber::Writer<VelodyneScan>>
writer_;
65 std::unique_ptr<Input>
input_ =
nullptr;
76 virtual int PollStandard(std::shared_ptr<VelodyneScan> scan);
93 bool Poll(
const std::shared_ptr<VelodyneScan> &scan)
override;
98 int PollStandardSync(std::shared_ptr<VelodyneScan> scan);
104 const std::shared_ptr<::apollo::cyber::Node> &node,
const Config &config);
The class which defines the lidar driver .
std::shared_ptr< cyber::Node > node_
Velodyne64Driver(const Config &config)
bool Poll(const std::shared_ptr< VelodyneScan > &scan) override
poll the device
Velodyne64Driver(const std::shared_ptr< cyber::Node > &node, const Config &config)
bool Init() override
Initialize the lidar driver.
static VelodyneDriver * CreateDriver(const std::shared_ptr<::apollo::cyber::Node > &node, const Config &config)
VelodyneDriver(const std::shared_ptr< cyber::Node > &node, const Config &config)
std::unique_ptr< Input > positioning_input_
static uint64_t sync_counter
void SetBaseTimeFromNmeaTime(NMEATimePtr nmea_time, uint64_t *basetime)
std::unique_ptr< Input > input_
virtual void PollPositioningPacket()
VelodyneDriver(const Config &config)
void SetPacketRate(const double packet_rate)
virtual bool Poll(const std::shared_ptr< VelodyneScan > &scan)
poll the device
std::thread positioning_thread_
bool Init() override
Initialize the lidar driver.
virtual ~VelodyneDriver()
std::shared_ptr< apollo::cyber::Writer< VelodyneScan > > writer_
virtual int PollStandard(std::shared_ptr< VelodyneScan > scan)
void UpdateGpsTopHour(uint32_t current_time)
Defines the CanFrame struct and CanClient interface.
constexpr double PACKET_RATE_HDL64E_S2
std::shared_ptr< NMEATime > NMEATimePtr
constexpr double PACKET_RATE_HDL64E_S3D
constexpr int BLOCK_SIZE
Raw Velodyne packet constants and structures.
constexpr double PACKET_RATE_VLP16
constexpr double PACKET_RATE_HDL32E
constexpr double PACKET_RATE_HDL64E_S3S
constexpr double PACKET_RATE_VLP32C
constexpr int BLOCKS_PER_PACKET
constexpr double PACKET_RATE_VLS128