Skip to content

Commit c6bd3f8

Browse files
authored
Merge pull request #1762 from borglab/fix/ahrs
Correctly deal with sensor rotation in AHRS
2 parents feab2a2 + a90dbc7 commit c6bd3f8

8 files changed

+567
-339
lines changed

.gitignore

+1
Original file line numberDiff line numberDiff line change
@@ -19,3 +19,4 @@ CMakeLists.txt.user*
1919
xcode/
2020
/Dockerfile
2121
/python/gtsam/notebooks/.ipynb_checkpoints/ellipses-checkpoint.ipynb
22+
.cache/

gtsam/navigation/AHRSFactor.cpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -49,13 +49,14 @@ void PreintegratedAhrsMeasurements::resetIntegration() {
4949
//------------------------------------------------------------------------------
5050
void PreintegratedAhrsMeasurements::integrateMeasurement(
5151
const Vector3& measuredOmega, double deltaT) {
52-
53-
Matrix3 D_incrR_integratedOmega, Fr;
54-
PreintegratedRotation::integrateMeasurement(measuredOmega,
55-
biasHat_, deltaT, &D_incrR_integratedOmega, &Fr);
56-
57-
// first order uncertainty propagation
58-
// the deltaT allows to pass from continuous time noise to discrete time noise
52+
Matrix3 Fr;
53+
PreintegratedRotation::integrateGyroMeasurement(measuredOmega, biasHat_,
54+
deltaT, &Fr);
55+
56+
// First order uncertainty propagation
57+
// The deltaT allows to pass from continuous time noise to discrete time
58+
// noise. Comparing with the IMUFactor.cpp implementation, the latter is an
59+
// approximation for C * (wCov / dt) * C.transpose(), with C \approx I * dt.
5960
preintMeasCov_ = Fr * preintMeasCov_ * Fr.transpose() + p().gyroscopeCovariance * deltaT;
6061
}
6162

gtsam/navigation/PreintegratedRotation.cpp

+40-23
Original file line numberDiff line numberDiff line change
@@ -68,49 +68,66 @@ bool PreintegratedRotation::equals(const PreintegratedRotation& other,
6868
&& equal_with_abs_tol(delRdelBiasOmega_, other.delRdelBiasOmega_, tol);
6969
}
7070

71-
Rot3 PreintegratedRotation::incrementalRotation(const Vector3& measuredOmega,
72-
const Vector3& biasHat, double deltaT,
73-
OptionalJacobian<3, 3> D_incrR_integratedOmega) const {
74-
71+
namespace internal {
72+
Rot3 IncrementalRotation::operator()(
73+
const Vector3& bias, OptionalJacobian<3, 3> H_bias) const {
7574
// First we compensate the measurements for the bias
76-
Vector3 correctedOmega = measuredOmega - biasHat;
75+
Vector3 correctedOmega = measuredOmega - bias;
7776

7877
// Then compensate for sensor-body displacement: we express the quantities
79-
// (originally in the IMU frame) into the body frame
80-
if (p_->body_P_sensor) {
81-
Matrix3 body_R_sensor = p_->body_P_sensor->rotation().matrix();
78+
// (originally in the IMU frame) into the body frame. If Jacobian is
79+
// requested, the rotation matrix is obtained as `rotate` Jacobian.
80+
Matrix3 body_R_sensor;
81+
if (body_P_sensor) {
8282
// rotation rate vector in the body frame
83-
correctedOmega = body_R_sensor * correctedOmega;
83+
correctedOmega = body_P_sensor->rotation().rotate(
84+
correctedOmega, {}, H_bias ? &body_R_sensor : nullptr);
8485
}
8586

8687
// rotation vector describing rotation increment computed from the
8788
// current rotation rate measurement
8889
const Vector3 integratedOmega = correctedOmega * deltaT;
89-
return Rot3::Expmap(integratedOmega, D_incrR_integratedOmega); // expensive !!
90+
Rot3 incrR = Rot3::Expmap(integratedOmega, H_bias); // expensive !!
91+
if (H_bias) {
92+
*H_bias *= -deltaT; // Correct so accurately reflects bias derivative
93+
if (body_P_sensor) *H_bias *= body_R_sensor;
94+
}
95+
return incrR;
9096
}
97+
} // namespace internal
9198

92-
void PreintegratedRotation::integrateMeasurement(const Vector3& measuredOmega,
93-
const Vector3& biasHat, double deltaT,
94-
OptionalJacobian<3, 3> optional_D_incrR_integratedOmega,
99+
void PreintegratedRotation::integrateGyroMeasurement(
100+
const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
95101
OptionalJacobian<3, 3> F) {
96-
Matrix3 D_incrR_integratedOmega;
97-
const Rot3 incrR = incrementalRotation(measuredOmega, biasHat, deltaT,
98-
D_incrR_integratedOmega);
99-
100-
// If asked, pass first derivative as well
101-
if (optional_D_incrR_integratedOmega) {
102-
*optional_D_incrR_integratedOmega << D_incrR_integratedOmega;
103-
}
102+
Matrix3 H_bias;
103+
internal::IncrementalRotation f{measuredOmega, deltaT, p_->body_P_sensor};
104+
const Rot3 incrR = f(biasHat, H_bias);
104105

105106
// Update deltaTij and rotation
106107
deltaTij_ += deltaT;
107108
deltaRij_ = deltaRij_.compose(incrR, F);
108109

109110
// Update Jacobian
110111
const Matrix3 incrRt = incrR.transpose();
111-
delRdelBiasOmega_ = incrRt * delRdelBiasOmega_
112-
- D_incrR_integratedOmega * deltaT;
112+
delRdelBiasOmega_ = incrRt * delRdelBiasOmega_ + H_bias;
113+
}
114+
115+
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
116+
void PreintegratedRotation::integrateMeasurement(
117+
const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
118+
OptionalJacobian<3, 3> optional_D_incrR_integratedOmega,
119+
OptionalJacobian<3, 3> F) {
120+
integrateGyroMeasurement(measuredOmega, biasHat, deltaT, F);
121+
122+
// If asked, pass obsolete Jacobians as well
123+
if (optional_D_incrR_integratedOmega) {
124+
Matrix3 H_bias;
125+
internal::IncrementalRotation f{measuredOmega, deltaT, p_->body_P_sensor};
126+
const Rot3 incrR = f(biasHat, H_bias);
127+
*optional_D_incrR_integratedOmega << H_bias / -deltaT;
128+
}
113129
}
130+
#endif
114131

115132
Rot3 PreintegratedRotation::biascorrectedDeltaRij(const Vector3& biasOmegaIncr,
116133
OptionalJacobian<3, 3> H) const {

gtsam/navigation/PreintegratedRotation.h

+73-27
Original file line numberDiff line numberDiff line change
@@ -21,12 +21,37 @@
2121

2222
#pragma once
2323

24-
#include <gtsam/geometry/Pose3.h>
2524
#include <gtsam/base/Matrix.h>
2625
#include <gtsam/base/std_optional_serialization.h>
26+
#include <gtsam/geometry/Pose3.h>
27+
#include "gtsam/dllexport.h"
2728

2829
namespace gtsam {
2930

31+
namespace internal {
32+
/**
33+
* @brief Function object for incremental rotation.
34+
* @param measuredOmega The measured angular velocity (as given by the sensor)
35+
* @param deltaT The time interval over which the rotation is integrated.
36+
* @param body_P_sensor Optional transform between body and IMU.
37+
*/
38+
struct GTSAM_EXPORT IncrementalRotation {
39+
const Vector3& measuredOmega;
40+
const double deltaT;
41+
const std::optional<Pose3>& body_P_sensor;
42+
43+
/**
44+
* @brief Integrate angular velocity, but corrected by bias.
45+
* @param bias The bias estimate
46+
* @param H_bias Jacobian of the rotation w.r.t. bias.
47+
* @return The incremental rotation
48+
*/
49+
Rot3 operator()(const Vector3& bias,
50+
OptionalJacobian<3, 3> H_bias = {}) const;
51+
};
52+
53+
} // namespace internal
54+
3055
/// Parameters for pre-integration:
3156
/// Usage: Create just a single Params and pass a shared pointer to the constructor
3257
struct GTSAM_EXPORT PreintegratedRotationParams {
@@ -65,7 +90,6 @@ struct GTSAM_EXPORT PreintegratedRotationParams {
6590
friend class boost::serialization::access;
6691
template<class ARCHIVE>
6792
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
68-
namespace bs = ::boost::serialization;
6993
ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance);
7094
ar & BOOST_SERIALIZATION_NVP(body_P_sensor);
7195

@@ -136,18 +160,10 @@ class GTSAM_EXPORT PreintegratedRotation {
136160

137161
/// @name Access instance variables
138162
/// @{
139-
const std::shared_ptr<Params>& params() const {
140-
return p_;
141-
}
142-
const double& deltaTij() const {
143-
return deltaTij_;
144-
}
145-
const Rot3& deltaRij() const {
146-
return deltaRij_;
147-
}
148-
const Matrix3& delRdelBiasOmega() const {
149-
return delRdelBiasOmega_;
150-
}
163+
const std::shared_ptr<Params>& params() const { return p_; }
164+
const double& deltaTij() const { return deltaTij_; }
165+
const Rot3& deltaRij() const { return deltaRij_; }
166+
const Matrix3& delRdelBiasOmega() const { return delRdelBiasOmega_; }
151167
/// @}
152168

153169
/// @name Testable
@@ -159,19 +175,24 @@ class GTSAM_EXPORT PreintegratedRotation {
159175
/// @name Main functionality
160176
/// @{
161177

162-
/// Take the gyro measurement, correct it using the (constant) bias estimate
163-
/// and possibly the sensor pose, and then integrate it forward in time to yield
164-
/// an incremental rotation.
165-
Rot3 incrementalRotation(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
166-
OptionalJacobian<3, 3> D_incrR_integratedOmega) const;
167-
168-
/// Calculate an incremental rotation given the gyro measurement and a time interval,
169-
/// and update both deltaTij_ and deltaRij_.
170-
void integrateMeasurement(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
171-
OptionalJacobian<3, 3> D_incrR_integratedOmega = {},
172-
OptionalJacobian<3, 3> F = {});
173-
174-
/// Return a bias corrected version of the integrated rotation, with optional Jacobian
178+
/**
179+
* @brief Calculate an incremental rotation given the gyro measurement and a
180+
* time interval, and update both deltaTij_ and deltaRij_.
181+
* @param measuredOmega The measured angular velocity (as given by the sensor)
182+
* @param bias The biasHat estimate
183+
* @param deltaT The time interval
184+
* @param F optional Jacobian of internal compose, used in AhrsFactor.
185+
*/
186+
void integrateGyroMeasurement(const Vector3& measuredOmega,
187+
const Vector3& biasHat, double deltaT,
188+
OptionalJacobian<3, 3> F = {});
189+
190+
/**
191+
* @brief Return a bias corrected version of the integrated rotation.
192+
* @param biasOmegaIncr An increment with respect to biasHat used above.
193+
* @param H optional Jacobian of the correction w.r.t. the bias increment.
194+
* @note The *key* functionality of this class used in optimizing the bias.
195+
*/
175196
Rot3 biascorrectedDeltaRij(const Vector3& biasOmegaIncr,
176197
OptionalJacobian<3, 3> H = {}) const;
177198

@@ -180,6 +201,31 @@ class GTSAM_EXPORT PreintegratedRotation {
180201

181202
/// @}
182203

204+
/// @name Deprecated API
205+
/// @{
206+
207+
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
208+
/// @deprecated: use IncrementalRotation functor with sane Jacobian
209+
inline Rot3 GTSAM_DEPRECATED incrementalRotation(
210+
const Vector3& measuredOmega, const Vector3& bias, double deltaT,
211+
OptionalJacobian<3, 3> D_incrR_integratedOmega) const {
212+
internal::IncrementalRotation f{measuredOmega, deltaT, p_->body_P_sensor};
213+
Rot3 incrR = f(bias, D_incrR_integratedOmega);
214+
// Backwards compatible "weird" Jacobian, no longer used.
215+
if (D_incrR_integratedOmega) *D_incrR_integratedOmega /= -deltaT;
216+
return incrR;
217+
}
218+
219+
/// @deprecated: use integrateGyroMeasurement from now on
220+
/// @note this returned hard-to-understand Jacobian D_incrR_integratedOmega.
221+
void GTSAM_DEPRECATED integrateMeasurement(
222+
const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
223+
OptionalJacobian<3, 3> D_incrR_integratedOmega, OptionalJacobian<3, 3> F);
224+
225+
#endif
226+
227+
/// @}
228+
183229
private:
184230
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
185231
/** Serialization function */

0 commit comments

Comments
 (0)