| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // This file is part of INSTINCT, the INS Toolkit for Integrated | ||
| 2 | // Navigation Concepts and Training by the Institute of Navigation of | ||
| 3 | // the University of Stuttgart, Germany. | ||
| 4 | // | ||
| 5 | // This Source Code Form is subject to the terms of the Mozilla Public | ||
| 6 | // License, v. 2.0. If a copy of the MPL was not distributed with this | ||
| 7 | // file, You can obtain one at https://mozilla.org/MPL/2.0/. | ||
| 8 | |||
| 9 | /// @file InertialPreIntegrator.cpp | ||
| 10 | /// @brief Inertial Measurement Preintegrator | ||
| 11 | /// @author T. Topp (topp@ins.uni-stuttgart.de) | ||
| 12 | /// @date 2025-07-03 | ||
| 13 | |||
| 14 | #include "InertialPreIntegrator.hpp" | ||
| 15 | |||
| 16 | #include "internal/gui/NodeEditorApplication.hpp" | ||
| 17 | #include "internal/gui/widgets/HelpMarker.hpp" | ||
| 18 | |||
| 19 | #include "Navigation/Math/Math.hpp" | ||
| 20 | #include "util/Eigen.hpp" | ||
| 21 | #include "util/Assert.h" | ||
| 22 | |||
| 23 | namespace NAV | ||
| 24 | { | ||
| 25 | |||
| 26 | ✗ | InertialPreIntegrator::InertialPreIntegrator(IntegrationFrame integrationFrame) | |
| 27 | ✗ | : _integrationFrame(integrationFrame), _lockIntegrationFrame(true) {} | |
| 28 | |||
| 29 | ✗ | void InertialPreIntegrator::reset() | |
| 30 | { | ||
| 31 | ✗ | _timeIncrement = 0.0; | |
| 32 | ✗ | _attitudeIncrement.setIdentity(); | |
| 33 | ✗ | _velocityIncrement.setZero(); | |
| 34 | ✗ | _positionIncrement.setZero(); | |
| 35 | ✗ | _covMatrix.setZero(); | |
| 36 | |||
| 37 | ✗ | _pAtt_pOmega.setZero(); | |
| 38 | ✗ | _pVel_pAccel.setZero(); | |
| 39 | ✗ | _pVel_pOmega.setZero(); | |
| 40 | ✗ | _pPos_pAccel.setZero(); | |
| 41 | ✗ | _pPos_pOmega.setZero(); | |
| 42 | ✗ | } | |
| 43 | |||
| 44 | ✗ | void InertialPreIntegrator::setImuNoiseScaleMatrix(const Eigen::Matrix6d& W) | |
| 45 | { | ||
| 46 | ✗ | _imuNoiseScale_W = W; | |
| 47 | ✗ | } | |
| 48 | |||
| 49 | ✗ | void InertialPreIntegrator::addInertialMeasurement(const Measurement& meas, const ImuPos& imuPos, [[maybe_unused]] const std::string& nameId) | |
| 50 | { | ||
| 51 | ✗ | INS_ASSERT_USER_ERROR((_attitudeIncrement == Eigen::Quaterniond::Identity() | |
| 52 | && _velocityIncrement == Eigen::Vector3d::Zero() | ||
| 53 | && _positionIncrement == Eigen::Vector3d::Zero()) | ||
| 54 | || _imuState == meas.imu, | ||
| 55 | "The IMU state (bias, scale factor, misalignment) must be constant over the whole increment period."); | ||
| 56 | |||
| 57 | // LOG_DATA("{}: addInertialMeasurement (dt = {})", nameId, meas.meas.dt); | ||
| 58 | // LOG_DATA("{}: timeIncrement (before) = {}", nameId, _timeIncrement); | ||
| 59 | // LOG_DATA("{}: attitudeIncrement (before) = {}", nameId, _attitudeIncrement); | ||
| 60 | // LOG_DATA("{}: velocityIncrement (before) = {}", nameId, _velocityIncrement.transpose()); | ||
| 61 | // LOG_DATA("{}: positionIncrement (before) = {}", nameId, _positionIncrement.transpose()); | ||
| 62 | |||
| 63 | ✗ | Eigen::Vector3d b_deltaRot = imuPos.b_quat_p() | |
| 64 | ✗ | * (/* (meas.imu.misalignmentGyro * */ meas.meas.p_angularRate /* ).cwiseProduct(meas.imu.scaleFactorGyro) */ | |
| 65 | ✗ | + meas.imu.p_biasAngularRate) | |
| 66 | ✗ | * meas.meas.dt; | |
| 67 | ✗ | Eigen::Quaterniond bk_quat_bkp1 = math::expMapQuat(b_deltaRot); | |
| 68 | // LOG_DATA("{}: bk_quat_bkp1 = {}", nameId, bk_quat_bkp1); | ||
| 69 | ✗ | Eigen::Vector3d b_accel = (imuPos.b_quat_p() | |
| 70 | ✗ | * (/* (meas.imu.misalignmentAccel * */ meas.meas.p_acceleration /* ).cwiseProduct(meas.imu.scaleFactorAccel) */ | |
| 71 | ✗ | + meas.imu.p_biasAcceleration)); | |
| 72 | ✗ | Eigen::Vector3d dv_k_kp1 = _attitudeIncrement * b_accel * meas.meas.dt; | |
| 73 | // LOG_DATA("{}: dv_k_kp1 = {}", nameId, dv_k_kp1.transpose()); | ||
| 74 | ✗ | Eigen::Vector3d dp_k_kp1 = (_velocityIncrement + 0.5 * dv_k_kp1) * meas.meas.dt; | |
| 75 | // LOG_DATA("{}: dp_k_kp1 = {}", nameId, dp_k_kp1.transpose()); | ||
| 76 | |||
| 77 | // --------------------------------------- Jacobian calculation ------------------------------------------ | ||
| 78 | ✗ | Eigen::Matrix3d i_R_k = _attitudeIncrement.toRotationMatrix(); | |
| 79 | ✗ | Eigen::Matrix3d b_accelSkew = math::skewSymmetricMatrix(b_accel); | |
| 80 | ✗ | Eigen::Matrix3d J_r_rot = math::J_r(b_deltaRot); | |
| 81 | ✗ | Eigen::Quaterniond bkp1_quat_bk = bk_quat_bkp1.conjugate(); | |
| 82 | |||
| 83 | ✗ | _pAtt_pOmega = bkp1_quat_bk * _pAtt_pOmega + J_r_rot * meas.meas.dt; | |
| 84 | ✗ | _pVel_pAccel += i_R_k * meas.meas.dt; | |
| 85 | ✗ | Eigen::Matrix3d pDeltaVel_pOmega = _attitudeIncrement * b_accelSkew * _pAtt_pOmega * meas.meas.dt; | |
| 86 | ✗ | _pVel_pOmega -= pDeltaVel_pOmega; | |
| 87 | ✗ | _pPos_pAccel += _pVel_pAccel * meas.meas.dt - i_R_k * (std::pow(meas.meas.dt, 2) / 2.0); | |
| 88 | ✗ | _pPos_pOmega += _pVel_pOmega * meas.meas.dt - pDeltaVel_pOmega * (meas.meas.dt / 2.0); | |
| 89 | |||
| 90 | // -------------------------------------- Covariance propagation ----------------------------------------- | ||
| 91 | ✗ | if (_imuNoiseScale_W) | |
| 92 | { | ||
| 93 | ✗ | Eigen::Matrix9d A = Eigen::Matrix9d::Zero(); | |
| 94 | ✗ | A.block<3, 3>(0, 0) = bkp1_quat_bk.toRotationMatrix(); | |
| 95 | ✗ | A.block<3, 3>(3, 0) = -i_R_k * b_accelSkew * meas.meas.dt; | |
| 96 | ✗ | A.block<3, 3>(3, 3).setIdentity(); | |
| 97 | ✗ | A.block<3, 3>(6, 0) = 0.5 * A.block<3, 3>(3, 0) * meas.meas.dt; | |
| 98 | ✗ | A.block<3, 3>(6, 3).diagonal().setConstant(meas.meas.dt); | |
| 99 | ✗ | A.block<3, 3>(6, 6).setIdentity(); | |
| 100 | |||
| 101 | ✗ | Eigen::Matrix<double, 9, 6> B = Eigen::Matrix<double, 9, 6>::Zero(); | |
| 102 | ✗ | B.block<3, 3>(0, 0) = J_r_rot * meas.meas.dt; | |
| 103 | ✗ | B.block<3, 3>(3, 3) = i_R_k * meas.meas.dt; | |
| 104 | ✗ | B.block<3, 3>(6, 3) = 0.5 * B.block<3, 3>(3, 3) * meas.meas.dt; | |
| 105 | |||
| 106 | ✗ | _covMatrix = A * _covMatrix * A.transpose() + B * (*_imuNoiseScale_W * meas.meas.dt) * B.transpose(); | |
| 107 | } | ||
| 108 | |||
| 109 | // --------------------------------------- Accumulate increments ----------------------------------------- | ||
| 110 | |||
| 111 | ✗ | _timeIncrement += meas.meas.dt; | |
| 112 | ✗ | _attitudeIncrement *= bk_quat_bkp1; // bi_q_bk --> bi_q_bkp1 ( final value: bi_q_bj ) | |
| 113 | ✗ | _velocityIncrement += dv_k_kp1; | |
| 114 | ✗ | _positionIncrement += dp_k_kp1; | |
| 115 | // LOG_DATA("{}: timeIncrement (after) = {}", nameId, _timeIncrement); | ||
| 116 | // LOG_DATA("{}: attitudeIncrement (after) = {}", nameId, _attitudeIncrement); | ||
| 117 | // LOG_DATA("{}: velocityIncrement (after) = {}", nameId, _velocityIncrement.transpose()); | ||
| 118 | // LOG_DATA("{}: positionIncrement (after) = {}", nameId, _positionIncrement.transpose()); | ||
| 119 | |||
| 120 | ✗ | _imuState = meas.imu; | |
| 121 | ✗ | } | |
| 122 | |||
| 123 | ✗ | [[nodiscard]] const Eigen::Matrix9d& InertialPreIntegrator::getCovMatrix() const | |
| 124 | { | ||
| 125 | ✗ | return _covMatrix; | |
| 126 | } | ||
| 127 | |||
| 128 | ✗ | [[nodiscard]] InertialPreIntegrator::IntegrationFrame InertialPreIntegrator::getIntegrationFrame() const | |
| 129 | { | ||
| 130 | ✗ | return _integrationFrame; | |
| 131 | } | ||
| 132 | |||
| 133 | ✗ | bool InertialPreIntegratorGui(const char* label, InertialPreIntegrator& integrator, float width) | |
| 134 | { | ||
| 135 | ✗ | bool changed = false; | |
| 136 | |||
| 137 | ✗ | if (integrator._lockIntegrationFrame) { ImGui::BeginDisabled(); } | |
| 138 | ✗ | ImGui::SetNextItemWidth(width * gui::NodeEditorApplication::windowFontRatio()); | |
| 139 | ✗ | if (auto integrationFrame = static_cast<int>(integrator._integrationFrame); | |
| 140 | ✗ | ImGui::Combo(fmt::format("Integration Frame##{}", label).c_str(), &integrationFrame, "ECEF\0NED\0\0")) | |
| 141 | { | ||
| 142 | ✗ | integrator._integrationFrame = static_cast<decltype(integrator._integrationFrame)>(integrationFrame); | |
| 143 | ✗ | LOG_DEBUG("Integration Frame changed to {}", integrator._integrationFrame == InertialPreIntegrator::IntegrationFrame::NED ? "NED" : "ECEF"); | |
| 144 | ✗ | changed = true; | |
| 145 | } | ||
| 146 | ✗ | if (integrator._lockIntegrationFrame) { ImGui::EndDisabled(); } | |
| 147 | |||
| 148 | ✗ | ImGui::SetNextItemOpen(false, ImGuiCond_FirstUseEver); | |
| 149 | ✗ | if (ImGui::TreeNode(fmt::format("Compensation models##{}", label).c_str())) | |
| 150 | { | ||
| 151 | ✗ | ImGui::TextUnformatted("Acceleration compensation"); | |
| 152 | { | ||
| 153 | ✗ | ImGui::Indent(); | |
| 154 | ✗ | ImGui::SetNextItemWidth(230 * gui::NodeEditorApplication::windowFontRatio()); | |
| 155 | ✗ | if (ComboGravitationModel(fmt::format("Gravitation Model##{}", label).c_str(), integrator._gravitationModel)) | |
| 156 | { | ||
| 157 | ✗ | LOG_DEBUG("Gravity Model changed to {}", NAV::to_string(integrator._gravitationModel)); | |
| 158 | ✗ | changed = true; | |
| 159 | } | ||
| 160 | // if (ImGui::Checkbox(fmt::format("Coriolis acceleration ##{}", label).c_str(), &integrator._posVelAttDerivativeConstants.coriolisAccelerationCompensationEnabled)) | ||
| 161 | // { | ||
| 162 | // LOG_DEBUG("coriolisAccelerationCompensationEnabled changed to {}", integrator._posVelAttDerivativeConstants.coriolisAccelerationCompensationEnabled); | ||
| 163 | // changed = true; | ||
| 164 | // } | ||
| 165 | // if (ImGui::Checkbox(fmt::format("Centrifugal acceleration##{}", label).c_str(), &integrator._posVelAttDerivativeConstants.centrifgalAccelerationCompensationEnabled)) | ||
| 166 | // { | ||
| 167 | // LOG_DEBUG("centrifgalAccelerationCompensationEnabled changed to {}", integrator._posVelAttDerivativeConstants.centrifgalAccelerationCompensationEnabled); | ||
| 168 | // changed = true; | ||
| 169 | // } | ||
| 170 | ✗ | ImGui::Unindent(); | |
| 171 | } | ||
| 172 | // ImGui::TextUnformatted("Angular rate compensation"); | ||
| 173 | // { | ||
| 174 | // ImGui::Indent(); | ||
| 175 | // if (ImGui::Checkbox(fmt::format("Earth rotation rate##{}", label).c_str(), &integrator._posVelAttDerivativeConstants.angularRateEarthRotationCompensationEnabled)) | ||
| 176 | // { | ||
| 177 | // LOG_DEBUG("angularRateEarthRotationCompensationEnabled changed to {}", integrator._posVelAttDerivativeConstants.angularRateEarthRotationCompensationEnabled); | ||
| 178 | // changed = true; | ||
| 179 | // } | ||
| 180 | // if (integrator._integrationFrame == InertialPreIntegrator::IntegrationFrame::NED) | ||
| 181 | // { | ||
| 182 | // if (ImGui::Checkbox(fmt::format("Transport rate##{}", label).c_str(), &integrator._posVelAttDerivativeConstants.angularRateTransportRateCompensationEnabled)) | ||
| 183 | // { | ||
| 184 | // LOG_DEBUG("angularRateTransportRateCompensationEnabled changed to {}", integrator._posVelAttDerivativeConstants.angularRateTransportRateCompensationEnabled); | ||
| 185 | // changed = true; | ||
| 186 | // } | ||
| 187 | // } | ||
| 188 | // ImGui::Unindent(); | ||
| 189 | // } | ||
| 190 | |||
| 191 | ✗ | ImGui::TreePop(); | |
| 192 | } | ||
| 193 | |||
| 194 | ✗ | return changed; | |
| 195 | } | ||
| 196 | |||
| 197 | ✗ | void to_json(json& j, const InertialPreIntegrator& data) | |
| 198 | { | ||
| 199 | ✗ | j = json{ | |
| 200 | ✗ | { "integrationFrame", data._integrationFrame }, | |
| 201 | ✗ | { "gravitationModel", data._gravitationModel }, | |
| 202 | ✗ | { "lockIntegrationFrame", data._lockIntegrationFrame }, | |
| 203 | ✗ | }; | |
| 204 | ✗ | } | |
| 205 | |||
| 206 | ✗ | void from_json(const json& j, InertialPreIntegrator& data) | |
| 207 | { | ||
| 208 | ✗ | if (j.contains("integrationFrame")) { j.at("integrationFrame").get_to(data._integrationFrame); } | |
| 209 | ✗ | if (j.contains("gravitationModel")) { j.at("gravitationModel").get_to(data._gravitationModel); } | |
| 210 | ✗ | if (j.contains("lockIntegrationFrame")) { j.at("lockIntegrationFrame").get_to(data._lockIntegrationFrame); } | |
| 211 | ✗ | } | |
| 212 | |||
| 213 | ✗ | const char* to_string(InertialPreIntegrator::IntegrationFrame frame) | |
| 214 | { | ||
| 215 | ✗ | switch (frame) | |
| 216 | { | ||
| 217 | ✗ | case InertialPreIntegrator::IntegrationFrame::ECEF: | |
| 218 | ✗ | return "ECEF"; | |
| 219 | ✗ | case InertialPreIntegrator::IntegrationFrame::NED: | |
| 220 | ✗ | return "NED"; | |
| 221 | } | ||
| 222 | ✗ | return ""; | |
| 223 | } | ||
| 224 | |||
| 225 | } // namespace NAV | ||
| 226 |