PreintegratedRotation.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 
22 #pragma once
23 
24 #include <gtsam/geometry/Pose3.h>
25 #include <gtsam/base/Matrix.h>
26 
27 namespace gtsam {
28 
31 struct GTSAM_EXPORT PreintegratedRotationParams {
35  boost::optional<Vector3> omegaCoriolis;
36  boost::optional<Pose3> body_P_sensor;
37 
38  PreintegratedRotationParams() : gyroscopeCovariance(I_3x3) {}
39 
40  PreintegratedRotationParams(const Matrix3& gyroscope_covariance,
41  boost::optional<Vector3> omega_coriolis)
42  : gyroscopeCovariance(gyroscope_covariance) {
43  if (omega_coriolis)
44  omegaCoriolis.reset(omega_coriolis.get());
45  }
46 
48 
49  virtual void print(const std::string& s) const;
50  virtual bool equals(const PreintegratedRotationParams& other, double tol=1e-9) const;
51 
52  void setGyroscopeCovariance(const Matrix3& cov) { gyroscopeCovariance = cov; }
53  void setOmegaCoriolis(const Vector3& omega) { omegaCoriolis.reset(omega); }
54  void setBodyPSensor(const Pose3& pose) { body_P_sensor.reset(pose); }
55 
56  const Matrix3& getGyroscopeCovariance() const { return gyroscopeCovariance; }
57  boost::optional<Vector3> getOmegaCoriolis() const { return omegaCoriolis; }
58  boost::optional<Pose3> getBodyPSensor() const { return body_P_sensor; }
59 
60  private:
62  friend class boost::serialization::access;
63  template<class ARCHIVE>
64  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
65  namespace bs = ::boost::serialization;
66  ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance);
67  ar & BOOST_SERIALIZATION_NVP(body_P_sensor);
68 
69  // Provide support for Eigen::Matrix in boost::optional
70  bool omegaCoriolisFlag = omegaCoriolis.is_initialized();
71  ar & boost::serialization::make_nvp("omegaCoriolisFlag", omegaCoriolisFlag);
72  if (omegaCoriolisFlag) {
73  ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis);
74  }
75  }
76 
77 #ifdef GTSAM_USE_QUATERNIONS
78  // Align if we are using Quaternions
79 public:
81 #endif
82 };
83 
89 class GTSAM_EXPORT PreintegratedRotation {
90  public:
92 
93  protected:
95  boost::shared_ptr<Params> p_;
96 
97  double deltaTij_;
100 
103 
104  public:
107 
109  explicit PreintegratedRotation(const boost::shared_ptr<Params>& p) : p_(p) {
110  resetIntegration();
111  }
112 
114  PreintegratedRotation(const boost::shared_ptr<Params>& p,
115  double deltaTij, const Rot3& deltaRij,
116  const Matrix3& delRdelBiasOmega)
117  : p_(p), deltaTij_(deltaTij), deltaRij_(deltaRij), delRdelBiasOmega_(delRdelBiasOmega) {}
118 
120 
123 
125  void resetIntegration();
126 
128  bool matchesParamsWith(const PreintegratedRotation& other) const {
129  return p_ == other.p_;
130  }
132 
135  const boost::shared_ptr<Params>& params() const {
136  return p_;
137  }
138  const double& deltaTij() const {
139  return deltaTij_;
140  }
141  const Rot3& deltaRij() const {
142  return deltaRij_;
143  }
144  const Matrix3& delRdelBiasOmega() const {
145  return delRdelBiasOmega_;
146  }
148 
151  void print(const std::string& s) const;
152  bool equals(const PreintegratedRotation& other, double tol) const;
154 
157 
161  Rot3 incrementalRotation(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
162  OptionalJacobian<3, 3> D_incrR_integratedOmega) const;
163 
166  void integrateMeasurement(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
167  OptionalJacobian<3, 3> D_incrR_integratedOmega = boost::none,
168  OptionalJacobian<3, 3> F = boost::none);
169 
171  Rot3 biascorrectedDeltaRij(const Vector3& biasOmegaIncr,
172  OptionalJacobian<3, 3> H = boost::none) const;
173 
175  Vector3 integrateCoriolis(const Rot3& rot_i) const;
176 
178 
179  private:
181  friend class boost::serialization::access;
182  template <class ARCHIVE>
183  void serialize(ARCHIVE& ar, const unsigned int /*version*/) { // NOLINT
184  ar& BOOST_SERIALIZATION_NVP(p_);
185  ar& BOOST_SERIALIZATION_NVP(deltaTij_);
186  ar& BOOST_SERIALIZATION_NVP(deltaRij_);
187  ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
188  }
189 
190 #ifdef GTSAM_USE_QUATERNIONS
191  // Align if we are using Quaternions
192  public:
194 #endif
195 };
196 
197 template <>
198 struct traits<PreintegratedRotation> : public Testable<PreintegratedRotation> {};
199 
200 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
PreintegratedRotationParams Params
void setOmegaCoriolis(const Vector3 &omega)
void serialize(ARCHIVE &ar, const unsigned int)
const Matrix3 & getGyroscopeCovariance() const
Eigen::Vector3d Vector3
Definition: Vector.h:43
const Matrix3 & delRdelBiasOmega() const
PreintegratedRotation(const boost::shared_ptr< Params > &p, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega)
Explicit initialization of all class members.
PreintegratedRotation(const boost::shared_ptr< Params > &p)
Default constructor, resets integration to zero.
boost::optional< Vector3 > omegaCoriolis
Coriolis constant.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
const double & deltaTij() const
bool matchesParamsWith(const PreintegratedRotation &other) const
check parameters equality: checks whether shared pointer points to same Params object.
void serialize(ARCHIVE &ar, const unsigned int)
Signature::Row F
Definition: Signature.cpp:53
const boost::shared_ptr< Params > & params() const
PreintegratedRotation()
Default constructor for serialization.
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Matrix3 delRdelBiasOmega_
Jacobian of preintegrated rotation w.r.t. angular rate bias.
static const double deltaT
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::optional< Pose3 > body_P_sensor
The pose of the sensor in the body frame.
traits
Definition: chartTesting.h:28
static const Vector3 measuredOmega(w, 0, 0)
boost::optional< Vector3 > getOmegaCoriolis() const
void setGyroscopeCovariance(const Matrix3 &cov)
PreintegratedRotationParams(const Matrix3 &gyroscope_covariance, boost::optional< Vector3 > omega_coriolis)
float * p
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
Rot3 deltaRij_
Preintegrated relative orientation (in frame i)
const G double tol
Definition: Group.h:83
boost::shared_ptr< Params > p_
Parameters.
3D Pose
boost::optional< Pose3 > getBodyPSensor() const
double deltaTij_
Time interval from i to j.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:29