21 #ifndef VELODYNE_DRIVER__VLS128_DATA_HPP_ 22 #define VELODYNE_DRIVER__VLS128_DATA_HPP_ 33 namespace velodyne_driver
46 static constexpr
float32_t MAINTENANCE_DURATION1_US = 2.665F;
48 static constexpr uint16_t NUM_GROUPS_PER_SEQ{16U};
49 static constexpr uint16_t NUM_LASERS{128U};
50 static constexpr uint16_t GROUP_SIZE{8U};
54 NUM_GROUPS_PER_SEQ * GROUP_SIZE == NUM_LASERS,
55 "VLS 128 driver has incorrect configuration. " 56 "Check the manual for the group size and number of lasers.");
59 static constexpr
float32_t DISTANCE_RESOLUTION{0.004f};
69 uint32_t azimuth_offset(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id)
const;
77 uint32_t altitude(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id)
const;
83 uint16_t seq_id(uint16_t num_blocks, uint32_t pt_id)
const noexcept;
86 uint16_t num_blocks_per_revolution()
const noexcept;
91 return DISTANCE_RESOLUTION;
98 std::pair<bool8_t, uint16_t> check_flag(
const BlockFlag & flag);
105 VELODYNE_DRIVER_LOCAL
void init_azimuth_table(
const float32_t rpm);
110 VELODYNE_DRIVER_LOCAL
void init_altitude_table();
113 std::array<uint32_t, NUM_LASERS> m_azimuth_ind;
115 std::array<uint32_t, NUM_LASERS> m_altitude_ind;
117 uint16_t m_num_blocks_per_revolution;
124 #endif // VELODYNE_DRIVER__VLS128_DATA_HPP_ Definition: vls128_data.hpp:39
static constexpr float32_t distance_resolution() noexcept
Get distance resolution of VLS128.
Definition: vls128_data.hpp:89
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: vls128_data.hpp:51
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