Public Member Functions | Public Attributes | List of all members
mp2p_icp_filters::FilterDeskew Class Reference

#include <FilterDeskew.h>

Inheritance diagram for mp2p_icp_filters::FilterDeskew:
Inheritance graph
[legend]

Public Member Functions

void filter (mp2p_icp::metric_map_t &inOut) const override
 
 FilterDeskew ()
 
void initialize (const mrpt::containers::yaml &c) override
 
- Public Member Functions inherited from mp2p_icp_filters::FilterBase
 FilterBase ()
 
virtual ~FilterBase ()
 
- Public Member Functions inherited from mp2p_icp::Parameterizable
ParameterSourceattachedSource ()
 
const ParameterSourceattachedSource () const
 
virtual void attachToParameterSource (ParameterSource &source)
 
void checkAllParametersAreRealized () const
 
auto & declaredParameters ()
 
const auto & declaredParameters () const
 
void unrealizeParameters ()
 Mark all non-constant parameters as non-evaluated again. More...
 

Public Attributes

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

Additional Inherited Members

- Protected Member Functions inherited from mp2p_icp::Parameterizable
void parseAndDeclareParameter (const std::string &value, double &target)
 
void parseAndDeclareParameter (const std::string &value, float &target)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
void parseAndDeclareParameter (const std::string &value, uint32_t &target)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 

Detailed Description

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:

Definition at line 39 of file FilterDeskew.h.

Constructor & Destructor Documentation

◆ FilterDeskew()

FilterDeskew::FilterDeskew ( )

Definition at line 35 of file FilterDeskew.cpp.

Member Function Documentation

◆ filter()

void FilterDeskew::filter ( mp2p_icp::metric_map_t inOut) const
overridevirtual

See docs above for FilterBase.

Implements mp2p_icp_filters::FilterBase.

Definition at line 61 of file FilterDeskew.cpp.

◆ initialize()

void FilterDeskew::initialize ( const mrpt::containers::yaml &  c)
overridevirtual

Parameters:

params:
# 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]

Implements mp2p_icp_filters::FilterBase.

Definition at line 40 of file FilterDeskew.cpp.

Member Data Documentation

◆ input_pointcloud_layer

std::string mp2p_icp_filters::FilterDeskew::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.

Definition at line 67 of file FilterDeskew.h.

◆ output_layer_class

std::string mp2p_icp_filters::FilterDeskew::output_layer_class = "mrpt::maps::CPointsMapXYZI"

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

Definition at line 74 of file FilterDeskew.h.

◆ output_pointcloud_layer

std::string mp2p_icp_filters::FilterDeskew::output_pointcloud_layer

The output point cloud layer name

Definition at line 70 of file FilterDeskew.h.

◆ silently_ignore_no_timestamps

bool mp2p_icp_filters::FilterDeskew::silently_ignore_no_timestamps = false

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

Definition at line 79 of file FilterDeskew.h.

◆ skip_deskew

bool mp2p_icp_filters::FilterDeskew::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.

Definition at line 84 of file FilterDeskew.h.

◆ twist

mrpt::math::TTwist3D mp2p_icp_filters::FilterDeskew::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.

Definition at line 90 of file FilterDeskew.h.


The documentation for this class was generated from the following files:
mp2p_icp_filters::FilterDeskew::input_pointcloud_layer
std::string input_pointcloud_layer
Definition: FilterDeskew.h:67
mp2p_icp_filters::FilterDeskew::output_pointcloud_layer
std::string output_pointcloud_layer
Definition: FilterDeskew.h:70


mp2p_icp
Author(s):
autogenerated on Thu Oct 17 2024 02:45:37