Go to the documentation of this file.
28 using namespace std::placeholders;
30 static const double kDt = 0.1;
33 return TangentPreintegration::UpdatePreintegrated(
a,
w,
kDt,
zeta);
38 static std::shared_ptr<PreintegrationParams>
Params() {
39 auto p = PreintegrationParams::MakeSharedD(
kGravity);
42 p->integrationCovariance = 0.0001 * I_3x3;
66 zeta << 0.01, 0.02, 0.03, 100, 200, 300, 10, 5, 3;
80 std::function<Vector9(
const Vector3&,
const Vector3&)> preintegrated =
109 f = std::bind(&TangentPreintegration::computeError, pim,
110 std::placeholders::_1, std::placeholders::_2,
111 std::placeholders::_3,
nullptr,
nullptr,
125 std::function<Vector9(
const Vector9&,
const Vector9&)>
f =
126 [pim](
const Vector9& zeta01,
const Vector9& zeta12) {
127 return TangentPreintegration::Compose(zeta01, zeta12, pim.
deltaTij());
141 const Vector9 actual_zeta =
static int runAllTests(TestResult &result)
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
void mergeWith(const TangentPreintegration &pim, Matrix9 *H1, Matrix9 *H2)
static const double kGyroSigma
static const double kAccelSigma
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define EXPECT(condition)
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
const Vector3 bias(1, 2, 3)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
static std::shared_ptr< PreintegrationParams > Params()
const Vector9 & preintegrated() const
Some functions to compute numerical derivatives.
Common expressions, both linear and non-linear.
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
const Matrix93 & preintegrated_H_biasAcc() const
Test harness methods for expressions.
Common testing infrastructure.
Vector9 f(const Vector9 &zeta, const Vector3 &a, const Vector3 &w)
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.
std::vector< double > measurements
imuBias::ConstantBias Bias
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
double zeta(double x, double q)
static const Vector kZero
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
const Matrix93 & preintegrated_H_biasOmega() const
static Vector9 UpdatePreintegrated(const Vector3 &a_body, const Vector3 &w_body, const double dt, const Vector9 &preintegrated, OptionalJacobian< 9, 9 > A={}, OptionalJacobian< 9, 3 > B={}, OptionalJacobian< 9, 3 > C={})
static std::shared_ptr< PreintegratedCombinedMeasurements::Params > Params(const Matrix3 &biasAccCovariance=Matrix3::Zero(), const Matrix3 &biasOmegaCovariance=Matrix3::Zero(), const Matrix6 &biasAccOmegaInt=Matrix6::Zero())
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
TEST(TangentPreintegration, UpdateEstimate1)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:45