Go to the documentation of this file.
17 #ifndef NDT__NDT_SCAN_HPP_
18 #define NDT__NDT_SCAN_HPP_
22 #include <sensor_msgs/msg/point_cloud2.hpp>
23 #include <sensor_msgs/point_cloud2_iterator.hpp>
34 namespace localization
42 template<
typename Derived,
typename NDTUnit,
typename IteratorT>
47 using TimePoint = std::chrono::system_clock::time_point;
53 return this->
impl().begin_();
60 return this->
impl().end_();
66 return this->
impl().clear_();
73 return this->
impl().empty_();
79 void insert(
const sensor_msgs::msg::PointCloud2 & msg)
81 this->
impl().insert_(msg);
88 return this->
impl().size_();
93 return this->
impl().stamp_();
100 Eigen::Vector3d, std::vector<Eigen::Vector3d>::const_iterator>
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.");
118 const sensor_msgs::msg::PointCloud2 & msg,
119 std::size_t capacity)
121 m_points.reserve(capacity);
138 m_points.reserve(capacity);
144 void insert_(
const sensor_msgs::msg::PointCloud2 & msg)
146 if (!m_points.empty()) {
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.";
156 if (msg.width > m_points.capacity()) {
157 throw std::length_error(container_full_error);
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");
166 while (x_it != x_it.end() &&
167 y_it != y_it.end() &&
170 if (m_points.size() == m_points.capacity()) {
171 throw std::length_error(container_full_error);
173 m_points.emplace_back(*x_it, *y_it, *z_it);
184 return m_points.cbegin();
191 return m_points.cend();
198 return m_points.empty();
211 return m_points.size();
228 #endif // NDT__NDT_SCAN_HPP_
TimePoint stamp()
Definition: ndt_scan.hpp:91
void insert_(const sensor_msgs::msg::PointCloud2 &msg)
Definition: ndt_scan.hpp:144
IteratorT end() const
Definition: ndt_scan.hpp:58
P2DNDTScan(std::size_t capacity)
Definition: ndt_scan.hpp:136
This file includes common type definition.
bool8_t empty()
Definition: ndt_scan.hpp:71
void clear()
Clear the states and the internal cache of the scan.
Definition: ndt_scan.hpp:64
void clear_()
Clear the states and the internal cache of the scan.
Definition: ndt_scan.hpp:202
iterator end_() const
Definition: ndt_scan.hpp:189
bool bool8_t
Definition: types.hpp:33
bool8_t empty_()
Definition: ndt_scan.hpp:196
P2DNDTScan(const sensor_msgs::msg::PointCloud2 &msg, std::size_t capacity)
Definition: ndt_scan.hpp:117
Eigen::Vector3d Point
Definition: ndt_scan.hpp:46
Definition: ndt_scan.hpp:43
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: ndt_scan.hpp:99
const Derived & impl() const
Definition: crtp.hpp:32
std::size_t size() const
Definition: ndt_scan.hpp:86
iterator begin_() const
Definition: ndt_scan.hpp:182
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
float float32_t
Definition: types.hpp:36
This file includes common helper functions.
void insert(const sensor_msgs::msg::PointCloud2 &msg)
Definition: ndt_scan.hpp:79
Container::const_iterator iterator
Definition: ndt_scan.hpp:104
IteratorT begin() const
Definition: ndt_scan.hpp:51
std::size_t size_() const
Definition: ndt_scan.hpp:209
std::chrono::system_clock::time_point TimePoint
Definition: ndt_scan.hpp:47
TimePoint stamp_()
Definition: ndt_scan.hpp:214
std::vector< Eigen::Vector3d > Container
Definition: ndt_scan.hpp:103