struct mola::LidarOdometry::Parameters¶
Overview¶
#include <LidarOdometry.h> struct Parameters { // structs struct ICP_case; // fields double min_time_between_scans {0.2}; double min_dist_xyz_between_keyframes {1.0}; double min_rotation_between_keyframes {mrpt::DEG2RAD(30.0)}; double min_icp_goodness {0.4}; double min_icp_goodness_lc {0.6}; unsigned int full_pointcloud_decimation {20}; double voxel_filter_resolution {.5}; unsigned int voxel_filter_decimation {1}; float voxel_filter_max_e2_e0 {30.f}; float voxel_filter_max_e1_e0 {30.f}; float voxel_filter_min_e2_e0 {100.f}; float voxel_filter_min_e1_e0 {100.f}; double min_dist_to_matching {6.0}; double max_dist_to_matching {12.0}; double max_dist_to_loop_closure {30.0}; unsigned int loop_closure_montecarlo_samples {10}; unsigned int max_nearby_align_checks {2}; unsigned int min_topo_dist_to_consider_loopclosure {20}; unsigned int max_KFs_local_graph {50000}; std::map<AlignKind, ICP_case> icp; int viz_decor_decimation {5}; float viz_decor_pointsize {2.0f}; };
Detailed Documentation¶
Fields¶
double min_time_between_scans {0.2}
Minimum time (seconds) between scans for being attempted to be aligned. Scans faster than this rate will be just silently ignored.
double min_dist_xyz_between_keyframes {1.0}
Minimum Euclidean distance (x,y,z) between keyframes inserted into the map [meters].
double min_rotation_between_keyframes {mrpt::DEG2RAD(30.0)}
Minimum rotation (in 3D space, yaw, pitch,roll, altogether) between keyframes inserted into the map [rad here, degrees in the yaml file].
double min_icp_goodness {0.4}
Minimum ICP “goodness” (in the range [0,1]) for a new KeyFrame to be accepted during regular lidar odometry & mapping
double min_icp_goodness_lc {0.6}
Minimum ICP quality for a loop closure to be accepted
unsigned int full_pointcloud_decimation {20}
Size of the voxel filter [meters]
double min_dist_to_matching {6.0}
Distance range to check for additional SE(3) edges
int viz_decor_decimation {5}
Generate render visualization decoration for every N keyframes