Struct PFLocalizationCore::Parameters

Nested Relationships

This struct is a nested type of Class PFLocalizationCore.

Struct Documentation

struct Parameters

Parameters the filter will use to initialize or to run. The ROS node will overwrite here when reading params from YAML file, CLI, or service-based changes.

Public Functions

Parameters()
~Parameters() = default
void load_from(const mrpt::containers::yaml &params)

This method loads all parameters from the YAML, except the metric_map (handled in parent class):

Public Members

std::optional<mrpt::poses::CPose3DPDFGaussian> initial_pose

initial pose used to intialize the filter. Empty=not set yet.

mrpt::maps::CMultiMetricMap::Ptr metric_map

Empty=uninitialized.

std::optional<mp2p_icp::metric_map_t::Georeferencing> georeferencing
std::vector<std::string> metric_map_layer_names
bool gui_enable = true

Shows a custom MRPT GUI with the PF and map state Can be changed at any moment.

bool use_se3_pf = false

If false (default), will use 2D (SE(2)) particle filter. Otherwise, the 3D mode (SE(3)) is enabled. Can be changed while state = UNINITIALIZED.

bool gui_camera_follow_robot = true

If gui_enable==true, makes the camera to follow the mean of the particles. Can be changed at any moment.

mrpt::obs::CActionRobotMovement2D::TMotionModelOptions motion_model_2d

For SE(2) mode: Uncertainty motion model for regular odometry-based motion. Can be changed at any moment.

mrpt::obs::CActionRobotMovement2D::TMotionModelOptions motion_model_no_odom_2d

For SE(2) mode: Uncertainty motion model to use when NO odometry has been received. Can be changed at any moment.

mrpt::obs::CActionRobotMovement3D::TMotionModelOptions motion_model_3d

For SE(3) mode: Uncertainty motion model for regular odometry-based motion. Can be changed at any moment.

mrpt::obs::CActionRobotMovement3D::TMotionModelOptions motion_model_no_odom_3d

For SE(3) mode: Uncertainty motion model to use when NO odometry has been received. Can be changed at any moment.

mrpt::bayes::CParticleFilter::TParticleFilterOptions pf_options

All the PF parameters: algorithm, number of samples, dynamic samples, etc. Can be changed while state = UNINITIALIZED.

mrpt::slam::TKLDParams kld_options

Dynamic sampling-related parameters. Can be changed at any moment.

std::optional<mrpt::maps::CPointsMap::TLikelihoodOptions> override_likelihood_point_maps
std::optional<mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions> override_likelihood_gridmaps
unsigned int initial_particles_per_m2 = 10

Number of particles/m² to use upon initialization. Can be changed while state = UNINITIALIZED.

bool initialize_from_gnns = false

If true, the particles will be initialized according to the first incomming GNNS observation, once the map has been also received.

Note

This requires a georeferencied metric_map_t.

uint32_t samples_drawn_from_gnns = 20

If >0, new tentative particles will be generated from GNNS data, to help re-localizing if using georeferenced maps:

double gnns_samples_num_sigmas = 6.0

If samples_drawn_from_gnns is enabled, the number of standard deviations (“sigmas”) to use as the area in which to draw random samples around the GNNS prediction:

double relocalize_num_sigmas = 3.0

The number of standard deviations (“sigmas”) to use as the area in which to draw random samples around the input initialization pose (when NOT using GNNS as input)

unsigned int relocalization_initial_divisions_xy = 4
unsigned int relocalization_initial_divisions_phi = 4
unsigned int relocalization_min_sample_copies_per_candidate = 4
double relocalization_resolution_xy = 0.50
double relocalization_resolution_phi = 0.20
double relocalization_minimum_icp_quality = 0.50
double relocalization_icp_sigma = 5.0
mp2p_icp::ICP::Ptr relocalization_icp
mp2p_icp::Parameters relocalization_icp_params
mp2p_icp_filters::FilterPipeline relocalization_obs_filter
mp2p_icp::ParameterSource paramSource