Go to the documentation of this file.
17 #ifndef NDT__NDT_MAP_HPP_
18 #define NDT__NDT_MAP_HPP_
24 #include <sensor_msgs/point_cloud2_iterator.hpp>
28 #include <unordered_map>
36 namespace localization
48 using TimePoint = std::chrono::system_clock::time_point;
55 static constexpr uint32_t kNumConfigPoints = 3U;
73 template<
typename DeserializingMapT>
92 const std::string & frame_id() const noexcept;
100 bool valid() const noexcept;
109 std::
size_t size() const noexcept;
113 typename
VoxelGrid::const_iterator begin() const noexcept;
117 typename
VoxelGrid::const_iterator
end() const noexcept;
120 void clear() noexcept;
125 std::string m_frame_id{};
136 using TimePoint = std::chrono::system_clock::time_point;
168 const std::string & frame_id() const noexcept;
176 bool valid() const noexcept;
185 std::
size_t size() const;
189 typename
VoxelGrid::const_iterator begin() const;
201 void deserialize_from(const sensor_msgs::msg::
PointCloud2 & msg);
204 std::string m_frame_id{};
209 #endif // NDT__NDT_MAP_HPP_
std::vector< VoxelView< Voxel > > VoxelViewVector
Definition: ndt_map.hpp:49
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
NDTGrid< Voxel >::ConfigPoint ConfigPoint
Definition: ndt_map.hpp:51
Eigen::Vector3d Point
Definition: ndt_map.hpp:137
A voxel grid implementation for normal distribution transform.
Definition: ndt_grid.hpp:40
Definition: ndt_voxel.hpp:101
NDTGrid< Voxel >::Grid VoxelGrid
Definition: ndt_map.hpp:139
NDTGrid< Voxel >::ConfigPoint ConfigPoint
Definition: ndt_map.hpp:140
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
std::chrono::system_clock::time_point TimePoint
Definition: ndt_map.hpp:136
NDTGrid< Voxel >::Grid VoxelGrid
Definition: ndt_map.hpp:50
Definition: ndt_map.hpp:42
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
std::vector< VoxelView< Voxel > > VoxelViewVector
Definition: ndt_map.hpp:138
float float32_t
Definition: types.hpp:45
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
std::chrono::system_clock::time_point TimePoint
Definition: ndt_map.hpp:48
Definition: ndt_map.hpp:131
std::unordered_map< uint64_t, VoxelT > Grid
Definition: ndt_grid.hpp:43
std::decay_t< decltype(std::declval< Config >().get_min_point())> ConfigPoint
Definition: ndt_grid.hpp:47
Definition: ndt_voxel.hpp:46
sensor_msgs::msg::PointCloud2 PointCloud2
Definition: filter_node_base.cpp:32
end
Definition: scripts/get_open_port.py:23
Eigen::Vector3d Point
Definition: ndt_map.hpp:47