#include <FilterDeskew.h>
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 | |
ParameterSource * | attachedSource () |
const ParameterSource * | attachedSource () 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... | |
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:
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).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. Definition at line 39 of file FilterDeskew.h.
FilterDeskew::FilterDeskew | ( | ) |
Definition at line 35 of file FilterDeskew.cpp.
|
overridevirtual |
See docs above for FilterBase.
Implements mp2p_icp_filters::FilterBase.
Definition at line 61 of file FilterDeskew.cpp.
|
overridevirtual |
Parameters:
Implements mp2p_icp_filters::FilterBase.
Definition at line 40 of file FilterDeskew.cpp.
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.
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.
std::string mp2p_icp_filters::FilterDeskew::output_pointcloud_layer |
The output point cloud layer name
Definition at line 70 of file FilterDeskew.h.
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.
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.
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.