Autoware.Auto
ndt_scan.hpp
Go to the documentation of this file.
1 // Copyright 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 
17 #ifndef NDT__NDT_SCAN_HPP_
18 #define NDT__NDT_SCAN_HPP_
19 
22 #include <sensor_msgs/msg/point_cloud2.hpp>
23 #include <sensor_msgs/point_cloud2_iterator.hpp>
25 #include <Eigen/Core>
26 #include <vector>
27 #include "common/types.hpp"
28 
31 
32 namespace autoware
33 {
34 namespace localization
35 {
36 namespace ndt
37 {
42 template<typename Derived, typename NDTUnit, typename IteratorT>
44 {
45 public:
46  using Point = NDTUnit;
47  using TimePoint = std::chrono::system_clock::time_point;
48 
51  IteratorT begin() const
52  {
53  return this->impl().begin_();
54  }
55 
58  IteratorT end() const
59  {
60  return this->impl().end_();
61  }
62 
64  void clear()
65  {
66  return this->impl().clear_();
67  }
68 
72  {
73  return this->impl().empty_();
74  }
75 
79  void insert(const sensor_msgs::msg::PointCloud2 & msg)
80  {
81  this->impl().insert_(msg);
82  }
83 
86  std::size_t size() const
87  {
88  return this->impl().size_();
89  }
90 
92  {
93  return this->impl().stamp_();
94  }
95 };
96 
99 class NDT_PUBLIC P2DNDTScan : public NDTScanBase<P2DNDTScan,
100  Eigen::Vector3d, std::vector<Eigen::Vector3d>::const_iterator>
101 {
102 public:
103  using Container = std::vector<Eigen::Vector3d>;
104  using iterator = Container::const_iterator;
105 
106  // Make sure the given iterator type in the template is compatible with the used container.
107  // container should have `iterator` type/alias defined.
108  static_assert(
109  std::is_same<decltype(std::declval<NDTScanBase>().begin()), iterator>::value,
110  "P2DNDTScan: The iterator type parameter should match the "
111  "iterator of the container.");
112 
118  const sensor_msgs::msg::PointCloud2 & msg,
119  std::size_t capacity)
120  {
121  m_points.reserve(capacity);
122  insert_(msg);
123  }
124 
125  // Scans should be moved rather than being copied.
126  P2DNDTScan(const P2DNDTScan &) = delete;
127  P2DNDTScan & operator=(const P2DNDTScan &) = delete;
128 
129  // Explicitly declaring to default is needed since we explicitly deleted the copy methods.
130  P2DNDTScan(P2DNDTScan &&) = default;
131  P2DNDTScan & operator=(P2DNDTScan &&) = default;
132 
136  explicit P2DNDTScan(std::size_t capacity)
137  {
138  m_points.reserve(capacity);
139  }
140 
144  void insert_(const sensor_msgs::msg::PointCloud2 & msg)
145  {
146  if (!m_points.empty()) {
147  m_points.clear();
148  }
149 
150  m_stamp = ::time_utils::from_message(msg.header.stamp);
151 
152  constexpr auto container_full_error = "received a lidar scan with more points than the "
153  "ndt scan representation can contain. Please re-configure the scan"
154  "representation accordingly.";
155 
156  if (msg.width > m_points.capacity()) {
157  throw std::length_error(container_full_error);
158  }
159 
160  // TODO(yunus.caliskan): Can we avoid copying and use PointCloud2 directly? #102
161  // Also validate map?
162  sensor_msgs::PointCloud2ConstIterator<float32_t> x_it(msg, "x");
163  sensor_msgs::PointCloud2ConstIterator<float32_t> y_it(msg, "y");
164  sensor_msgs::PointCloud2ConstIterator<float32_t> z_it(msg, "z");
165 
166  while (x_it != x_it.end() &&
167  y_it != y_it.end() &&
168  z_it != z_it.end())
169  {
170  if (m_points.size() == m_points.capacity()) {
171  throw std::length_error(container_full_error);
172  }
173  m_points.emplace_back(*x_it, *y_it, *z_it);
174  ++x_it;
175  ++y_it;
176  ++z_it;
177  }
178  }
179 
182  iterator begin_() const
183  {
184  return m_points.cbegin();
185  }
186 
189  iterator end_() const
190  {
191  return m_points.cend();
192  }
193 
197  {
198  return m_points.empty();
199  }
200 
202  void clear_()
203  {
204  m_points.clear();
205  }
206 
209  std::size_t size_() const
210  {
211  return m_points.size();
212  }
213 
215  {
216  return m_stamp;
217  }
218 
219 private:
220  Container m_points;
221  NDTScanBase::TimePoint m_stamp{};
222 };
223 
224 } // namespace ndt
225 } // namespace localization
226 } // namespace autoware
227 
228 #endif // NDT__NDT_SCAN_HPP_
autoware::localization::ndt::NDTScanBase::stamp
TimePoint stamp()
Definition: ndt_scan.hpp:91
autoware::localization::ndt::P2DNDTScan::insert_
void insert_(const sensor_msgs::msg::PointCloud2 &msg)
Definition: ndt_scan.hpp:144
autoware::localization::ndt::NDTScanBase::end
IteratorT end() const
Definition: ndt_scan.hpp:58
autoware::localization::ndt::P2DNDTScan::P2DNDTScan
P2DNDTScan(std::size_t capacity)
Definition: ndt_scan.hpp:136
types.hpp
This file includes common type definition.
autoware::localization::ndt::NDTScanBase::empty
bool8_t empty()
Definition: ndt_scan.hpp:71
autoware::localization::ndt::NDTScanBase::clear
void clear()
Clear the states and the internal cache of the scan.
Definition: ndt_scan.hpp:64
autoware::localization::ndt::P2DNDTScan::clear_
void clear_()
Clear the states and the internal cache of the scan.
Definition: ndt_scan.hpp:202
autoware::localization::ndt::P2DNDTScan::end_
iterator end_() const
Definition: ndt_scan.hpp:189
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
autoware::localization::ndt::P2DNDTScan::empty_
bool8_t empty_()
Definition: ndt_scan.hpp:196
autoware::localization::ndt::P2DNDTScan::P2DNDTScan
P2DNDTScan(const sensor_msgs::msg::PointCloud2 &msg, std::size_t capacity)
Definition: ndt_scan.hpp:117
autoware::localization::ndt::NDTScanBase< P2DNDTScan, Eigen::Vector3d, std::vector< Eigen::Vector3d >::const_iterator >::Point
Eigen::Vector3d Point
Definition: ndt_scan.hpp:46
autoware::localization::ndt::NDTScanBase
Definition: ndt_scan.hpp:43
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::P2DNDTScan
Definition: ndt_scan.hpp:99
autoware::common::helper_functions::crtp::impl
const Derived & impl() const
Definition: crtp.hpp:32
autoware::common::helper_functions::crtp
Definition: crtp.hpp:29
autoware::localization::ndt::NDTScanBase::size
std::size_t size() const
Definition: ndt_scan.hpp:86
autoware::localization::ndt::P2DNDTScan::begin_
iterator begin_() const
Definition: ndt_scan.hpp:182
time_utils::from_message
TIME_UTILS_PUBLIC std::chrono::system_clock::time_point from_message(builtin_interfaces::msg::Time t) noexcept
Convert from std::chrono::time_point from time message.
Definition: time_utils.cpp:84
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
crtp.hpp
This file includes common helper functions.
visibility_control.hpp
time_utils.hpp
autoware::localization::ndt::NDTScanBase::insert
void insert(const sensor_msgs::msg::PointCloud2 &msg)
Definition: ndt_scan.hpp:79
autoware::localization::ndt::P2DNDTScan::iterator
Container::const_iterator iterator
Definition: ndt_scan.hpp:104
autoware::localization::ndt::NDTScanBase::begin
IteratorT begin() const
Definition: ndt_scan.hpp:51
autoware::localization::ndt::P2DNDTScan::size_
std::size_t size_() const
Definition: ndt_scan.hpp:209
autoware::localization::ndt::NDTScanBase< P2DNDTScan, Eigen::Vector3d, std::vector< Eigen::Vector3d >::const_iterator >::TimePoint
std::chrono::system_clock::time_point TimePoint
Definition: ndt_scan.hpp:47
autoware::localization::ndt::P2DNDTScan::stamp_
TimePoint stamp_()
Definition: ndt_scan.hpp:214
autoware::localization::ndt::P2DNDTScan::Container
std::vector< Eigen::Vector3d > Container
Definition: ndt_scan.hpp:103