35 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 36 struct PoseVelocityBias {
40 imuBias::ConstantBias bias;
41 PoseVelocityBias(
const Pose3& _pose,
const Vector3& _velocity,
42 const imuBias::ConstantBias _bias) :
43 pose(_pose), velocity(_velocity), bias(_bias) {
45 PoseVelocityBias(
const NavState& navState,
const imuBias::ConstantBias _bias) :
46 pose(navState.pose()), velocity(navState.velocity()), bias(_bias) {
48 NavState navState()
const {
49 return NavState(pose, velocity);
68 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 71 boost::shared_ptr<Params>
p_;
102 virtual void resetIntegration() = 0;
107 void resetIntegrationAndSetBias(
const Bias& biasHat);
111 return p_.get() == other.
p_.get();
115 const boost::shared_ptr<Params>&
params()
const {
121 return *boost::static_pointer_cast<Params>(p_);
124 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 125 void set_body_P_sensor(
const Pose3& body_P_sensor) {
126 p_->body_P_sensor = body_P_sensor;
133 const imuBias::ConstantBias& biasHat()
const {
return biasHat_; }
134 double deltaTij()
const {
return deltaTij_; }
136 virtual Vector3 deltaPij()
const = 0;
137 virtual Vector3 deltaVij()
const = 0;
138 virtual Rot3 deltaRij()
const = 0;
139 virtual NavState deltaXij()
const = 0;
142 Vector6 biasHatVector()
const {
return biasHat_.
vector(); }
147 GTSAM_EXPORT
friend std::ostream& operator<<(std::ostream& os,
const PreintegrationBase& pim);
148 virtual void print(
const std::string& s)
const;
159 std::pair<Vector3, Vector3> correctMeasurementsBySensorPose(
160 const Vector3& unbiasedAcc,
const Vector3& unbiasedOmega,
161 OptionalJacobian<3, 3> correctedAcc_H_unbiasedAcc = boost::none,
162 OptionalJacobian<3, 3> correctedAcc_H_unbiasedOmega = boost::none,
163 OptionalJacobian<3, 3> correctedOmega_H_unbiasedOmega = boost::none)
const;
170 virtual void update(
const Vector3& measuredAcc,
const Vector3& measuredOmega,
171 const double dt, Matrix9* A, Matrix93* B, Matrix93* C) = 0;
174 virtual void integrateMeasurement(
const Vector3& measuredAcc,
175 const Vector3& measuredOmega,
const double dt);
179 virtual Vector9 biasCorrectedDelta(
const imuBias::ConstantBias& bias_i,
180 OptionalJacobian<9, 6> H = boost::none)
const = 0;
183 NavState predict(
const NavState& state_i,
const imuBias::ConstantBias& bias_i,
184 OptionalJacobian<9, 9> H1 = boost::none,
185 OptionalJacobian<9, 6> H2 = boost::none)
const;
188 Vector9 computeError(
const NavState& state_i,
const NavState& state_j,
189 const imuBias::ConstantBias& bias_i,
190 OptionalJacobian<9, 9> H1, OptionalJacobian<9, 9> H2,
191 OptionalJacobian<9, 6> H3)
const;
197 Vector9 computeErrorAndJacobians(
const Pose3& pose_i,
const Vector3& vel_i,
198 const Pose3& pose_j,
const Vector3& vel_j,
199 const imuBias::ConstantBias& bias_i, OptionalJacobian<9, 6> H1 =
200 boost::none, OptionalJacobian<9, 3> H2 = boost::none,
201 OptionalJacobian<9, 6> H3 = boost::none, OptionalJacobian<9, 3> H4 =
202 boost::none, OptionalJacobian<9, 6> H5 = boost::none)
const;
204 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 209 PoseVelocityBias predict(
const Pose3& pose_i,
const Vector3& vel_i,
210 const imuBias::ConstantBias& bias_i,
const Vector3& n_gravity,
211 const Vector3& omegaCoriolis,
const bool use2ndOrderCoriolis =
false)
const;
217 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool matchesParamsWith(const PreintegrationBase &other) const
check parameters equality: checks whether shared pointer points to same Params object.
Definition: PreintegrationBase.h:110
const boost::shared_ptr< Params > & params() const
shared pointer to params
Definition: PreintegrationBase.h:115
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
PreintegrationBase is the base class for PreintegratedMeasurements (in ImuFactor) and CombinedPreinte...
Definition: PreintegrationBase.h:60
Bias biasHat_
Acceleration and gyro bias used for preintegration.
Definition: PreintegrationBase.h:74
PreintegrationBase()
Default constructor for serialization.
Definition: PreintegrationBase.h:80
boost::shared_ptr< Params > p_
Parameters.
Definition: PreintegrationBase.h:71
virtual ~PreintegrationBase()
Virtual destructor for serialization.
Definition: PreintegrationBase.h:83
double deltaTij_
Time interval from i to j.
Definition: PreintegrationBase.h:77
Vector6 vector() const
return the accelerometer and gyro biases in a single vector
Definition: ImuBias.h:52
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Navigation state composing of attitude, position, and velocity.
const Params & p() const
const reference to params
Definition: PreintegrationBase.h:120
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegrationParams.h:26