20 #ifndef VOXEL_GRID_NODES__ALGORITHM__VOXEL_CLOUD_BASE_HPP_ 21 #define VOXEL_GRID_NODES__ALGORITHM__VOXEL_CLOUD_BASE_HPP_ 23 #include <sensor_msgs/msg/point_cloud2.hpp> 34 namespace voxel_grid_nodes
49 virtual void insert(
const sensor_msgs::msg::PointCloud2 & msg) = 0;
54 virtual const sensor_msgs::msg::PointCloud2 &
get() = 0;
60 uint32_t m_point_cloud_idx{0};
68 #endif // VOXEL_GRID_NODES__ALGORITHM__VOXEL_CLOUD_BASE_HPP_ This file defines the voxel grid data structure for downsampling point clouds.
A pure interface meant for dynamically dispatching to different voxel grid instances at runtime...
Definition: voxel_cloud_base.hpp:42
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24