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);
86 const Config &config) {
93 bool Poll(
const std::shared_ptr<VelodyneScan> &scan)
override;
97 bool CheckAngle(
const VelodynePacket &packet);
98 int PollStandardSync(std::shared_ptr<VelodyneScan> scan);
104 const std::shared_ptr<::apollo::cyber::Node> &node,
const Config &config);
uint64_t last_count_
Definition: driver.h:72
std::thread positioning_thread_
Definition: driver.h:75
uint64_t basetime_
Definition: driver.h:70
std::shared_ptr< cyber::Node > node_
Definition: driver_base.h:66
uint32_t last_gps_time_
Definition: driver.h:71
std::unique_ptr< Input > positioning_input_
Definition: driver.h:66
virtual void PollPositioningPacket()
VelodyneDriver(const Config &config)
Definition: driver.h:47
constexpr double PACKET_RATE_HDL64E_S3D
Definition: driver.h:40
constexpr double PACKET_RATE_HDL32E
Definition: driver.h:37
void UpdateGpsTopHour(uint32_t current_time)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void SetBaseTimeFromNmeaTime(NMEATimePtr nmea_time, uint64_t *basetime)
static uint64_t sync_counter
Definition: driver.h:73
constexpr double PACKET_RATE_VLS128
Definition: driver.h:41
constexpr double PACKET_RATE_VLP16
Definition: driver.h:36
constexpr int BLOCKS_PER_PACKET
Definition: driver.h:33
The class which defines the lidar driver .
Definition: driver_base.h:45
std::unique_ptr< Input > input_
Definition: driver.h:65
Defines the CanFrame struct and CanClient interface.
virtual bool Poll(const std::shared_ptr< VelodyneScan > &scan)
VelodyneDriver()
Definition: driver.h:46
constexpr int BLOCK_SIZE
Definition: driver.h:34
std::thread poll_thread_
Definition: driver.h:62
std::shared_ptr< NMEATime > NMEATimePtr
Definition: input.h:46
constexpr double PACKET_RATE_HDL64E_S3S
Definition: driver.h:39
std::shared_ptr< apollo::cyber::Writer< VelodyneScan > > writer_
Definition: driver.h:64
virtual ~VelodyneDriver()
constexpr double PACKET_RATE_VLP32C
Definition: driver.h:42
constexpr double PACKET_RATE_HDL64E_S2
Definition: driver.h:38
Config config_
Definition: driver.h:63
Velodyne64Driver(const Config &config)
Definition: driver.h:84
bool Init() override
Initialize the lidar driver.
VelodyneDriver(const std::shared_ptr< cyber::Node > &node, const Config &config)
Definition: driver.h:48
virtual int PollStandard(std::shared_ptr< VelodyneScan > scan)
double packet_rate_
Definition: driver.h:68
void SetPacketRate(const double packet_rate)
Definition: driver.h:58
Velodyne64Driver(const std::shared_ptr< cyber::Node > &node, const Config &config)
Definition: driver.h:85
std::string topic_
Definition: driver.h:67