Autoware.Auto
voxel_grid.hpp
Go to the documentation of this file.
1 // Copyright 2017-2019 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 
19 
20 #ifndef VOXEL_GRID__VOXEL_GRID_HPP_
21 #define VOXEL_GRID__VOXEL_GRID_HPP_
22 
23 #include <voxel_grid/config.hpp>
24 #include <voxel_grid/voxels.hpp>
25 #include <common/types.hpp>
26 #include <forward_list>
27 #include <unordered_map>
28 
30 
31 namespace autoware
32 {
33 namespace perception
34 {
35 namespace filters
36 {
37 namespace voxel_grid
38 {
39 
43 template<typename VoxelT>
44 class VOXEL_GRID_PUBLIC VoxelGrid
45 {
46  using Grid = std::unordered_map<uint64_t, VoxelT>;
47  using IT = typename Grid::const_iterator;
48  using OutputQueue = std::forward_list<IT>;
49  // TODO(c.ho) static assert for better error messages
50 
51 public:
54  explicit VoxelGrid(const Config & cfg)
55  : m_config(cfg),
56  m_map(m_config.get_capacity()),
57  m_output_pool(m_config.get_capacity()),
58  m_output(m_output_pool.get_allocator()),
59  m_new_voxels_called(false),
60  m_last_output_begin(m_output.end())
61  {
62  }
63 
64  using point_t = typename VoxelT::point_t;
67  void insert(const point_t & pt)
68  {
69  // Get voxel
70  const uint64_t idx = m_config.index(pt);
71  // Check capacity if it would be a new voxel
72  if (m_map.end() == m_map.find(idx)) {
73  if (capacity() <= size()) {
74  throw std::length_error{"VoxelGrid: insertion would overrun capacity"};
75  }
76  }
77  // TODO(c.ho) #2023 adding a new node allocates memory...
78  VoxelT & vx = m_map[idx];
79  // Add to new queue if newly activated, set up any stateful information
80  if (!vx.occupied()) {
81  // Set hint here, rationale:
82  // Using some conditional constructor would require C++17 (my preferred solution)
83  // In addition, doing the voxel centroid calculation for every point is wasted work
84  // I in general agree that an `init` or `configure` method is poor style, but in this case
85  // The details of the voxel should be mostly hidden from the user
86  //lint -e{523} NOLINT This is to support multiple voxel implementations, see above
87  vx.configure(m_config, idx);
88  // TODO(c.ho) clean up logic
89  // Add to output queue
90  const auto it = m_output_pool.begin();
91  *it = m_map.find(idx);
92  m_output.splice_after(m_output.cbefore_begin(), m_output_pool, m_output_pool.before_begin());
93  if (m_new_voxels_called) {
94  m_last_output_begin = m_output.begin();
95  m_new_voxels_called = false;
96  }
97  }
98  // Add observation to voxel
99  vx.add_observation(pt);
100  }
105  template<typename IT>
106  void insert(const IT begin, const IT end)
107  {
108  for (IT it = begin; it != end; ++it) {
109  insert(*it);
110  }
111  }
112  // TODO(c.ho) operator[]? centroid(uint64_t) out here?
113 
124  const OutputQueue & new_voxels()
125  {
126  // Remove old outputs and put it into the pool
127  m_output_pool.splice_after(
128  m_output_pool.cbefore_begin(),
129  m_output,
130  m_last_output_begin,
131  m_output.end());
132  m_new_voxels_called = true;
133  m_last_output_begin = m_output.before_begin();
134  return m_output;
135  }
136 
139  IT begin() const
140  {
141  return cbegin();
142  }
145  IT cbegin() const
146  {
147  return m_map.cbegin();
148  }
151  IT end() const
152  {
153  return cend();
154  }
157  IT cend() const
158  {
159  return m_map.cend();
160  }
162  void clear()
163  {
164  // TODO(c.ho) clear deallocates nodes #2023
165  m_output_pool.splice_after(m_output_pool.before_begin(), m_output);
166  m_new_voxels_called = false;
167  m_last_output_begin = m_output.end();
168  m_map.clear();
169  }
171  std::size_t size() const
172  {
173  return m_map.size();
174  }
177  std::size_t capacity() const
178  {
179  return m_config.get_capacity();
180  }
183  bool8_t empty() const
184  {
185  return m_map.empty();
186  }
187 
188 private:
189  const Config m_config;
190  Grid m_map;
191  // Mechanisms to support output queueing in static memory
192  OutputQueue m_output_pool;
193  OutputQueue m_output;
194  bool8_t m_new_voxels_called;
195  typename OutputQueue::iterator m_last_output_begin;
196 }; // class VoxelGrid
197 
198 } // namespace voxel_grid
199 } // namespace filters
200 } // namespace perception
201 } // namespace autoware
202 
203 #endif // VOXEL_GRID__VOXEL_GRID_HPP_
autoware::perception::filters::voxel_grid::VoxelGrid< autoware::perception::filters::voxel_grid::CentroidVoxel< autoware::common::types::PointXYZIF > >::point_t
typename autoware::perception::filters::voxel_grid::CentroidVoxel< autoware::common::types::PointXYZIF > ::point_t point_t
Definition: voxel_grid.hpp:64
voxels.hpp
This file defines children and specializations of the Voxel class.
autoware::perception::filters::voxel_grid::VoxelGrid::size
std::size_t size() const
Returns the current size of the voxel grid.
Definition: voxel_grid.hpp:171
autoware::perception::filters::voxel_grid::VoxelGrid::cbegin
IT cbegin() const
Returns an iterator to the first element of the voxel grid.
Definition: voxel_grid.hpp:145
types.hpp
This file includes common type definition.
config.hpp
This file defines the configuration class for the voxel grid data structure.
autoware::perception::filters::voxel_grid::VoxelGrid::cend
IT cend() const
Returns an iterator to one past the last element of the voxel grid.
Definition: voxel_grid.hpp:157
autoware::perception::filters::voxel_grid::VoxelGrid::end
IT end() const
Returns an iterator to one past the last element of the voxel grid.
Definition: voxel_grid.hpp:151
autoware::perception::filters::voxel_grid::VoxelGrid::VoxelGrid
VoxelGrid(const Config &cfg)
Constructor.
Definition: voxel_grid.hpp:54
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::perception::filters::voxel_grid::VoxelGrid::insert
void insert(const point_t &pt)
Inserts a point into the voxel grid, may result in new voxels being activated.
Definition: voxel_grid.hpp:67
autoware::perception::filters::voxel_grid::Config
A configuration class for the VoxelGrid data structure, also includes some helper functionality for c...
Definition: perception/filters/voxel_grid/include/voxel_grid/config.hpp:52
autoware::perception::filters::voxel_grid::VoxelGrid::empty
bool8_t empty() const
Whether the voxel grid is empty.
Definition: voxel_grid.hpp:183
autoware::perception::filters::voxel_grid::VoxelGrid::new_voxels
const OutputQueue & new_voxels()
Return a list of iterators pointing to newly activated voxels. Voxels will be removed from queue duri...
Definition: voxel_grid.hpp:124
autoware::perception::filters::voxel_grid::VoxelGrid::begin
IT begin() const
Returns an iterator to the first element of the voxel grid.
Definition: voxel_grid.hpp:139
autoware::perception::filters::voxel_grid::VoxelGrid::clear
void clear()
Resets the state of the voxel grid.
Definition: voxel_grid.hpp:162
autoware::perception::filters::voxel_grid::VoxelGrid::insert
void insert(const IT begin, const IT end)
Inserts many points into the voxel grid, dispatches to the core insert method.
Definition: voxel_grid.hpp:106
get_open_port.end
end
Definition: scripts/get_open_port.py:23
autoware::perception::filters::voxel_grid::VoxelGrid::capacity
std::size_t capacity() const
Returns the preallocated capacity of the voxel grid.
Definition: voxel_grid.hpp:177
autoware::perception::filters::voxel_grid::VoxelGrid
A voxel grid data structure for downsampling point clouds.
Definition: voxel_grid.hpp:44