47 boost::shared_ptr<Params> p_;
78 virtual void resetIntegration() = 0;
83 void resetIntegrationAndSetBias(
const Bias& biasHat);
87 return p_.get() == other.p_.get();
91 const boost::shared_ptr<Params>&
params()
const {
105 double deltaTij()
const {
return deltaTij_; }
107 virtual Vector3 deltaPij()
const = 0;
108 virtual Vector3 deltaVij()
const = 0;
109 virtual Rot3 deltaRij()
const = 0;
110 virtual NavState deltaXij()
const = 0;
113 Vector6 biasHatVector()
const {
return biasHat_.
vector(); }
118 GTSAM_EXPORT
friend std::ostream& operator<<(std::ostream& os,
const PreintegrationBase& pim);
119 virtual void print(
const std::string& s=
"")
const;
130 std::pair<Vector3, Vector3> correctMeasurementsBySensorPose(
131 const Vector3& unbiasedAcc,
const Vector3& unbiasedOmega,
132 OptionalJacobian<3, 3> correctedAcc_H_unbiasedAcc = boost::none,
133 OptionalJacobian<3, 3> correctedAcc_H_unbiasedOmega = boost::none,
134 OptionalJacobian<3, 3> correctedOmega_H_unbiasedOmega = boost::none)
const;
141 virtual void update(
const Vector3& measuredAcc,
const Vector3& measuredOmega,
142 const double dt, Matrix9* A, Matrix93* B, Matrix93* C) = 0;
145 virtual void integrateMeasurement(
const Vector3& measuredAcc,
146 const Vector3& measuredOmega,
const double dt);
168 Vector9 computeErrorAndJacobians(
const Pose3& pose_i,
const Vector3& vel_i,
169 const Pose3& pose_j,
const Vector3& vel_j,
177 friend class boost::serialization::access;
178 template<
class ARCHIVE>
179 void serialize(ARCHIVE & ar,
const unsigned int ) {
180 ar & BOOST_SERIALIZATION_NVP(p_);
181 ar & BOOST_SERIALIZATION_NVP(biasHat_);
182 ar & BOOST_SERIALIZATION_NVP(deltaTij_);
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
This marks a GTSAM object to require alignment.
Definition: types.h:277
Navigation state composing of attitude, position, and velocity.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Vector6 vector() const
return the accelerometer and gyro biases in a single vector
Definition: ImuBias.h:52
Navigation state: Pose (rotation, translation) + velocity NOTE(frank): it does not make sense to make...
Definition: NavState.h:34
PreintegrationBase is the base class for PreintegratedMeasurements (in ImuFactor) and CombinedPreinte...
Definition: PreintegrationBase.h:41
double deltaTij_
Time interval from i to j.
Definition: PreintegrationBase.h:53
virtual ~PreintegrationBase()
Virtual destructor for serialization.
Definition: PreintegrationBase.h:59
bool matchesParamsWith(const PreintegrationBase &other) const
check parameters equality: checks whether shared pointer points to same Params object.
Definition: PreintegrationBase.h:86
virtual Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const =0
Given the estimate of the bias, return a NavState tangent vector summarizing the preintegrated IMU me...
Params & p() const
const reference to params
Definition: PreintegrationBase.h:96
Bias biasHat_
Acceleration and gyro bias used for preintegration.
Definition: PreintegrationBase.h:50
PreintegrationBase()
Default constructor for serialization.
Definition: PreintegrationBase.h:56
const boost::shared_ptr< Params > & params() const
shared pointer to params
Definition: PreintegrationBase.h:91
virtual void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C)=0
Update preintegrated measurements and get derivatives It takes measured quantities in the j frame Mod...
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegrationParams.h:26