39 static std::shared_ptr<PreintegrationParams>
Params() {
40 auto p = PreintegrationParams::MakeSharedD(
kGravity);
43 p->integrationCovariance = 0.0001 * I_3x3;
56 factor.
evaluateError(pose_i, vel_i, pose_j, vel_j, bias).head(3));
98 const double a = 0.2,
v = 50;
103 const Point3 initial_position(10, 20, 0);
104 const Vector3 initial_velocity(
v, 0, 0);
109 const double T = 3.0;
122 const double a = 0.1,
w =
M_PI / 100.0;
128 Vector3 expectedDeltaR1(
w * deltaT, 0.0, 0.0);
129 Vector3 expectedDeltaP1(0.5 * a * deltaT*deltaT, 0, 0);
130 Vector3 expectedDeltaV1(0.05, 0.0, 0.0);
148 std::function<Vector9(const NavState&, const NavState&, const Bias&)>
f =
149 std::bind(&PreintegrationBase::computeError, actual,
150 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
151 nullptr,
nullptr,
nullptr);
158 Vector3 expectedDeltaR2(2.0 * 0.5 *
M_PI / 100.0, 0.0, 0.0);
159 Vector3 expectedDeltaP2(0.025 + expectedDeltaP1(0) + 0.5 * 0.1 * 0.5 * 0.5, 0, 0);
182 -kGravityAlongNavZDown);
195 p->omegaCoriolis =
Vector3(0.02, 0.03, 0.04);
196 p->use2ndOrderCoriolis =
true;
205 Matrix expectedH = numericalDerivative11<Vector9, Bias>(
206 std::bind(&PreintegrationBase::biasCorrectedDelta, pim,
207 std::placeholders::_1,
nullptr), kZeroBias);
213 Matrix eH1 = numericalDerivative11<NavState, NavState>(
214 std::bind(&PreintegrationBase::predict, pim, std::placeholders::_1,
215 kZeroBias,
nullptr,
nullptr),
state1);
217 Matrix eH2 = numericalDerivative11<NavState, Bias>(
218 std::bind(&PreintegrationBase::predict, pim, state1,
219 std::placeholders::_1,
nullptr,
nullptr), kZeroBias);
255 expectedError << 0, 0, 0, 0, 0, 0, 0, 0, 0;
265 values.
insert(
B(1), kZeroBias);
269 double diffDelta = 1
e-7;
273 Matrix H1a, H2a, H3a, H4a, H5a;
279 Matrix H1Rot3 = numericalDerivative11<Rot3, Pose3>(
280 std::bind(&evaluateRotationError, factor, std::placeholders::_1, v1,
x2,
v2, kZeroBias),
284 Matrix H3Rot3 = numericalDerivative11<Rot3, Pose3>(
285 std::bind(&evaluateRotationError, factor, x1, v1, std::placeholders::_1,
v2, kZeroBias),
292 expectedError << 0, 0, 0, 0, 0, 0, -0.0724744871, -0.040715657, -0.151952901;
301 Vector whitened = R * expectedError;
319 measuredOmega << 0, 0,
M_PI / 10.0 + 0.3;
325 p->omegaCoriolis = kNonZeroOmegaCoriolis;
334 Matrix expectedH = numericalDerivative11<Vector9, Bias>(
335 std::bind(&PreintegrationBase::biasCorrectedDelta, pim,
336 std::placeholders::_1,
nullptr), bias);
350 double diffDelta = 1
e-7;
365 measuredOmega << 0, 0,
M_PI / 10.0 + 0.3;
371 p->omegaCoriolis = kNonZeroOmegaCoriolis;
372 p->use2ndOrderCoriolis =
true;
389 double diffDelta = 1
e-7;
402 auto evaluateRotation = [=](
const Vector3 biasOmega) {
403 return Rot3::Expmap((measuredOmega - biasOmega) * deltaT);
407 Matrix expectedDelRdelBiasOmega =
408 numericalDerivative11<Rot3, Vector3>(evaluateRotation, biasOmega);
411 Rot3::ExpmapDerivative((measuredOmega - biasOmega) * deltaT);
413 Matrix3 actualdelRdelBiasOmega = -Jr *
deltaT;
427 auto evaluateLogRotation = [=](
const Vector3 deltatheta) {
433 Matrix expectedDelFdeltheta =
434 numericalDerivative11<Vector, Vector3>(evaluateLogRotation, deltatheta);
436 Matrix3 actualDelFdeltheta = Rot3::LogmapDerivative(thetahat);
456 const Matrix3 Jr = Rot3::ExpmapDerivative(
457 (measuredOmega - biasOmega) * deltaT);
459 Matrix3 delRdelBiasOmega = -Jr *
deltaT;
462 (measuredOmega - biasOmega - deltabiasOmega) * deltaT).matrix();
464 const Matrix3 hatRot =
465 Rot3::Expmap((measuredOmega - biasOmega) * deltaT).matrix();
466 const Matrix3 actualRot = hatRot
467 *
Rot3::Expmap(delRdelBiasOmega * deltabiasOmega).matrix();
494 p->omegaCoriolis = kNonZeroOmegaCoriolis;
498 const double T = 3.0;
515 const Vector3 accNoiseVar2(0.01, 0.02, 0.03);
516 const Vector3 omegaNoiseVar2(0.03, 0.01, 0.02);
520 Matrix3 D_correctedAcc_measuredOmega = Z_3x3;
522 nullptr, D_correctedAcc_measuredOmega,
nullptr);
523 Matrix3 expectedD = numericalDerivative11<Vector3, Vector3>(
524 std::bind(
correctedAcc, pim, measuredAcc, std::placeholders::_1),
571 double diffDelta = 1
e-8;
577 gttic(PredictPositionAndVelocity);
582 measuredOmega << 0, 0, 0;
585 double deltaT = 0.001;
590 for (
int i = 0;
i < 1000; ++
i)
606 gttic(PredictRotation);
611 measuredOmega << 0, 0,
M_PI / 10;
614 double deltaT = 0.001;
619 for (
int i = 0;
i < 1000; ++
i)
633 gttic(PredictArbitrary);
640 const double T = 3.0;
657 p->integrationCovariance = Z_3x3;
664 for (
int i = 0;
i < 1000; ++
i)
675 +0.903715275, -0.250741668, 0.347026393,
676 +0.347026393, 0.903715275, -0.250741668,
677 -0.250741668, 0.347026393, 0.903715275);
679 Vector3 expectedV(-1.62337767, 1.57954409, 0.343833571);
686 gttic(bodyPSensorNoBias);
704 for (
int i = 0;
i < 1000; ++
i)
716 Vector3 expectedVelocity(0, 0, 0);
727 gttic(bodyPSensorWithBias);
732 Vector6 noiseBetweenBiasSigma;
735 SharedDiagonal biasNoiseModel = Diagonal::Sigmas(noiseBetweenBiasSigma);
748 p->accelerometerCovariance = 1
e-7 * I_3x3;
749 p->gyroscopeCovariance = 1
e-8 * I_3x3;
750 p->integrationCovariance = 1
e-9 * I_3x3;
751 double deltaT = 0.005;
754 Vector6 priorNoisePoseSigmas(
755 (
Vector(6) << 0.001, 0.001, 0.001, 0.01, 0.01, 0.01).finished());
756 Vector3 priorNoiseVelSigmas((
Vector(3) << 0.1, 0.1, 0.1).finished());
757 Vector6 priorNoiseBiasSigmas(
758 (
Vector(6) << 0.1, 0.1, 0.1, 0.5
e-1, 0.5
e-1, 0.5
e-1).finished());
759 SharedDiagonal priorNoisePose = Diagonal::Sigmas(priorNoisePoseSigmas);
760 SharedDiagonal priorNoiseVel = Diagonal::Sigmas(priorNoiseVelSigmas);
761 SharedDiagonal priorNoiseBias = Diagonal::Sigmas(priorNoiseBiasSigmas);
762 Vector3 zeroVel(0, 0, 0);
771 graph.
addPrior(
V(0), zeroVel, priorNoiseVel);
778 graph.
addPrior(
B(0), priorBias, priorNoiseBias);
779 values.
insert(
B(0), priorBias);
783 for (
int i = 1;
i < numFactors;
i++) {
786 for (
int j = 0;
j < 200; ++
j)
800 Bias biasActual = results.
at<Bias>(
B(numFactors - 1));
808 #ifdef GTSAM_TANGENT_PREINTEGRATION 809 static const double kVelocity = 2.0, kAngularVelocity =
M_PI / 6;
811 struct ImuFactorMergeTest {
812 std::shared_ptr<PreintegrationParams> p_;
816 : p_(PreintegrationParams::MakeSharedU(
kGravity)),
818 loop_(
Vector3(0, -kAngularVelocity, 0),
Vector3(kVelocity, 0, 0)) {
820 p_->gyroscopeCovariance = I_3x3 * 0.01;
821 p_->accelerometerCovariance = I_3x3 * 0.03;
824 int TestScenario(
TestResult& result_,
const std::string& name_,
827 const Bias& bias12,
double tol) {
834 double deltaT = 0.01;
837 for (
int i = 0;
i < 100;
i++) {
849 auto actual_pim02 = ImuFactor::Merge(pim01, pim12);
851 actual_pim02.preintegrated(),
tol));
855 std::make_shared<ImuFactor>(
X(0),
V(0),
X(1),
V(1),
B(0), pim01);
857 std::make_shared<ImuFactor>(
X(1),
V(1),
X(2),
V(2),
B(0), pim12);
859 X(0),
V(0),
X(2),
V(2),
B(0), pim02_expected);
866 void TestScenarios(
TestResult& result_,
const std::string& name_,
868 const Bias& bias12,
double tol) {
869 for (
auto scenario : {forward_, loop_})
870 TestScenario(result_, name_, scenario, bias01, bias12, tol);
877 ImuFactorMergeTest mergeTest;
878 mergeTest.TestScenarios(result_, name_, kZeroBias, kZeroBias, 1
e-4);
883 ImuFactorMergeTest mergeTest;
885 mergeTest.TestScenarios(result_, name_, bias, bias, 1
e-4);
890 ImuFactorMergeTest mergeTest;
891 mergeTest.TestScenarios(result_, name_,
898 ImuFactorMergeTest mergeTest;
899 mergeTest.p_->omegaCoriolis =
Vector3(0.1, 0.2, -0.1);
900 mergeTest.TestScenarios(result_, name_, kZeroBias, kZeroBias, 1
e-4);
907 gttic(CheckCovariance);
916 expected << 1.0577e-08, 0, 0, 0, 0, 0, 0, 0, 0,
917 0, 1.0577e-08, 0, 0, 0, 0, 0, 0, 0,
918 0, 0, 1.0577e-08, 0, 0, 0, 0, 0, 0,
919 0, 0, 0, 5.00868e-05, 0, 0, 3.47222e-07, 0, 0,
920 0, 0, 0, 0, 5.00868e-05, 0, 0, 3.47222e-07, 0,
921 0, 0, 0, 0, 0, 5.00868e-05, 0, 0, 3.47222e-07,
922 0, 0, 0, 3.47222e-07, 0, 0, 1.38889e-06, 0, 0,
923 0, 0, 0, 0, 3.47222e-07, 0, 0, 1.38889e-06, 0,
924 0, 0, 0, 0, 0, 3.47222e-07, 0, 0, 1.38889e-06;
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
Vector3 actualAngularVelocity(double t) const
Provides additional testing facilities for common data structures.
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Vector3 correctedAcc(const PreintegratedImuMeasurements &pim, const Vector3 &measuredAcc, const Vector3 &measuredOmega)
void integrateMeasurements(const Matrix &measuredAccs, const Matrix &measuredOmegas, const Matrix &dts)
Add multiple measurements, in matrix columns.
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
virtual const Values & optimize()
Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H={}) const override
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Matrix9 estimateCovariance(double T, size_t N=1000, const Bias &estimatedBias=Bias()) const
Compute a Monte Carlo estimate of the predict covariance using N samples.
Factor Graph consisting of non-linear factors.
const ValueType at(Key j) const
#define DOUBLES_EQUAL(expected, actual, threshold)
PreintegratedImuMeasurements integrate(double T, const Bias &estimatedBias=Bias(), bool corrupted=false) const
Integrate measurements for T seconds into a PIM.
Vector3 actualSpecificForce(double t) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Rot2 R(Rot2::fromAngle(0.1))
void update(Key j, const Value &val)
Pose2_ Expmap(const Vector3_ &xi)
static const Velocity3 kVelocity(0.4, 0.5, 0.6)
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
Some functions to compute numerical derivatives.
Evaluate derivatives of a nonlinear factor numerically.
static const Vector3 v2(Vector3(0.5, 0.0, 0.0))
Common testing infrastructure.
static const NavState state1(x1, v1)
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
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 RtR(const Matrix &A)
T compose(const T &t1, const T &t2)
Point2 expectedT(-0.0446635, 0.29552)
static const double kAccelSigma
NavState predict(const PreintegratedImuMeasurements &pim, const Bias &estimatedBias=Bias()) const
Predict predict given a PIM.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
static const Pose3 x2(Rot3::RzRyRx(M_PI/12.0+w, M_PI/6.0, M_PI/4.0), Point3(5.5, 1.0, 0))
Vector3 deltaPij() const override
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)
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
Vector3 deltaVij() const override
void resetIntegrationAndSetBias(const Bias &biasHat)
static const NavState state2(x2, v2)
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)
#define EXPECT(condition)
Vector3 correctAccelerometer(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Array< int, Dynamic, 1 > v
static const double deltaT
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)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
const imuBias::ConstantBias & biasHat() const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Vector3 measuredAcc
sampling from a NoiseModel
ConstantTwistScenario scenario(Z_3x1, Vector3(v, 0, 0))
Pose3 pose(double t) const override
pose at time t
Simple trajectory simulator.
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H={}) const
noiseModel::Diagonal::shared_ptr SharedDiagonal
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
static const Vector kZero
imuBias::ConstantBias Bias
static const Pose3 x1(Rot3::RzRyRx(M_PI/12.0, M_PI/6.0, M_PI/4.0), Point3(5.0, 1.0, 0))
static const Vector3 measuredOmega(w, 0, 0)
static const Vector3 v1(Vector3(0.5, 0.0, 0.0))
NavState predict(const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 6 > H2={}) const
Predict state at time j.
double error(const Values &c) const override
Simple class to test navigation scenarios.
std::map< std::string, Array< float, 1, 8, DontAlign|RowMajor > > results
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
Rot3 deltaRij() const override
Matrix preintMeasCov() const
Return pre-integrated measurement covariance.
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose(const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc={}, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega={}, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega={}) const
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
void insert(Key j, const Value &val)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
A class for computing marginals in a NonlinearFactorGraph.
TEST(ImuFactor, PreintegratedMeasurementsConstruction)
static std::shared_ptr< PreintegratedCombinedMeasurements::Params > Params(const Matrix3 &biasAccCovariance=Matrix3::Zero(), const Matrix3 &biasOmegaCovariance=Matrix3::Zero(), const Matrix6 &biasAccOmegaInt=Matrix6::Zero())
std::shared_ptr< ImuFactor > shared_ptr
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
void resetIntegration() override
Re-initialize PreintegratedIMUMeasurements.
Accelerating from an arbitrary initial state, with optional rotation.
static const double kGyroSigma