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>
27 
28 namespace gtsam {
29 
32 struct GTSAM_EXPORT PreintegratedRotationParams {
36  std::optional<Vector3> omegaCoriolis;
37  std::optional<Pose3> body_P_sensor;
38 
39  PreintegratedRotationParams() : gyroscopeCovariance(I_3x3) {}
40 
41  PreintegratedRotationParams(const Matrix3& gyroscope_covariance,
42  std::optional<Vector3> omega_coriolis)
43  : gyroscopeCovariance(gyroscope_covariance) {
44  if (omega_coriolis) {
45  omegaCoriolis = *omega_coriolis;
46  }
47  }
48 
50 
51  virtual void print(const std::string& s) const;
52  virtual bool equals(const PreintegratedRotationParams& other, double tol=1e-9) const;
53 
54  void setGyroscopeCovariance(const Matrix3& cov) { gyroscopeCovariance = cov; }
55  void setOmegaCoriolis(const Vector3& omega) { omegaCoriolis = omega; }
56  void setBodyPSensor(const Pose3& pose) { body_P_sensor = pose; }
57 
58  const Matrix3& getGyroscopeCovariance() const { return gyroscopeCovariance; }
59  std::optional<Vector3> getOmegaCoriolis() const { return omegaCoriolis; }
60  std::optional<Pose3> getBodyPSensor() const { return body_P_sensor; }
61 
62  private:
63 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
64 
65  friend class boost::serialization::access;
66  template<class ARCHIVE>
67  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
68  namespace bs = ::boost::serialization;
69  ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance);
70  ar & BOOST_SERIALIZATION_NVP(body_P_sensor);
71 
72  // Provide support for Eigen::Matrix in std::optional
73  bool omegaCoriolisFlag = omegaCoriolis.has_value();
74  ar & boost::serialization::make_nvp("omegaCoriolisFlag", omegaCoriolisFlag);
75  if (omegaCoriolisFlag) {
76  ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis);
77  }
78  }
79 #endif
80 
81 #ifdef GTSAM_USE_QUATERNIONS
82  // Align if we are using Quaternions
83 public:
85 #endif
86 };
87 
93 class GTSAM_EXPORT PreintegratedRotation {
94  public:
96 
97  protected:
99  std::shared_ptr<Params> p_;
100 
101  double deltaTij_;
104 
107 
108  public:
111 
113  explicit PreintegratedRotation(const std::shared_ptr<Params>& p) : p_(p) {
114  resetIntegration();
115  }
116 
118  PreintegratedRotation(const std::shared_ptr<Params>& p,
119  double deltaTij, const Rot3& deltaRij,
120  const Matrix3& delRdelBiasOmega)
121  : p_(p), deltaTij_(deltaTij), deltaRij_(deltaRij), delRdelBiasOmega_(delRdelBiasOmega) {}
122 
124 
127 
129  void resetIntegration();
130 
133  return p_ == other.p_;
134  }
136 
139  const std::shared_ptr<Params>& params() const {
140  return p_;
141  }
142  const double& deltaTij() const {
143  return deltaTij_;
144  }
145  const Rot3& deltaRij() const {
146  return deltaRij_;
147  }
148  const Matrix3& delRdelBiasOmega() const {
149  return delRdelBiasOmega_;
150  }
152 
155  void print(const std::string& s) const;
156  bool equals(const PreintegratedRotation& other, double tol) const;
158 
161 
165  Rot3 incrementalRotation(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
166  OptionalJacobian<3, 3> D_incrR_integratedOmega) const;
167 
170  void integrateMeasurement(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT,
171  OptionalJacobian<3, 3> D_incrR_integratedOmega = {},
173 
175  Rot3 biascorrectedDeltaRij(const Vector3& biasOmegaIncr,
176  OptionalJacobian<3, 3> H = {}) const;
177 
179  Vector3 integrateCoriolis(const Rot3& rot_i) const;
180 
182 
183  private:
184 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
185 
186  friend class boost::serialization::access;
187  template <class ARCHIVE>
188  void serialize(ARCHIVE& ar, const unsigned int /*version*/) { // NOLINT
189  ar& BOOST_SERIALIZATION_NVP(p_);
190  ar& BOOST_SERIALIZATION_NVP(deltaTij_);
191  ar& BOOST_SERIALIZATION_NVP(deltaRij_);
192  ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
193  }
194 #endif
195 
196 #ifdef GTSAM_USE_QUATERNIONS
197  // Align if we are using Quaternions
198  public:
200 #endif
201 };
202 
203 template <>
204 struct traits<PreintegratedRotation> : public Testable<PreintegratedRotation> {};
205 
206 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
PreintegratedRotationParams Params
void setOmegaCoriolis(const Vector3 &omega)
bool matchesParamsWith(const PreintegratedRotation &other) const
check parameters equality: checks whether shared pointer points to same Params object.
Key F(std::uint64_t j)
Eigen::Vector3d Vector3
Definition: Vector.h:43
std::string serialize(const T &input)
serializes to a string
PreintegratedRotation(const std::shared_ptr< Params > &p)
Default constructor, resets integration to zero.
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
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 Matrix3 & delRdelBiasOmega() const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
PreintegratedRotation(const std::shared_ptr< Params > &p, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega)
Explicit initialization of all class members.
PreintegratedRotation()
Default constructor for serialization.
Matrix3 delRdelBiasOmega_
Jacobian of preintegrated rotation w.r.t. angular rate bias.
PreintegratedRotationParams(const Matrix3 &gyroscope_covariance, std::optional< Vector3 > omega_coriolis)
std::optional< Pose3 > getBodyPSensor() const
std::optional< Vector3 > getOmegaCoriolis() const
static const double deltaT
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
Definition: IDRS.h:36
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::optional< Vector3 > omegaCoriolis
Coriolis constant.
traits
Definition: chartTesting.h:28
static const Vector3 measuredOmega(w, 0, 0)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
void setGyroscopeCovariance(const Matrix3 &cov)
std::optional< Pose3 > body_P_sensor
The pose of the sensor in the body frame.
float * p
std::shared_ptr< Params > p_
Parameters.
const Matrix3 & getGyroscopeCovariance() const
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
Rot3 deltaRij_
Preintegrated relative orientation (in frame i)
const G double tol
Definition: Group.h:86
3D Pose
const std::shared_ptr< Params > & params() const
double deltaTij_
Time interval from i to j.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:15