Class Parameters

Class Documentation

class Parameters

Parameters needed by StateEstimationSmoother.

Public Functions

Parameters() = default
~Parameters() = default
void loadFrom(const mrpt::containers::yaml &cfg)

Loads all parameters from a YAML map node.

Public Members

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.

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 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
double robust_param = 0.0
double max_rmse = 2.0
mrpt::math::TTwist3D initial_twist
double initial_twist_sigma_lin = 20.0
double initial_twist_sigma_ang = 3.0
bool enforce_planar_motion = false

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

std::regex do_process_imu_labels = {".*"}

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

std::regex do_process_odometry_labels = {".*"}

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

std::regex do_process_gnss_labels = {".*"}