39 static std::shared_ptr<PreintegratedCombinedMeasurements::Params>
Params(
40 const Matrix3& biasAccCovariance = Matrix3::Zero(),
41 const Matrix3& biasOmegaCovariance = Matrix3::Zero(),
42 const Matrix6& biasAccOmegaInt = Matrix6::Zero()) {
43 auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(
kGravity);
46 p->integrationCovariance = 0.0001 * I_3x3;
47 p->biasAccCovariance = biasAccCovariance;
48 p->biasOmegaCovariance = biasOmegaCovariance;
49 p->biasAccOmegaInt = biasAccOmegaInt;
93 p->omegaCoriolis =
Vector3(0,0.1,0.1);
99 measuredOmega << 0, 0,
M_PI / 10.0 + 0.3;
116 noiseModel::Gaussian::Covariance(combined_pim.
preintMeasCov());
121 Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias,
126 Matrix H1e, H2e, H3e, H4e, H5e;
127 (void) imuFactor.
evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e);
130 Matrix H1a, H2a, H3a, H4a, H5a, H6a;
131 (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a,
142 #ifdef GTSAM_TANGENT_PREINTEGRATION 150 return pim.preintegrated();
158 pim.preintegrated_H_biasAcc()));
160 pim.preintegrated_H_biasOmega(), 1
e-3));
173 const double deltaT = 0.01;
177 for (
int i = 0;
i < 100; ++
i)
188 const Vector3 expectedVelocity(0, 1, 0);
200 const double deltaT = 0.01;
201 const double tol = 1
e-4;
202 for (
int i = 0;
i < 100; ++
i)
217 auto params = PreintegrationCombinedParams::MakeSharedU(9.81);
219 params->setAccelerometerCovariance(
pow(0.01, 2) * I_3x3);
220 params->setGyroscopeCovariance(
pow(1.75
e-4, 2) * I_3x3);
221 params->setIntegrationCovariance(
pow(0.0, 2) * I_3x3);
222 params->setOmegaCoriolis(Vector3::Zero());
236 expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
237 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
238 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
239 0, 0, 0, 2.50025e-07, 0, 0, 5.0005e-05, 0, 0, 0, 0, 0, 0, 0, 0,
240 0, 0, 0, 0, 2.50025e-07, 0, 0, 5.0005e-05, 0, 0, 0, 0, 0, 0, 0,
241 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 5.0005e-05, 0, 0, 0, 0, 0, 0,
242 0, 0, 0, 5.0005e-05, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0,
243 0, 0, 0, 0, 5.0005e-05, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0,
244 0, 0, 0, 0, 0, 5.0005e-05, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0,
245 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0,
246 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0,
247 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0,
248 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0,
249 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0,
250 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01;
261 Vector3 accMeas(0.1577, -0.8251, 9.6111);
262 Vector3 omegaMeas(-0.0210, 0.0311, 0.0145);
269 auto params = PreintegrationParams::MakeSharedU();
270 params->setAccelerometerCovariance(
pow(0.01, 2) * I_3x3);
271 params->setGyroscopeCovariance(
pow(1.75
e-4, 2) * I_3x3);
272 params->setIntegrationCovariance(
pow(0, 2) * I_3x3);
273 params->setOmegaCoriolis(Vector3::Zero());
280 auto combined_params = PreintegrationCombinedParams::MakeSharedU();
281 combined_params->setAccelerometerCovariance(
pow(0.01, 2) * I_3x3);
282 combined_params->setGyroscopeCovariance(
pow(1.75
e-4, 2) * I_3x3);
284 combined_params->setIntegrationCovariance(Z_3x3);
285 combined_params->setOmegaCoriolis(
Z_3x1);
287 combined_params->setBiasAccOmegaInit(Z_6x6);
300 const double a = 0.2,
v = 50;
305 const Point3 initial_position(10, 20, 0);
306 const Vector3 initial_velocity(
v, 0, 0);
311 const double T = 3.0;
325 const double a = 0.2,
v = 50;
330 const Point3 initial_position(10, 20, 0);
331 const Vector3 initial_velocity(
v, 0, 0);
336 const double T = 3.0;
342 0.1 * Matrix6::Identity()),
355 Matrix6 expected_Q_init = I_6x6 * 0.001;
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
Provides additional testing facilities for common data structures.
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Eigen::Matrix< double, 15, 15 > estimateCovariance(double T, size_t N=1000, const Bias &estimatedBias=Bias()) const
Compute a Monte Carlo estimate of the predict covariance using N samples.
Bias bias2(biasAcc2, biasGyro2)
Matrix6 biasAccOmegaInt
covariance of bias used as initial estimate.
#define DOUBLES_EQUAL(expected, actual, threshold)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Params & p() const
const reference to params, shadows definition in base class
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
Pose2_ Expmap(const Vector3_ &xi)
TEST(CombinedImuFactor, PreintegratedMeasurements)
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.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Common testing infrastructure.
void resetIntegration() override
Re-initialize PreintegratedCombinedMeasurements.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static const SmartProjectionParams params
static const double kAccelSigma
Vector3 deltaPij() const override
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
#define EXPECT(condition)
Array< int, Dynamic, 1 > v
static const double deltaT
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Vector3 measuredAcc
ConstantTwistScenario scenario(Z_3x1, Vector3(v, 0, 0))
Pose3 pose(double t) const override
pose at time t
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H={}) const
imuBias::ConstantBias Bias
Matrix preintMeasCov() const
static const Vector3 measuredOmega(w, 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.
NavState predict(const PreintegratedCombinedMeasurements &pim, const Bias &estimatedBias=Bias()) const
Predict predict given a PIM.
PreintegratedCombinedMeasurements integrate(double T, const Bias &estimatedBias=Bias(), bool corrupted=false) const
Integrate measurements for T seconds into a PIM.
Simple class to test navigation scenarios.
Rot3 deltaRij() const override
Matrix preintMeasCov() const
Return pre-integrated measurement covariance.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
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< Gaussian > shared_ptr
Jet< T, N > pow(const Jet< T, N > &f, double g)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Accelerating from an arbitrary initial state, with optional rotation.
static const double kGyroSigma