struct mola::WheelOdometry::Parameters¶
Overview¶
#include <WheelOdometry.h> struct Parameters { // structs struct OffPlaneNoiseModel; // fields double min_dist_xyz_between_keyframes {1.5}; double min_rotation_between_keyframes {mrpt::DEG2RAD(30.0)}; OdometryPlanarUncertaintyModel noise_model_planar; OffPlaneNoiseModel noise_model_vertical; };
Detailed Documentation¶
Fields¶
double min_dist_xyz_between_keyframes {1.5}
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].
OdometryPlanarUncertaintyModel noise_model_planar
SE(2) components of odometry Gaussin uncertainty model. Refer to: https://www.mrpt.org/tutorials/programming/odometry-and-motion-models/probabilistic_motion_models/#2_Gaussian_probabilistic_motion_model