ImuFactor.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 
23 
24 /* External or standard includes */
25 #include <ostream>
26 
27 namespace gtsam {
28 
29 using namespace std;
30 
31 //------------------------------------------------------------------------------
32 // Inner class PreintegratedImuMeasurements
33 //------------------------------------------------------------------------------
34 void PreintegratedImuMeasurements::print(const string& s) const {
36  cout << " preintMeasCov \n[" << preintMeasCov_ << "]" << endl;
37 }
38 
39 //------------------------------------------------------------------------------
41  const PreintegratedImuMeasurements& other, double tol) const {
42  return PreintegrationType::equals(other, tol)
43  && equal_with_abs_tol(preintMeasCov_, other.preintMeasCov_, tol);
44 }
45 
46 //------------------------------------------------------------------------------
49  preintMeasCov_.setZero();
50 }
51 
52 //------------------------------------------------------------------------------
54  const Vector3& measuredAcc, const Vector3& measuredOmega, double dt) {
55  if (dt <= 0) {
56  throw std::runtime_error(
57  "PreintegratedImuMeasurements::integrateMeasurement: dt <=0");
58  }
59 
60  // Update preintegrated measurements (also get Jacobian)
61  Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx)
62  Matrix93 B, C;
63  PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C);
64 
65  // first order covariance propagation:
66  // as in [2] we consider a first order propagation that can be seen as a
67  // prediction phase in EKF
68 
69  // propagate uncertainty
70  // TODO(frank): use noiseModel routine so we can have arbitrary noise models.
71  const Matrix3& aCov = p().accelerometerCovariance;
72  const Matrix3& wCov = p().gyroscopeCovariance;
73  const Matrix3& iCov = p().integrationCovariance;
74 
75  // (1/dt) allows to pass from continuous time noise to discrete time noise
76  preintMeasCov_ = A * preintMeasCov_ * A.transpose();
77  preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose();
78  preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose();
79 
80  // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3
81  preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt;
82 }
83 
84 //------------------------------------------------------------------------------
86  const Matrix& measuredAccs, const Matrix& measuredOmegas,
87  const Matrix& dts) {
88  assert(
89  measuredAccs.rows() == 3 && measuredOmegas.rows() == 3 && dts.rows() == 1);
90  assert(dts.cols() >= 1);
91  assert(measuredAccs.cols() == dts.cols());
92  assert(measuredOmegas.cols() == dts.cols());
93  size_t n = static_cast<size_t>(dts.cols());
94  for (size_t j = 0; j < n; j++) {
95  integrateMeasurement(measuredAccs.col(j), measuredOmegas.col(j), dts(0, j));
96  }
97 }
98 
99 //------------------------------------------------------------------------------
100 #ifdef GTSAM_TANGENT_PREINTEGRATION
101 void PreintegratedImuMeasurements::mergeWith(const PreintegratedImuMeasurements& pim12, //
102  Matrix9* H1, Matrix9* H2) {
103  PreintegrationType::mergeWith(pim12, H1, H2);
104  // NOTE(gareth): Temporary P is needed as of Eigen 3.3
105  const Matrix9 P = *H1 * preintMeasCov_ * H1->transpose();
106  preintMeasCov_ = P + *H2 * pim12.preintMeasCov_ * H2->transpose();
107 }
108 #endif
109 
110 //------------------------------------------------------------------------------
111 // ImuFactor methods
112 //------------------------------------------------------------------------------
113 ImuFactor::ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
114  const PreintegratedImuMeasurements& pim) :
115  Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i,
116  pose_j, vel_j, bias), _PIM_(pim) {
117 }
118 
119 //------------------------------------------------------------------------------
121  return boost::static_pointer_cast<NonlinearFactor>(
122  NonlinearFactor::shared_ptr(new This(*this)));
123 }
124 
125 //------------------------------------------------------------------------------
126 std::ostream& operator<<(std::ostream& os, const ImuFactor& f) {
127  f._PIM_.print("preintegrated measurements:\n");
128  os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose();
129  return os;
130 }
131 
132 //------------------------------------------------------------------------------
133 void ImuFactor::print(const string& s, const KeyFormatter& keyFormatter) const {
134  cout << (s.empty() ? s : s + "\n") << "ImuFactor(" << keyFormatter(this->key1())
135  << "," << keyFormatter(this->key2()) << "," << keyFormatter(this->key3())
136  << "," << keyFormatter(this->key4()) << "," << keyFormatter(this->key5())
137  << ")\n";
138  cout << *this << endl;
139 }
140 
141 //------------------------------------------------------------------------------
142 bool ImuFactor::equals(const NonlinearFactor& other, double tol) const {
143  const This *e = dynamic_cast<const This*>(&other);
144  const bool base = Base::equals(*e, tol);
145  const bool pim = _PIM_.equals(e->_PIM_, tol);
146  return e != nullptr && base && pim;
147 }
148 
149 //------------------------------------------------------------------------------
150 Vector ImuFactor::evaluateError(const Pose3& pose_i, const Vector3& vel_i,
151  const Pose3& pose_j, const Vector3& vel_j,
152  const imuBias::ConstantBias& bias_i, boost::optional<Matrix&> H1,
153  boost::optional<Matrix&> H2, boost::optional<Matrix&> H3,
154  boost::optional<Matrix&> H4, boost::optional<Matrix&> H5) const {
155  return _PIM_.computeErrorAndJacobians(pose_i, vel_i, pose_j, vel_j, bias_i,
156  H1, H2, H3, H4, H5);
157 }
158 
159 //------------------------------------------------------------------------------
160 #ifdef GTSAM_TANGENT_PREINTEGRATION
161 PreintegratedImuMeasurements ImuFactor::Merge(
162  const PreintegratedImuMeasurements& pim01,
163  const PreintegratedImuMeasurements& pim12) {
164  if (!pim01.matchesParamsWith(pim12))
165  throw std::domain_error(
166  "Cannot merge PreintegratedImuMeasurements with different params");
167 
168  if (pim01.params()->body_P_sensor)
169  throw std::domain_error(
170  "Cannot merge PreintegratedImuMeasurements with sensor pose yet");
171 
172  // the bias for the merged factor will be the bias from 01
173  PreintegratedImuMeasurements pim02 = pim01;
174 
175  Matrix9 H1, H2;
176  pim02.mergeWith(pim12, &H1, &H2);
177 
178  return pim02;
179 }
180 
181 //------------------------------------------------------------------------------
182 ImuFactor::shared_ptr ImuFactor::Merge(const shared_ptr& f01,
183  const shared_ptr& f12) {
184  // IMU bias keys must be the same.
185  if (f01->key5() != f12->key5())
186  throw std::domain_error("ImuFactor::Merge: IMU bias keys must be the same");
187 
188  // expect intermediate pose, velocity keys to matchup.
189  if (f01->key3() != f12->key1() || f01->key4() != f12->key2())
190  throw std::domain_error(
191  "ImuFactor::Merge: intermediate pose, velocity keys need to match up");
192 
193  // return new factor
194  auto pim02 =
195  Merge(f01->preintegratedMeasurements(), f12->preintegratedMeasurements());
196  return boost::make_shared<ImuFactor>(f01->key1(), // P0
197  f01->key2(), // V0
198  f12->key3(), // P2
199  f12->key4(), // V2
200  f01->key5(), // B
201  pim02);
202 }
203 #endif
204 
205 //------------------------------------------------------------------------------
206 // ImuFactor2 methods
207 //------------------------------------------------------------------------------
209  const PreintegratedImuMeasurements& pim) :
210  Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), state_i, state_j,
211  bias), _PIM_(pim) {
212 }
213 
214 //------------------------------------------------------------------------------
216  return boost::static_pointer_cast<NonlinearFactor>(
217  NonlinearFactor::shared_ptr(new This(*this)));
218 }
219 
220 //------------------------------------------------------------------------------
221 std::ostream& operator<<(std::ostream& os, const ImuFactor2& f) {
222  f._PIM_.print("preintegrated measurements:\n");
223  os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose();
224  return os;
225 }
226 
227 //------------------------------------------------------------------------------
228 void ImuFactor2::print(const string& s,
229  const KeyFormatter& keyFormatter) const {
230  cout << (s.empty() ? s : s + "\n") << "ImuFactor2("
231  << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ","
232  << keyFormatter(this->key3()) << ")\n";
233  cout << *this << endl;
234 }
235 
236 //------------------------------------------------------------------------------
237 bool ImuFactor2::equals(const NonlinearFactor& other, double tol) const {
238  const This *e = dynamic_cast<const This*>(&other);
239  const bool base = Base::equals(*e, tol);
240  const bool pim = _PIM_.equals(e->_PIM_, tol);
241  return e != nullptr && base && pim;
242 }
243 
244 //------------------------------------------------------------------------------
246  const NavState& state_j,
247  const imuBias::ConstantBias& bias_i, //
248  boost::optional<Matrix&> H1, boost::optional<Matrix&> H2,
249  boost::optional<Matrix&> H3) const {
250  return _PIM_.computeError(state_i, state_j, bias_i, H1, H2, H3);
251 }
252 
253 //------------------------------------------------------------------------------
254 
255 }
256 // namespace gtsam
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
Definition: ImuFactor.cpp:53
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
void integrateMeasurements(const Matrix &measuredAccs, const Matrix &measuredOmegas, const Matrix &dts)
Add multiple measurements, in matrix columns.
Definition: ImuFactor.cpp:85
Eigen::Vector3d Vector3
Definition: Vector.h:43
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Definition: ImuFactor.cpp:142
Definition: Half.h:150
Vector9 computeError(const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1, OptionalJacobian< 9, 9 > H2, OptionalJacobian< 9, 6 > H3) const
Calculate error given navStates.
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
bool equals(const ManifoldPreintegration &other, double tol) const
const SharedNoiseModel & noiseModel() const
access to the noise model
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const ImuFactor2 &)
Definition: ImuFactor.cpp:221
ImuFactor This
Definition: ImuFactor.h:170
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: ImuFactor.cpp:228
Vector evaluateError(const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
vector of errors
Definition: ImuFactor.cpp:245
const double dt
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: ImuFactor.cpp:120
void print(const std::string &s="Preintegrated Measurements:") const override
print
Definition: ImuFactor.cpp:34
PreintegratedImuMeasurements _PIM_
Definition: ImuFactor.h:174
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
bool equals(const PreintegratedImuMeasurements &expected, double tol=1e-9) const
equals
Definition: ImuFactor.cpp:40
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, 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) const override
vector of errors
Definition: ImuFactor.cpp:150
Eigen::VectorXd Vector
Definition: Vector.h:38
PreintegratedImuMeasurements _PIM_
Definition: ImuFactor.h:263
boost::shared_ptr< This > shared_ptr
boost::shared_ptr< ImuFactor > shared_ptr
Definition: ImuFactor.h:182
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 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Matrix9 preintMeasCov_
(first-order propagation from measurementCovariance).
Definition: ImuFactor.h:78
static const Vector3 measuredAcc
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const ImuFactor &)
Definition: ImuFactor.cpp:126
Point3 bias(10,-10, 50)
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
ImuFactor2 This
Definition: ImuFactor.h:260
traits
Definition: chartTesting.h:28
static const Vector3 measuredOmega(w, 0, 0)
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:60
SharedNoiseModel noiseModel_
ofstream os("timeSchurFactors.csv")
bool matchesParamsWith(const PreintegrationBase &other) const
check parameters equality: checks whether shared pointer points to same Params object.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: ImuFactor.cpp:133
float * p
const boost::shared_ptr< Params > & params() const
shared pointer to params
Annotation indicating that a class derives from another given type.
Definition: attr.h:42
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
void resetIntegration() override
Re-initialize PreintegratedIMUMeasurements.
Definition: ImuFactor.cpp:47
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Definition: ImuFactor.cpp:237
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: ImuFactor.cpp:215


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:13