Autoware.Auto
voxel.hpp
Go to the documentation of this file.
1 // Copyright 2017-2018 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_HPP_
21 #define VOXEL_GRID__VOXEL_HPP_
22 
23 
25 
26 namespace autoware
27 {
28 namespace perception
29 {
30 namespace filters
31 {
33 namespace voxel_grid
34 {
35 
41 template<typename PointT>
42 class VOXEL_GRID_PUBLIC Voxel
43 {
44 public:
45  using point_t = PointT;
48  : m_num_points{0U}
49  {
50  }
52  explicit Voxel(const PointT & pt)
53  : m_num_points(1U),
54  m_centroid(pt)
55  {
56  }
59  explicit operator bool() const
60  {
61  return occupied();
62  }
66  explicit operator PointT() const
67  {
68  return get();
69  }
70 
73  bool occupied() const
74  {
75  return count() > 0U;
76  }
77 
79  void clear()
80  {
81  m_num_points = 0U;
82  }
83 
87  const PointT & get() const
88  {
89  if (!occupied()) {
90  throw std::out_of_range("Voxel: Cannot get point from an unoccupied voxel");
91  }
92  return m_centroid;
93  }
94 
97  uint32_t count() const
98  {
99  return m_num_points;
100  }
101 
102 protected:
106  void set_count(const uint32_t next)
107  {
108  m_num_points = next;
109  }
110 
114  void set_centroid(const PointT & pt)
115  {
116  m_centroid = pt;
117  }
118 
119 private:
120  // TODO(c.ho) static_assert for better error messages
121  uint32_t m_num_points;
122  PointT m_centroid;
123 }; // class Voxel
124 } // namespace voxel_grid
125 } // namespace filters
126 } // namespace perception
127 } // namespace autoware
128 
129 #endif // VOXEL_GRID__VOXEL_HPP_
autoware::perception::filters::voxel_grid::Voxel::occupied
bool occupied() const
Whether or not this object has at least one point associated with it.
Definition: voxel.hpp:73
visibility_control.hpp
autoware::perception::filters::voxel_grid::Voxel::set_centroid
void set_centroid(const PointT &pt)
Sets the centroid. This is to properly encapsulate the member variables. Intended to be used by child...
Definition: voxel.hpp:114
autoware::perception::filters::voxel_grid::Voxel::count
uint32_t count() const
Get the current number of points associated with this voxel.
Definition: voxel.hpp:97
autoware::perception::filters::voxel_grid::Voxel::Voxel
Voxel()
Default constructor, corresponds to an empty/uninitialized voxel.
Definition: voxel.hpp:47
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::perception::filters::voxel_grid::Voxel::get
const PointT & get() const
Emit the centroid.
Definition: voxel.hpp:87
autoware::perception::filters::voxel_grid::Voxel::clear
void clear()
Resets the centroid for incremental updating.
Definition: voxel.hpp:79
autoware::perception::filters::voxel_grid::Voxel::set_count
void set_count(const uint32_t next)
Sets the count. This is to properly encapsulate the member variables. Intended to be used by child cl...
Definition: voxel.hpp:106
autoware::perception::filters::voxel_grid::Voxel::Voxel
Voxel(const PointT &pt)
Point constructor, voxel is assumed to be created based on this point.
Definition: voxel.hpp:52
autoware::perception::filters::voxel_grid::Voxel
A simple class to accumulate points for a voxel and emit the centroid.
Definition: voxel.hpp:42
autoware::perception::filters::voxel_grid::Voxel::point_t
PointT point_t
Definition: voxel.hpp:45