class mp2p_icp_filters::FilterVoxelSlice
Overview
Takes an input layer of type mrpt::maps::CVoxelMap (Bonxai) and extracts one 2D slice as an occupancy gridmap, taken at a given height (“z”) range of values. That is, each voxel column will be collapsed into a 2D grid cell.
If the output layer already exists, it will be overwritten.
#include <FilterVoxelSlice.h> class FilterVoxelSlice: public mp2p_icp_filters::FilterBase { public: // structs struct Parameters; // fields Parameters params; // methods virtual void initialize_filter(const mrpt::containers::yaml& c); virtual void filter(mp2p_icp::metric_map_t& inOut) const; void initializeFilterBase(const mrpt::containers::yaml& cfg_block); };
Inherited Members
public: // methods virtual void filter(mp2p_icp::metric_map_t& inOut) const = 0; FilterBase& operator = (const FilterBase&); FilterBase& operator = (FilterBase&&);
Fields
Parameters params
Algorithm parameters
Methods
virtual void filter(mp2p_icp::metric_map_t& inOut) const
See docs above for FilterBase.