Go to the documentation of this file.
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;
77 preintMeasCov_ =
A * preintMeasCov_ *
A.transpose();
79 preintMeasCov_.noalias() +=
B * (aCov /
dt) *
B.transpose();
80 preintMeasCov_.noalias() +=
C * (wCov /
dt) *
C.transpose();
83 preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov *
dt;
88 const Matrix& measuredAccs,
const Matrix& measuredOmegas,
91 measuredAccs.rows() == 3 && measuredOmegas.rows() == 3 && dts.rows() == 1);
92 assert(dts.cols() >= 1);
93 assert(measuredAccs.cols() == dts.cols());
94 assert(measuredOmegas.cols() == dts.cols());
95 size_t n =
static_cast<size_t>(dts.cols());
96 for (
size_t j = 0;
j <
n;
j++) {
97 integrateMeasurement(measuredAccs.col(
j), measuredOmegas.col(
j), dts(0,
j));
102 #ifdef GTSAM_TANGENT_PREINTEGRATION
105 PreintegrationType::mergeWith(pim12, H1, H2);
107 const Matrix9 P = *H1 * preintMeasCov_ * H1->transpose();
117 Base(noiseModel::
Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i,
118 pose_j, vel_j,
bias), _PIM_(pim) {
123 return std::static_pointer_cast<NonlinearFactor>(
129 f._PIM_.print(
"preintegrated measurements:\n");
130 os <<
" noise model sigmas: " <<
f.noiseModel_->sigmas().transpose();
136 cout << (
s.empty() ?
s :
s +
"\n") <<
"ImuFactor(" << keyFormatter(this->key<1>())
137 <<
"," << keyFormatter(this->key<2>()) <<
"," << keyFormatter(this->key<3>())
138 <<
"," << keyFormatter(this->key<4>()) <<
"," << keyFormatter(this->key<5>())
140 cout << *
this << endl;
148 return e !=
nullptr &&
base && pim;
162 #ifdef GTSAM_TANGENT_PREINTEGRATION
167 throw std::domain_error(
168 "Cannot merge PreintegratedImuMeasurements with different params");
170 if (pim01.
params()->body_P_sensor)
171 throw std::domain_error(
172 "Cannot merge PreintegratedImuMeasurements with sensor pose yet");
178 pim02.mergeWith(pim12, &H1, &H2);
185 const shared_ptr& f12) {
187 if (f01->key<5>() != f12->key<5>())
188 throw std::domain_error(
"ImuFactor::Merge: IMU bias keys must be the same");
191 if (f01->key<3>() != f12->key<1>() || f01->key<4>() != f12->key<2>())
192 throw std::domain_error(
193 "ImuFactor::Merge: intermediate pose, velocity keys need to match up");
197 Merge(f01->preintegratedMeasurements(), f12->preintegratedMeasurements());
198 return std::make_shared<ImuFactor>(f01->key<1>(),
212 Base(noiseModel::
Gaussian::Covariance(pim.preintMeasCov_), state_i, state_j,
218 return std::static_pointer_cast<NonlinearFactor>(
224 f._PIM_.print(
"preintegrated measurements:\n");
225 os <<
" noise model sigmas: " <<
f.noiseModel_->sigmas().transpose();
232 cout << (
s.empty() ?
s :
s +
"\n") <<
"ImuFactor2("
233 << keyFormatter(this->key<1>()) <<
"," << keyFormatter(this->key<2>()) <<
","
234 << keyFormatter(this->key<3>()) <<
")\n";
235 cout << *
this << endl;
243 return e !=
nullptr &&
base && pim;
double Gaussian(double mu, double sigma, double z)
Gaussian density function.
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
std::shared_ptr< This > shared_ptr
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={}, OptionalJacobian< 9, 3 > H2={}, OptionalJacobian< 9, 6 > H3={}, OptionalJacobian< 9, 3 > H4={}, OptionalJacobian< 9, 6 > H5={}) const
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Annotation indicating that a class derives from another given type.
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
virtual void print(const std::string &s="") const
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
const Vector3 bias(1, 2, 3)
void resetIntegration() override
Re-initialize PreintegratedIMUMeasurements.
std::shared_ptr< ImuFactor > shared_ptr
PreintegratedImuMeasurements _PIM_
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Matrix9 preintMeasCov_
(first-order propagation from measurementCovariance).
ofstream os("timeSchurFactors.csv")
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
PreintegratedImuMeasurements _PIM_
bool matchesParamsWith(const PreintegrationBase &other) const
check parameters equality: checks whether shared pointer points to same Params object.
gtsam::NonlinearFactor::shared_ptr clone() const override
const Vector3 measuredOmega
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4, OptionalMatrixType H5) const override
vector of errors
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
gtsam::NonlinearFactor::shared_ptr clone() const override
bool equals(const PreintegratedImuMeasurements &expected, double tol=1e-9) const
equals
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
void resetIntegration() 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.
Matrix< Scalar, Dynamic, Dynamic > C
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Vector evaluateError(const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
vector of errors
void integrateMeasurements(const Matrix &measuredAccs, const Matrix &measuredOmegas, const Matrix &dts)
Add multiple measurements, in matrix columns.
Matrix * OptionalMatrixType
static const Vector3 measuredAcc
void print(const std::string &s="Preintegrated Measurements:") const override
print
std::uint64_t Key
Integer nonlinear key type.
bool equals(const ManifoldPreintegration &other, double tol) const
const std::shared_ptr< Params > & params() const
shared pointer to params
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:27