33 #ifdef GTSAM_TANGENT_PREINTEGRATION 34 typedef TangentPreintegration PreintegrationType;
36 typedef ManifoldPreintegration PreintegrationType;
69 : biasAccCovariance(I_3x3),
70 biasOmegaCovariance(I_3x3),
71 biasAccOmegaInt(I_6x6) {}
76 biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) {
81 static std::shared_ptr<PreintegrationCombinedParams> MakeSharedD(
double g = 9.81) {
86 static std::shared_ptr<PreintegrationCombinedParams> MakeSharedU(
double g = 9.81) {
90 void print(
const std::string& s=
"")
const override;
93 void setBiasAccCovariance(
const Matrix3& cov) { biasAccCovariance=cov; }
94 void setBiasOmegaCovariance(
const Matrix3& cov) { biasOmegaCovariance=cov; }
95 void setBiasAccOmegaInit(
const Matrix6& cov) { biasAccOmegaInt=cov; }
97 const Matrix3& getBiasAccCovariance()
const {
return biasAccCovariance; }
98 const Matrix3& getBiasOmegaCovariance()
const {
return biasOmegaCovariance; }
99 const Matrix6& getBiasAccOmegaInit()
const {
return biasAccOmegaInt; }
103 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 105 friend class boost::serialization::access;
106 template <
class ARCHIVE>
107 void serialize(ARCHIVE& ar,
const unsigned int ) {
108 namespace bs = ::boost::serialization;
110 ar & BOOST_SERIALIZATION_NVP(biasAccCovariance);
111 ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance);
112 ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt);
142 Eigen::Matrix<double, 15, 15> preintMeasCov_;
152 preintMeasCov_.setZero();
161 const std::shared_ptr<Params>& p,
163 : PreintegrationType(p, biasHat) {
164 preintMeasCov_.setZero();
173 : PreintegrationType(base),
174 preintMeasCov_(preintMeasCov) {
186 void resetIntegration()
override;
189 Params&
p()
const {
return *std::static_pointer_cast<Params>(this->p_); }
195 Matrix preintMeasCov()
const {
return preintMeasCov_; }
201 void print(
const std::string& s =
"Preintegrated Measurements:")
const override;
204 double tol = 1e-9)
const;
221 void integrateMeasurement(
const Vector3& measuredAcc,
222 const Vector3& measuredOmega,
const double dt)
override;
227 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 228 friend class boost::serialization::access; 230 template <
class ARCHIVE>
231 void serialize(ARCHIVE& ar,
const unsigned int ) {
232 namespace bs = ::boost::serialization;
233 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
234 ar& BOOST_SERIALIZATION_NVP(preintMeasCov_);
262 Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
276 using Base::evaluateError;
279 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5 280 typedef typename std::shared_ptr<CombinedImuFactor> shared_ptr;
305 gtsam::NonlinearFactor::shared_ptr clone()
const override;
309 GTSAM_EXPORT
friend std::ostream& operator<<(std::ostream& os,
315 DefaultKeyFormatter)
const override;
329 Vector evaluateError(
const Pose3& pose_i,
const Vector3& vel_i,
331 const Pose3& pose_j,
const Vector3& vel_j,
332 const imuBias::ConstantBias& bias_i,
const imuBias::ConstantBias& bias_j,
338 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 340 friend class boost::serialization::access;
341 template <
class ARCHIVE>
342 void serialize(ARCHIVE& ar,
const unsigned int ) {
344 ar& boost::serialization::make_nvp(
345 "NoiseModelFactor6", boost::serialization::base_object<Base>(*
this));
346 ar& BOOST_SERIALIZATION_NVP(_PIM_);
357 :
public Testable<PreintegrationCombinedParams> {};
361 :
public Testable<PreintegratedCombinedMeasurements> {};
Definition: NonlinearFactor.h:431
std::shared_ptr< CombinedImuFactor > shared_ptr
Definition: CombinedImuFactor.h:282
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Matrix6 biasAccOmegaInt
covariance of bias used as initial estimate.
Definition: CombinedImuFactor.h:64
Definition: Testable.h:152
Definition: CombinedImuFactor.h:130
Params & p() const
const reference to params, shadows definition in base class
Definition: CombinedImuFactor.h:189
Definition: NonlinearFactor.h:68
PreintegratedCombinedMeasurements()
Default constructor only for serialization and wrappers.
Definition: CombinedImuFactor.h:151
const PreintegratedCombinedMeasurements & preintegratedMeasurements() const
Definition: CombinedImuFactor.h:323
CombinedImuFactor()
Definition: CombinedImuFactor.h:286
Definition: Testable.h:112
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
PreintegrationCombinedParams(const Vector3 &_n_gravity)
See two named constructors below for good values of n_gravity in body frame.
Definition: CombinedImuFactor.h:74
~PreintegratedCombinedMeasurements() override
Virtual destructor.
Definition: CombinedImuFactor.h:178
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
PreintegrationCombinedParams()
Definition: CombinedImuFactor.h:68
typedef and functions to augment Eigen's MatrixXd
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
Definition: CombinedImuFactor.h:61
Definition: chartTesting.h:28
Matrix3 biasOmegaCovariance
continuous-time "Covariance" describing gyroscope bias random walk
Definition: CombinedImuFactor.h:63
PreintegratedCombinedMeasurements(const std::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
Definition: CombinedImuFactor.h:160
Non-linear factor base classes.
Definition: PreintegratedRotation.h:32
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
PreintegratedCombinedMeasurements(const PreintegrationType &base, const Eigen::Matrix< double, 15, 15 > &preintMeasCov)
Definition: CombinedImuFactor.h:172
Definition: CombinedImuFactor.h:261
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Definition: PreintegrationParams.h:25
Matrix3 biasAccCovariance
continuous-time "Covariance" describing accelerometer bias random walk
Definition: CombinedImuFactor.h:62