struct mola::LidarOdometry::Parameters

Overview

#include <LidarOdometry.h>

struct Parameters: public mp2p_icp::Parameterizable
{
    // structs

    struct AdaptiveThreshold;
    struct ICP_case;
    struct MapUpdateOptions;
    struct MultipleLidarOptions;
    struct SimpleMapOptions;
    struct TrajectoryOutputOptions;
    struct Visualization;

    // fields

    std::vector<std::regex> lidar_sensor_labels;
    std::optional<std::regex> imu_sensor_label;
    std::optional<std::regex> wheel_odometry_sensor_label;
    std::optional<std::regex> gnns_sensor_label;
    double min_time_between_scans = 0.05;
    double max_sensor_range_filter_coefficient = 0.999;
    double absolute_minimum_sensor_range = 5.0;
    MultipleLidarOptions multiple_lidars;
    MapUpdateOptions local_map_updates;
    double min_icp_goodness = 0.4;
    bool pipeline_profiler_enabled = false;
    bool icp_profiler_enabled = false;
    bool icp_profiler_full_history = false;
    Visualization visualization;
    AdaptiveThreshold adaptive_threshold;
    std::map<AlignKind, ICP_case> icp;
    mola::NavStateFuseParams navstate_fuse_params;
    SimpleMapOptions simplemap;
    TrajectoryOutputOptions estimated_trajectory;
    std::optional<mrpt::math::TTwist3D> initial_twist;
    bool start_active = true;
    uint32_t max_worker_thread_queue_before_drop = 500;
    uint32_t gnns_queue_max_size = 100;
};

Fields

std::vector<std::regex> lidar_sensor_labels

List of sensor labels or regex’s to be matched to input observations to be used as raw lidar observations.

std::optional<std::regex> imu_sensor_label

Sensor labels or regex to be matched to input observations to be used as raw IMU observations.

std::optional<std::regex> wheel_odometry_sensor_label

Sensor labels or regex to be matched to input observations to be used as wheel odometry observations.

std::optional<std::regex> gnns_sensor_label

Sensor labels or regex to be matched to input observations to be used as GNNS (GPS) observations.

double min_time_between_scans = 0.05

Minimum time (seconds) between scans for being attempted to be aligned. Scans faster than this rate will be just silently ignored.

double min_icp_goodness = 0.4

Minimum ICP “goodness” (in the range [0,1]) for a new KeyFrame to be accepted during regular lidar odometry & mapping