32 #ifdef GTSAM_TANGENT_PREINTEGRATION 33 typedef TangentPreintegration PreintegrationType;
35 typedef ManifoldPreintegration PreintegrationType;
85 static boost::shared_ptr<Params> MakeSharedD(
double g = 9.81) {
86 return boost::shared_ptr<Params>(
new Params(Vector3(0, 0, g)));
90 static boost::shared_ptr<Params> MakeSharedU(
double g = 9.81) {
91 return boost::shared_ptr<Params>(
new Params(Vector3(0, 0, -g)));
100 template <
class ARCHIVE>
101 void serialize(ARCHIVE& ar,
const unsigned int ) {
109 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
119 Eigen::Matrix<double, 15, 15> preintMeasCov_;
136 const boost::shared_ptr<Params>&
p,
139 preintMeasCov_.setZero();
151 Params&
p()
const {
return *boost::static_pointer_cast<Params>(this->
p_);}
156 Matrix preintMeasCov()
const {
return preintMeasCov_; }
161 void print(
const std::string& s =
"Preintegrated Measurements:")
const override;
178 const Vector3& measuredOmega,
const double dt)
override;
182 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 186 const Matrix3& measuredAccCovariance,
187 const Matrix3& measuredOmegaCovariance,
188 const Matrix3& integrationErrorCovariance,
189 const Matrix3& biasAccCovariance,
const Matrix3& biasOmegaCovariance,
190 const Matrix6& biasAccOmegaInt,
const bool use2ndOrderIntegration =
true);
196 template <
class ARCHIVE>
197 void serialize(ARCHIVE& ar,
const unsigned int ) {
199 ar& BOOST_SERIALIZATION_NVP(preintMeasCov_);
203 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
226 Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
243 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5 244 typedef typename boost::shared_ptr<CombinedImuFactor>
shared_ptr;
266 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const;
272 DefaultKeyFormatter)
const;
287 const Pose3& pose_j,
const Vector3& vel_j,
289 boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 =
290 boost::none, boost::optional<Matrix&> H3 = boost::none,
291 boost::optional<Matrix&> H4 = boost::none, boost::optional<Matrix&> H5 =
292 boost::none, boost::optional<Matrix&> H6 = boost::none)
const;
294 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 300 Key bias_j,
const CombinedPreintegratedMeasurements& pim,
301 const Vector3& n_gravity,
const Vector3& omegaCoriolis,
302 const boost::optional<Pose3>& body_P_sensor = boost::none,
303 const bool use2ndOrderCoriolis =
false);
306 static void Predict(
const Pose3& pose_i,
const Vector3& vel_i,
Pose3& pose_j,
308 CombinedPreintegratedMeasurements& pim,
309 const Vector3& n_gravity,
const Vector3& omegaCoriolis,
310 const bool use2ndOrderCoriolis =
false);
317 template<
class ARCHIVE>
318 void serialize(ARCHIVE & ar,
const unsigned int ) {
319 ar & boost::serialization::make_nvp(
"NoiseModelFactor6",
320 boost::serialization::base_object<Base>(*
this));
321 ar & BOOST_SERIALIZATION_NVP(_PIM_);
325 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Vector3 n_gravity
Gravity vector in nav frame.
Definition: PreintegrationParams.h:30
virtual bool equals(const NonlinearFactor &expected, double tol=1e-9) const
equals
Definition: CombinedImuFactor.cpp:175
This is the base class for all factor types.
Definition: Factor.h:54
Params(const Vector3 &n_gravity)
See two named constructors below for good values of n_gravity in body frame.
Definition: CombinedImuFactor.h:79
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: CombinedImuFactor.cpp:158
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: CombinedImuFactor.h:73
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
Add a single IMU measurement to the preintegration.
Definition: CombinedImuFactor.cpp:67
IMU pre-integration on NavSatet manifold.
Definition: ManifoldPreintegration.h:33
boost::shared_ptr< Params > p_
Parameters.
Definition: PreintegrationBase.h:71
Definition: CombinedImuFactor.h:67
Matrix6 biasAccOmegaInt
covariance of bias used for pre-integration
Definition: CombinedImuFactor.h:76
PreintegratedCombinedMeasurements()
Default constructor only for serialization and Cython wrapper.
Definition: CombinedImuFactor.h:129
Params & p() const
const reference to params, shadows definition in base class
Definition: CombinedImuFactor.h:151
friend class boost::serialization::access
Serialization function.
Definition: CombinedImuFactor.h:316
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
Definition: CombinedImuFactor.h:225
A convenient base class for creating your own NoiseModelFactor with 6 variables.
Definition: NonlinearFactor.h:663
Non-linear factor base classes.
virtual void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
implement functions needed for Testable
Definition: CombinedImuFactor.cpp:164
friend class boost::serialization::access
Serialization function.
Definition: CombinedImuFactor.h:195
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, const imuBias::ConstantBias &bias_j, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none, boost::optional< Matrix & > H6=boost::none) const
implement functions needed to derive from Factor
Definition: CombinedImuFactor.cpp:181
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
void resetIntegration() override
Re-initialize PreintegratedCombinedMeasurements.
Definition: CombinedImuFactor.cpp:47
const PreintegratedCombinedMeasurements & preintegratedMeasurements() const
Access the preintegrated measurements.
Definition: CombinedImuFactor.h:279
typedef and functions to augment Eigen's MatrixXd
Matrix3 biasOmegaCovariance
continuous-time "Covariance" describing gyroscope bias random walk
Definition: CombinedImuFactor.h:75
boost::shared_ptr< CombinedImuFactor > shared_ptr
Shorthand for a smart pointer to a factor.
Definition: CombinedImuFactor.h:246
PreintegratedCombinedMeasurements(const boost::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
Default constructor, initializes the class with no measurements.
Definition: CombinedImuFactor.h:135
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegrationParams.h:26
Matrix3 biasAccCovariance
continuous-time "Covariance" describing accelerometer bias random walk
Definition: CombinedImuFactor.h:74
friend class boost::serialization::access
Serialization function.
Definition: CombinedImuFactor.h:99