63 if (poll_result == SOCKET_TIMEOUT || poll_result == RECEIVE_FAIL) {
67 if (scan->firing_pkts().empty()) {
73 ADEBUG <<
"Publishing a full Velodyne scan.";
74 scan->mutable_header()->set_timestamp_sec(
cyber::Time().Now().ToSecond());
87 const unsigned char* raw_ptr = (
const unsigned char*)packet.
data().c_str();
89 uint16_t angle =
static_cast<uint16_t
>(raw_ptr[i *
BLOCK_SIZE + 3] * 256 +
102int Velodyne64Driver::PollStandardSync(std::shared_ptr<VelodyneScan> scan) {
108 VelodynePacket* packet = scan->add_firing_pkts();
109 int rc =
input_->get_firing_data_packet(packet);
113 if (CheckAngle(*packet) &&
136 std::shared_ptr<VelodyneScan> scan = std::make_shared<VelodyneScan>();
137 bool ret =
Poll(scan);
139 apollo::common::util::FillHeader(
"velodyne", scan.get());
142 AWARN <<
"device poll failed";
146 AERROR <<
"CompVelodyneDriver thread exit";
Cyber has builtin time type Time.
std::shared_ptr< cyber::Node > node_
bool Poll(const std::shared_ptr< VelodyneScan > &scan) override
poll the device
bool Init() override
Initialize the lidar driver.
std::unique_ptr< Input > input_
std::shared_ptr< apollo::cyber::Writer< VelodyneScan > > writer_
virtual int PollStandard(std::shared_ptr< VelodyneScan > scan)
Some string util functions.
constexpr int BLOCK_SIZE
Raw Velodyne packet constants and structures.
constexpr int BLOCKS_PER_PACKET
optional int32 firing_data_port
optional string scan_channel
optional int32 prefix_angle
optional bool use_sensor_sync