26 #include "modules/drivers/lidar/proto/velodyne.pb.h" 32 static const size_t FIRING_DATA_PACKET_SIZE = 1206;
33 static const size_t POSITIONING_DATA_PACKET_SIZE = 512;
34 static const size_t ETHERNET_HEADER_SIZE = 42;
35 static const int SOCKET_TIMEOUT = -2;
36 static const int RECEIVE_FAIL = -3;
62 virtual int get_firing_data_packet(VelodynePacket* pkt) = 0;
63 virtual int get_positioning_data_packet(NMEATimePtr nmea_time) = 0;
65 virtual void init(
const int& port) {}
68 bool exract_nmea_time_from_packet(NMEATimePtr nmea_time,
69 const uint8_t* bytes);
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
uint16_t mon
Definition: input.h:40
uint16_t sec
Definition: input.h:44
uint16_t hour
Definition: input.h:42
uint16_t min
Definition: input.h:43
std::shared_ptr< NMEATime > NMEATimePtr
Definition: input.h:46
uint16_t day
Definition: input.h:41
uint16_t year
Definition: input.h:39