40 virtual void print(
const std::string& s)
const;
41 virtual bool equals(
const PreintegratedRotationParams& other,
double tol=1e-9)
const;
43 void setGyroscopeCovariance(
const Matrix3& cov) { gyroscopeCovariance = cov; }
44 void setOmegaCoriolis(
const Vector3& omega) { omegaCoriolis.reset(omega); }
45 void setBodyPSensor(
const Pose3& pose) { body_P_sensor.reset(pose); }
47 const Matrix3& getGyroscopeCovariance()
const {
return gyroscopeCovariance; }
48 boost::optional<Vector3> getOmegaCoriolis()
const {
return omegaCoriolis; }
49 boost::optional<Pose3> getBodyPSensor()
const {
return body_P_sensor; }
53 friend class boost::serialization::access;
54 template<
class ARCHIVE>
55 void serialize(ARCHIVE & ar,
const unsigned int ) {
56 namespace bs = ::boost::serialization;
57 ar & bs::make_nvp(
"gyroscopeCovariance", bs::make_array(gyroscopeCovariance.data(), gyroscopeCovariance.size()));
58 ar & BOOST_SERIALIZATION_NVP(omegaCoriolis);
59 ar & BOOST_SERIALIZATION_NVP(body_P_sensor);
62 #ifdef GTSAM_USE_QUATERNIONS 65 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 boost::shared_ptr<Params>
p_;
100 double deltaTij,
const Rot3& deltaRij,
101 const Matrix3& delRdelBiasOmega)
102 : p_(p), deltaTij_(deltaTij), deltaRij_(deltaRij), delRdelBiasOmega_(delRdelBiasOmega) {}
110 void resetIntegration();
114 return p_ == other.
p_;
120 const boost::shared_ptr<Params>& params()
const {
123 const double& deltaTij()
const {
126 const Rot3& deltaRij()
const {
129 const Matrix3& delRdelBiasOmega()
const {
130 return delRdelBiasOmega_;
136 void print(
const std::string& s)
const;
137 bool equals(
const PreintegratedRotation& other,
double tol)
const;
146 Rot3 incrementalRotation(
const Vector3& measuredOmega,
const Vector3& biasHat,
double deltaT,
147 OptionalJacobian<3, 3> D_incrR_integratedOmega)
const;
151 void integrateMeasurement(
const Vector3& measuredOmega,
const Vector3& biasHat,
double deltaT,
152 OptionalJacobian<3, 3> D_incrR_integratedOmega = boost::none,
153 OptionalJacobian<3, 3> F = boost::none);
156 Rot3 biascorrectedDeltaRij(
const Vector3& biasOmegaIncr,
157 OptionalJacobian<3, 3> H = boost::none)
const;
160 Vector3 integrateCoriolis(
const Rot3& rot_i)
const;
166 friend class boost::serialization::access;
167 template <
class ARCHIVE>
168 void serialize(ARCHIVE& ar,
const unsigned int ) {
169 ar& BOOST_SERIALIZATION_NVP(p_);
170 ar& BOOST_SERIALIZATION_NVP(deltaTij_);
171 ar& BOOST_SERIALIZATION_NVP(deltaRij_);
172 ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
175 #ifdef GTSAM_USE_QUATERNIONS 178 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
double deltaTij_
Time interval from i to j.
Definition: PreintegratedRotation.h:82
PreintegratedRotation is the base class for all PreintegratedMeasurements classes (in AHRSFactor,...
Definition: PreintegratedRotation.h:74
bool matchesParamsWith(const PreintegratedRotation &other) const
check parameters equality: checks whether shared pointer points to same Params object.
Definition: PreintegratedRotation.h:113
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegratedRotation.h:31
PreintegratedRotation()
Default constructor for serialization.
Definition: PreintegratedRotation.h:87
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
Rot3 deltaRij_
Preintegrated relative orientation (in frame i)
Definition: PreintegratedRotation.h:83
PreintegratedRotation(const boost::shared_ptr< Params > &p, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega)
Explicit initialization of all class members.
Definition: PreintegratedRotation.h:99
boost::shared_ptr< Params > p_
Parameters.
Definition: PreintegratedRotation.h:80
Matrix3 gyroscopeCovariance
continuous-time "Covariance" of gyroscope measurements
Definition: PreintegratedRotation.h:32
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Matrix3 delRdelBiasOmega_
Jacobian of preintegrated rotation w.r.t. angular rate bias.
Definition: PreintegratedRotation.h:84
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
PreintegratedRotation(const boost::shared_ptr< Params > &p)
Default constructor, resets integration to zero.
Definition: PreintegratedRotation.h:94
typedef and functions to augment Eigen's MatrixXd
boost::optional< Vector3 > omegaCoriolis
Coriolis constant.
Definition: PreintegratedRotation.h:33
boost::optional< Pose3 > body_P_sensor
The pose of the sensor in the body frame.
Definition: PreintegratedRotation.h:34