42 std::optional<Vector3> omega_coriolis)
43 : gyroscopeCovariance(gyroscope_covariance) {
45 omegaCoriolis = *omega_coriolis;
51 virtual void print(
const std::string&
s)
const;
63 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 65 friend class boost::serialization::access;
66 template<
class ARCHIVE>
67 void serialize(ARCHIVE & ar,
const unsigned int ) {
68 namespace bs = ::boost::serialization;
69 ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance);
70 ar & BOOST_SERIALIZATION_NVP(body_P_sensor);
73 bool omegaCoriolisFlag = omegaCoriolis.has_value();
74 ar & boost::serialization::make_nvp(
"omegaCoriolisFlag", omegaCoriolisFlag);
75 if (omegaCoriolisFlag) {
76 ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis);
81 #ifdef GTSAM_USE_QUATERNIONS 99 std::shared_ptr<Params>
p_;
119 double deltaTij,
const Rot3& deltaRij,
120 const Matrix3& delRdelBiasOmega)
121 : p_(p), deltaTij_(deltaTij), deltaRij_(deltaRij), delRdelBiasOmega_(delRdelBiasOmega) {}
129 void resetIntegration();
133 return p_ == other.
p_;
139 const std::shared_ptr<Params>&
params()
const {
149 return delRdelBiasOmega_;
155 void print(
const std::string&
s)
const;
170 void integrateMeasurement(
const Vector3& measuredOmega,
const Vector3& biasHat,
double deltaT,
175 Rot3 biascorrectedDeltaRij(
const Vector3& biasOmegaIncr,
179 Vector3 integrateCoriolis(
const Rot3& rot_i)
const;
184 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 186 friend class boost::serialization::access;
187 template <
class ARCHIVE>
188 void serialize(ARCHIVE& ar,
const unsigned int ) {
189 ar& BOOST_SERIALIZATION_NVP(p_);
190 ar& BOOST_SERIALIZATION_NVP(deltaTij_);
191 ar& BOOST_SERIALIZATION_NVP(deltaRij_);
192 ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
196 #ifdef GTSAM_USE_QUATERNIONS void print(const Matrix &A, const string &s, ostream &stream)
const Rot3 & deltaRij() const
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.
void setBodyPSensor(const Pose3 &pose)
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...
PreintegratedRotationParams()
const double & deltaTij() const
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)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::optional< Vector3 > omegaCoriolis
Coriolis constant.
virtual ~PreintegratedRotationParams()
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.
std::shared_ptr< Params > p_
Parameters.
const Matrix3 & getGyroscopeCovariance() const
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Rot3 deltaRij_
Preintegrated relative orientation (in frame i)
Matrix3 gyroscopeCovariance
const std::shared_ptr< Params > & params() const
double deltaTij_
Time interval from i to j.