struct mola::LidarOdometry::Parameters::MapUpdateOptions
Overview
#include <LidarOdometry.h> struct MapUpdateOptions { // fields bool enabled = true; double min_translation_between_keyframes = 1.0; double min_rotation_between_keyframes = 30.0; bool measure_from_last_kf_only = false; double max_distance_to_keep_keyframes = 0; uint32_t check_for_removal_every_n = 100; uint32_t publish_map_updates_every_n = 10; std::string load_existing_local_map; // methods void initialize( const Yaml& c, Parameters& parent ); };
Fields
bool enabled = true
If set to false, the odometry system can be used as localization-only.
double min_translation_between_keyframes = 1.0
Minimum Euclidean distance (x,y,z) between keyframes inserted into the local map [meters].
double min_rotation_between_keyframes = 30.0
Minimum rotation (in 3D space, yaw, pitch,roll, altogether) between keyframes inserted into the local map [in degrees].
bool measure_from_last_kf_only = false
If true, distance from the last map update are only considered. Use if mostly mapping without “closed loops”.
If false (default), a KD-tree will be used to check the distance to all past map insert poses.
double max_distance_to_keep_keyframes = 0
Should match the “remove farther than” option of the local metric map. 0 means deletion of distant keyframes is disabled. In meters.
uint32_t check_for_removal_every_n = 100
If max_distance_to_keep_keyframes
is not zero, this indicates how often to do the distant keyframes clean up.
uint32_t publish_map_updates_every_n = 10
Publish updated map via mola::MapSourceBase once every N frames
std::string load_existing_local_map
If non-empty, the local map will be loaded from the given *.mm
file instead of generating it from scratch. This can be used for multi-session SLAM, or for localization-only.