30 using namespace gtsam;
61 Vector3 measurement_acc(0.1, 0.2, 0.4);
62 Vector3 measurement_gyro(-0.2, 0.5, 0.03);
64 double measurement_dt(0.1);
69 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
80 Vector3 measurement_acc(0.1, 0.2, 0.4);
81 Vector3 measurement_gyro(-0.2, 0.5, 0.03);
83 double measurement_dt(0.1);
88 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
91 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
103 double measurement_dt(0.1);
112 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
123 f.
predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
136 double measurement_dt(0.1);
145 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
156 Vector ExpectedErr(Z_9x1);
168 double measurement_dt(0.1);
177 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
189 Vector ExpectedErr(Z_9x1);
201 double measurement_dt(0.1);
207 Vector3(6.501390843381716, -6.763926150509185, -2.300389940090343));
211 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
215 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
216 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
220 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
221 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
229 Vector ExpectedErr(Z_9x1);
270 double measurement_dt(0.01);
275 Vector3(6.501390843381716, -6.763926150509185, -2.300389940090343));
276 Vector measurement_gyro((
Vector(3) << 3.14, 3.14 / 2, -3.14).finished());
279 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
283 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
284 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
288 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
289 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
290 Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
293 Vector3(0.510000000000000, -0.480000000000000, 0.430000000000000));
296 Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
299 factor.
evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual,
300 H2_actual, H3_actual, H4_actual, H5_actual));
304 Matrix H1_actualPose(H1_actual.block(0, 0, 6, H1_actual.cols()));
305 Matrix H2_actualPose(H2_actual.block(0, 0, 6, H2_actual.cols()));
306 Matrix H3_actualPose(H3_actual.block(0, 0, 6, H3_actual.cols()));
307 Matrix H4_actualPose(H4_actual.block(0, 0, 6, H4_actual.cols()));
308 Matrix H5_actualPose(H5_actual.block(0, 0, 6, H5_actual.cols()));
311 Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose,
313 H1_expectedPose = numericalDerivative11<Pose3, Pose3>(
316 H2_expectedPose = numericalDerivative11<Pose3, Vector3>(
319 H3_expectedPose = numericalDerivative11<Pose3, imuBias::ConstantBias>(
322 H4_expectedPose = numericalDerivative11<Pose3, Pose3>(
325 H5_expectedPose = numericalDerivative11<Pose3, Vector3>(
338 Matrix H1_actualVel(H1_actual.block(6, 0, 3, H1_actual.cols()));
339 Matrix H2_actualVel(H2_actual.block(6, 0, 3, H2_actual.cols()));
340 Matrix H3_actualVel(H3_actual.block(6, 0, 3, H3_actual.cols()));
341 Matrix H4_actualVel(H4_actual.block(6, 0, 3, H4_actual.cols()));
342 Matrix H5_actualVel(H5_actual.block(6, 0, 3, H5_actual.cols()));
345 Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel,
347 H1_expectedVel = numericalDerivative11<Vector, Pose3>(
348 std::bind(&
predictionErrorVel, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2, factor),
350 H2_expectedVel = numericalDerivative11<Vector, Vector3>(
351 std::bind(&
predictionErrorVel, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2, factor),
353 H3_expectedVel = numericalDerivative11<Vector, imuBias::ConstantBias>(
354 std::bind(&
predictionErrorVel, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2, factor),
356 H4_expectedVel = numericalDerivative11<Vector, Pose3>(
357 std::bind(&
predictionErrorVel, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2, factor),
359 H5_expectedVel = numericalDerivative11<Vector, Vector3>(
360 std::bind(&
predictionErrorVel, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1, factor),
381 double measurement_dt(0.1);
385 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(0.0, 0.0, 0.0));
388 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
403 double measurement_dt(0.1);
407 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(0.0, 0.0, 0.0));
410 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
414 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
427 double measurement_dt(0.1);
431 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
437 + omega__cross * omega__cross
442 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
444 model, body_P_sensor);
453 f.
predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
466 double measurement_dt(0.1);
470 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
476 + omega__cross * omega__cross
481 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
483 model, body_P_sensor);
492 Vector ExpectedErr(Z_9x1);
504 double measurement_dt(0.1);
508 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
514 + omega__cross * omega__cross
519 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
521 model, body_P_sensor);
527 * measurement_dt),
Point3(2.0, 1.0, 3.0));
533 Vector ExpectedErr(Z_9x1);
545 double measurement_dt(0.1);
549 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
555 Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
556 + omega__cross * omega__cross
561 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
563 model, body_P_sensor);
565 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
566 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
570 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
571 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
577 *
Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
583 Vector ExpectedErr(Z_9x1);
597 double measurement_dt(0.01);
601 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
603 Vector measurement_gyro((
Vector(3) << 3.14 / 2, 3.14, +3.14).finished());
606 Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
607 + omega__cross * omega__cross
612 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
614 model, body_P_sensor);
616 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
617 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
621 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
622 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
623 Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
625 Vector3 Vel2(0.510000000000000, -0.480000000000000, 0.430000000000000);
628 Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
631 factor.
evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual,
632 H2_actual, H3_actual, H4_actual, H5_actual));
636 Matrix H1_actualPose(H1_actual.block(0, 0, 6, H1_actual.cols()));
637 Matrix H2_actualPose(H2_actual.block(0, 0, 6, H2_actual.cols()));
638 Matrix H3_actualPose(H3_actual.block(0, 0, 6, H3_actual.cols()));
639 Matrix H4_actualPose(H4_actual.block(0, 0, 6, H4_actual.cols()));
640 Matrix H5_actualPose(H5_actual.block(0, 0, 6, H5_actual.cols()));
643 Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose,
645 H1_expectedPose = numericalDerivative11<Pose3, Pose3>(
648 H2_expectedPose = numericalDerivative11<Pose3, Vector3>(
651 H3_expectedPose = numericalDerivative11<Pose3, imuBias::ConstantBias>(
654 H4_expectedPose = numericalDerivative11<Pose3, Pose3>(
657 H5_expectedPose = numericalDerivative11<Pose3, Vector3>(
670 Matrix H1_actualVel(H1_actual.block(6, 0, 3, H1_actual.cols()));
671 Matrix H2_actualVel(H2_actual.block(6, 0, 3, H2_actual.cols()));
672 Matrix H3_actualVel(H3_actual.block(6, 0, 3, H3_actual.cols()));
673 Matrix H4_actualVel(H4_actual.block(6, 0, 3, H4_actual.cols()));
674 Matrix H5_actualVel(H5_actual.block(6, 0, 3, H5_actual.cols()));
677 Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel,
679 H1_expectedVel = numericalDerivative11<Vector, Pose3>(
680 std::bind(&
predictionErrorVel, std::placeholders::_1, Vel1, Bias1, Pose2, Vel2, factor),
682 H2_expectedVel = numericalDerivative11<Vector, Vector3>(
683 std::bind(&
predictionErrorVel, Pose1, std::placeholders::_1, Bias1, Pose2, Vel2, factor),
685 H3_expectedVel = numericalDerivative11<Vector, imuBias::ConstantBias>(
686 std::bind(&
predictionErrorVel, Pose1, Vel1, std::placeholders::_1, Pose2, Vel2, factor),
688 H4_expectedVel = numericalDerivative11<Vector, Pose3>(
689 std::bind(&
predictionErrorVel, Pose1, Vel1, Bias1, std::placeholders::_1, Vel2, factor),
691 H5_expectedVel = numericalDerivative11<Vector, Vector3>(
692 std::bind(&
predictionErrorVel, Pose1, Vel1, Bias1, Pose2, std::placeholders::_1, factor),
Provides additional testing facilities for common data structures.
Vector predictionErrorVel(const Pose3 &p1, const Vector3 &v1, const imuBias::ConstantBias &b1, const Pose3 &p2, const Vector3 &v2, const InertialNavFactor_GlobalVelocity< Pose3, Vector3, imuBias::ConstantBias > &factor)
TEST(InertialNavFactor_GlobalVelocity, Constructor)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Inertial navigation factor (velocity in the global frame)
noiseModel::Diagonal::shared_ptr model
Pose3 predictionErrorPose(const Pose3 &p1, const Vector3 &v1, const imuBias::ConstantBias &b1, const Pose3 &p2, const Vector3 &v2, const InertialNavFactor_GlobalVelocity< Pose3, Vector3, imuBias::ConstantBias > &factor)
void predict(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, POSE &Pose2, VELOCITY &Vel2) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Rot3 world_R_ECEF(0.31686, 0.51505, 0.79645, 0.85173, -0.52399, 0, 0.41733, 0.67835, -0.60471)
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
Pose2_ Expmap(const Vector3_ &xi)
Some functions to compute numerical derivatives.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
void g(const string &key, int i)
static const Vector3 world_omega_earth
Rot3 inverse() const
inverse of a rotation
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector evaluateError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4, OptionalMatrixType H5) const override
static const Vector3 world_g(0.0, 0.0, 9.81)
Matrix3 skewSymmetric(double wx, double wy, double wz)
static const Vector3 ECEF_omega_earth(0.0, 0.0, 7.292115e-5)
static const Vector3 world_rho(0.0, -1.5724e-05, 0.0)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Gaussian::shared_ptr SharedGaussian