struct mola::ASLAM_gtsam::Parameters¶
Overview¶
#include <ASLAM_gtsam.h> struct Parameters { // fields StateVectorType state_vector {StateVectorType::Undefined}; bool use_incremental_solver {true}; int isam2_additional_update_steps {0}; double isam2_relinearize_threshold {0.1}; int isam2_relinearize_skip {1}; std::string save_trajectory_file_prefix {}; bool save_map_at_end {true}; double const_vel_model_std_pos {0.1}; double const_vel_model_std_vel {1.0}; double max_interval_between_kfs_for_dynamic_model {5.0}; };
Detailed Documentation¶
Fields¶
StateVectorType state_vector {StateVectorType::Undefined}
See StateVectorType
bool use_incremental_solver {true}
Use iSAM2 (true) or Lev-Marq. (false)
int isam2_additional_update_steps {0}
iSAM2 additional update() steps. Set >0 to fasten convergence, at the cost of more processing time for each timestep
double isam2_relinearize_threshold {0.1}
iSAM2 relinearize threshold. Refer to iSAM2 docs
int isam2_relinearize_skip {1}
iSAM2 relinearize skip. Refer to iSAM2 docs
std::string save_trajectory_file_prefix {}
Saves the overall optimized trajectory at the end, in different file formats, if !=”” (default:”“)
bool save_map_at_end {true}
Save map at end of a SLAM session. See WorldModel::map_base_directory() to see where maps are stored by default and how to change it.
double const_vel_model_std_pos {0.1}
Const. velocity model: sigma of the position equation (see paper)
double const_vel_model_std_vel {1.0}
Const. velocity model: sigma of the velocity equation (see paper)