gtsam  4.0.0
gtsam
AHRSFactor.h
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 
20 #pragma once
21 
22 /* GTSAM includes */
25 #include <gtsam/geometry/Pose3.h>
26 
27 namespace gtsam {
28 
35 
36  protected:
37 
38  Vector3 biasHat_;
39  Matrix3 preintMeasCov_;
40 
41  friend class AHRSFactor;
42 
43  public:
44 
47 
52  PreintegratedAhrsMeasurements(const boost::shared_ptr<Params>& p,
53  const Vector3& biasHat) :
54  PreintegratedRotation(p), biasHat_(biasHat) {
55  resetIntegration();
56  }
57 
58  const Params& p() const { return *boost::static_pointer_cast<const Params>(p_);}
59  const Vector3& biasHat() const { return biasHat_; }
60  const Matrix3& preintMeasCov() const { return preintMeasCov_; }
61 
63  void print(const std::string& s = "Preintegrated Measurements: ") const;
64 
66  bool equals(const PreintegratedAhrsMeasurements&, double tol = 1e-9) const;
67 
69  void resetIntegration();
70 
76  void integrateMeasurement(const Vector3& measuredOmega, double deltaT);
77 
80  Vector3 predict(const Vector3& bias, OptionalJacobian<3,3> H = boost::none) const;
81 
82  // This function is only used for test purposes
83  // (compare numerical derivatives wrt analytic ones)
84  static Vector DeltaAngles(const Vector& msr_gyro_t, const double msr_dt,
85  const Vector3& delta_angles);
86 
88  PreintegratedAhrsMeasurements(const Vector3& biasHat,
89  const Matrix3& measuredOmegaCovariance)
90  : PreintegratedRotation(boost::make_shared<Params>()),
91  biasHat_(biasHat) {
92  p_->gyroscopeCovariance = measuredOmegaCovariance;
93  resetIntegration();
94  }
95 
96 private:
97 
99  friend class boost::serialization::access;
100  template<class ARCHIVE>
101  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
102  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation);
103  ar & BOOST_SERIALIZATION_NVP(p_);
104  ar & BOOST_SERIALIZATION_NVP(biasHat_);
105  }
106 };
107 
108 class GTSAM_EXPORT AHRSFactor: public NoiseModelFactor3<Rot3, Rot3, Vector3> {
109 
110  typedef AHRSFactor This;
112 
114 
116  AHRSFactor() {}
117 
118 public:
119 
121 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
122  typedef typename boost::shared_ptr<AHRSFactor> shared_ptr;
123 #else
124  typedef boost::shared_ptr<AHRSFactor> shared_ptr;
125 #endif
126 
134  AHRSFactor(Key rot_i, Key rot_j, Key bias,
135  const PreintegratedAhrsMeasurements& preintegratedMeasurements);
136 
137  virtual ~AHRSFactor() {
138  }
139 
141  virtual gtsam::NonlinearFactor::shared_ptr clone() const;
142 
144  virtual void print(const std::string& s, const KeyFormatter& keyFormatter =
145  DefaultKeyFormatter) const;
146 
148  virtual bool equals(const NonlinearFactor&, double tol = 1e-9) const;
149 
152  return _PIM_;
153  }
154 
157  Vector evaluateError(const Rot3& rot_i, const Rot3& rot_j,
159  const Vector3& bias, boost::optional<Matrix&> H1 = boost::none,
160  boost::optional<Matrix&> H2 = boost::none, boost::optional<Matrix&> H3 =
161  boost::none) const;
162 
165  static Rot3 Predict(
166  const Rot3& rot_i, const Vector3& bias,
167  const PreintegratedAhrsMeasurements preintegratedMeasurements);
168 
171 
173  AHRSFactor(Key rot_i, Key rot_j, Key bias,
174  const PreintegratedMeasurements& preintegratedMeasurements,
175  const Vector3& omegaCoriolis,
176  const boost::optional<Pose3>& body_P_sensor = boost::none);
177 
179  static Rot3 predict(const Rot3& rot_i, const Vector3& bias,
180  const PreintegratedMeasurements preintegratedMeasurements,
181  const Vector3& omegaCoriolis,
182  const boost::optional<Pose3>& body_P_sensor = boost::none);
183 
184 private:
185 
187  friend class boost::serialization::access;
188  template<class ARCHIVE>
189  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
190  ar
191  & boost::serialization::make_nvp("NoiseModelFactor3",
192  boost::serialization::base_object<Base>(*this));
193  ar & BOOST_SERIALIZATION_NVP(_PIM_);
194  }
195 
196 };
197 // AHRSFactor
198 
199 } //namespace gtsam
PreintegratedRotation is the base class for all PreintegratedMeasurements classes (in AHRSFactor,...
Definition: PreintegratedRotation.h:74
This is the base class for all factor types.
Definition: Factor.h:54
PreintegratedAHRSMeasurements accumulates (integrates) the Gyroscope measurements (rotation rates) an...
Definition: AHRSFactor.h:34
PreintegratedAhrsMeasurements()
Default constructor, only for serialization and Cython wrapper.
Definition: AHRSFactor.h:46
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
boost::shared_ptr< AHRSFactor > shared_ptr
Shorthand for a smart pointer to a factor.
Definition: AHRSFactor.h:124
PreintegratedAhrsMeasurements(const boost::shared_ptr< Params > &p, const Vector3 &biasHat)
Default constructor, initialize with no measurements.
Definition: AHRSFactor.h:52
const PreintegratedAhrsMeasurements & preintegratedMeasurements() const
Access the preintegrated measurements.
Definition: AHRSFactor.h:151
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegratedRotation.h:31
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
Template to create a binary predicate.
Definition: Testable.h:110
Definition: Rot3.h:56
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:420
Non-linear factor base classes.
3D Pose
PreintegratedAhrsMeasurements(const Vector3 &biasHat, const Matrix3 &measuredOmegaCovariance)
Definition: AHRSFactor.h:88
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Vector3 biasHat_
Angular rate bias values used during preintegration.
Definition: AHRSFactor.h:38
PreintegratedAhrsMeasurements PreintegratedMeasurements
Definition: AHRSFactor.h:170
Definition: AHRSFactor.h:108
Matrix3 preintMeasCov_
Covariance matrix of the preintegrated measurements (first-order propagation from measurementCovarian...
Definition: AHRSFactor.h:39