Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

CombinedImuFactor: Add bias effect on position jacobian #874

Merged
merged 45 commits into from
Aug 21, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
45 commits
Select commit Hold shift + click to select a range
5e735e1
minor improvements to CombinedImuFactor
varunagrawal Sep 16, 2021
9dbb431
account for bias on position in jacobians of CombinedImuFactor
varunagrawal Sep 16, 2021
7e48962
Add unit test for checking covariance of CombinedImuFactor
varunagrawal Sep 17, 2021
b0fcd17
additional comments to make understanding the code easier
varunagrawal Sep 17, 2021
5656308
no need to assign negative to jacobians as they cancel out later
varunagrawal Sep 17, 2021
810f973
add details about noise propagation for CombinedImuFactor in ImuFacto…
varunagrawal Sep 17, 2021
da220dc
Add the Preintegrated IMU jacobians tech report and mention it in the…
varunagrawal Sep 18, 2021
a516415
update ImuFactor reference
varunagrawal Sep 20, 2021
61f2cf7
Merge branch 'develop' into fix/368
varunagrawal Sep 20, 2021
28d0393
add test for checking covariances between ImuFactor and CombinedImuFa…
varunagrawal Sep 19, 2021
a10c776
print statements in ImuFactor
varunagrawal Sep 19, 2021
65bbe6b
typedef for Vector15
varunagrawal Sep 19, 2021
3a3640c
updated CombinedImuFactor covariance with additional off-diagonal ele…
varunagrawal Sep 19, 2021
3132cfb
CombinedScenarioRunner
varunagrawal Sep 19, 2021
5371214
actually test the covariances and fix bug
varunagrawal Sep 20, 2021
10a7333
update test with comments
varunagrawal Sep 21, 2021
755c752
update ImuFactor doc
varunagrawal Sep 21, 2021
bbde7b9
remove print statements
varunagrawal Sep 21, 2021
a2bf0c4
minor refactoring
varunagrawal Sep 21, 2021
aa4a163
updated ImuFactor doc with details about CombinedImuFactor
varunagrawal Sep 28, 2021
0968c60
added details about covariance discretization with references
varunagrawal Sep 28, 2021
6bc9b50
add test for MC based covariance estimation
varunagrawal Sep 30, 2021
af714cd
undo name change from 984a90
varunagrawal Sep 28, 2021
e38ea50
detailed implementation of CombinedImuFactor noise propagation
varunagrawal Sep 28, 2021
3cee1b7
test passes
varunagrawal Sep 30, 2021
dfa32e5
lyx update
varunagrawal Oct 10, 2021
40e6d8b
formatting
varunagrawal Oct 10, 2021
995710f
update PDF doc
varunagrawal May 5, 2022
2d3859d
Merge branch 'develop' into fix/combined-imu
varunagrawal May 5, 2022
239dd62
Merge branch 'develop' into fix/combined-imu-cov
varunagrawal May 5, 2022
008bb93
Merge branch 'develop' into fix/368
varunagrawal May 5, 2022
63e2a59
Merge branch 'fix/368' into fix/combined-imu-cov
varunagrawal May 5, 2022
f0be857
Merge branch 'fix/combined-imu-cov' into fix/combined-imu
varunagrawal May 5, 2022
8dbbb1f
fix test
varunagrawal May 6, 2022
ce7c71b
fix test
varunagrawal May 8, 2022
a17134d
minor refactor to follow the math better
varunagrawal May 8, 2022
cb75d92
use prior naming scheme for bias jacobians
varunagrawal May 22, 2022
bbd1e3f
update Lyx document based on Luca's review
varunagrawal Jul 3, 2022
4244345
Merge pull request #882 from borglab/fix/combined-imu
varunagrawal Jul 5, 2022
c767dfa
Merge pull request #879 from borglab/fix/combined-imu-cov
varunagrawal Jul 20, 2022
2d41b01
change python CI cores to 1
varunagrawal Jul 20, 2022
8a33a5b
Revert "change python CI cores to 1"
varunagrawal Jul 22, 2022
322c080
Merge branch 'develop' into fix/368
varunagrawal Jul 22, 2022
ac28b0e
fix setter and getter for biasAccOmegaInit
varunagrawal Aug 2, 2022
103c78b
revert name change, save for another PR
varunagrawal Aug 10, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
872 changes: 826 additions & 46 deletions doc/ImuFactor.lyx

Large diffs are not rendered by default.

Binary file modified doc/ImuFactor.pdf
Binary file not shown.
Binary file added doc/PreintegratedIMUJacobians.pdf
Binary file not shown.
88 changes: 67 additions & 21 deletions doc/refs.bib
Original file line number Diff line number Diff line change
@@ -1,26 +1,72 @@
%% This BibTeX bibliography file was created using BibDesk.
%% https://bibdesk.sourceforge.io/

%% Created for Varun Agrawal at 2021-09-27 17:39:09 -0400


%% Saved with string encoding Unicode (UTF-8)



@article{Lupton12tro,
author = {Lupton, Todd and Sukkarieh, Salah},
date-added = {2021-09-27 17:38:56 -0400},
date-modified = {2021-09-27 17:39:09 -0400},
doi = {10.1109/TRO.2011.2170332},
journal = {IEEE Transactions on Robotics},
number = {1},
pages = {61-76},
title = {Visual-Inertial-Aided Navigation for High-Dynamic Motion in Built Environments Without Initial Conditions},
volume = {28},
year = {2012},
Bdsk-Url-1 = {https://doi.org/10.1109/TRO.2011.2170332}}

@inproceedings{Forster15rss,
author = {Christian Forster and Luca Carlone and Frank Dellaert and Davide Scaramuzza},
booktitle = {Robotics: Science and Systems},
date-added = {2021-09-26 20:44:41 -0400},
date-modified = {2021-09-26 20:45:03 -0400},
title = {IMU Preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation},
year = {2015}}

@article{Iserles00an,
title = {Lie-group methods},
author = {Iserles, Arieh and Munthe-Kaas, Hans Z and
N{\o}rsett, Syvert P and Zanna, Antonella},
journal = {Acta Numerica 2000},
volume = {9},
pages = {215--365},
year = {2000},
publisher = {Cambridge Univ Press}
}
author = {Iserles, Arieh and Munthe-Kaas, Hans Z and N{\o}rsett, Syvert P and Zanna, Antonella},
journal = {Acta Numerica 2000},
pages = {215--365},
publisher = {Cambridge Univ Press},
title = {Lie-group methods},
volume = {9},
year = {2000}}

@book{Murray94book,
title = {A mathematical introduction to robotic manipulation},
author = {Murray, Richard M and Li, Zexiang and Sastry, S
Shankar and Sastry, S Shankara},
year = {1994},
publisher = {CRC press}
}
author = {Murray, Richard M and Li, Zexiang and Sastry, S Shankar and Sastry, S Shankara},
publisher = {CRC press},
title = {A mathematical introduction to robotic manipulation},
year = {1994}}

@book{Spivak65book,
title = {Calculus on manifolds},
author = {Spivak, Michael},
volume = {1},
year = {1965},
publisher = {WA Benjamin New York}
}
author = {Spivak, Michael},
publisher = {WA Benjamin New York},
title = {Calculus on manifolds},
volume = {1},
year = {1965}}

@phdthesis{Nikolic16thesis,
title={Characterisation, calibration, and design of visual-inertial sensor systems for robot navigation},
author={Nikolic, Janosch},
year={2016},
school={ETH Zurich}
}

@book{Simon06book,
title={Optimal state estimation: Kalman, H infinity, and nonlinear approaches},
author={Simon, Dan},
year={2006},
publisher={John Wiley \& Sons}
}

@inproceedings{Trawny05report_IndirectKF,
title={Indirect Kalman Filter for 3 D Attitude Estimation},
author={Nikolas Trawny and Stergios I. Roumeliotis},
year={2005}
}
19 changes: 10 additions & 9 deletions examples/CombinedImuFactorsExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,13 +60,14 @@ namespace po = boost::program_options;

po::variables_map parseOptions(int argc, char* argv[]) {
po::options_description desc;
desc.add_options()("help,h", "produce help message")(
"data_csv_path", po::value<string>()->default_value("imuAndGPSdata.csv"),
"path to the CSV file with the IMU data")(
"output_filename",
po::value<string>()->default_value("imuFactorExampleResults.csv"),
"path to the result file to use")("use_isam", po::bool_switch(),
"use ISAM as the optimizer");
desc.add_options()("help,h", "produce help message") // help message
("data_csv_path", po::value<string>()->default_value("imuAndGPSdata.csv"),
"path to the CSV file with the IMU data") // path to the data file
("output_filename",
po::value<string>()->default_value("imuFactorExampleResults.csv"),
"path to the result file to use") // filename to save results to
("use_isam", po::bool_switch(),
"use ISAM as the optimizer"); // flag for ISAM optimizer

po::variables_map vm;
po::store(po::parse_command_line(argc, argv, desc), vm);
Expand Down Expand Up @@ -106,7 +107,7 @@ boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
I_3x3 * 1e-8; // error committed in integrating position from velocities
Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2);
Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2);
Matrix66 bias_acc_omega_int =
Matrix66 bias_acc_omega_init =
I_6x6 * 1e-5; // error in the bias used for preintegration

auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0);
Expand All @@ -122,7 +123,7 @@ boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
// PreintegrationCombinedMeasurements params:
p->biasAccCovariance = bias_acc_cov; // acc bias in continuous
p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous
p->biasAccOmegaInt = bias_acc_omega_int;
p->biasAccOmegaInt = bias_acc_omega_init;

return p;
}
Expand Down
4 changes: 2 additions & 2 deletions examples/ImuFactorsExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
I_3x3 * 1e-8; // error committed in integrating position from velocities
Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2);
Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2);
Matrix66 bias_acc_omega_int =
Matrix66 bias_acc_omega_init =
I_6x6 * 1e-5; // error in the bias used for preintegration

auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0);
Expand All @@ -110,7 +110,7 @@ boost::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
// PreintegrationCombinedMeasurements params:
p->biasAccCovariance = bias_acc_cov; // acc bias in continuous
p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous
p->biasAccOmegaInt = bias_acc_omega_int;
p->biasAccOmegaInt = bias_acc_omega_init;

return p;
}
Expand Down
1 change: 1 addition & 0 deletions gtsam/base/Vector.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ GTSAM_MAKE_VECTOR_DEFS(9)
GTSAM_MAKE_VECTOR_DEFS(10)
GTSAM_MAKE_VECTOR_DEFS(11)
GTSAM_MAKE_VECTOR_DEFS(12)
GTSAM_MAKE_VECTOR_DEFS(15)

typedef Eigen::VectorBlock<Vector> SubVector;
typedef Eigen::VectorBlock<const Vector> ConstSubVector;
Expand Down
77 changes: 56 additions & 21 deletions gtsam/navigation/CombinedImuFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,9 +93,14 @@ void PreintegratedCombinedMeasurements::resetIntegration() {
//------------------------------------------------------------------------------
void PreintegratedCombinedMeasurements::integrateMeasurement(
const Vector3& measuredAcc, const Vector3& measuredOmega, double dt) {
if (dt <= 0) {
throw std::runtime_error(
"PreintegratedCombinedMeasurements::integrateMeasurement: dt <=0");
}

// Update preintegrated measurements.
Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx)
Matrix93 B, C;
Matrix9 A; // Jacobian wrt preintegrated measurements without bias (df/dx)
Matrix93 B, C; // Jacobian of state wrpt accel bias and omega bias respectively.
PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C);

// Update preintegrated measurements covariance: as in [2] we consider a first
Expand All @@ -105,47 +110,78 @@ void PreintegratedCombinedMeasurements::integrateMeasurement(
// and preintegrated measurements

// Single Jacobians to propagate covariance
// TODO(frank): should we not also account for bias on position?
Matrix3 theta_H_biasOmega = -C.topRows<3>();
Matrix3 vel_H_biasAcc = -B.bottomRows<3>();
Matrix3 theta_H_biasOmega = C.topRows<3>();
Matrix3 pos_H_biasAcc = B.middleRows<3>(3);
Matrix3 vel_H_biasAcc = B.bottomRows<3>();

Matrix3 theta_H_biasOmegaInit = -theta_H_biasOmega;
Matrix3 pos_H_biasAccInit = -pos_H_biasAcc;
Matrix3 vel_H_biasAccInit = -vel_H_biasAcc;

// overall Jacobian wrt preintegrated measurements (df/dx)
Eigen::Matrix<double, 15, 15> F;
F.setZero();
F.block<9, 9>(0, 0) = A;
F.block<3, 3>(0, 12) = theta_H_biasOmega;
F.block<3, 3>(3, 9) = pos_H_biasAcc;
F.block<3, 3>(6, 9) = vel_H_biasAcc;
F.block<6, 6>(9, 9) = I_6x6;

// Update the uncertainty on the state (matrix F in [4]).
preintMeasCov_ = F * preintMeasCov_ * F.transpose();

// propagate uncertainty
// TODO(frank): use noiseModel routine so we can have arbitrary noise models.
const Matrix3& aCov = p().accelerometerCovariance;
const Matrix3& wCov = p().gyroscopeCovariance;
const Matrix3& iCov = p().integrationCovariance;
const Matrix6& bInitCov = p().biasAccOmegaInt;

// first order uncertainty propagation
// Optimized matrix multiplication (1/dt) * G * measurementCovariance *
// G.transpose()
// Optimized matrix mult: (1/dt) * G * measurementCovariance * G.transpose()
Eigen::Matrix<double, 15, 15> G_measCov_Gt;
G_measCov_Gt.setZero(15, 15);

const Matrix3& bInitCov11 = bInitCov.block<3, 3>(0, 0) / dt;
const Matrix3& bInitCov12 = bInitCov.block<3, 3>(0, 3) / dt;
const Matrix3& bInitCov21 = bInitCov.block<3, 3>(3, 0) / dt;
const Matrix3& bInitCov22 = bInitCov.block<3, 3>(3, 3) / dt;

// BLOCK DIAGONAL TERMS
D_t_t(&G_measCov_Gt) = dt * iCov;
D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc
* (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0))
* (vel_H_biasAcc.transpose());
D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega
* (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3))
* (theta_H_biasOmega.transpose());
D_R_R(&G_measCov_Gt) =
(theta_H_biasOmega * (wCov / dt) * theta_H_biasOmega.transpose()) //
+
(theta_H_biasOmegaInit * bInitCov22 * theta_H_biasOmegaInit.transpose());

D_t_t(&G_measCov_Gt) =
(pos_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose()) //
+ (pos_H_biasAccInit * bInitCov11 * pos_H_biasAccInit.transpose()) //
+ (dt * iCov);

D_v_v(&G_measCov_Gt) =
(vel_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose()) //
+ (vel_H_biasAccInit * bInitCov11 * vel_H_biasAccInit.transpose());

D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance;
D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance;

// OFF BLOCK DIAGONAL TERMS
Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInt.block<3, 3>(3, 0)
* theta_H_biasOmega.transpose();
D_v_R(&G_measCov_Gt) = temp;
D_R_v(&G_measCov_Gt) = temp.transpose();
preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt;
D_R_t(&G_measCov_Gt) =
theta_H_biasOmegaInit * bInitCov21 * pos_H_biasAccInit.transpose();
D_R_v(&G_measCov_Gt) =
theta_H_biasOmegaInit * bInitCov21 * vel_H_biasAccInit.transpose();
D_t_R(&G_measCov_Gt) =
pos_H_biasAccInit * bInitCov12 * theta_H_biasOmegaInit.transpose();
D_t_v(&G_measCov_Gt) =
(pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose()) +
(pos_H_biasAccInit * bInitCov11 * vel_H_biasAccInit.transpose());
D_v_R(&G_measCov_Gt) =
vel_H_biasAccInit * bInitCov12 * theta_H_biasOmegaInit.transpose();
D_v_t(&G_measCov_Gt) =
(vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose()) +
(vel_H_biasAccInit * bInitCov11 * pos_H_biasAccInit.transpose());

preintMeasCov_.noalias() += G_measCov_Gt;
}

//------------------------------------------------------------------------------
Expand Down Expand Up @@ -253,6 +289,5 @@ std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) {
os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose();
return os;
}
}
/// namespace gtsam

} // namespace gtsam
7 changes: 4 additions & 3 deletions gtsam/navigation/CombinedImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ typedef ManifoldPreintegration PreintegrationType;
* TRO, 28(1):61-76, 2012.
* [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor:
* Computation of the Jacobian Matrices", Tech. Report, 2013.
* Available in this repo as "PreintegratedIMUJacobians.pdf".
* [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, IMU Preintegration on
* Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation,
* Robotics: Science and Systems (RSS), 2015.
Expand All @@ -61,7 +62,7 @@ typedef ManifoldPreintegration PreintegrationType;
struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {
Matrix3 biasAccCovariance; ///< continuous-time "Covariance" describing accelerometer bias random walk
Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk
Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration
Matrix6 biasAccOmegaInt; ///< covariance of bias used as initial estimate.

/// Default constructor makes uninitialized params struct.
/// Used for serialization.
Expand Down Expand Up @@ -92,11 +93,11 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {

void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; }
void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; }
void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInt=cov; }
void setBiasAccOmegaInit(const Matrix6& cov) { biasAccOmegaInt=cov; }

const Matrix3& getBiasAccCovariance() const { return biasAccCovariance; }
const Matrix3& getBiasOmegaCovariance() const { return biasOmegaCovariance; }
const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInt; }
const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; }

private:

Expand Down
6 changes: 4 additions & 2 deletions gtsam/navigation/ImuFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ void PreintegratedImuMeasurements::integrateMeasurement(

// Update preintegrated measurements (also get Jacobian)
Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx)
Matrix93 B, C;
Matrix93 B, C; // Jacobian of state wrpt accel bias and omega bias respectively.
PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C);

// first order covariance propagation:
Expand All @@ -73,11 +73,13 @@ void PreintegratedImuMeasurements::integrateMeasurement(
const Matrix3& iCov = p().integrationCovariance;

// (1/dt) allows to pass from continuous time noise to discrete time noise
// Update the uncertainty on the state (matrix A in [4]).
preintMeasCov_ = A * preintMeasCov_ * A.transpose();
// These 2 updates account for uncertainty on the IMU measurement (matrix B in [4]).
preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose();
preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose();

// NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3
// NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 (9x3 matrix)
preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt;
}

Expand Down
1 change: 1 addition & 0 deletions gtsam/navigation/ImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ typedef ManifoldPreintegration PreintegrationType;
* TRO, 28(1):61-76, 2012.
* [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor:
* Computation of the Jacobian Matrices", Tech. Report, 2013.
* Available in this repo as "PreintegratedIMUJacobians.pdf".
* [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on
* Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation",
* Robotics: Science and Systems (RSS), 2015.
Expand Down
4 changes: 2 additions & 2 deletions gtsam/navigation/PreintegrationBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,9 +157,9 @@ Vector9 PreintegrationBase::computeError(const NavState& state_i,
state_j.localCoordinates(predictedState_j, H2 ? &D_error_state_j : 0,
H1 || H3 ? &D_error_predict : 0);

if (H1) *H1 << D_error_predict* D_predict_state_i;
if (H1) *H1 << D_error_predict * D_predict_state_i;
if (H2) *H2 << D_error_state_j;
if (H3) *H3 << D_error_predict* D_predict_bias_i;
if (H3) *H3 << D_error_predict * D_predict_bias_i;

return error;
}
Expand Down
Loading