29 using namespace gtsam;
30 using namespace std::placeholders;
35 static const Point3 P(0.2,0.7,-2);
36 static const Rot3 R = Rot3::Rodrigues(0.3,0,0);
37 static const Point3 P2(3.5,-8.2,4.2);
39 static const Pose3 T2(Rot3::Rodrigues(0.3,0.2,0.1),
P2);
40 static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0),
Point3(1, 2, 3));
41 static const double tol=1
e-5;
61 #ifndef GTSAM_POSE3_EXPMAP
68 v(3)=0.2;
v(4)=0.7;
v(5)=-2;
88 v(3)=0.2;
v(4)=0.394742;
v(5)=-2.08998;
99 v(3)=0.2;
v(4)=0.394742;
v(5)=-2.08998;
107 Pose3 p2 =
p1.retract((
Vector(6) << 0.0, 0.0, 0.1, 0.0, 0.0, 0.0).finished());
151 Vector6
xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
159 Matrix6 actualH1, actualH2, expectedH1, expectedH2;
160 std::function<Vector6(
const Pose3&,
const Vector6&)> Adjoint_proxy =
161 [&](
const Pose3&
T,
const Vector6&
xi) {
return T.Adjoint(
xi); };
163 T.Adjoint(
xi, actualH1, actualH2);
186 Vector6
xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
190 T.AdjointTranspose(
xi));
197 Matrix6 actualH1, actualH2, expectedH1, expectedH2;
198 std::function<Vector6(
const Pose3&,
const Vector6&)> AdjointTranspose_proxy =
199 [&](
const Pose3&
T,
const Vector6&
xi) {
200 return T.AdjointTranspose(
xi);
203 T.AdjointTranspose(
xi, actualH1, actualH2);
259 xi = (
Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
265 xi = (
Vector(6) << 0.1, -0.2, 0.3, -0.4, 0.5, -0.6).finished();
266 for (
double theta=1.0;0.3*theta<=
M_PI;theta*=2) {
277 xi = (
Vector(6) << 0.2, 0.3, -0.8, 100.0, 120.0, -60.0).finished();
291 Matrix numericalH = numericalDerivative11<Point3, Pose3>(
f,
T);
301 std::function<
Rot3(
const Pose3&)>
f = [](
const Pose3&
T) {
return T.rotation(); };
302 Matrix numericalH = numericalDerivative11<Rot3, Pose3>(
f,
T);
312 Vector x = (
Vector(6) << 0.1, 0.1, 0.1, 0.4, 0.2, 0.8).finished();
328 Matrix actualDcompose1, actualDcompose2;
348 Matrix actualDcompose1, actualDcompose2;
363 Matrix actual =
T.inverse(actualDinverse).matrix();
375 Rot3 R = Rot3::Rodrigues(0.3,0.4,-0.5);
381 T.inverse(actualDinverse);
399 Matrix actualDtransform_from1;
400 T.transformFrom(
P, actualDtransform_from1, {});
407 Matrix actualDtransform_from1;
408 origin.transformFrom(
P, actualDtransform_from1, {});
416 Matrix actualDtransform_from1;
426 Matrix actualDtransform_from1;
436 Matrix actualDtransform_from2;
437 T.transformFrom(
P, {}, actualDtransform_from2);
448 T.transformTo(
P, computed, {});
456 T.transformTo(
P, {}, computed);
464 T.transformTo(
P, actH1, actH2);
474 T.transformFrom(
P, actH1, actH2);
580 d << 1,2,3,4,5,6;
d/=10;
581 const Rot3 R = Rot3::Retract(
d.head<3>());
589 d12 << 1,2,3,4,5,6; d12/=10;
596 Vector d12 = Vector6::Constant(0.1);
634 Vector d = (
Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
649 Matrix actualDBetween1,actualDBetween2;
662 Point3 l1(1, 0, 0),
l2(1, 1, 0),
l3(2, 2, 0),
l4(1, 4,-4);
665 xl1(Rot3::Ypr(0.0, 0.0, 0.0),
Point3(1, 0, 0)),
666 xl2(Rot3::Ypr(0.0, 1.0, 0.0),
Point3(1, 1, 0)),
667 xl3(Rot3::Ypr(1.0, 0.0, 0.0),
Point3(2, 2, 0)),
668 xl4(Rot3::Ypr(0.0, 0.0, 1.0),
Point3(1, 4,-4));
676 Matrix expectedH1, actualH1, expectedH2, actualH2;
685 double actual23 =
x2.
range(
l3, actualH1, actualH2);
695 double actual34 =
x3.
range(
l4, actualH1, actualH2);
711 Matrix expectedH1, actualH1, expectedH2, actualH2;
720 double actual23 =
x2.
range(
xl3, actualH1, actualH2);
730 double actual34 =
x3.
range(
xl4, actualH1, actualH2);
745 Matrix expectedH1, actualH1, expectedH2, actualH2;
756 Matrix expectedH1, actualH1, expectedH2, actualH2;
767 Matrix expectedH1, actualH1, expectedH2, actualH2, H2block;
779 expectedH2 =
Matrix(2, 6);
780 expectedH2.setZero();
781 expectedH2.block<2, 3>(0, 3) = H2block;
791 Vector x_step = Vector::Unit(6,3)*1.0;
814 const vector<Point3Pair> correspondences{ab1, ab2, ab3};
816 std::optional<Pose3> actual =
Pose3::Align(correspondences);
823 Rot3 R = Rot3::RzRyRx(0.3, 0.2, 0.1);
831 const vector<Point3Pair> correspondences{ab1, ab2, ab3};
833 std::optional<Pose3> actual =
Pose3::Align(correspondences);
851 auto xi = [](
double t) {
856 auto xi_dot = [](
double t) {
865 for (
double t = -2.0;
t < 2.0;
t += 0.3) {
867 const Matrix actual = Pose3::ExpmapDerivative(
xi(
t)) * xi_dot(
t);
874 std::vector<Vector3>
small{{0, 0, 0},
875 {1
e-5, 0, 0}, {0, 1
e-5, 0}, {0, 0, 1
e-5},
876 {1
e-4, 0, 0}, {0, 1
e-4, 0}, {0, 0, 1
e-4}};
877 std::vector<Vector3>
large{{0, 0, 0}, {1, 0, 0}, {0, 1, 0},
878 {0, 0, 1}, {.1, .2, .3}, {1, -2, 3}};
880 std::vector<Vector3>
vs{{1, 0, 0}, {0, 1, 0}, {0, 0, 1},
881 {.4, .3, .2}, {4, 5, 6}, {-10, -20, 30}};
886 for (
bool nearZero : {
true,
false}) {
889 const Vector6
xi = (Vector6() <<
w,
v).finished();
890 const Matrix6 expectedH =
891 numericalDerivative21<Pose3, Vector6, OptionalJacobian<6, 6> >(
904 static constexpr
bool nearZero =
true;
907 const Vector6
xi = (Vector6() <<
w,
v).finished();
917 for (
bool nearZero : {
true,
false}) {
920 const Vector6
xi = (Vector6() <<
w,
v).finished();
922 const Matrix6 expectedH =
923 numericalDerivative21<Vector6, Pose3, OptionalJacobian<6, 6> >(
924 &Pose3::Logmap,
pose, {});
926 Pose3::Logmap(
pose, actualH);
927 #ifdef GTSAM_USE_QUATERNIONS
941 return Pose3::adjointMap(
xi) *
v;
945 Vector6
v = (Vector6() << 1, 2, 3, 4, 5, 6).finished();
948 Matrix actualH1, actualH2;
951 Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
953 Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
963 return Pose3::adjointMap(
xi).transpose() *
v;
967 Vector xi = (
Vector(6) << 0.01, 0.02, 0.03, 1.0, 2.0, 3.0).finished();
968 Vector v = (
Vector(6) << 0.04, 0.05, 0.06, 4.0, 5.0, 6.0).finished();
971 Matrix actualH1, actualH2;
972 Vector actual = Pose3::adjointTranspose(
xi,
v, actualH1, actualH2);
974 Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
976 Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
986 std::ostringstream
os;
989 string expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0 0 0";
997 EXPECT(check_group_invariants(
id,
id));
998 EXPECT(check_group_invariants(
id,
T3));
999 EXPECT(check_group_invariants(
T2,
id));
1002 EXPECT(check_manifold_invariants(
id,
id));
1003 EXPECT(check_manifold_invariants(
id,
T3));
1004 EXPECT(check_manifold_invariants(
T2,
id));
1038 auto cov2 = FullCovarianceFromSigmas<Pose2>(s2);
1041 auto match_cov3_to_cov2 = [&](
int spatial_axis0,
int spatial_axis1,
int r_axis,
1042 const Pose2::Jacobian &cov2,
const Pose3::Jacobian &cov3) ->
void
1046 Vector3{cov3(spatial_axis0, spatial_axis0), cov3(spatial_axis1, spatial_axis1), cov3(r_axis, r_axis)}));
1048 Vector3{cov2(1, 0), cov2(2, 0), cov2(2, 1)},
1049 Vector3{cov3(spatial_axis1, spatial_axis0), cov3(r_axis, spatial_axis0), cov3(r_axis, spatial_axis1)}));
1054 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << s2(2), 0., 0., 0., s2(0), s2(1)).finished());
1056 match_cov3_to_cov2(4, 5, 0, transformed2, transformed3);
1061 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., s2(2), 0., s2(1), 0., s2(0)).finished());
1063 match_cov3_to_cov2(5, 3, 1, transformed2, transformed3);
1068 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., 0., s2(2), s2(0), s2(1), 0.).finished());
1070 match_cov3_to_cov2(3, 4, 2, transformed2, transformed3);
1082 auto cov = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0.1, 0.2, 0.3, 0.5, 0.7, 1.1).finished());
1086 (Vector6{} << cov(1, 1), cov(2, 2), cov(0, 0), cov(4, 4), cov(5, 5), cov(3, 3)).finished(),
1087 Vector6{transformed.diagonal()}));
1090 (Vector5{} << -cov(2, 1), cov(0, 1), cov(4, 1), -cov(5, 1), cov(3, 1)).finished(),
1091 (Vector5{} << transformed(1, 0), transformed(2, 0), transformed(3, 0),
1092 transformed(4, 0), transformed(5, 0)).finished()));
1097 auto cov = TwoVariableCovarianceFromSigmas<Pose3>(1, 2, 0.7, 0.3);
1111 auto cov = SingleVariableCovarianceFromSigma<Pose3>(0, 0.1);
1119 auto cov = SingleVariableCovarianceFromSigma<Pose3>(1, 0.1);
1123 (Vector6{} << 0., 0., 0.1 * 0.1, 0., 0.1 * 0.1 * 20. * 20., 0.).finished(),
1124 Vector6{transformed.diagonal()}));
1166 Pose3 X = Pose3::Identity();
1170 Matrix actualJacobianX, actualJacobianY;
1180 Pose3 X = Pose3::Identity();
1183 Pose3 expectedPoseInterp(Rot3::Identity(),
Point3(0.3, 0, 0));
1184 Matrix actualJacobianX, actualJacobianY;
1194 Pose3 X = Pose3::Identity();
1198 Matrix actualJacobianX, actualJacobianY;
1212 Matrix actualJacobianX, actualJacobianY;
1225 Matrix63 actualH1, actualH2;
1226 Pose3 actual = Pose3::Create(
R,
P2, actualH1, actualH2);
1229 return Pose3::Create(
R,
t);
1240 std::string
expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 1 2 3\n";
1249 M << 1, 2, 3, 4, 5, 6,
1255 auto g = [&](
const Vector6&
omega) {
1260 const Matrix6
expected = numericalDerivative11<Pose3, Vector6>(
g, Z_6x1);
1264 const Vector6
delta{0.1, 0.2, 0.3, 0.4, 0.5, 0.6};
1265 const Matrix6 expected2 = numericalDerivative11<Pose3, Vector6>(
g,
delta);
1266 const Matrix6 analytic = Pose3::ExpmapDerivative(
M*
delta) *
M;
1267 EXPECT(assert_equal<Matrix6>(expected2, analytic, 1
e-5));