class mp2p_icp_filters::FilterDeskew

Overview

Builds a new layer with a deskewed (motion compensated) version of an input pointcloud from a moving LIDAR, where points are time-stamped.

Important notes:

  • The time field of each point is assumed to be in seconds since the begining of the scan (e.g. from 0.0 to 0.1 for 10 Hz scans).

  • The input layer must contain a point cloud in the format mrpt::maps::CPointsMapXYZIRT so timestamps are present.

  • If the input layer is of a different type, or the time field is missing, an exception will be thrown by default, unless the option silently_ignore_no_timestamps is set to true, in which case the input cloud will be just moved forward to the output.

#include <FilterDeskew.h>

class FilterDeskew: public mp2p_icp_filters::FilterBase
{
public:
    // fields

    std::string input_pointcloud_layer = mp2p_icp::metric_map_t::PT_LAYER_RAW;
    std::string output_pointcloud_layer;
    std::string output_layer_class = "mrpt::maps::CPointsXYZI";
    bool silently_ignore_no_timestamps = false;
    bool skip_deskew = false;
    mrpt::math::TTwist3D twist;

    // methods

    virtual void initialize(const mrpt::containers::yaml& c);
    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;
    void attachToParameterSource(ParameterSource& source);
    void checkAllParametersAreRealized() const;
    void unrealizeParameters();

Fields

std::string input_pointcloud_layer = mp2p_icp::metric_map_t::PT_LAYER_RAW

An input layer, from which to read input points Points must be already in the vehicle frame.

std::string output_pointcloud_layer

The output point cloud layer name

std::string output_layer_class = "mrpt::maps::CPointsXYZI"

The class name for output layer if it does not exist and needs to be created

bool silently_ignore_no_timestamps = false

Whether to skip throwing an exception if the input layer does not contain timestamps.

bool skip_deskew = false

If enabled (set to true), no “de-skew” will be performed, and the input points will be just copied into the output layer.

mrpt::math::TTwist3D twist

The velocity (linear and angular) of the vehicle in the local vehicle frame. See FilterDeskew::initialize for an example of how to define it via dynamic variables.

Methods

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

Parameters:

params:
  input_pointcloud_layer: 'raw'
  output_pointcloud_layer: 'deskewed'
  # silently_ignore_no_timestamps: false
  # skip_deskew: false  # Can be enabled to bypass deskew
  # These (vx,...wz) are variable names that must be defined via the
  # mp2p_icp::Parameterizable API to update them dynamically.
  twist: [VX,VY,VZ,WX,WY,WZ]
virtual void filter(mp2p_icp::metric_map_t& inOut) const

See docs above for FilterBase.