CombinedImuFactor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
24 #include <boost/serialization/export.hpp>
25 
26 /* External or standard includes */
27 #include <ostream>
28 
29 namespace gtsam {
30 
31 using namespace std;
32 
33 //------------------------------------------------------------------------------
34 // Inner class PreintegrationCombinedParams
35 //------------------------------------------------------------------------------
36 void PreintegrationCombinedParams::print(const string& s) const {
38  cout << "biasAccCovariance:\n[\n" << biasAccCovariance << "\n]"
39  << endl;
40  cout << "biasOmegaCovariance:\n[\n" << biasOmegaCovariance << "\n]"
41  << endl;
42  cout << "biasAccOmegaInt:\n[\n" << biasAccOmegaInt << "\n]"
43  << endl;
44 }
45 
46 //------------------------------------------------------------------------------
48  double tol) const {
49  auto e = dynamic_cast<const PreintegrationCombinedParams*>(&other);
50  return e != nullptr && PreintegrationParams::equals(other, tol) &&
51  equal_with_abs_tol(biasAccCovariance, e->biasAccCovariance,
52  tol) &&
53  equal_with_abs_tol(biasOmegaCovariance, e->biasOmegaCovariance,
54  tol) &&
55  equal_with_abs_tol(biasAccOmegaInt, e->biasAccOmegaInt, tol);
56 }
57 
58 //------------------------------------------------------------------------------
59 // Inner class PreintegratedCombinedMeasurements
60 //------------------------------------------------------------------------------
61 void PreintegratedCombinedMeasurements::print(const string& s) const {
63  cout << " preintMeasCov [ " << preintMeasCov_ << " ]" << endl;
64 }
65 
66 //------------------------------------------------------------------------------
68  const PreintegratedCombinedMeasurements& other, double tol) const {
69  return PreintegrationType::equals(other, tol)
70  && equal_with_abs_tol(preintMeasCov_, other.preintMeasCov_, tol);
71 }
72 
73 //------------------------------------------------------------------------------
76  preintMeasCov_.setZero();
77 }
78 
79 //------------------------------------------------------------------------------
80 // sugar for derivative blocks
81 #define D_R_R(H) (H)->block<3,3>(0,0)
82 #define D_R_t(H) (H)->block<3,3>(0,3)
83 #define D_R_v(H) (H)->block<3,3>(0,6)
84 #define D_t_R(H) (H)->block<3,3>(3,0)
85 #define D_t_t(H) (H)->block<3,3>(3,3)
86 #define D_t_v(H) (H)->block<3,3>(3,6)
87 #define D_v_R(H) (H)->block<3,3>(6,0)
88 #define D_v_t(H) (H)->block<3,3>(6,3)
89 #define D_v_v(H) (H)->block<3,3>(6,6)
90 #define D_a_a(H) (H)->block<3,3>(9,9)
91 #define D_g_g(H) (H)->block<3,3>(12,12)
92 
93 //------------------------------------------------------------------------------
95  const Vector3& measuredAcc, const Vector3& measuredOmega, double dt) {
96  // Update preintegrated measurements.
97  Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx)
98  Matrix93 B, C;
99  PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C);
100 
101  // Update preintegrated measurements covariance: as in [2] we consider a first
102  // order propagation that can be seen as a prediction phase in an EKF
103  // framework. In this implementation, in contrast to [2], we consider the
104  // uncertainty of the bias selection and we keep correlation between biases
105  // and preintegrated measurements
106 
107  // Single Jacobians to propagate covariance
108  // TODO(frank): should we not also account for bias on position?
109  Matrix3 theta_H_biasOmega = -C.topRows<3>();
110  Matrix3 vel_H_biasAcc = -B.bottomRows<3>();
111 
112  // overall Jacobian wrt preintegrated measurements (df/dx)
114  F.setZero();
115  F.block<9, 9>(0, 0) = A;
116  F.block<3, 3>(0, 12) = theta_H_biasOmega;
117  F.block<3, 3>(6, 9) = vel_H_biasAcc;
118  F.block<6, 6>(9, 9) = I_6x6;
119 
120  // propagate uncertainty
121  // TODO(frank): use noiseModel routine so we can have arbitrary noise models.
122  const Matrix3& aCov = p().accelerometerCovariance;
123  const Matrix3& wCov = p().gyroscopeCovariance;
124  const Matrix3& iCov = p().integrationCovariance;
125 
126  // first order uncertainty propagation
127  // Optimized matrix multiplication (1/dt) * G * measurementCovariance *
128  // G.transpose()
129  Eigen::Matrix<double, 15, 15> G_measCov_Gt;
130  G_measCov_Gt.setZero(15, 15);
131 
132  // BLOCK DIAGONAL TERMS
133  D_t_t(&G_measCov_Gt) = dt * iCov;
134  D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc
135  * (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0))
136  * (vel_H_biasAcc.transpose());
137  D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega
138  * (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3))
139  * (theta_H_biasOmega.transpose());
140  D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance;
141  D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance;
142 
143  // OFF BLOCK DIAGONAL TERMS
144  Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInt.block<3, 3>(3, 0)
145  * theta_H_biasOmega.transpose();
146  D_v_R(&G_measCov_Gt) = temp;
147  D_R_v(&G_measCov_Gt) = temp.transpose();
148  preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt;
149 }
150 
151 //------------------------------------------------------------------------------
152 // CombinedImuFactor methods
153 //------------------------------------------------------------------------------
155  Key vel_j, Key bias_i, Key bias_j,
157  Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i,
158  pose_j, vel_j, bias_i, bias_j), _PIM_(pim) {
159 }
160 
161 //------------------------------------------------------------------------------
163  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
165 }
166 
167 //------------------------------------------------------------------------------
168 void CombinedImuFactor::print(const string& s,
169  const KeyFormatter& keyFormatter) const {
170  cout << (s.empty() ? s : s + "\n") << "CombinedImuFactor("
171  << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ","
172  << keyFormatter(this->key3()) << "," << keyFormatter(this->key4()) << ","
173  << keyFormatter(this->key5()) << "," << keyFormatter(this->key6())
174  << ")\n";
175  _PIM_.print(" preintegrated measurements:");
176  this->noiseModel_->print(" noise model: ");
177 }
178 
179 //------------------------------------------------------------------------------
180 bool CombinedImuFactor::equals(const NonlinearFactor& other, double tol) const {
181  const This* e = dynamic_cast<const This*>(&other);
182  return e != nullptr && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol);
183 }
184 
185 //------------------------------------------------------------------------------
187  const Vector3& vel_i, const Pose3& pose_j, const Vector3& vel_j,
188  const imuBias::ConstantBias& bias_i, const imuBias::ConstantBias& bias_j,
189  boost::optional<Matrix&> H1, boost::optional<Matrix&> H2,
190  boost::optional<Matrix&> H3, boost::optional<Matrix&> H4,
191  boost::optional<Matrix&> H5, boost::optional<Matrix&> H6) const {
192 
193  // error wrt bias evolution model (random walk)
194  Matrix6 Hbias_i, Hbias_j;
195  Vector6 fbias = traits<imuBias::ConstantBias>::Between(bias_j, bias_i,
196  H6 ? &Hbias_j : 0, H5 ? &Hbias_i : 0).vector();
197 
198  Matrix96 D_r_pose_i, D_r_pose_j, D_r_bias_i;
199  Matrix93 D_r_vel_i, D_r_vel_j;
200 
201  // error wrt preintegrated measurements
202  Vector9 r_Rpv = _PIM_.computeErrorAndJacobians(pose_i, vel_i, pose_j, vel_j,
203  bias_i, H1 ? &D_r_pose_i : 0, H2 ? &D_r_vel_i : 0, H3 ? &D_r_pose_j : 0,
204  H4 ? &D_r_vel_j : 0, H5 ? &D_r_bias_i : 0);
205 
206  // if we need the jacobians
207  if (H1) {
208  H1->resize(15, 6);
209  H1->block<9, 6>(0, 0) = D_r_pose_i;
210  // adding: [dBiasAcc/dPi ; dBiasOmega/dPi]
211  H1->block<6, 6>(9, 0).setZero();
212  }
213  if (H2) {
214  H2->resize(15, 3);
215  H2->block<9, 3>(0, 0) = D_r_vel_i;
216  // adding: [dBiasAcc/dVi ; dBiasOmega/dVi]
217  H2->block<6, 3>(9, 0).setZero();
218  }
219  if (H3) {
220  H3->resize(15, 6);
221  H3->block<9, 6>(0, 0) = D_r_pose_j;
222  // adding: [dBiasAcc/dPj ; dBiasOmega/dPj]
223  H3->block<6, 6>(9, 0).setZero();
224  }
225  if (H4) {
226  H4->resize(15, 3);
227  H4->block<9, 3>(0, 0) = D_r_vel_j;
228  // adding: [dBiasAcc/dVi ; dBiasOmega/dVi]
229  H4->block<6, 3>(9, 0).setZero();
230  }
231  if (H5) {
232  H5->resize(15, 6);
233  H5->block<9, 6>(0, 0) = D_r_bias_i;
234  // adding: [dBiasAcc/dBias_i ; dBiasOmega/dBias_i]
235  H5->block<6, 6>(9, 0) = Hbias_i;
236  }
237  if (H6) {
238  H6->resize(15, 6);
239  H6->block<9, 6>(0, 0).setZero();
240  // adding: [dBiasAcc/dBias_j ; dBiasOmega/dBias_j]
241  H6->block<6, 6>(9, 0) = Hbias_j;
242  }
243 
244  // overall error
245  Vector r(15);
246  r << r_Rpv, fbias; // vector of size 15
247  return r;
248 }
249 
250 //------------------------------------------------------------------------------
251 std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) {
252  f._PIM_.print("combined preintegrated measurements:\n");
253  os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose();
254  return os;
255 }
256 }
258 
261 
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
equals
Eigen::Vector3d Vector3
Definition: Vector.h:43
#define D_g_g(H)
bool equals(const PreintegratedRotationParams &other, double tol) const override
void print(const std::string &s="") const override
void print(const std::string &s="") const override
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: Half.h:150
void resetIntegration() override
Re-initialize PreintegratedCombinedMeasurements.
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
bool equals(const ManifoldPreintegration &other, double tol) const
void print(const std::string &s="Preintegrated Measurements:") const override
#define D_R_R(H)
const double dt
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
Signature::Row F
Definition: Signature.cpp:53
Eigen::VectorXd Vector
Definition: Vector.h:38
#define D_R_v(H)
#define D_v_R(H)
#define D_a_a(H)
boost::shared_ptr< This > shared_ptr
BOOST_CLASS_EXPORT_IMPLEMENT(gtsam::PreintegrationCombinedParams)
namespace gtsam
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
BetweenFactor< Rot3 > Between
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
#define D_t_t(H)
static const Vector3 measuredAcc
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const CombinedImuFactor &)
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
traits
Definition: chartTesting.h:28
PreintegratedCombinedMeasurements _PIM_
static const Vector3 measuredOmega(w, 0, 0)
SharedNoiseModel noiseModel_
ofstream os("timeSchurFactors.csv")
Eigen::Matrix< double, 15, 15 > preintMeasCov_
bool equals(const PreintegratedRotationParams &other, double tol) const override
float * p
const G double tol
Definition: Group.h:83
virtual void print(const std::string &s="") const
Vector9 computeErrorAndJacobians(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H1=boost::none, OptionalJacobian< 9, 3 > H2=boost::none, OptionalJacobian< 9, 6 > H3=boost::none, OptionalJacobian< 9, 3 > H4=boost::none, OptionalJacobian< 9, 6 > H5=boost::none) const
bool equals(const PreintegratedCombinedMeasurements &expected, double tol=1e-9) const
equals
#define D_v_v(H)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, const imuBias::ConstantBias &bias_j, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none, boost::optional< Matrix & > H6=boost::none) const override
vector of errors
v setZero(3)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:48