Autoware.Auto
vlp16_data.hpp
Go to the documentation of this file.
1 // Copyright 2018-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__VLP16_DATA_HPP_
22 #define VELODYNE_DRIVER__VLP16_DATA_HPP_
23 
26 #include <cmath>
27 #include <utility>
28 
29 namespace autoware
30 {
33 namespace drivers
34 {
40 namespace velodyne_driver
41 {
42 
44 class VELODYNE_DRIVER_PUBLIC VLP16Data
45 {
46 public:
48  static constexpr float32_t FIRE_SEQ_OFFSET_US = 55.296F;
50  static constexpr float32_t FIRE_DURATION_US = 2.304F;
51  static constexpr uint16_t NUM_LASERS{16U};
52  static constexpr float32_t NUM_SEQUENCES_PER_BLOCK{NUM_POINTS_PER_BLOCK / NUM_LASERS};
53  static constexpr float32_t DISTANCE_RESOLUTION{0.002f};
54  using BlockFlag = uint8_t[2U];
55  explicit VLP16Data(const float32_t rpm);
56 
63  uint32_t azimuth_offset(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id) const;
64 
71  uint32_t altitude(uint16_t num_banked_pts, uint32_t block_id, uint32_t pt_id) const;
72 
77  uint16_t seq_id(uint16_t num_blocks, uint32_t pt_id) const noexcept;
78 
80  uint16_t num_blocks_per_revolution() const noexcept;
81 
87  std::pair<bool8_t, uint16_t> check_flag(const BlockFlag & flag);
88 
90  static constexpr float32_t distance_resolution() noexcept
91  {
92  return DISTANCE_RESOLUTION;
93  }
94 
95 private:
100  VELODYNE_DRIVER_LOCAL void init_azimuth_table(const float32_t rpm);
101 
105  VELODYNE_DRIVER_LOCAL void init_altitude_table();
106 
108  std::array<uint32_t, NUM_POINTS_PER_BLOCK> m_azimuth_ind;
110  std::array<uint32_t, NUM_LASERS> m_altitude_ind;
111 
112  uint16_t m_num_blocks_per_revolution;
113 };
114 } // namespace velodyne_driver
115 } // namespace drivers
116 } // namespace autoware
117 
118 #endif // VELODYNE_DRIVER__VLP16_DATA_HPP_
autoware::drivers::velodyne_driver::VLP16Data::BlockFlag
uint8_t[2U] BlockFlag
Definition: vlp16_data.hpp:54
common.hpp
This file defines a driver for Velodyne LiDARs.
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
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::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::VLP16Data
Class implementing VLP16 specific computation and caches.
Definition: vlp16_data.hpp:44
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36