29 using namespace gtsam;
60 Vector3 measurement_acc(0.1, 0.2, 0.4);
61 Vector3 measurement_gyro(-0.2, 0.5, 0.03);
63 double measurement_dt(0.1);
68 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
79 Vector3 measurement_acc(0.1, 0.2, 0.4);
80 Vector3 measurement_gyro(-0.2, 0.5, 0.03);
82 double measurement_dt(0.1);
87 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
90 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
102 double measurement_dt(0.1);
111 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
122 f.
predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
135 double measurement_dt(0.1);
144 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
155 Vector ExpectedErr(Z_9x1);
167 double measurement_dt(0.1);
176 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
188 Vector ExpectedErr(Z_9x1);
200 double measurement_dt(0.1);
206 Vector3(6.501390843381716, -6.763926150509185, -2.300389940090343));
210 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
214 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
215 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
219 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
220 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
228 Vector ExpectedErr(Z_9x1);
269 double measurement_dt(0.01);
274 Vector3(6.501390843381716, -6.763926150509185, -2.300389940090343));
275 Vector measurement_gyro((
Vector(3) << 3.14, 3.14 / 2, -3.14).finished());
278 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
282 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
283 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
287 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
288 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
289 Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
292 Vector3(0.510000000000000, -0.480000000000000, 0.430000000000000));
295 Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
298 factor.
evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual,
299 H2_actual, H3_actual, H4_actual, H5_actual));
303 Matrix H1_actualPose(H1_actual.block(0, 0, 6, H1_actual.cols()));
304 Matrix H2_actualPose(H2_actual.block(0, 0, 6, H2_actual.cols()));
305 Matrix H3_actualPose(H3_actual.block(0, 0, 6, H3_actual.cols()));
306 Matrix H4_actualPose(H4_actual.block(0, 0, 6, H4_actual.cols()));
307 Matrix H5_actualPose(H5_actual.block(0, 0, 6, H5_actual.cols()));
310 Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose,
312 H1_expectedPose = numericalDerivative11<Pose3, Pose3>(
315 H2_expectedPose = numericalDerivative11<Pose3, Vector3>(
318 H3_expectedPose = numericalDerivative11<Pose3, imuBias::ConstantBias>(
321 H4_expectedPose = numericalDerivative11<Pose3, Pose3>(
324 H5_expectedPose = numericalDerivative11<Pose3, Vector3>(
337 Matrix H1_actualVel(H1_actual.block(6, 0, 3, H1_actual.cols()));
338 Matrix H2_actualVel(H2_actual.block(6, 0, 3, H2_actual.cols()));
339 Matrix H3_actualVel(H3_actual.block(6, 0, 3, H3_actual.cols()));
340 Matrix H4_actualVel(H4_actual.block(6, 0, 3, H4_actual.cols()));
341 Matrix H5_actualVel(H5_actual.block(6, 0, 3, H5_actual.cols()));
344 Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel,
346 H1_expectedVel = numericalDerivative11<Vector, Pose3>(
349 H2_expectedVel = numericalDerivative11<Vector, Vector3>(
352 H3_expectedVel = numericalDerivative11<Vector, imuBias::ConstantBias>(
355 H4_expectedVel = numericalDerivative11<Vector, Pose3>(
358 H5_expectedVel = numericalDerivative11<Vector, Vector3>(
380 double measurement_dt(0.1);
384 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(0.0, 0.0, 0.0));
387 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
402 double measurement_dt(0.1);
406 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(0.0, 0.0, 0.0));
409 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
413 Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro,
426 double measurement_dt(0.1);
430 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
436 + omega__cross * omega__cross
441 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
443 model, body_P_sensor);
452 f.
predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
465 double measurement_dt(0.1);
469 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
475 + omega__cross * omega__cross
480 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
482 model, body_P_sensor);
491 Vector ExpectedErr(Z_9x1);
503 double measurement_dt(0.1);
507 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
513 + omega__cross * omega__cross
518 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
520 model, body_P_sensor);
526 * measurement_dt),
Point3(2.0, 1.0, 3.0));
532 Vector ExpectedErr(Z_9x1);
544 double measurement_dt(0.1);
548 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
554 Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
555 + omega__cross * omega__cross
560 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
562 model, body_P_sensor);
564 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
565 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
569 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
570 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
576 *
Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
582 Vector ExpectedErr(Z_9x1);
596 double measurement_dt(0.01);
600 Pose3 body_P_sensor(
Rot3(0, 1, 0, 1, 0, 0, 0, 0, -1),
Point3(1.0, -2.0, 3.0));
602 Vector measurement_gyro((
Vector(3) << 3.14 / 2, 3.14, +3.14).finished());
605 Vector3(-6.763926150509185, 6.501390843381716, +2.300389940090343)
606 + omega__cross * omega__cross
611 PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc,
613 model, body_P_sensor);
615 Rot3 R1(0.487316618, 0.125253866, 0.86419557, 0.580273724, 0.693095498,
616 -0.427669306, -0.652537293, 0.709880342, 0.265075427);
620 Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888,
621 -0.422594037, -0.636011287, 0.731761397, 0.244979388);
622 Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
624 Vector3 Vel2(0.510000000000000, -0.480000000000000, 0.430000000000000);
627 Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
630 factor.
evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual,
631 H2_actual, H3_actual, H4_actual, H5_actual));
635 Matrix H1_actualPose(H1_actual.block(0, 0, 6, H1_actual.cols()));
636 Matrix H2_actualPose(H2_actual.block(0, 0, 6, H2_actual.cols()));
637 Matrix H3_actualPose(H3_actual.block(0, 0, 6, H3_actual.cols()));
638 Matrix H4_actualPose(H4_actual.block(0, 0, 6, H4_actual.cols()));
639 Matrix H5_actualPose(H5_actual.block(0, 0, 6, H5_actual.cols()));
642 Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose,
644 H1_expectedPose = numericalDerivative11<Pose3, Pose3>(
647 H2_expectedPose = numericalDerivative11<Pose3, Vector3>(
650 H3_expectedPose = numericalDerivative11<Pose3, imuBias::ConstantBias>(
653 H4_expectedPose = numericalDerivative11<Pose3, Pose3>(
656 H5_expectedPose = numericalDerivative11<Pose3, Vector3>(
669 Matrix H1_actualVel(H1_actual.block(6, 0, 3, H1_actual.cols()));
670 Matrix H2_actualVel(H2_actual.block(6, 0, 3, H2_actual.cols()));
671 Matrix H3_actualVel(H3_actual.block(6, 0, 3, H3_actual.cols()));
672 Matrix H4_actualVel(H4_actual.block(6, 0, 3, H4_actual.cols()));
673 Matrix H5_actualVel(H5_actual.block(6, 0, 3, H5_actual.cols()));
676 Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel,
678 H1_expectedVel = numericalDerivative11<Vector, Pose3>(
681 H2_expectedVel = numericalDerivative11<Vector, Vector3>(
684 H3_expectedVel = numericalDerivative11<Vector, imuBias::ConstantBias>(
687 H4_expectedVel = numericalDerivative11<Vector, Pose3>(
690 H5_expectedVel = numericalDerivative11<Vector, Vector3>(
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)
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)
Pose2_ Expmap(const Vector3_ &xi)
Some functions to compute numerical derivatives.
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
void g(const string &key, int i)
static const Vector3 world_omega_earth
Rot3 inverse() const
inverse of a rotation
static const Vector3 world_rho(0.0,-1.5724e-05, 0.0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Vector3 world_g(0.0, 0.0, 9.81)
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Matrix3 skewSymmetric(double wx, double wy, double wz)
static const Vector3 ECEF_omega_earth(0.0, 0.0, 7.292115e-5)
Rot3 world_R_ECEF(0.31686, 0.51505, 0.79645, 0.85173,-0.52399, 0, 0.41733, 0.67835,-0.60471)
void predict(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, POSE &Pose2, VELOCITY &Vel2) const
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Vector evaluateError(const POSE &Pose1, const VELOCITY &Vel1, const IMUBIAS &Bias1, const POSE &Pose2, const VELOCITY &Vel2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none) const override
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Gaussian::shared_ptr SharedGaussian
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation