diff --git a/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp b/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp index 690bf0b8..e574d07f 100644 --- a/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp +++ b/apps/lidar_odometry_step_1/drag_folder_with_mandeye_data_and_drop_here-precision_forestry.cpp @@ -719,7 +719,8 @@ void settings_gui() ImGui::Checkbox("Use VQF (instead of Fusion/Madgwick)", ¶ms.use_vqf); if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Unchecked = Fusion (Madgwick complementary filter, default)\nChecked = VQF (Versatile Quaternion-based Filter)"); + ImGui::SetTooltip( + "Unchecked = Fusion (Madgwick complementary filter, default)\nChecked = VQF (Versatile Quaternion-based Filter)"); if (!params.use_vqf) { @@ -759,159 +760,170 @@ void settings_gui() ImGui::Checkbox("Use motion from previous step", ¶ms.use_motion_from_previous_step); if (params.use_vqf) { - ImGui::InputDouble("VQF tauAcc [s]", ¶ms.vqf_tauAcc, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - { - ImGui::BeginTooltip(); - ImGui::Text("VQF accelerometer time constant (tauAcc) in seconds."); - ImGui::Text("Controls how strongly accelerometer corrects the gyroscope-based orientation."); - ImGui::Text("Higher = more gyro trust (stable but may drift). Lower = more acc trust (noisy but no drift)."); - ImGui::EndTooltip(); - } - - if (ImGui::TreeNode("VQF Gyro Bias Estimation")) - { - ImGui::Checkbox("Motion bias estimation", ¶ms.vqf_motionBiasEstEnabled); + ImGui::InputDouble("VQF tauAcc [s]", ¶ms.vqf_tauAcc, 0.0, 0.0, "%.3f"); if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Enables gyroscope bias estimation during motion phases,\nbased on the inclination correction only (without " - "magnetometer)."); - if (params.vqf_motionBiasEstEnabled) { - ImGui::InputDouble("Bias sigma motion [deg/s]", ¶ms.vqf_biasSigmaMotion, 0.0, 0.0, "%.4f"); + ImGui::BeginTooltip(); + ImGui::Text("VQF accelerometer time constant (tauAcc) in seconds."); + ImGui::Text("Controls how strongly accelerometer corrects the gyroscope-based orientation."); + ImGui::Text("Higher = more gyro trust (stable but may drift). Lower = more acc trust (noisy but no drift)."); + ImGui::EndTooltip(); + } + + if (ImGui::TreeNode("VQF Gyro Bias Estimation")) + { + ImGui::Checkbox("Motion bias estimation", ¶ms.vqf_motionBiasEstEnabled); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Enables gyroscope bias estimation during motion phases,\nbased on the inclination correction only (without " + "magnetometer)."); + if (params.vqf_motionBiasEstEnabled) + { + ImGui::InputDouble("Bias sigma motion [deg/s]", ¶ms.vqf_biasSigmaMotion, 0.0, 0.0, "%.4f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Std dev of converged bias estimation uncertainty during motion.\nDetermines trust on motion bias " + "estimation " + "updates.\nSmall value leads to fast convergence. Default: 0.1"); + ImGui::InputDouble("Bias vertical forgetting", ¶ms.vqf_biasVerticalForgettingFactor, 0.0, 0.0, "%.6f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Forgetting factor for unobservable bias in vertical direction during motion.\nGyro bias is not observable " + "vertically without magnetometer.\nRelative weight of artificial zero measurement ensuring\nbias estimate " + "decays to zero. Default: 0.0001"); + } + ImGui::Checkbox("Rest bias estimation", ¶ms.vqf_restBiasEstEnabled); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Enables rest detection and gyroscope bias estimation during rest phases.\nDuring rest, gyro bias is estimated " + "from low-pass filtered gyro readings."); + if (params.vqf_restBiasEstEnabled) + { + ImGui::InputDouble("Bias sigma rest [deg/s]", ¶ms.vqf_biasSigmaRest, 0.0, 0.0, "%.4f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Std dev of converged bias estimation uncertainty during rest.\nDetermines trust on rest bias estimation " + "updates.\nSmall value leads to fast convergence. Default: 0.03"); + } + ImGui::InputDouble("Bias sigma init [deg/s]", ¶ms.vqf_biasSigmaInit, 0.0, 0.0, "%.3f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip("Std dev of the initial bias estimation uncertainty. Default: 0.5 deg/s"); + ImGui::InputDouble("Bias forgetting time [s]", ¶ms.vqf_biasForgettingTime, 0.0, 0.0, "%.1f"); if (ImGui::IsItemHovered()) ImGui::SetTooltip( - "Std dev of converged bias estimation uncertainty during motion.\nDetermines trust on motion bias estimation " - "updates.\nSmall value leads to fast convergence. Default: 0.1"); - ImGui::InputDouble("Bias vertical forgetting", ¶ms.vqf_biasVerticalForgettingFactor, 0.0, 0.0, "%.6f"); + "Time in which bias estimation uncertainty increases from 0 to 0.1 deg/s.\nDetermines the system noise assumed " + "by " + "the Kalman filter. Default: 100.0"); + ImGui::InputDouble("Bias clip [deg/s]", ¶ms.vqf_biasClip, 0.0, 0.0, "%.2f"); if (ImGui::IsItemHovered()) ImGui::SetTooltip( - "Forgetting factor for unobservable bias in vertical direction during motion.\nGyro bias is not observable " - "vertically without magnetometer.\nRelative weight of artificial zero measurement ensuring\nbias estimate " - "decays to zero. Default: 0.0001"); + "Maximum expected gyroscope bias.\nUsed to clip bias estimate and measurement error in update step.\nAlso used " + "by " + "rest detection to not regard large constant angular rate as rest.\nDefault: 2.0"); + ImGui::TreePop(); } - ImGui::Checkbox("Rest bias estimation", ¶ms.vqf_restBiasEstEnabled); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Enables rest detection and gyroscope bias estimation during rest phases.\nDuring rest, gyro bias is estimated " - "from low-pass filtered gyro readings."); - if (params.vqf_restBiasEstEnabled) + + if (params.vqf_restBiasEstEnabled && ImGui::TreeNode("VQF Rest Detection")) { - ImGui::InputDouble("Bias sigma rest [deg/s]", ¶ms.vqf_biasSigmaRest, 0.0, 0.0, "%.4f"); + ImGui::InputDouble("Rest min time [s]", ¶ms.vqf_restMinT, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time threshold for rest detection.\nRest is detected when measurements have been close to\nthe low-pass " + "filtered " + "reference for the given time. Default: 1.5"); + ImGui::InputDouble("Rest filter tau [s]", ¶ms.vqf_restFilterTau, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time constant for the second-order Butterworth low-pass filter\nused to obtain the reference for rest " + "detection. " + "Default: 0.5"); + ImGui::InputDouble("Rest threshold gyro [deg/s]", ¶ms.vqf_restThGyr, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Angular velocity threshold for rest detection.\nDeviation norm between measurement and reference must be " + "below " + "threshold.\nEach component must also be below biasClip. Default: 2.0"); + ImGui::InputDouble("Rest threshold acc [m/s2]", ¶ms.vqf_restThAcc, 0.0, 0.0, "%.2f"); if (ImGui::IsItemHovered()) ImGui::SetTooltip( - "Std dev of converged bias estimation uncertainty during rest.\nDetermines trust on rest bias estimation " - "updates.\nSmall value leads to fast convergence. Default: 0.03"); + "Acceleration threshold for rest detection.\nDeviation norm between measurement and reference must be below " + "threshold.\nDefault: 0.5"); + ImGui::TreePop(); } - ImGui::InputDouble("Bias sigma init [deg/s]", ¶ms.vqf_biasSigmaInit, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Std dev of the initial bias estimation uncertainty. Default: 0.5 deg/s"); - ImGui::InputDouble("Bias forgetting time [s]", ¶ms.vqf_biasForgettingTime, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time in which bias estimation uncertainty increases from 0 to 0.1 deg/s.\nDetermines the system noise assumed by " - "the Kalman filter. Default: 100.0"); - ImGui::InputDouble("Bias clip [deg/s]", ¶ms.vqf_biasClip, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Maximum expected gyroscope bias.\nUsed to clip bias estimate and measurement error in update step.\nAlso used by " - "rest detection to not regard large constant angular rate as rest.\nDefault: 2.0"); - ImGui::TreePop(); - } - if (params.vqf_restBiasEstEnabled && ImGui::TreeNode("VQF Rest Detection")) - { - ImGui::InputDouble("Rest min time [s]", ¶ms.vqf_restMinT, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time threshold for rest detection.\nRest is detected when measurements have been close to\nthe low-pass filtered " - "reference for the given time. Default: 1.5"); - ImGui::InputDouble("Rest filter tau [s]", ¶ms.vqf_restFilterTau, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time constant for the second-order Butterworth low-pass filter\nused to obtain the reference for rest detection. " - "Default: 0.5"); - ImGui::InputDouble("Rest threshold gyro [deg/s]", ¶ms.vqf_restThGyr, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Angular velocity threshold for rest detection.\nDeviation norm between measurement and reference must be below " - "threshold.\nEach component must also be below biasClip. Default: 2.0"); - ImGui::InputDouble("Rest threshold acc [m/s2]", ¶ms.vqf_restThAcc, 0.0, 0.0, "%.2f"); + ImGui::Checkbox("Use magnetometer", ¶ms.vqf_useMagnetometer); if (ImGui::IsItemHovered()) ImGui::SetTooltip( - "Acceleration threshold for rest detection.\nDeviation norm between measurement and reference must be below " - "threshold.\nDefault: 0.5"); - ImGui::TreePop(); - } - - ImGui::Checkbox("Use magnetometer", ¶ms.vqf_useMagnetometer); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Enable 9D mode (gyro+acc+mag) for absolute heading correction.\nDefault: off (6D mode, gyro+acc only, heading from " - "gyro integration)."); - if (params.vqf_useMagnetometer && ImGui::TreeNode("VQF Magnetometer")) - { - ImGui::InputDouble("tauMag [s]", ¶ms.vqf_tauMag, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time constant for magnetometer update.\nSmall values imply trust on magnetometer, large values trust on " - "gyroscope.\nCorresponds to cutoff frequency of first-order LP filter\nfor heading correction. Default: 9.0"); - ImGui::Checkbox("Mag disturbance rejection", ¶ms.vqf_magDistRejectionEnabled); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Enables magnetic disturbance detection and rejection.\nFor short disturbances, mag correction is fully " - "disabled.\nFor long disturbances (>magMaxRejectionTime), correction uses\nincreased time constant " - "(magRejectionFactor)."); - ImGui::InputDouble("Mag current tau [s]", ¶ms.vqf_magCurrentTau, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time constant for current norm/dip value in disturbance detection.\nFast LP filter for robustness with noisy or " - "async mag measurements.\nSet to -1 to disable. Default: 0.05"); - ImGui::InputDouble("Mag ref tau [s]", ¶ms.vqf_magRefTau, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time constant for adjustment of the magnetic field reference.\nAllows reference to converge to observed " - "undisturbed field. Default: 20.0"); - ImGui::InputDouble("Mag norm threshold", ¶ms.vqf_magNormTh, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Relative threshold for magnetic field strength for disturbance detection.\nRelative to the reference norm. " - "Default: 0.1 (10%%)"); - ImGui::InputDouble("Mag dip threshold [deg]", ¶ms.vqf_magDipTh, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Threshold for the magnetic field dip angle for disturbance detection. Default: 10.0"); - ImGui::InputDouble("Mag new time [s]", ¶ms.vqf_magNewTime, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Duration after which to accept a different homogeneous magnetic field.\nNew reference accepted when within " - "magNormTh and magDipTh for this time.\nOnly phases with sufficient movement (magNewMinGyr) count. Default: 20.0"); - ImGui::InputDouble("Mag new first time [s]", ¶ms.vqf_magNewFirstTime, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Duration after which to accept a homogeneous magnetic field for the first time.\nUsed instead of magNewTime when " - "no current estimate exists,\nto allow faster initial reference acquisition. Default: 5.0"); - ImGui::InputDouble("Mag new min gyro [deg/s]", ¶ms.vqf_magNewMinGyr, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Minimum angular velocity needed to count time for new mag field acceptance.\nPeriods with angular velocity norm " - "below this threshold\ndo not count towards magNewTime. Default: 20.0"); - ImGui::InputDouble("Mag min undisturbed [s]", ¶ms.vqf_magMinUndisturbedTime, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Minimum duration within thresholds after which to regard\nthe field as undisturbed again. Default: 0.5"); - ImGui::InputDouble("Mag max rejection [s]", ¶ms.vqf_magMaxRejectionTime, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Maximum duration of full magnetic disturbance rejection.\nUp to this duration, heading correction is fully " - "disabled\nand tracked by gyroscope only. After this, correction uses\nincreased time constant " - "(magRejectionFactor). Default: 60.0"); - ImGui::InputDouble("Mag rejection factor", ¶ms.vqf_magRejectionFactor, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Factor by which to slow heading correction during long disturbed phases.\nAfter magMaxRejectionTime of full " - "rejection, correction uses\nthis factor to increase the time constant. Default: 2.0"); - ImGui::TreePop(); - } + "Enable 9D mode (gyro+acc+mag) for absolute heading correction.\nDefault: off (6D mode, gyro+acc only, heading " + "from " + "gyro integration)."); + if (params.vqf_useMagnetometer && ImGui::TreeNode("VQF Magnetometer")) + { + ImGui::InputDouble("tauMag [s]", ¶ms.vqf_tauMag, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time constant for magnetometer update.\nSmall values imply trust on magnetometer, large values trust on " + "gyroscope.\nCorresponds to cutoff frequency of first-order LP filter\nfor heading correction. Default: 9.0"); + ImGui::Checkbox("Mag disturbance rejection", ¶ms.vqf_magDistRejectionEnabled); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Enables magnetic disturbance detection and rejection.\nFor short disturbances, mag correction is fully " + "disabled.\nFor long disturbances (>magMaxRejectionTime), correction uses\nincreased time constant " + "(magRejectionFactor)."); + ImGui::InputDouble("Mag current tau [s]", ¶ms.vqf_magCurrentTau, 0.0, 0.0, "%.3f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time constant for current norm/dip value in disturbance detection.\nFast LP filter for robustness with noisy " + "or " + "async mag measurements.\nSet to -1 to disable. Default: 0.05"); + ImGui::InputDouble("Mag ref tau [s]", ¶ms.vqf_magRefTau, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time constant for adjustment of the magnetic field reference.\nAllows reference to converge to observed " + "undisturbed field. Default: 20.0"); + ImGui::InputDouble("Mag norm threshold", ¶ms.vqf_magNormTh, 0.0, 0.0, "%.3f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Relative threshold for magnetic field strength for disturbance detection.\nRelative to the reference norm. " + "Default: 0.1 (10%%)"); + ImGui::InputDouble("Mag dip threshold [deg]", ¶ms.vqf_magDipTh, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip("Threshold for the magnetic field dip angle for disturbance detection. Default: 10.0"); + ImGui::InputDouble("Mag new time [s]", ¶ms.vqf_magNewTime, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Duration after which to accept a different homogeneous magnetic field.\nNew reference accepted when within " + "magNormTh and magDipTh for this time.\nOnly phases with sufficient movement (magNewMinGyr) count. Default: " + "20.0"); + ImGui::InputDouble("Mag new first time [s]", ¶ms.vqf_magNewFirstTime, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Duration after which to accept a homogeneous magnetic field for the first time.\nUsed instead of magNewTime " + "when " + "no current estimate exists,\nto allow faster initial reference acquisition. Default: 5.0"); + ImGui::InputDouble("Mag new min gyro [deg/s]", ¶ms.vqf_magNewMinGyr, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Minimum angular velocity needed to count time for new mag field acceptance.\nPeriods with angular velocity " + "norm " + "below this threshold\ndo not count towards magNewTime. Default: 20.0"); + ImGui::InputDouble("Mag min undisturbed [s]", ¶ms.vqf_magMinUndisturbedTime, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Minimum duration within thresholds after which to regard\nthe field as undisturbed again. Default: 0.5"); + ImGui::InputDouble("Mag max rejection [s]", ¶ms.vqf_magMaxRejectionTime, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Maximum duration of full magnetic disturbance rejection.\nUp to this duration, heading correction is fully " + "disabled\nand tracked by gyroscope only. After this, correction uses\nincreased time constant " + "(magRejectionFactor). Default: 60.0"); + ImGui::InputDouble("Mag rejection factor", ¶ms.vqf_magRejectionFactor, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Factor by which to slow heading correction during long disturbed phases.\nAfter magMaxRejectionTime of full " + "rejection, correction uses\nthis factor to increase the time constant. Default: 2.0"); + ImGui::TreePop(); + } } // end if (params.use_vqf) ImGui::PopItemWidth(); diff --git a/apps/lidar_odometry_step_1/lidar_odometry.cpp b/apps/lidar_odometry_step_1/lidar_odometry.cpp index f68216d5..7ffb6250 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry.cpp +++ b/apps/lidar_odometry_step_1/lidar_odometry.cpp @@ -4,6 +4,7 @@ #include #include +#include namespace fs = std::filesystem; @@ -344,7 +345,9 @@ void calculate_trajectory(Trajectory& trajectory, Imu& imu_data, LidarOdometryPa { const double g = 9.81; vqf_real_t gyr_vqf[3] = { static_cast(gyr.x()), static_cast(gyr.y()), static_cast(gyr.z()) }; - vqf_real_t acc_vqf[3] = { static_cast(acc.x()) * g, static_cast(acc.y()) * g, static_cast(acc.z()) * g }; + vqf_real_t acc_vqf[3] = { static_cast(acc.x()) * g, + static_cast(acc.y()) * g, + static_cast(acc.z()) * g }; vqf.update(gyr_vqf, acc_vqf); @@ -393,7 +396,9 @@ void calculate_trajectory(Trajectory& trajectory, Imu& imu_data, LidarOdometryPa if (params.use_removie_imu_bias_from_first_stationary_scan && imu_data.size() > 1000) { std::vector gyr_x, gyr_y, gyr_z; - gyr_x.reserve(1000); gyr_y.reserve(1000); gyr_z.reserve(1000); + gyr_x.reserve(1000); + gyr_y.reserve(1000); + gyr_z.reserve(1000); for (int i = 0; i < 1000; i++) { const auto& [timestamp_pair, gyr, acc] = imu_data[i]; @@ -404,7 +409,9 @@ void calculate_trajectory(Trajectory& trajectory, Imu& imu_data, LidarOdometryPa std::nth_element(gyr_x.begin(), gyr_x.begin() + 500, gyr_x.end()); std::nth_element(gyr_y.begin(), gyr_y.begin() + 500, gyr_y.end()); std::nth_element(gyr_z.begin(), gyr_z.begin() + 500, gyr_z.end()); - bias_gyr_x = gyr_x[500]; bias_gyr_y = gyr_y[500]; bias_gyr_z = gyr_z[500]; + bias_gyr_x = gyr_x[500]; + bias_gyr_y = gyr_y[500]; + bias_gyr_z = gyr_z[500]; params.estimated_gyro_bias_dps = Eigen::Vector3d(bias_gyr_x, bias_gyr_y, bias_gyr_z); std::cout << "------------------\nGYRO BIAS\n" @@ -453,8 +460,8 @@ void calculate_trajectory(Trajectory& trajectory, Imu& imu_data, LidarOdometryPa if (counter % 100 == 0) { const FusionEuler euler = FusionQuaternionToEuler(quat); - std::cout << "Roll " << euler.angle.roll << ", Pitch " << euler.angle.pitch << ", Yaw " << euler.angle.yaw - << " [" << counter << " of " << imu_data.size() << "]" << std::endl; + std::cout << "Roll " << euler.angle.roll << ", Pitch " << euler.angle.pitch << ", Yaw " << euler.angle.yaw << " [" + << counter << " of " << imu_data.size() << "]" << std::endl; } } } diff --git a/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp b/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp index 9a8868ce..b8e65b7f 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp +++ b/apps/lidar_odometry_step_1/lidar_odometry_gui.cpp @@ -929,7 +929,8 @@ void settings_gui() // AHRS type selection ImGui::Checkbox("Use VQF (instead of Fusion/Madgwick)", ¶ms.use_vqf); if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Unchecked = Fusion (Madgwick complementary filter, default)\nChecked = VQF (Versatile Quaternion-based Filter)"); + ImGui::SetTooltip( + "Unchecked = Fusion (Madgwick complementary filter, default)\nChecked = VQF (Versatile Quaternion-based Filter)"); if (!params.use_vqf) { @@ -971,161 +972,176 @@ void settings_gui() ImGui::Checkbox("Use IMU preintegration", ¶ms.use_imu_preintegration); if (params.use_imu_preintegration) { - const char* methods[] = { - "Euler, no gravity comp., SM velocity", - "Trapezoidal, no gravity comp., SM velocity", - "Euler, gravity comp., SM velocity", - "Trapezoidal, gravity comp., SM velocity", - "Kalman, gravity comp., SM velocity", - "Euler, gravity comp., AHRS velocity", - "Trapezoidal, gravity comp., AHRS velocity", - "Kalman, gravity comp., AHRS velocity" }; + const char* methods[] = { "Euler, no gravity comp., SM velocity", "Trapezoidal, no gravity comp., SM velocity", + "Euler, gravity comp., SM velocity", "Trapezoidal, gravity comp., SM velocity", + "Kalman, gravity comp., SM velocity", "Euler, gravity comp., AHRS velocity", + "Trapezoidal, gravity comp., AHRS velocity", "Kalman, gravity comp., AHRS velocity" }; ImGui::Combo("IMU preintegration method", ¶ms.imu_preintegration_method, methods, IM_ARRAYSIZE(methods)); } if (params.use_vqf) { - ImGui::InputDouble("VQF tauAcc [s]", ¶ms.vqf_tauAcc, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - { - ImGui::BeginTooltip(); - ImGui::Text("VQF accelerometer time constant (tauAcc) in seconds."); - ImGui::Text("Controls how strongly accelerometer corrects the gyroscope-based orientation."); - ImGui::Text("Higher = more gyro trust (stable but may drift). Lower = more acc trust (noisy but no drift)."); - ImGui::EndTooltip(); - } - - if (ImGui::TreeNode("VQF Gyro Bias Estimation")) - { - ImGui::Checkbox("Motion bias estimation", ¶ms.vqf_motionBiasEstEnabled); + ImGui::InputDouble("VQF tauAcc [s]", ¶ms.vqf_tauAcc, 0.0, 0.0, "%.3f"); if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Enables gyroscope bias estimation during motion phases,\nbased on the inclination correction only (without " - "magnetometer)."); + { + ImGui::BeginTooltip(); + ImGui::Text("VQF accelerometer time constant (tauAcc) in seconds."); + ImGui::Text("Controls how strongly accelerometer corrects the gyroscope-based orientation."); + ImGui::Text("Higher = more gyro trust (stable but may drift). Lower = more acc trust (noisy but no drift)."); + ImGui::EndTooltip(); + } - if (params.vqf_motionBiasEstEnabled) + if (ImGui::TreeNode("VQF Gyro Bias Estimation")) { - ImGui::InputDouble("Bias sigma motion [deg/s]", ¶ms.vqf_biasSigmaMotion, 0.0, 0.0, "%.4f"); + ImGui::Checkbox("Motion bias estimation", ¶ms.vqf_motionBiasEstEnabled); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Enables gyroscope bias estimation during motion phases,\nbased on the inclination correction only (without " + "magnetometer)."); + + if (params.vqf_motionBiasEstEnabled) + { + ImGui::InputDouble("Bias sigma motion [deg/s]", ¶ms.vqf_biasSigmaMotion, 0.0, 0.0, "%.4f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Std dev of converged bias estimation uncertainty during motion.\nDetermines trust on motion bias " + "estimation " + "updates.\nSmall value leads to fast convergence. Default: 0.1"); + ImGui::InputDouble("Bias vertical forgetting", ¶ms.vqf_biasVerticalForgettingFactor, 0.0, 0.0, "%.6f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Forgetting factor for unobservable bias in vertical direction during motion.\nGyro bias is not observable " + "vertically without magnetometer.\nRelative weight of artificial zero measurement ensuring\nbias estimate " + "decays to zero. Default: 0.0001"); + } + + ImGui::InputDouble("Bias sigma init [deg/s]", ¶ms.vqf_biasSigmaInit, 0.0, 0.0, "%.3f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip("Std dev of the initial bias estimation uncertainty. Default: 0.5 deg/s"); + ImGui::InputDouble("Bias forgetting time [s]", ¶ms.vqf_biasForgettingTime, 0.0, 0.0, "%.1f"); if (ImGui::IsItemHovered()) ImGui::SetTooltip( - "Std dev of converged bias estimation uncertainty during motion.\nDetermines trust on motion bias estimation " - "updates.\nSmall value leads to fast convergence. Default: 0.1"); - ImGui::InputDouble("Bias vertical forgetting", ¶ms.vqf_biasVerticalForgettingFactor, 0.0, 0.0, "%.6f"); + "Time in which bias estimation uncertainty increases from 0 to 0.1 deg/s.\nDetermines the system noise assumed " + "by " + "the Kalman filter. Default: 100.0"); + ImGui::InputDouble("Bias clip [deg/s]", ¶ms.vqf_biasClip, 0.0, 0.0, "%.2f"); if (ImGui::IsItemHovered()) ImGui::SetTooltip( - "Forgetting factor for unobservable bias in vertical direction during motion.\nGyro bias is not observable " - "vertically without magnetometer.\nRelative weight of artificial zero measurement ensuring\nbias estimate " - "decays to zero. Default: 0.0001"); + "Maximum expected gyroscope bias.\nUsed to clip bias estimate and measurement error in update step.\nAlso used " + "by " + "rest detection to not regard large constant angular rate as rest.\nDefault: 2.0"); + + ImGui::Checkbox("Rest bias estimation", ¶ms.vqf_restBiasEstEnabled); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Enables rest detection and gyroscope bias estimation during rest phases.\nDuring rest, gyro bias is estimated " + "from low-pass filtered gyro readings."); + + if (params.vqf_restBiasEstEnabled) + { + ImGui::InputDouble("Bias sigma rest [deg/s]", ¶ms.vqf_biasSigmaRest, 0.0, 0.0, "%.4f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Std dev of converged bias estimation uncertainty during rest.\nDetermines trust on rest bias estimation " + "updates.\nSmall value leads to fast convergence. Default: 0.03"); + ImGui::InputDouble("Rest min time [s]", ¶ms.vqf_restMinT, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time threshold for rest detection.\nRest is detected when measurements have been close to\nthe low-pass " + "filtered reference for the given time. Default: 1.5"); + ImGui::InputDouble("Rest filter tau [s]", ¶ms.vqf_restFilterTau, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time constant for the second-order Butterworth low-pass filter\nused to obtain the reference for rest " + "detection. Default: 0.5"); + ImGui::InputDouble("Rest threshold gyro [deg/s]", ¶ms.vqf_restThGyr, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Angular velocity threshold for rest detection.\nDeviation norm between measurement and reference must be " + "below threshold.\nEach component must also be below biasClip. Default: 2.0"); + ImGui::InputDouble("Rest threshold acc [m/s2]", ¶ms.vqf_restThAcc, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Acceleration threshold for rest detection.\nDeviation norm between measurement and reference must be " + "below threshold.\nDefault: 0.5"); + } + + ImGui::TreePop(); } - ImGui::InputDouble("Bias sigma init [deg/s]", ¶ms.vqf_biasSigmaInit, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Std dev of the initial bias estimation uncertainty. Default: 0.5 deg/s"); - ImGui::InputDouble("Bias forgetting time [s]", ¶ms.vqf_biasForgettingTime, 0.0, 0.0, "%.1f"); + ImGui::Checkbox("Use magnetometer", ¶ms.vqf_useMagnetometer); if (ImGui::IsItemHovered()) ImGui::SetTooltip( - "Time in which bias estimation uncertainty increases from 0 to 0.1 deg/s.\nDetermines the system noise assumed by " - "the Kalman filter. Default: 100.0"); - ImGui::InputDouble("Bias clip [deg/s]", ¶ms.vqf_biasClip, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Maximum expected gyroscope bias.\nUsed to clip bias estimate and measurement error in update step.\nAlso used by " - "rest detection to not regard large constant angular rate as rest.\nDefault: 2.0"); - - ImGui::Checkbox("Rest bias estimation", ¶ms.vqf_restBiasEstEnabled); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Enables rest detection and gyroscope bias estimation during rest phases.\nDuring rest, gyro bias is estimated from low-pass filtered gyro readings."); + "Enable 9D mode (gyro+acc+mag) for absolute heading correction.\nDefault: off (6D mode, gyro+acc only, heading " + "from " + "gyro integration)."); - if (params.vqf_restBiasEstEnabled) + if (params.vqf_useMagnetometer && ImGui::TreeNode("VQF Magnetometer")) { - ImGui::InputDouble("Bias sigma rest [deg/s]", ¶ms.vqf_biasSigmaRest, 0.0, 0.0, "%.4f"); + ImGui::InputDouble("tauMag [s]", ¶ms.vqf_tauMag, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Time constant for magnetometer update.\nSmall values imply trust on magnetometer, large values trust on " + "gyroscope.\nCorresponds to cutoff frequency of first-order LP filter\nfor heading correction. Default: 9.0"); + ImGui::Checkbox("Mag disturbance rejection", ¶ms.vqf_magDistRejectionEnabled); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Enables magnetic disturbance detection and rejection.\nFor short disturbances, mag correction is fully " + "disabled.\nFor long disturbances (>magMaxRejectionTime), correction uses\nincreased time constant " + "(magRejectionFactor)."); + ImGui::InputDouble("Mag current tau [s]", ¶ms.vqf_magCurrentTau, 0.0, 0.0, "%.3f"); if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Std dev of converged bias estimation uncertainty during rest.\nDetermines trust on rest bias estimation updates.\nSmall value leads to fast convergence. Default: 0.03"); - ImGui::InputDouble("Rest min time [s]", ¶ms.vqf_restMinT, 0.0, 0.0, "%.2f"); + ImGui::SetTooltip( + "Time constant for current norm/dip value in disturbance detection.\nFast LP filter for robustness with noisy " + "or " + "async mag measurements.\nSet to -1 to disable. Default: 0.05"); + ImGui::InputDouble("Mag ref tau [s]", ¶ms.vqf_magRefTau, 0.0, 0.0, "%.1f"); if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Time threshold for rest detection.\nRest is detected when measurements have been close to\nthe low-pass filtered reference for the given time. Default: 1.5"); - ImGui::InputDouble("Rest filter tau [s]", ¶ms.vqf_restFilterTau, 0.0, 0.0, "%.2f"); + ImGui::SetTooltip( + "Time constant for adjustment of the magnetic field reference.\nAllows reference to converge to observed " + "undisturbed field. Default: 20.0"); + ImGui::InputDouble("Mag norm threshold", ¶ms.vqf_magNormTh, 0.0, 0.0, "%.3f"); if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Time constant for the second-order Butterworth low-pass filter\nused to obtain the reference for rest detection. Default: 0.5"); - ImGui::InputDouble("Rest threshold gyro [deg/s]", ¶ms.vqf_restThGyr, 0.0, 0.0, "%.2f"); + ImGui::SetTooltip( + "Relative threshold for magnetic field strength for disturbance detection.\nRelative to the reference norm. " + "Default: 0.1 (10%%)"); + ImGui::InputDouble("Mag dip threshold [deg]", ¶ms.vqf_magDipTh, 0.0, 0.0, "%.1f"); if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Angular velocity threshold for rest detection.\nDeviation norm between measurement and reference must be below threshold.\nEach component must also be below biasClip. Default: 2.0"); - ImGui::InputDouble("Rest threshold acc [m/s2]", ¶ms.vqf_restThAcc, 0.0, 0.0, "%.2f"); + ImGui::SetTooltip("Threshold for the magnetic field dip angle for disturbance detection. Default: 10.0"); + ImGui::InputDouble("Mag new time [s]", ¶ms.vqf_magNewTime, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Duration after which to accept a different homogeneous magnetic field.\nNew reference accepted when within " + "magNormTh and magDipTh for this time.\nOnly phases with sufficient movement (magNewMinGyr) count. Default: " + "20.0"); + ImGui::InputDouble("Mag new first time [s]", ¶ms.vqf_magNewFirstTime, 0.0, 0.0, "%.1f"); if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Acceleration threshold for rest detection.\nDeviation norm between measurement and reference must be below threshold.\nDefault: 0.5"); + ImGui::SetTooltip( + "Duration after which to accept a homogeneous magnetic field for the first time.\nUsed instead of magNewTime " + "when " + "no current estimate exists,\nto allow faster initial reference acquisition. Default: 5.0"); + ImGui::InputDouble("Mag new min gyro [deg/s]", ¶ms.vqf_magNewMinGyr, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Minimum angular velocity needed to count time for new mag field acceptance.\nPeriods with angular velocity " + "norm " + "below this threshold\ndo not count towards magNewTime. Default: 20.0"); + ImGui::InputDouble("Mag min undisturbed [s]", ¶ms.vqf_magMinUndisturbedTime, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Minimum duration within thresholds after which to regard\nthe field as undisturbed again. Default: 0.5"); + ImGui::InputDouble("Mag max rejection [s]", ¶ms.vqf_magMaxRejectionTime, 0.0, 0.0, "%.1f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Maximum duration of full magnetic disturbance rejection.\nUp to this duration, heading correction is fully " + "disabled\nand tracked by gyroscope only. After this, correction uses\nincreased time constant " + "(magRejectionFactor). Default: 60.0"); + ImGui::InputDouble("Mag rejection factor", ¶ms.vqf_magRejectionFactor, 0.0, 0.0, "%.2f"); + if (ImGui::IsItemHovered()) + ImGui::SetTooltip( + "Factor by which to slow heading correction during long disturbed phases.\nAfter magMaxRejectionTime of full " + "rejection, correction uses\nthis factor to increase the time constant. Default: 2.0"); + ImGui::TreePop(); } - - ImGui::TreePop(); - } - - ImGui::Checkbox("Use magnetometer", ¶ms.vqf_useMagnetometer); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Enable 9D mode (gyro+acc+mag) for absolute heading correction.\nDefault: off (6D mode, gyro+acc only, heading from " - "gyro integration)."); - - if (params.vqf_useMagnetometer && ImGui::TreeNode("VQF Magnetometer")) - { - ImGui::InputDouble("tauMag [s]", ¶ms.vqf_tauMag, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time constant for magnetometer update.\nSmall values imply trust on magnetometer, large values trust on " - "gyroscope.\nCorresponds to cutoff frequency of first-order LP filter\nfor heading correction. Default: 9.0"); - ImGui::Checkbox("Mag disturbance rejection", ¶ms.vqf_magDistRejectionEnabled); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Enables magnetic disturbance detection and rejection.\nFor short disturbances, mag correction is fully " - "disabled.\nFor long disturbances (>magMaxRejectionTime), correction uses\nincreased time constant " - "(magRejectionFactor)."); - ImGui::InputDouble("Mag current tau [s]", ¶ms.vqf_magCurrentTau, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time constant for current norm/dip value in disturbance detection.\nFast LP filter for robustness with noisy or " - "async mag measurements.\nSet to -1 to disable. Default: 0.05"); - ImGui::InputDouble("Mag ref tau [s]", ¶ms.vqf_magRefTau, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Time constant for adjustment of the magnetic field reference.\nAllows reference to converge to observed " - "undisturbed field. Default: 20.0"); - ImGui::InputDouble("Mag norm threshold", ¶ms.vqf_magNormTh, 0.0, 0.0, "%.3f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Relative threshold for magnetic field strength for disturbance detection.\nRelative to the reference norm. " - "Default: 0.1 (10%%)"); - ImGui::InputDouble("Mag dip threshold [deg]", ¶ms.vqf_magDipTh, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip("Threshold for the magnetic field dip angle for disturbance detection. Default: 10.0"); - ImGui::InputDouble("Mag new time [s]", ¶ms.vqf_magNewTime, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Duration after which to accept a different homogeneous magnetic field.\nNew reference accepted when within " - "magNormTh and magDipTh for this time.\nOnly phases with sufficient movement (magNewMinGyr) count. Default: 20.0"); - ImGui::InputDouble("Mag new first time [s]", ¶ms.vqf_magNewFirstTime, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Duration after which to accept a homogeneous magnetic field for the first time.\nUsed instead of magNewTime when " - "no current estimate exists,\nto allow faster initial reference acquisition. Default: 5.0"); - ImGui::InputDouble("Mag new min gyro [deg/s]", ¶ms.vqf_magNewMinGyr, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Minimum angular velocity needed to count time for new mag field acceptance.\nPeriods with angular velocity norm " - "below this threshold\ndo not count towards magNewTime. Default: 20.0"); - ImGui::InputDouble("Mag min undisturbed [s]", ¶ms.vqf_magMinUndisturbedTime, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Minimum duration within thresholds after which to regard\nthe field as undisturbed again. Default: 0.5"); - ImGui::InputDouble("Mag max rejection [s]", ¶ms.vqf_magMaxRejectionTime, 0.0, 0.0, "%.1f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Maximum duration of full magnetic disturbance rejection.\nUp to this duration, heading correction is fully " - "disabled\nand tracked by gyroscope only. After this, correction uses\nincreased time constant " - "(magRejectionFactor). Default: 60.0"); - ImGui::InputDouble("Mag rejection factor", ¶ms.vqf_magRejectionFactor, 0.0, 0.0, "%.2f"); - if (ImGui::IsItemHovered()) - ImGui::SetTooltip( - "Factor by which to slow heading correction during long disturbed phases.\nAfter magMaxRejectionTime of full " - "rejection, correction uses\nthis factor to increase the time constant. Default: 2.0"); - ImGui::TreePop(); - } } // end if (params.use_vqf) ImGui::PopItemWidth(); @@ -1974,7 +1990,7 @@ void display() Eigen::Vector3d start = wd.intermediate_trajectory.front().translation(); Eigen::Vector3d end = start + wd.imu_prediction_vector; - glColor3f(1.0f, 0.0f, 1.0f); // magenta + glColor3f(1.0f, 0.0f, 1.0f); // magenta glVertex3d(start.x(), start.y(), start.z()); glVertex3d(end.x(), end.y(), end.z()); } diff --git a/apps/lidar_odometry_step_1/lidar_odometry_utils.h b/apps/lidar_odometry_step_1/lidar_odometry_utils.h index 79fc86b9..fe0beebf 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry_utils.h +++ b/apps/lidar_odometry_step_1/lidar_odometry_utils.h @@ -14,7 +14,6 @@ #include #include #include -#include #include #include @@ -195,7 +194,8 @@ struct LidarOdometryParams // IMU preintegration bool use_imu_preintegration = false; - int imu_preintegration_method = 6; // 0=euler_body, 1=trapezoidal_body, 2=euler_gravity, 3=trapezoidal_gravity, 4=kalman, 5=euler_ahrs, 6=trapezoidal_ahrs, 7=kalman_ahrs + int imu_preintegration_method = 6; // 0=euler_body, 1=trapezoidal_body, 2=euler_gravity, 3=trapezoidal_gravity, 4=kalman, 5=euler_ahrs, + // 6=trapezoidal_ahrs, 7=kalman_ahrs // ablation study bool ablation_study_use_planarity = false; diff --git a/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp b/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp index 39576215..228ad6d6 100644 --- a/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp +++ b/apps/lidar_odometry_step_1/lidar_odometry_utils_optimizers.cpp @@ -2434,16 +2434,16 @@ bool process_worker_step_1( if (total_imu_time > 0.0) { - bool uses_ahrs_velocity = (method == PreintegrationMethod::euler_gravity_ahrs_vel || - method == PreintegrationMethod::trapezoidal_gravity_ahrs_vel || - method == PreintegrationMethod::kalman_gravity_ahrs_vel); + bool uses_ahrs_velocity = + (method == PreintegrationMethod::euler_gravity_ahrs_vel || + method == PreintegrationMethod::trapezoidal_gravity_ahrs_vel || + method == PreintegrationMethod::kalman_gravity_ahrs_vel); if (uses_ahrs_velocity) { // Methods 5-7: SM-independent velocity // Direction from VQF AHRS, speed from motion model displacement - Eigen::Vector3d prev_mm_displacement = - prev_worker_data.intermediate_trajectory_motion_model.back().translation() - + Eigen::Vector3d prev_mm_displacement = prev_worker_data.intermediate_trajectory_motion_model.back().translation() - prev_worker_data.intermediate_trajectory_motion_model.front().translation(); double speed = prev_mm_displacement.norm() / total_imu_time; @@ -2457,8 +2457,7 @@ bool process_worker_step_1( else { // Methods 0-4: velocity from previous SM trajectory - Eigen::Vector3d prev_displacement = - prev_worker_data.intermediate_trajectory.back().translation() - + Eigen::Vector3d prev_displacement = prev_worker_data.intermediate_trajectory.back().translation() - prev_prev_worker_data.intermediate_trajectory.back().translation(); imu_params.initial_velocity = prev_displacement / total_imu_time; } @@ -2472,7 +2471,7 @@ bool process_worker_step_1( // No preintegration: simple velocity from previous two workers mean_shift = (prev_worker_data.intermediate_trajectory.back().translation() - prev_prev_worker_data.intermediate_trajectory.back().translation()) / - static_cast(prev_worker_data.intermediate_trajectory.size()); + static_cast(prev_worker_data.intermediate_trajectory.size()); } if (mean_shift.norm() > 1.0) diff --git a/apps/mandeye_raw_data_viewer/CMakeLists.txt b/apps/mandeye_raw_data_viewer/CMakeLists.txt index e41f2072..31e4e140 100644 --- a/apps/mandeye_raw_data_viewer/CMakeLists.txt +++ b/apps/mandeye_raw_data_viewer/CMakeLists.txt @@ -39,13 +39,14 @@ target_include_directories( ${THIRDPARTY_DIRECTORY}/portable-file-dialogs-master ${LASZIP_INCLUDE_DIR}/LASzip/include ${THIRDPARTY_DIRECTORY}/observation_equations/codes - ${THIRDPARTY_DIRECTORY}/vqf/vqf/cpp) + ${THIRDPARTY_DIRECTORY}/vqf/vqf/cpp + ${THIRDPARTY_DIRECTORY}/Fusion/Fusion) target_compile_definitions(mandeye_raw_data_viewer PRIVATE UTL_PROFILER_DISABLE) target_link_libraries( mandeye_raw_data_viewer - PRIVATE vqf + PRIVATE vqf Fusion unordered_dense::unordered_dense spdlog::spdlog UTL::include diff --git a/core/include/imu_preintegration.h b/core/include/imu_preintegration.h index 702e928b..c15ab11b 100644 --- a/core/include/imu_preintegration.h +++ b/core/include/imu_preintegration.h @@ -30,16 +30,16 @@ struct IntegrationParams namespace imu_utils { -Eigen::Vector3d convert_accel_to_ms2(const Eigen::Vector3d& raw, bool units_in_g, double g = 9.81); -Eigen::Vector3d convert_gyro_to_rads(const Eigen::Vector3d& raw, bool units_in_deg); -double safe_dt(double t_prev, double t_curr, double max_dt); -bool has_nan(const Eigen::Vector3d& v); -bool is_accel_valid(const Eigen::Vector3d& accel_ms2, double threshold); -std::vector estimate_orientations( - const std::vector& raw_imu_data, - const Eigen::Matrix3d& initial_orientation, - const IntegrationParams& params, - const VQFParams& vqf_params = VQFParams()); + Eigen::Vector3d convert_accel_to_ms2(const Eigen::Vector3d& raw, bool units_in_g, double g = 9.81); + Eigen::Vector3d convert_gyro_to_rads(const Eigen::Vector3d& raw, bool units_in_deg); + double safe_dt(double t_prev, double t_curr, double max_dt); + bool has_nan(const Eigen::Vector3d& v); + bool is_accel_valid(const Eigen::Vector3d& accel_ms2, double threshold); + std::vector estimate_orientations( + const std::vector& raw_imu_data, + const Eigen::Matrix3d& initial_orientation, + const IntegrationParams& params, + const VQFParams& vqf_params = VQFParams()); } // namespace imu_utils class AccelerationModel @@ -128,15 +128,24 @@ inline const char* to_string(PreintegrationMethod method) { switch (method) { - case PreintegrationMethod::euler_no_gravity_sm_vel: return "Euler, no gravity comp., SM velocity"; - case PreintegrationMethod::trapezoidal_no_gravity_sm_vel: return "Trapezoidal, no gravity comp., SM velocity"; - case PreintegrationMethod::euler_gravity_sm_vel: return "Euler, gravity comp., SM velocity"; - case PreintegrationMethod::trapezoidal_gravity_sm_vel: return "Trapezoidal, gravity comp., SM velocity"; - case PreintegrationMethod::kalman_gravity_sm_vel: return "Kalman, gravity comp., SM velocity"; - case PreintegrationMethod::euler_gravity_ahrs_vel: return "Euler, gravity comp., AHRS velocity"; - case PreintegrationMethod::trapezoidal_gravity_ahrs_vel: return "Trapezoidal, gravity comp., AHRS velocity"; - case PreintegrationMethod::kalman_gravity_ahrs_vel: return "Kalman, gravity comp., AHRS velocity"; - default: return "unknown"; + case PreintegrationMethod::euler_no_gravity_sm_vel: + return "Euler, no gravity comp., SM velocity"; + case PreintegrationMethod::trapezoidal_no_gravity_sm_vel: + return "Trapezoidal, no gravity comp., SM velocity"; + case PreintegrationMethod::euler_gravity_sm_vel: + return "Euler, gravity comp., SM velocity"; + case PreintegrationMethod::trapezoidal_gravity_sm_vel: + return "Trapezoidal, gravity comp., SM velocity"; + case PreintegrationMethod::kalman_gravity_sm_vel: + return "Kalman, gravity comp., SM velocity"; + case PreintegrationMethod::euler_gravity_ahrs_vel: + return "Euler, gravity comp., AHRS velocity"; + case PreintegrationMethod::trapezoidal_gravity_ahrs_vel: + return "Trapezoidal, gravity comp., AHRS velocity"; + case PreintegrationMethod::kalman_gravity_ahrs_vel: + return "Kalman, gravity comp., AHRS velocity"; + default: + return "unknown"; } } diff --git a/core/src/imu_preintegration.cpp b/core/src/imu_preintegration.cpp index f825edbd..60f6f697 100644 --- a/core/src/imu_preintegration.cpp +++ b/core/src/imu_preintegration.cpp @@ -10,136 +10,138 @@ namespace imu_utils { -Eigen::Vector3d convert_accel_to_ms2(const Eigen::Vector3d& raw, bool units_in_g, double g) -{ - if (units_in_g) - return raw * g; - return raw; -} - -Eigen::Vector3d convert_gyro_to_rads(const Eigen::Vector3d& raw, bool units_in_deg) -{ - if (units_in_deg) - return raw * (M_PI / 180.0); - return raw; -} - -double safe_dt(double t_prev, double t_curr, double max_dt) -{ - double dt = t_curr - t_prev; - if (dt <= 0.0 || std::isnan(dt)) - return 0.0; - return std::min(dt, max_dt); -} - -bool has_nan(const Eigen::Vector3d& v) -{ - return std::isnan(v.x()) || std::isnan(v.y()) || std::isnan(v.z()); -} - -bool is_accel_valid(const Eigen::Vector3d& accel_ms2, double threshold) -{ - return accel_ms2.norm() < threshold && !has_nan(accel_ms2); -} - -std::vector estimate_orientations( - const std::vector& raw_imu_data, - const Eigen::Matrix3d& initial_orientation, - const IntegrationParams& params, - const VQFParams& vqf_params) -{ - std::vector orientations; - orientations.reserve(raw_imu_data.size()); - orientations.push_back(initial_orientation); + Eigen::Vector3d convert_accel_to_ms2(const Eigen::Vector3d& raw, bool units_in_g, double g) + { + if (units_in_g) + return raw * g; + return raw; + } - // Compute average dt - double avg_dt = 1.0 / 200.0; - if (raw_imu_data.size() >= 2) + Eigen::Vector3d convert_gyro_to_rads(const Eigen::Vector3d& raw, bool units_in_deg) { - double total_time = raw_imu_data.back().timestamp - raw_imu_data.front().timestamp; - if (total_time > 0.0) - avg_dt = total_time / static_cast(raw_imu_data.size() - 1); + if (units_in_deg) + return raw * (M_PI / 180.0); + return raw; } - // Seed quaternion from initial_orientation - Eigen::Quaterniond init_q(initial_orientation); - init_q.normalize(); + double safe_dt(double t_prev, double t_curr, double max_dt) + { + double dt = t_curr - t_prev; + if (dt <= 0.0 || std::isnan(dt)) + return 0.0; + return std::min(dt, max_dt); + } - // Initialize selected AHRS - VQF vqf(vqf_params, avg_dt); - FusionAhrs fusion_ahrs; - if (!params.use_vqf) + bool has_nan(const Eigen::Vector3d& v) { - FusionAhrsInitialise(&fusion_ahrs); - switch (params.fusion_convention) - { - case AhrsConvention::NWU: fusion_ahrs.settings.convention = FusionConventionNwu; break; - case AhrsConvention::ENU: fusion_ahrs.settings.convention = FusionConventionEnu; break; - case AhrsConvention::NED: fusion_ahrs.settings.convention = FusionConventionNed; break; - } - fusion_ahrs.settings.gain = static_cast(params.fusion_gain); - // Seed Fusion with initial orientation (Fusion has no internal bias estimation) - fusion_ahrs.quaternion = (FusionQuaternion){ - .element = { .w = static_cast(init_q.w()), - .x = static_cast(init_q.x()), - .y = static_cast(init_q.y()), - .z = static_cast(init_q.z()) } }; - fusion_ahrs.initialising = false; + return std::isnan(v.x()) || std::isnan(v.y()) || std::isnan(v.z()); } - constexpr double RAD_TO_DEG = 180.0 / M_PI; + bool is_accel_valid(const Eigen::Vector3d& accel_ms2, double threshold) + { + return accel_ms2.norm() < threshold && !has_nan(accel_ms2); + } - for (size_t k = 1; k < raw_imu_data.size(); k++) + std::vector estimate_orientations( + const std::vector& raw_imu_data, + const Eigen::Matrix3d& initial_orientation, + const IntegrationParams& params, + const VQFParams& vqf_params) { - double dt = safe_dt(raw_imu_data[k - 1].timestamp, raw_imu_data[k].timestamp, params.max_dt_threshold); - if (dt == 0.0) + std::vector orientations; + orientations.reserve(raw_imu_data.size()); + orientations.push_back(initial_orientation); + + // Compute average dt + double avg_dt = 1.0 / 200.0; + if (raw_imu_data.size() >= 2) { - orientations.push_back(orientations.back()); - continue; + double total_time = raw_imu_data.back().timestamp - raw_imu_data.front().timestamp; + if (total_time > 0.0) + avg_dt = total_time / static_cast(raw_imu_data.size() - 1); } - if (params.use_vqf) + // Seed quaternion from initial_orientation + Eigen::Quaterniond init_q(initial_orientation); + init_q.normalize(); + + // Initialize selected AHRS + VQF vqf(vqf_params, avg_dt); + FusionAhrs fusion_ahrs; + if (!params.use_vqf) { - // VQF expects: gyro in rad/s, acc in m/s² - const double g = 9.81; - vqf_real_t gyr[3] = { - raw_imu_data[k].guroscopes.x(), - raw_imu_data[k].guroscopes.y(), - raw_imu_data[k].guroscopes.z() }; - vqf_real_t acc[3] = { - raw_imu_data[k].accelerometers.x() * g, - raw_imu_data[k].accelerometers.y() * g, - raw_imu_data[k].accelerometers.z() * g }; - - vqf.update(gyr, acc); - - vqf_real_t quat[4]; - vqf.getQuat6D(quat); - Eigen::Quaterniond q(quat[0], quat[1], quat[2], quat[3]); - orientations.push_back(q.toRotationMatrix()); + FusionAhrsInitialise(&fusion_ahrs); + switch (params.fusion_convention) + { + case AhrsConvention::NWU: + fusion_ahrs.settings.convention = FusionConventionNwu; + break; + case AhrsConvention::ENU: + fusion_ahrs.settings.convention = FusionConventionEnu; + break; + case AhrsConvention::NED: + fusion_ahrs.settings.convention = FusionConventionNed; + break; + } + fusion_ahrs.settings.gain = static_cast(params.fusion_gain); + // Seed Fusion with initial orientation (Fusion has no internal bias estimation) + FusionQuaternion init_fq; + init_fq.element.w = static_cast(init_q.w()); + init_fq.element.x = static_cast(init_q.x()); + init_fq.element.y = static_cast(init_q.y()); + init_fq.element.z = static_cast(init_q.z()); + fusion_ahrs.quaternion = init_fq; + fusion_ahrs.initialising = false; } - else + + constexpr double RAD_TO_DEG = 180.0 / M_PI; + + for (size_t k = 1; k < raw_imu_data.size(); k++) { - // Fusion expects: gyro in deg/s, acc in g - // Subtract gyro bias (Fusion has no internal bias estimation, unlike VQF) - const FusionVector gyroscope = { - static_cast(raw_imu_data[k].guroscopes.x() * RAD_TO_DEG - params.gyro_bias_dps.x()), - static_cast(raw_imu_data[k].guroscopes.y() * RAD_TO_DEG - params.gyro_bias_dps.y()), - static_cast(raw_imu_data[k].guroscopes.z() * RAD_TO_DEG - params.gyro_bias_dps.z()) }; - const FusionVector accelerometer = { - static_cast(raw_imu_data[k].accelerometers.x()), - static_cast(raw_imu_data[k].accelerometers.y()), - static_cast(raw_imu_data[k].accelerometers.z()) }; - - FusionAhrsUpdateNoMagnetometer(&fusion_ahrs, gyroscope, accelerometer, static_cast(dt)); - - FusionQuaternion quat = FusionAhrsGetQuaternion(&fusion_ahrs); - Eigen::Quaterniond q(quat.element.w, quat.element.x, quat.element.y, quat.element.z); - orientations.push_back(q.toRotationMatrix()); + double dt = safe_dt(raw_imu_data[k - 1].timestamp, raw_imu_data[k].timestamp, params.max_dt_threshold); + if (dt == 0.0) + { + orientations.push_back(orientations.back()); + continue; + } + + if (params.use_vqf) + { + // VQF expects: gyro in rad/s, acc in m/s² + const double g = 9.81; + vqf_real_t gyr[3] = { raw_imu_data[k].guroscopes.x(), raw_imu_data[k].guroscopes.y(), raw_imu_data[k].guroscopes.z() }; + vqf_real_t acc[3] = { raw_imu_data[k].accelerometers.x() * g, + raw_imu_data[k].accelerometers.y() * g, + raw_imu_data[k].accelerometers.z() * g }; + + vqf.update(gyr, acc); + + vqf_real_t quat[4]; + vqf.getQuat6D(quat); + Eigen::Quaterniond q(quat[0], quat[1], quat[2], quat[3]); + orientations.push_back(q.toRotationMatrix()); + } + else + { + // Fusion expects: gyro in deg/s, acc in g + // Subtract gyro bias (Fusion has no internal bias estimation, unlike VQF) + const FusionVector gyroscope = { static_cast(raw_imu_data[k].guroscopes.x() * RAD_TO_DEG - params.gyro_bias_dps.x()), + static_cast(raw_imu_data[k].guroscopes.y() * RAD_TO_DEG - params.gyro_bias_dps.y()), + static_cast( + raw_imu_data[k].guroscopes.z() * RAD_TO_DEG - params.gyro_bias_dps.z()) }; + const FusionVector accelerometer = { static_cast(raw_imu_data[k].accelerometers.x()), + static_cast(raw_imu_data[k].accelerometers.y()), + static_cast(raw_imu_data[k].accelerometers.z()) }; + + FusionAhrsUpdateNoMagnetometer(&fusion_ahrs, gyroscope, accelerometer, static_cast(dt)); + + FusionQuaternion quat = FusionAhrsGetQuaternion(&fusion_ahrs); + Eigen::Quaterniond q(quat.element.w, quat.element.x, quat.element.y, quat.element.z); + orientations.push_back(q.toRotationMatrix()); + } } + return orientations; } - return orientations; -} } // namespace imu_utils @@ -350,25 +352,24 @@ Eigen::Vector3d ImuPreintegration::create_and_preintegrate( case PreintegrationMethod::euler_gravity_ahrs_vel: case PreintegrationMethod::trapezoidal_gravity_ahrs_vel: case PreintegrationMethod::kalman_gravity_ahrs_vel: - { - // Per-worker AHRS: estimate local orientations from IMU data (VQF or Fusion based on params.use_vqf) - auto orientations = imu_utils::estimate_orientations( - raw_imu_data, new_trajectory[0].rotation(), params, vqf_params); - - std::vector imu_trajectory = new_trajectory; - for (size_t k = 0; k < imu_trajectory.size() && k < orientations.size(); k++) - imu_trajectory[k].linear() = orientations[k]; - - accel_model = std::make_unique(); - if (method == PreintegrationMethod::euler_gravity_ahrs_vel) - integration_method = std::make_unique(); - else if (method == PreintegrationMethod::trapezoidal_gravity_ahrs_vel) - integration_method = std::make_unique(); - else - integration_method = std::make_unique(); - - return preint.preintegrate(raw_imu_data, imu_trajectory, *accel_model, *integration_method); - } + { + // Per-worker AHRS: estimate local orientations from IMU data (VQF or Fusion based on params.use_vqf) + auto orientations = imu_utils::estimate_orientations(raw_imu_data, new_trajectory[0].rotation(), params, vqf_params); + + std::vector imu_trajectory = new_trajectory; + for (size_t k = 0; k < imu_trajectory.size() && k < orientations.size(); k++) + imu_trajectory[k].linear() = orientations[k]; + + accel_model = std::make_unique(); + if (method == PreintegrationMethod::euler_gravity_ahrs_vel) + integration_method = std::make_unique(); + else if (method == PreintegrationMethod::trapezoidal_gravity_ahrs_vel) + integration_method = std::make_unique(); + else + integration_method = std::make_unique(); + + return preint.preintegrate(raw_imu_data, imu_trajectory, *accel_model, *integration_method); + } default: std::cerr << "ImuPreintegration: unknown method " << static_cast(method) << std::endl; return Eigen::Vector3d::Zero(); diff --git a/pybind/CMakeLists.txt b/pybind/CMakeLists.txt index a08647a7..54400962 100644 --- a/pybind/CMakeLists.txt +++ b/pybind/CMakeLists.txt @@ -91,6 +91,7 @@ target_include_directories(lidar_odometry_py ${EIGEN3_INCLUDE_DIR} ${LASZIP_INCLUDE_DIR}/LASzip/include ${THIRDPARTY_DIRECTORY}/vqf/vqf/cpp + ${THIRDPARTY_DIRECTORY}/Fusion/Fusion ${THIRDPARTY_DIRECTORY}/json/include ${THIRDPARTY_DIRECTORY}/tomlplusplus/include ${THIRDPARTY_DIRECTORY} @@ -129,6 +130,7 @@ target_link_libraries(lidar_odometry_py UTL::include ${PLATFORM_LASZIP_LIB} vqf + Fusion ${PLATFORM_MISCELLANEOUS_LIBS} )