30 using namespace gtsam;
31 using namespace std::placeholders;
36 static const Point3 P(0.2,0.7,-2);
37 static const Rot3 R = Rot3::Rodrigues(0.3,0,0);
38 static const Point3 P2(3.5,-8.2,4.2);
40 static const Pose3 T2(Rot3::Rodrigues(0.3,0.2,0.1),
P2);
41 static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0),
Point3(1, 2, 3));
42 static const double tol=1
e-5;
69 #ifndef GTSAM_POSE3_EXPMAP
76 v(3)=0.2;
v(4)=0.7;
v(5)=-2;
96 v(3)=0.2;
v(4)=0.394742;
v(5)=-2.08998;
107 v(3)=0.2;
v(4)=0.394742;
v(5)=-2.08998;
115 Pose3 p2 =
p1.retract((
Vector(6) << 0.0, 0.0, 0.1, 0.0, 0.0, 0.0).finished());
159 Vector6
xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
167 Matrix6 actualH1, actualH2, expectedH1, expectedH2;
168 std::function<Vector6(
const Pose3&,
const Vector6&)> Adjoint_proxy =
169 [&](
const Pose3&
T,
const Vector6&
xi) {
return T.Adjoint(
xi); };
171 T.Adjoint(
xi, actualH1, actualH2);
194 Vector6
xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
198 T.AdjointTranspose(
xi));
205 Matrix6 actualH1, actualH2, expectedH1, expectedH2;
206 std::function<Vector6(
const Pose3&,
const Vector6&)> AdjointTranspose_proxy =
207 [&](
const Pose3&
T,
const Vector6&
xi) {
208 return T.AdjointTranspose(
xi);
211 T.AdjointTranspose(
xi, actualH1, actualH2);
233 Vector6
v1(1, 2, 3, 4, 5, 6);
234 Vector6
v2(0.1, -0.5, 1.0, -1.0, 0.5, 2.0);
235 Vector6
v3(0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
288 xi = (
Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
294 xi = (
Vector(6) << 0.1, -0.2, 0.3, -0.4, 0.5, -0.6).finished();
295 for (
double theta=1.0;0.3*theta<=
M_PI;theta*=2) {
306 xi = (
Vector(6) << 0.2, 0.3, -0.8, 100.0, 120.0, -60.0).finished();
320 Matrix numericalH = numericalDerivative11<Point3, Pose3>(
f,
T);
330 std::function<
Rot3(
const Pose3&)>
f = [](
const Pose3&
T) {
return T.rotation(); };
331 Matrix numericalH = numericalDerivative11<Rot3, Pose3>(
f,
T);
341 Vector x = (
Vector(6) << 0.1, 0.1, 0.1, 0.4, 0.2, 0.8).finished();
357 Matrix actualDcompose1, actualDcompose2;
377 Matrix actualDcompose1, actualDcompose2;
392 Matrix actual =
T.inverse(actualDinverse).matrix();
404 Rot3 R = Rot3::Rodrigues(0.3,0.4,-0.5);
410 T.inverse(actualDinverse);
428 Matrix actualDtransform_from1;
429 T.transformFrom(
P, actualDtransform_from1, {});
436 Matrix actualDtransform_from1;
437 origin.transformFrom(
P, actualDtransform_from1, {});
445 Matrix actualDtransform_from1;
455 Matrix actualDtransform_from1;
465 Matrix actualDtransform_from2;
466 T.transformFrom(
P, {}, actualDtransform_from2);
477 T.transformTo(
P, computed, {});
485 T.transformTo(
P, {}, computed);
493 T.transformTo(
P, actH1, actH2);
503 T.transformFrom(
P, actH1, actH2);
609 d << 1,2,3,4,5,6;
d/=10;
610 const Rot3 R = Rot3::Retract(
d.head<3>());
618 d12 << 1,2,3,4,5,6; d12/=10;
625 Vector d12 = Vector6::Constant(0.1);
663 Vector d = (
Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
678 Matrix actualDBetween1,actualDBetween2;
691 Point3 l1(1, 0, 0),
l2(1, 1, 0),
l3(2, 2, 0),
l4(1, 4,-4);
694 xl1(Rot3::Ypr(0.0, 0.0, 0.0),
Point3(1, 0, 0)),
695 xl2(Rot3::Ypr(0.0, 1.0, 0.0),
Point3(1, 1, 0)),
696 xl3(Rot3::Ypr(1.0, 0.0, 0.0),
Point3(2, 2, 0)),
697 xl4(Rot3::Ypr(0.0, 0.0, 1.0),
Point3(1, 4,-4));
705 Matrix expectedH1, actualH1, expectedH2, actualH2;
714 double actual23 =
x2.
range(
l3, actualH1, actualH2);
724 double actual34 =
x3.
range(
l4, actualH1, actualH2);
740 Matrix expectedH1, actualH1, expectedH2, actualH2;
749 double actual23 =
x2.
range(
xl3, actualH1, actualH2);
759 double actual34 =
x3.
range(
xl4, actualH1, actualH2);
774 Matrix expectedH1, actualH1, expectedH2, actualH2;
785 Matrix expectedH1, actualH1, expectedH2, actualH2;
796 Matrix expectedH1, actualH1, expectedH2, actualH2, H2block;
811 Vector x_step = Vector::Unit(6,3)*1.0;
834 const vector<Point3Pair> correspondences{ab1, ab2, ab3};
836 std::optional<Pose3> actual =
Pose3::Align(correspondences);
843 Rot3 R = Rot3::RzRyRx(0.3, 0.2, 0.1);
851 const vector<Point3Pair> correspondences{ab1, ab2, ab3};
853 std::optional<Pose3> actual =
Pose3::Align(correspondences);
871 auto xi = [](
double t) {
876 auto xi_dot = [](
double t) {
885 for (
double t = -2.0;
t < 2.0;
t += 0.3) {
887 const Matrix actual = Pose3::ExpmapDerivative(
xi(
t)) * xi_dot(
t);
894 std::vector<Vector3>
small{{0, 0, 0},
895 {1
e-5, 0, 0}, {0, 1
e-5, 0}, {0, 0, 1
e-5},
896 {1
e-4, 0, 0}, {0, 1
e-4, 0}, {0, 0, 1
e-4}};
897 std::vector<Vector3>
large{{0, 0, 0}, {1, 0, 0}, {0, 1, 0},
898 {0, 0, 1}, {.1, .2, .3}, {1, -2, 3}};
900 std::vector<Vector3>
vs{{1, 0, 0}, {0, 1, 0}, {0, 0, 1},
901 {.4, .3, .2}, {4, 5, 6}, {-10, -20, 30}};
906 for (
bool nearZero : {
true,
false}) {
909 const Vector6
xi = (Vector6() <<
w,
v).finished();
911 numericalDerivative21<Pose3, Vector6, OptionalJacobian<6, 6> >(
924 static constexpr
bool nearZero =
true;
927 const Vector6
xi = (Vector6() <<
w,
v).finished();
937 for (
bool nearZero : {
true,
false}) {
940 const Vector6
xi = (Vector6() <<
w,
v).finished();
943 numericalDerivative21<Vector6, Pose3, OptionalJacobian<6, 6> >(
944 &Pose3::Logmap,
pose, {});
946 Pose3::Logmap(
pose, actualH);
947 #ifdef GTSAM_USE_QUATERNIONS
961 return Pose3::adjointMap(
xi) *
v;
965 Vector6
v = (Vector6() << 1, 2, 3, 4, 5, 6).finished();
968 Matrix actualH1, actualH2;
971 Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
973 Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
983 return Pose3::adjointMap(
xi).transpose() *
v;
987 Vector xi = (
Vector(6) << 0.01, 0.02, 0.03, 1.0, 2.0, 3.0).finished();
988 Vector v = (
Vector(6) << 0.04, 0.05, 0.06, 4.0, 5.0, 6.0).finished();
991 Matrix actualH1, actualH2;
992 Vector actual = Pose3::adjointTranspose(
xi,
v, actualH1, actualH2);
994 Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
996 Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
1006 std::ostringstream
os;
1009 string expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0 0 0";
1017 EXPECT(check_group_invariants(
id,
id));
1018 EXPECT(check_group_invariants(
id,
T3));
1019 EXPECT(check_group_invariants(
T2,
id));
1022 EXPECT(check_manifold_invariants(
id,
id));
1023 EXPECT(check_manifold_invariants(
id,
T3));
1024 EXPECT(check_manifold_invariants(
T2,
id));
1058 auto cov2 = FullCovarianceFromSigmas<Pose2>(s2);
1061 auto match_cov3_to_cov2 = [&](
int spatial_axis0,
int spatial_axis1,
int r_axis,
1062 const Pose2::Jacobian &cov2,
const Pose3::Jacobian &cov3) ->
void
1066 Vector3{cov3(spatial_axis0, spatial_axis0), cov3(spatial_axis1, spatial_axis1), cov3(r_axis, r_axis)}));
1068 Vector3{cov2(1, 0), cov2(2, 0), cov2(2, 1)},
1069 Vector3{cov3(spatial_axis1, spatial_axis0), cov3(r_axis, spatial_axis0), cov3(r_axis, spatial_axis1)}));
1074 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << s2(2), 0., 0., 0., s2(0), s2(1)).finished());
1076 match_cov3_to_cov2(4, 5, 0, transformed2, transformed3);
1081 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., s2(2), 0., s2(1), 0., s2(0)).finished());
1083 match_cov3_to_cov2(5, 3, 1, transformed2, transformed3);
1088 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., 0., s2(2), s2(0), s2(1), 0.).finished());
1090 match_cov3_to_cov2(3, 4, 2, transformed2, transformed3);
1102 auto cov = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0.1, 0.2, 0.3, 0.5, 0.7, 1.1).finished());
1106 (Vector6{} << cov(1, 1), cov(2, 2), cov(0, 0), cov(4, 4), cov(5, 5), cov(3, 3)).finished(),
1107 Vector6{transformed.diagonal()}));
1110 (Vector5{} << -cov(2, 1), cov(0, 1), cov(4, 1), -cov(5, 1), cov(3, 1)).finished(),
1111 (Vector5{} << transformed(1, 0), transformed(2, 0), transformed(3, 0),
1112 transformed(4, 0), transformed(5, 0)).finished()));
1117 auto cov = TwoVariableCovarianceFromSigmas<Pose3>(1, 2, 0.7, 0.3);
1131 auto cov = SingleVariableCovarianceFromSigma<Pose3>(0, 0.1);
1139 auto cov = SingleVariableCovarianceFromSigma<Pose3>(1, 0.1);
1143 (Vector6{} << 0., 0., 0.1 * 0.1, 0., 0.1 * 0.1 * 20. * 20., 0.).finished(),
1144 Vector6{transformed.diagonal()}));
1186 Pose3 X = Pose3::Identity();
1190 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1203 Pose3 X = Pose3::Identity();
1206 Pose3 expectedPoseInterp(Rot3::Identity(),
Point3(0.3, 0, 0));
1207 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1220 Pose3 X = Pose3::Identity();
1224 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1241 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1242 interpolate(
X,
Y,
t, actualJacobianX, actualJacobianY, actualJacobianT);
1259 Pose3 X = Pose3::Identity();
1262 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1263 X.interpolateRt(
Y,
t, actualJacobianX, actualJacobianY, actualJacobianT);
1275 Pose3 X = Pose3::Identity();
1278 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1279 X.interpolateRt(
Y,
t, actualJacobianX, actualJacobianY, actualJacobianT);
1291 Pose3 X = Pose3::Identity();
1294 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1295 X.interpolateRt(
Y,
t, actualJacobianX, actualJacobianY, actualJacobianT);
1310 Matrix actualJacobianX, actualJacobianY, actualJacobianT;
1311 X.interpolateRt(
Y,
t, actualJacobianX, actualJacobianY, actualJacobianT);
1334 Matrix expectedJacobianX, expectedJacobianY, expectedJacobianT;
1335 std::vector<Matrix> Hlist = {{},{},{}};
1345 Matrix expectedJacobianX, expectedJacobianY, expectedJacobianT;
1346 std::vector<Matrix> Hlist = {{},{},{}};
1347 Pose3 expected =
X.interpolateRt(
Y,
t, expectedJacobianX, expectedJacobianY, expectedJacobianT);
1359 Matrix63 actualH1, actualH2;
1360 Pose3 actual = Pose3::Create(
R,
P2, actualH1, actualH2);
1363 return Pose3::Create(
R,
t);
1374 std::string
expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 1 2 3\n";
1383 M << 1, 2, 3, 4, 5, 6,
1389 auto g = [&](
const Vector6&
omega) {
1398 const Vector6
delta{0.1, 0.2, 0.3, 0.4, 0.5, 0.6};
1399 const Matrix6 expected2 = numericalDerivative11<Pose3, Vector6>(
g,
delta);
1401 EXPECT(assert_equal<Matrix6>(expected2, analytic, 1
e-5));
1415 Matrix numericalH = numericalDerivative11<Vector16, Pose3>(
f,
T);