21 #ifndef VELODYNE_DRIVER__VLP32C_DATA_HPP_ 22 #define VELODYNE_DRIVER__VLP32C_DATA_HPP_ 33 namespace velodyne_driver
46 static constexpr uint16_t NUM_GROUPS_PER_SEQ{16U};
47 static constexpr uint16_t NUM_LASERS{32U};
48 static constexpr uint16_t GROUP_SIZE{2U};
52 NUM_GROUPS_PER_SEQ * GROUP_SIZE == NUM_LASERS,
53 "VLP32C driver has incorrect configuration. " 54 "Check the manual for the group size and number of lasers.");
57 static constexpr
float32_t DISTANCE_RESOLUTION{0.004f};
67 uint32_t azimuth_offset(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id)
const;
75 uint32_t altitude(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id)
const;
81 uint16_t seq_id(uint16_t num_blocks, uint32_t pt_id)
const noexcept;
84 uint16_t num_blocks_per_revolution()
const noexcept;
89 return DISTANCE_RESOLUTION;
96 std::pair<bool8_t, uint16_t> check_flag(
const BlockFlag & flag);
103 VELODYNE_DRIVER_LOCAL
void init_azimuth_table(
const float32_t rpm);
108 VELODYNE_DRIVER_LOCAL
void init_altitude_table();
111 std::array<uint32_t, NUM_LASERS> m_azimuth_ind;
113 std::array<uint32_t, NUM_LASERS> m_altitude_ind;
115 uint16_t m_num_blocks_per_revolution;
122 #endif // VELODYNE_DRIVER__VLP32C_DATA_HPP_ static constexpr uint16_t NUM_POINTS_PER_BLOCK
number of points stored in a data block
Definition: common.hpp:57
float float32_t
Definition: types.hpp:36
uint8_t[2U] BlockFlag
Definition: vlp32c_data.hpp:49
Definition: vlp32c_data.hpp:39
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 distance_resolution() noexcept
Get distance resolution of VLP32C.
Definition: vlp32c_data.hpp:87
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