Autoware.Auto
vlp32c_data.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
20 
21 #ifndef VELODYNE_DRIVER__VLP32C_DATA_HPP_
22 #define VELODYNE_DRIVER__VLP32C_DATA_HPP_
23 
26 #include <cmath>
27 #include <utility>
28 
29 namespace autoware
30 {
31 namespace drivers
32 {
33 namespace velodyne_driver
34 {
35 
39 class VELODYNE_DRIVER_PUBLIC VLP32CData
40 {
41 public:
43  static constexpr float32_t FIRE_SEQ_OFFSET_US = 55.296F;
45  static constexpr float32_t FIRE_DURATION_US = 2.304F;
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};
49  using BlockFlag = uint8_t[2U];
50 
51  static_assert(
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.");
55 
56  static constexpr float32_t NUM_SEQUENCES_PER_BLOCK{float32_t(NUM_POINTS_PER_BLOCK) / NUM_LASERS};
57  static constexpr float32_t DISTANCE_RESOLUTION{0.004f};
58 
59  explicit VLP32CData(const float32_t rpm);
60 
67  uint32_t azimuth_offset(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id) const;
68 
75  uint32_t altitude(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id) const;
76 
81  uint16_t seq_id(uint16_t num_blocks, uint32_t pt_id) const noexcept;
82 
84  uint16_t num_blocks_per_revolution() const noexcept;
85 
87  static constexpr float32_t distance_resolution() noexcept
88  {
89  return DISTANCE_RESOLUTION;
90  }
91 
96  std::pair<bool8_t, uint16_t> check_flag(const BlockFlag & flag);
97 
98 private:
103  VELODYNE_DRIVER_LOCAL void init_azimuth_table(const float32_t rpm);
104 
108  VELODYNE_DRIVER_LOCAL void init_altitude_table();
109 
111  std::array<uint32_t, NUM_LASERS> m_azimuth_ind;
113  std::array<uint32_t, NUM_LASERS> m_altitude_ind;
114 
115  uint16_t m_num_blocks_per_revolution;
116 };
117 
118 } // namespace velodyne_driver
119 } // namespace drivers
120 } // namespace autoware
121 
122 #endif // VELODYNE_DRIVER__VLP32C_DATA_HPP_
common.hpp
This file defines a driver for Velodyne LiDARs.
visibility_control.hpp
lidar_integration::FIRE_SEQ_OFFSET_US
static constexpr float32_t FIRE_SEQ_OFFSET_US
full (16 point) fire sequence takes this long to cycle
Definition: vlp16_integration_spoofer.cpp:131
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
lidar_integration::FIRE_DURATION_US
static constexpr float32_t FIRE_DURATION_US
one laser fires for this long
Definition: vlp16_integration_spoofer.cpp:133
autoware::drivers::velodyne_driver::VLP32CData::BlockFlag
uint8_t[2U] BlockFlag
Definition: vlp32c_data.hpp:49
autoware::drivers::velodyne_driver::NUM_POINTS_PER_BLOCK
static constexpr uint16_t NUM_POINTS_PER_BLOCK
number of points stored in a data block
Definition: common.hpp:57
autoware::drivers::velodyne_driver::VLP32CData
Definition: vlp32c_data.hpp:39
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45