21 #ifndef VELODYNE_DRIVER__VLP16_DATA_HPP_ 22 #define VELODYNE_DRIVER__VLP16_DATA_HPP_ 40 namespace velodyne_driver
51 static constexpr uint16_t NUM_LASERS{16U};
53 static constexpr
float32_t DISTANCE_RESOLUTION{0.002f};
63 uint32_t azimuth_offset(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id)
const;
71 uint32_t altitude(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id)
const;
77 uint16_t seq_id(uint16_t num_blocks, uint32_t pt_id)
const noexcept;
80 uint16_t num_blocks_per_revolution() const noexcept;
90 static constexpr
float32_t distance_resolution() noexcept
92 return DISTANCE_RESOLUTION;
100 VELODYNE_DRIVER_LOCAL
void init_azimuth_table(
const float32_t rpm);
105 VELODYNE_DRIVER_LOCAL
void init_altitude_table();
108 std::array<uint32_t, NUM_POINTS_PER_BLOCK> m_azimuth_ind;
110 std::array<uint32_t, NUM_LASERS> m_altitude_ind;
112 uint16_t m_num_blocks_per_revolution;
118 #endif // VELODYNE_DRIVER__VLP16_DATA_HPP_ static constexpr uint16_t NUM_POINTS_PER_BLOCK
number of points stored in a data block
Definition: common.hpp:57
uint8_t[2U] BlockFlag
Definition: vlp16_data.hpp:54
float float32_t
Definition: types.hpp:36
bool bool8_t
Definition: types.hpp:33
Class implementing VLP16 specific computation and caches.
Definition: vlp16_data.hpp:44
This file defines a driver for Velodyne LiDARs.
static constexpr float32_t FIRE_DURATION_US
one laser fires for this long
Definition: vlp16_integration_spoofer.cpp:133
static constexpr float32_t FIRE_SEQ_OFFSET_US
full (16 point) fire sequence takes this long to cycle
Definition: vlp16_integration_spoofer.cpp:131
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24