32 #ifdef GTSAM_TANGENT_PREINTEGRATION 95 PreintegrationType(p, biasHat) {
105 : PreintegrationType(base),
106 preintMeasCov_(preintMeasCov) {
114 void print(
const std::string&
s =
"Preintegrated Measurements:")
const override;
120 void resetIntegration()
override;
138 #ifdef GTSAM_TANGENT_PREINTEGRATION 145 friend class boost::serialization::access;
146 template<
class ARCHIVE>
148 namespace bs = ::boost::serialization;
149 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
150 ar & BOOST_SERIALIZATION_NVP(preintMeasCov_);
167 imuBias::ConstantBias> {
179 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5 180 typedef typename boost::shared_ptr<ImuFactor>
shared_ptr;
223 Vector evaluateError(
const Pose3& pose_i,
const Vector3& vel_i,
225 const Pose3& pose_j,
const Vector3& vel_j,
227 boost::none, boost::optional<Matrix&> H2 = boost::none,
228 boost::optional<Matrix&> H3 = boost::none, boost::optional<Matrix&> H4 =
229 boost::none, boost::optional<Matrix&> H5 = boost::none)
const override;
231 #ifdef GTSAM_TANGENT_PREINTEGRATION 238 static shared_ptr Merge(
const shared_ptr& f01,
const shared_ptr& f12);
243 friend class boost::serialization::access;
244 template<
class ARCHIVE>
246 ar & boost::serialization::make_nvp(
"NoiseModelFactor5",
247 boost::serialization::base_object<Base>(*
this));
248 ar & BOOST_SERIALIZATION_NVP(_PIM_);
304 boost::optional<Matrix&> H1 = boost::none,
305 boost::optional<Matrix&> H2 = boost::none,
306 boost::optional<Matrix&> H3 = boost::none)
const override;
311 friend class boost::serialization::access;
312 template<
class ARCHIVE>
314 ar & boost::serialization::make_nvp(
"NoiseModelFactor3",
315 boost::serialization::base_object<Base>(*
this));
316 ar & BOOST_SERIALIZATION_NVP(_PIM_);
void print(const Matrix &A, const string &s, ostream &stream)
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
~PreintegratedImuMeasurements() override
Virtual destructor.
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
void serialize(ARCHIVE &ar, const unsigned int)
static const KeyFormatter DefaultKeyFormatter
PreintegratedImuMeasurements _PIM_
PreintegratedImuMeasurements _PIM_
ManifoldPreintegration PreintegrationType
PreintegratedImuMeasurements()
Default constructor for serialization and wrappers.
boost::shared_ptr< This > shared_ptr
Matrix preintMeasCov() const
Return pre-integrated measurement covariance.
boost::shared_ptr< ImuFactor > shared_ptr
NoiseModelFactor3< NavState, NavState, imuBias::ConstantBias > Base
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Matrix9 preintMeasCov_
(first-order propagation from measurementCovariance).
static const Vector3 measuredAcc
NoiseModelFactor5< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias > Base
static const Vector3 measuredOmega(w, 0, 0)
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
void serialize(ARCHIVE &ar, const unsigned int)
Non-linear factor base classes.
ofstream os("timeSchurFactors.csv")
const PreintegratedImuMeasurements & preintegratedMeasurements() const
void serialize(ARCHIVE &ar, const unsigned int)
const PreintegratedImuMeasurements & preintegratedMeasurements() const
PreintegratedImuMeasurements(const boost::shared_ptr< PreintegrationParams > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
PreintegratedImuMeasurements(const PreintegrationType &base, const Matrix9 &preintMeasCov)
Annotation indicating that a class derives from another given type.
std::uint64_t Key
Integer nonlinear key type.