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(const mrpt::containers::yaml& cfg_block);
    virtual void filter(mp2p_icp::metric_map_t& inOut) const;
};

Inherited Members

public:
    // methods

    virtual void initialize(const mrpt::containers::yaml& cfg_block) = 0;
    virtual void filter(mp2p_icp::metric_map_t& inOut) const = 0;

Fields

Parameters params_

Algorithm parameters

Methods

virtual void initialize(const mrpt::containers::yaml& cfg_block)

Loads, from a YAML configuration block, all the common, and implementation-specific parameters.

virtual void filter(mp2p_icp::metric_map_t& inOut) const

See docs above for FilterBase.