class mola::state_estimation_smoother::Parameters

Overview

Parameters needed by StateEstimationSmoother.

#include <Parameters.h>

class Parameters
{
public:
    // fields

    std::string vehicle_frame_name = "base_link";
    std::string reference_frame_name = "map";
    std::string enu_frame_name = "enu";
    KinematicModel kinematic_model = KinematicModel::ConstantVelocity;
    double max_time_to_use_velocity_model = 2.0;
    double sliding_window_length = 5.0;
    double min_time_difference_to_create_new_frame = 0.01;
    double time_between_frames_to_warning = 3.0;
    double gnss_nearby_keyframe_stamp_tolerance = 1.0;
    double imu_nearby_keyframe_stamp_tolerance = 0.10;
    double sigma_random_walk_acceleration_linear = 1.0;
    double sigma_random_walk_acceleration_angular = 1.0;
    double sigma_integrator_position = 0.10;
    double sigma_integrator_orientation = 0.10;
    double sigma_twist_from_consecutive_poses_linear = 1.0;
    double sigma_twist_from_consecutive_poses_angular = 1.0;
    mrpt::math::TTwist3D initial_twist;
    double initial_twist_sigma_lin = 0.1;
    double initial_twist_sigma_ang = 0.1;
    bool enforce_planar_motion = false;
    std::optional<double> link_first_pose_to_reference_origin_sigma;
    double imu_attitude_sigma_deg = 2.0;
    double imu_attitude_azimuth_offset_deg = 0.0;
    double imu_normalized_gravity_alignment_sigma = 0.4;
    bool estimate_geo_reference = false;
    std::optional<mola::Georeferencing> fixed_geo_reference;
    uint32_t additional_isam2_update_steps = 3;
    std::regex do_process_imu_labels_re {".*"};
    std::regex do_process_odometry_labels_re {".*"};
    std::regex do_process_gnss_labels_re {".*"};

    // methods

    void loadFrom(const mrpt::containers::yaml& cfg);
};

Fields

std::string vehicle_frame_name = "base_link"

Used to publish timely pose updates.

std::string reference_frame_name = "map"

Used to publish timely pose updates. Typically, ‘map’ or ‘odom’, etc. See the docs online.

std::string enu_frame_name = "enu"

The ENU geo-reference frame. See the docs online.

KinematicModel kinematic_model = KinematicModel::ConstantVelocity

Kinematic model to be used in the internal motion model factors. Options: KinematicModel::ConstantVelocity, KinematicModel::Tricycle

double max_time_to_use_velocity_model = 2.0

Valid estimations will be extrapolated only up to this time since the last incorporated observation. If a request is done farther away, an empty estimation will be returned.

double sliding_window_length = 5.0

Time to keep past observations in the filter.

double time_between_frames_to_warning = 3.0

If the time between two keyframes is larger than this, a warning will be emitted; but the algorithm will keep trying its best.

double gnss_nearby_keyframe_stamp_tolerance = 1.0

When adding GNSS observations, specially with consumer grade receivers with errors larger than a few centimeters, we may be more permissive in the temporal distance between the GNSS datum and the associated existing keyframe. This parameter is the extended, alternative value to use instead of “min_time_difference_to_create_new_frame”. [seconds]

double imu_nearby_keyframe_stamp_tolerance = 0.10

When adding IMU observations, this is the temporal distance between the IMU reading and the associated existing keyframe. This applies to gravity-oriented (IMU attitude) and gravity-estimation (accelerometer) only factors, not to high-frequency IMU preintegration.

This parameter is the extended, alternative value to use instead of “min_time_difference_to_create_new_frame”. [seconds]

std::optional<double> link_first_pose_to_reference_origin_sigma

If set, the first ever frame will also have an SE(3) edge favoring it to be the identity in the “reference_frame”, with a sigma given by this value. Use a small number, like 1e-6, for initialing the first odometry pose near the map origin. Do not set when using geo-referenced maps.

double imu_attitude_sigma_deg = 2.0

When an IMU provides global attitude measurements (azimuth and gravity aligned), this is the uncertainty or noise sigma [degrees].

double imu_attitude_azimuth_offset_deg = 0.0

When an IMU provides global attitude measurements (azimuth and gravity aligned), this must define the angle (in degrees) to add to IMU yaw orientation to obtain azimuth so 0 deg is North. Note that ENU axes are such vehicle yaw is 0 when pointing East instead. Example cases:

  • IMU absolute yaw=0 points True North ==> offset=0

  • IMU absolute yaw=0 points East ==> offset=-90

double imu_normalized_gravity_alignment_sigma = 0.4

When using an IMU with acceleration, use this sigma to estimate the up-vector, hence gravity-align the map. Set to 0 to disable.

bool estimate_geo_reference = false

If true, this estimator will try to estimate the best geo-referencing for {enu} -> {map} from incoming GNSS readings and other sensors. If false, geo-referencing is assumed to be given from either these initial parameters or, if not set, from an external source (e.g. a geo-referenced .mm map loaded in mola_lidar_odometry).

std::optional<mola::Georeferencing> fixed_geo_reference

If estimate_geo_reference is false and this is set, the geo-referencing will be taken from this value and never attempted to be optimized or changed. Other geo-reference information coming from external sources may override this fixed initial value, though.

uint32_t additional_isam2_update_steps = 3

Each new sensor will become a call to isam2.update(), plus this number of additional refining steps. In theory, more steps lead to more accurate results.

std::regex do_process_imu_labels_re {".*"}

< regex for IMU sensor labels (ROS topics) to accept as IMU readings.

regex for odometry inputs labels (ROS topics) to be accepted as inputs

std::regex do_process_odometry_labels_re {".*"}

regex for GNSS (GPS) labels (ROS topics) to be accepted as inputs

Methods

void loadFrom(const mrpt::containers::yaml& cfg)

Loads all parameters from a YAML map node.