Autoware.Auto
vls128_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__VLS128_DATA_HPP_
22 #define VELODYNE_DRIVER__VLS128_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 VLS128Data
40 {
41 public:
43  static constexpr float32_t FIRE_SEQ_OFFSET_US = 53.3F;
45  static constexpr float32_t FIRE_DURATION_US = 2.665F;
46  static constexpr float32_t MAINTENANCE_DURATION1_US = 2.665F;
47 // static constexpr float32_t MAINTENANCE_DURATION2_US = 7.995F;
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};
51  using BlockFlag = uint8_t[2U];
52 
53  static_assert(
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.");
57 
58  static constexpr float32_t NUM_SEQUENCES_PER_BLOCK{float32_t(NUM_POINTS_PER_BLOCK) / NUM_LASERS};
59  static constexpr float32_t DISTANCE_RESOLUTION{0.004f};
60 
61  explicit VLS128Data(const float32_t rpm);
62 
69  uint32_t azimuth_offset(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id) const;
70 
77  uint32_t altitude(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id) const;
78 
83  uint16_t seq_id(uint16_t num_blocks, uint32_t pt_id) const noexcept;
84 
86  uint16_t num_blocks_per_revolution() const noexcept;
87 
89  static constexpr float32_t distance_resolution() noexcept
90  {
91  return DISTANCE_RESOLUTION;
92  }
93 
98  std::pair<bool8_t, uint16_t> check_flag(const BlockFlag & flag);
99 
100 private:
105  VELODYNE_DRIVER_LOCAL void init_azimuth_table(const float32_t rpm);
106 
110  VELODYNE_DRIVER_LOCAL void init_altitude_table();
111 
113  std::array<uint32_t, NUM_LASERS> m_azimuth_ind;
115  std::array<uint32_t, NUM_LASERS> m_altitude_ind;
116 
117  uint16_t m_num_blocks_per_revolution;
118 };
119 
120 } // namespace velodyne_driver
121 } // namespace drivers
122 } // namespace autoware
123 
124 #endif // VELODYNE_DRIVER__VLS128_DATA_HPP_
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