class mp2p_icp_filters::FilterAdjustTimestamps
Overview
Modifies the per-point timestamps of a map layer according to one of a set of criteria (see TimestampAdjustMethod).
An optional time offset to be added on top of that adjustment is available via Parameters::time_offset
#include <FilterAdjustTimestamps.h> class FilterAdjustTimestamps: public mp2p_icp_filters::FilterBase { public: // structs struct Parameters; // fields Parameters params; std::string name; // methods void initialize(const mrpt::containers::yaml& cfg_block); virtual void initialize_filter(const mrpt::containers::yaml& c); virtual void filter(mp2p_icp::metric_map_t& inOut) const; };
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
std::string name
If not empty, it will be used instead of class name in Logger and Profiler. This is loaded from the name key in the YAML configuration block.
Methods
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.