Go to the documentation of this file.
27 #include "gtsam/dllexport.h"
67 std::optional<Vector3> omega_coriolis)
68 : gyroscopeCovariance(gyroscope_covariance) {
70 omegaCoriolis = *omega_coriolis;
76 virtual void print(
const std::string&
s)
const;
88 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
90 friend class boost::serialization::access;
91 template<
class ARCHIVE>
92 void serialize(ARCHIVE & ar,
const unsigned int ) {
93 ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance);
97 bool omegaCoriolisFlag = omegaCoriolis.has_value();
98 ar & boost::serialization::make_nvp(
"omegaCoriolisFlag", omegaCoriolisFlag);
99 if (omegaCoriolisFlag) {
100 ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis);
105 #ifdef GTSAM_USE_QUATERNIONS
123 std::shared_ptr<Params>
p_;
143 double deltaTij,
const Rot3& deltaRij,
144 const Matrix3& delRdelBiasOmega)
145 : p_(
p), deltaTij_(deltaTij), deltaRij_(deltaRij), delRdelBiasOmega_(delRdelBiasOmega) {}
153 void resetIntegration();
157 return p_ ==
other.p_;
163 const std::shared_ptr<Params>&
params()
const {
return p_; }
164 const double&
deltaTij()
const {
return deltaTij_; }
171 void print(
const std::string&
s)
const;
196 Rot3 biascorrectedDeltaRij(
const Vector3& biasOmegaIncr,
197 OptionalJacobian<3, 3>
H = {})
const;
200 Vector3 integrateCoriolis(
const Rot3& rot_i)
const;
207 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
211 OptionalJacobian<3, 3> D_incrR_integratedOmega)
const {
213 Rot3 incrR =
f(
bias, D_incrR_integratedOmega);
215 if (D_incrR_integratedOmega) *D_incrR_integratedOmega /= -
deltaT;
223 OptionalJacobian<3, 3> D_incrR_integratedOmega, OptionalJacobian<3, 3>
F);
230 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
232 friend class boost::serialization::access;
233 template <
class ARCHIVE>
234 void serialize(ARCHIVE& ar,
const unsigned int ) {
235 ar& BOOST_SERIALIZATION_NVP(p_);
236 ar& BOOST_SERIALIZATION_NVP(deltaTij_);
237 ar& BOOST_SERIALIZATION_NVP(deltaRij_);
238 ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
242 #ifdef GTSAM_USE_QUATERNIONS
const Vector3 & measuredOmega
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
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
const Matrix3 & delRdelBiasOmega() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
typedef and functions to augment Eigen's MatrixXd
const Rot3 & deltaRij() const
bool matchesParamsWith(const PreintegratedRotation &other) const
check parameters equality: checks whether shared pointer points to same Params object.
PreintegratedRotationParams(const Matrix3 &gyroscope_covariance, std::optional< Vector3 > omega_coriolis)
std::optional< Pose3 > getBodyPSensor() const
double deltaTij_
Time interval from i to j.
const Vector3 bias(1, 2, 3)
PreintegratedRotationParams Params
const std::optional< Pose3 > & body_P_sensor
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
Matrix3 delRdelBiasOmega_
Jacobian of preintegrated rotation w.r.t. angular rate bias.
PreintegratedRotation()
Default constructor for serialization.
PreintegratedRotation(const std::shared_ptr< Params > &p)
Default constructor, resets integration to zero.
PreintegratedRotationParams()
static const double deltaT
std::optional< Vector3 > getOmegaCoriolis() const
void print(const Matrix &A, const string &s, ostream &stream)
const Matrix3 & getGyroscopeCovariance() const
const Vector3 measuredOmega
Matrix3 gyroscopeCovariance
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
void setGyroscopeCovariance(const Matrix3 &cov)
std::optional< Pose3 > body_P_sensor
The pose of the sensor in the body frame.
void setOmegaCoriolis(const Vector3 &omega)
virtual ~PreintegratedRotationParams()
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
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.
const std::shared_ptr< Params > & params() const
std::optional< Vector3 > omegaCoriolis
Coriolis constant.
void setBodyPSensor(const Pose3 &pose)
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Function object for incremental rotation.
3D Pose manifold SO(3) x R^3 and group SE(3)
Rot3 deltaRij_
Preintegrated relative orientation (in frame i)
std::shared_ptr< Params > p_
Parameters.
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:46