41 boost::optional<Vector3> omega_coriolis)
42 : gyroscopeCovariance(gyroscope_covariance) {
44 omegaCoriolis.reset(omega_coriolis.get());
49 virtual void print(
const std::string&
s)
const;
62 friend class boost::serialization::access;
63 template<
class ARCHIVE>
65 namespace bs = ::boost::serialization;
66 ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance);
67 ar & BOOST_SERIALIZATION_NVP(body_P_sensor);
70 bool omegaCoriolisFlag = omegaCoriolis.is_initialized();
71 ar & boost::serialization::make_nvp(
"omegaCoriolisFlag", omegaCoriolisFlag);
72 if (omegaCoriolisFlag) {
73 ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis);
77 #ifdef GTSAM_USE_QUATERNIONS 95 boost::shared_ptr<Params>
p_;
115 double deltaTij,
const Rot3& deltaRij,
116 const Matrix3& delRdelBiasOmega)
117 : p_(p), deltaTij_(deltaTij), deltaRij_(deltaRij), delRdelBiasOmega_(delRdelBiasOmega) {}
125 void resetIntegration();
129 return p_ == other.
p_;
135 const boost::shared_ptr<Params>&
params()
const {
145 return delRdelBiasOmega_;
151 void print(
const std::string&
s)
const;
166 void integrateMeasurement(
const Vector3& measuredOmega,
const Vector3& biasHat,
double deltaT,
171 Rot3 biascorrectedDeltaRij(
const Vector3& biasOmegaIncr,
175 Vector3 integrateCoriolis(
const Rot3& rot_i)
const;
181 friend class boost::serialization::access;
182 template <
class ARCHIVE>
184 ar& BOOST_SERIALIZATION_NVP(p_);
185 ar& BOOST_SERIALIZATION_NVP(deltaTij_);
186 ar& BOOST_SERIALIZATION_NVP(deltaRij_);
187 ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
190 #ifdef GTSAM_USE_QUATERNIONS void print(const Matrix &A, const string &s, ostream &stream)
PreintegratedRotationParams Params
void setOmegaCoriolis(const Vector3 &omega)
void serialize(ARCHIVE &ar, const unsigned int)
const Matrix3 & getGyroscopeCovariance() const
void setBodyPSensor(const Pose3 &pose)
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
PreintegratedRotationParams()
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)
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.)
boost::optional< Pose3 > body_P_sensor
The pose of the sensor in the body frame.
virtual ~PreintegratedRotationParams()
static const Vector3 measuredOmega(w, 0, 0)
boost::optional< Vector3 > getOmegaCoriolis() const
void setGyroscopeCovariance(const Matrix3 &cov)
const Rot3 & deltaRij() const
PreintegratedRotationParams(const Matrix3 &gyroscope_covariance, boost::optional< Vector3 > omega_coriolis)
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Rot3 deltaRij_
Preintegrated relative orientation (in frame i)
Matrix3 gyroscopeCovariance
boost::shared_ptr< Params > p_
Parameters.
boost::optional< Pose3 > getBodyPSensor() const
double deltaTij_
Time interval from i to j.