36 cout <<
" preintMeasCov \n[" << preintMeasCov_ <<
"]" << endl;
49 preintMeasCov_.setZero();
56 throw std::runtime_error(
57 "PreintegratedImuMeasurements::integrateMeasurement: dt <=0");
71 const Matrix3& aCov =
p().accelerometerCovariance;
72 const Matrix3& wCov =
p().gyroscopeCovariance;
73 const Matrix3& iCov =
p().integrationCovariance;
76 preintMeasCov_ = A * preintMeasCov_ * A.transpose();
77 preintMeasCov_.noalias() += B * (aCov /
dt) * B.transpose();
78 preintMeasCov_.noalias() += C * (wCov /
dt) * C.transpose();
81 preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov *
dt;
86 const Matrix& measuredAccs,
const Matrix& measuredOmegas,
89 measuredAccs.rows() == 3 && measuredOmegas.rows() == 3 && dts.rows() == 1);
90 assert(dts.cols() >= 1);
91 assert(measuredAccs.cols() == dts.cols());
92 assert(measuredOmegas.cols() == dts.cols());
93 size_t n =
static_cast<size_t>(dts.cols());
94 for (
size_t j = 0;
j <
n;
j++) {
95 integrateMeasurement(measuredAccs.col(
j), measuredOmegas.col(
j), dts(0,
j));
100 #ifdef GTSAM_TANGENT_PREINTEGRATION 103 PreintegrationType::mergeWith(pim12, H1, H2);
105 const Matrix9 P = *H1 * preintMeasCov_ * H1->transpose();
106 preintMeasCov_ = P + *H2 * pim12.
preintMeasCov_ * H2->transpose();
115 Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i,
116 pose_j, vel_j, bias), _PIM_(pim) {
127 f.
_PIM_.
print(
"preintegrated measurements:\n");
128 os <<
" noise model sigmas: " << f.
noiseModel_->sigmas().transpose();
134 cout << (s.empty() ? s : s +
"\n") <<
"ImuFactor(" << keyFormatter(this->
key1())
135 <<
"," << keyFormatter(this->
key2()) <<
"," << keyFormatter(this->
key3())
136 <<
"," << keyFormatter(this->
key4()) <<
"," << keyFormatter(this->
key5())
138 cout << *
this << endl;
143 const This *
e =
dynamic_cast<const This*
>(&other);
146 return e !=
nullptr && base && pim;
153 boost::optional<Matrix&> H2, boost::optional<Matrix&> H3,
154 boost::optional<Matrix&> H4, boost::optional<Matrix&> H5)
const {
160 #ifdef GTSAM_TANGENT_PREINTEGRATION 165 throw std::domain_error(
166 "Cannot merge PreintegratedImuMeasurements with different params");
168 if (pim01.
params()->body_P_sensor)
169 throw std::domain_error(
170 "Cannot merge PreintegratedImuMeasurements with sensor pose yet");
176 pim02.mergeWith(pim12, &H1, &H2);
185 if (f01->key5() != f12->key5())
186 throw std::domain_error(
"ImuFactor::Merge: IMU bias keys must be the same");
189 if (f01->key3() != f12->key1() || f01->key4() != f12->key2())
190 throw std::domain_error(
191 "ImuFactor::Merge: intermediate pose, velocity keys need to match up");
195 Merge(f01->preintegratedMeasurements(), f12->preintegratedMeasurements());
196 return boost::make_shared<ImuFactor>(f01->key1(),
210 Base(
noiseModel::Gaussian::Covariance(pim.preintMeasCov_), state_i, state_j,
222 f.
_PIM_.
print(
"preintegrated measurements:\n");
223 os <<
" noise model sigmas: " << f.
noiseModel_->sigmas().transpose();
230 cout << (s.empty() ? s : s +
"\n") <<
"ImuFactor2(" 231 << keyFormatter(this->
key1()) <<
"," << keyFormatter(this->
key2()) <<
"," 232 << keyFormatter(this->
key3()) <<
")\n";
233 cout << *
this << endl;
238 const This *
e =
dynamic_cast<const This*
>(&other);
241 return e !=
nullptr && base && pim;
248 boost::optional<Matrix&> H1, boost::optional<Matrix&> H2,
249 boost::optional<Matrix&> H3)
const {
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
void integrateMeasurements(const Matrix &measuredAccs, const Matrix &measuredOmegas, const Matrix &dts)
Add multiple measurements, in matrix columns.
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Vector9 computeError(const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1, OptionalJacobian< 9, 9 > H2, OptionalJacobian< 9, 6 > H3) const
Calculate error given navStates.
void resetIntegration() override
Matrix< SCALARB, Dynamic, Dynamic > B
bool equals(const ManifoldPreintegration &other, double tol) const
const SharedNoiseModel & noiseModel() const
access to the noise model
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const ImuFactor2 &)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Vector evaluateError(const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
vector of errors
gtsam::NonlinearFactor::shared_ptr clone() const override
void print(const std::string &s="Preintegrated Measurements:") const override
print
PreintegratedImuMeasurements _PIM_
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
bool equals(const PreintegratedImuMeasurements &expected, double tol=1e-9) const
equals
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, 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) const override
vector of errors
PreintegratedImuMeasurements _PIM_
boost::shared_ptr< This > shared_ptr
boost::shared_ptr< ImuFactor > shared_ptr
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Matrix9 preintMeasCov_
(first-order propagation from measurementCovariance).
static const Vector3 measuredAcc
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const ImuFactor &)
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Matrix< Scalar, Dynamic, Dynamic > C
static const Vector3 measuredOmega(w, 0, 0)
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
SharedNoiseModel noiseModel_
ofstream os("timeSchurFactors.csv")
bool matchesParamsWith(const PreintegrationBase &other) const
check parameters equality: checks whether shared pointer points to same Params object.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
const boost::shared_ptr< Params > & params() const
shared pointer to params
Annotation indicating that a class derives from another given type.
virtual void print(const std::string &s="") const
Vector9 computeErrorAndJacobians(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H1=boost::none, OptionalJacobian< 9, 3 > H2=boost::none, OptionalJacobian< 9, 6 > H3=boost::none, OptionalJacobian< 9, 3 > H4=boost::none, OptionalJacobian< 9, 6 > H5=boost::none) const
void resetIntegration() override
Re-initialize PreintegratedIMUMeasurements.
std::uint64_t Key
Integer nonlinear key type.
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
gtsam::NonlinearFactor::shared_ptr clone() const override