#include <FilterAdjustTimestamps.h>
Public Member Functions | |
void | load_from_yaml (const mrpt::containers::yaml &c, FilterAdjustTimestamps &parent) |
Public Attributes | |
TimestampAdjustMethod | method = TimestampAdjustMethod::MiddleIsZero |
std::string | pointcloud_layer |
bool | silently_ignore_no_timestamps = false |
double | time_offset = .0 |
Definition at line 58 of file FilterAdjustTimestamps.h.
void FilterAdjustTimestamps::Parameters::load_from_yaml | ( | const mrpt::containers::yaml & | c, |
FilterAdjustTimestamps & | parent | ||
) |
Definition at line 23 of file FilterAdjustTimestamps.cpp.
TimestampAdjustMethod mp2p_icp_filters::FilterAdjustTimestamps::Parameters::method = TimestampAdjustMethod::MiddleIsZero |
The criterion to adjust timestamps.
Definition at line 74 of file FilterAdjustTimestamps.h.
std::string mp2p_icp_filters::FilterAdjustTimestamps::Parameters::pointcloud_layer |
Definition at line 63 of file FilterAdjustTimestamps.h.
bool mp2p_icp_filters::FilterAdjustTimestamps::Parameters::silently_ignore_no_timestamps = false |
Whether to skip throwing an exception if the input layer does not contain timestamps.
Definition at line 68 of file FilterAdjustTimestamps.h.
double mp2p_icp_filters::FilterAdjustTimestamps::Parameters::time_offset = .0 |
Additional time offset, useful when synchronizing several sensors
Definition at line 71 of file FilterAdjustTimestamps.h.