29 using namespace gtsam;
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;
151 Vector6 xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
154 EQUALITY(static_cast<gtsam::Vector>(
T.AdjointMap() *
xi),
T.Adjoint(xi));
159 Matrix6 actualH1, actualH2, expectedH1, expectedH2;
160 std::function<Vector6(const Pose3&, const Vector6&)> Adjoint_proxy =
163 T.
Adjoint(xi, actualH1, actualH2);
186 Vector6 xi = (Vector6() << 0.1, 1.2, 2.3, 3.1, 1.4, 4.5).finished();
189 EQUALITY(static_cast<Vector>(
T.AdjointMap().transpose() *
xi),
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) {
250 Matrix A = I_3x3 + ((1 -
cos(t)) / t) * W + ((t -
sin(t)) / t) * (W *
W);
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();
290 std::function<Point3(const Pose3&)>
f = [](
const Pose3&
T) {
return T.translation(); };
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();
314 Vector y = T2.inverse().Adjoint(x);
328 Matrix actualDcompose1, actualDcompose2;
348 Matrix actualDcompose1, actualDcompose2;
349 T1.
compose(
T2, actualDcompose1, actualDcompose2);
363 Matrix actual =
T.inverse(actualDinverse).matrix();
375 Rot3 R = Rot3::Rodrigues(0.3,0.4,-0.5);
399 Matrix actualDtransform_from1;
400 T.transformFrom(
P, actualDtransform_from1, {});
407 Matrix 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>());
582 Pose3 t = Pose3::Retract(d);
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));
672 return pose.
range(point);
676 Matrix expectedH1, actualH1, expectedH2, actualH2;
685 double actual23 =
x2.
range(
l3, actualH1, actualH2);
695 double actual34 =
x3.
range(l4, actualH1, actualH2);
707 return pose.
range(point);
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;
803 expected << wh, Z_3x3, vh, wh;
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);
840 Vector6
w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0;
861 auto xi = [](
double t) {
863 v << 2 *
t,
sin(t), 4 * t *
t, 2 *
t,
sin(t), 4 * t *
t;
866 auto xi_dot = [](
double t) {
875 for (
double t = -2.0;
t < 2.0;
t += 0.3) {
877 const Matrix actual = Pose3::ExpmapDerivative(
xi(
t)) * xi_dot(
t);
883 Vector6 w = Vector6::Random();
885 w.head<3>() = w.head<3>() * 0.9e-2;
886 Matrix3 actualQr = Pose3::ComputeQforExpmapDerivative(w, 0.01);
889 Matrix3 expectedQr = expectedH.bottomLeftCorner<3, 3>();
896 Vector6
w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0;
906 return Pose3::adjointMap(xi) *
v;
910 Vector6
v = (Vector6() << 1, 2, 3, 4, 5, 6).finished();
913 Matrix actualH1, actualH2;
916 Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
918 Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
928 return Pose3::adjointMap(xi).transpose() *
v;
932 Vector xi = (
Vector(6) << 0.01, 0.02, 0.03, 1.0, 2.0, 3.0).finished();
933 Vector v = (
Vector(6) << 0.04, 0.05, 0.06, 4.0, 5.0, 6.0).finished();
936 Matrix actualH1, actualH2;
937 Vector actual = Pose3::adjointTranspose(xi, v, actualH1, actualH2);
939 Matrix numericalH1 = numericalDerivative21<Vector6, Vector6, Vector6>(
941 Matrix numericalH2 = numericalDerivative22<Vector6, Vector6, Vector6>(
951 std::ostringstream
os;
954 string expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0 0 0";
962 EXPECT(check_group_invariants(
id,
id));
963 EXPECT(check_group_invariants(
id,
T3));
964 EXPECT(check_group_invariants(
T2,
id));
967 EXPECT(check_manifold_invariants(
id,
id));
968 EXPECT(check_manifold_invariants(
id,
T3));
969 EXPECT(check_manifold_invariants(
T2,
id));
1003 auto cov2 = FullCovarianceFromSigmas<Pose2>(s2);
1006 auto match_cov3_to_cov2 = [&](
int spatial_axis0,
int spatial_axis1,
int r_axis,
1007 const Pose2::Jacobian &cov2,
const Pose3::Jacobian &cov3) ->
void 1011 Vector3{cov3(spatial_axis0, spatial_axis0), cov3(spatial_axis1, spatial_axis1), cov3(r_axis, r_axis)}));
1013 Vector3{cov2(1, 0), cov2(2, 0), cov2(2, 1)},
1014 Vector3{cov3(spatial_axis1, spatial_axis0), cov3(r_axis, spatial_axis0), cov3(r_axis, spatial_axis1)}));
1019 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << s2(2), 0., 0., 0., s2(0), s2(1)).finished());
1021 match_cov3_to_cov2(4, 5, 0, transformed2, transformed3);
1026 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., s2(2), 0., s2(1), 0., s2(0)).finished());
1028 match_cov3_to_cov2(5, 3, 1, transformed2, transformed3);
1033 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., 0., s2(2), s2(0), s2(1), 0.).finished());
1035 match_cov3_to_cov2(3, 4, 2, transformed2, transformed3);
1047 auto cov = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0.1, 0.2, 0.3, 0.5, 0.7, 1.1).finished());
1051 (Vector6{} << cov(1, 1), cov(2, 2), cov(0, 0), cov(4, 4), cov(5, 5), cov(3, 3)).finished(),
1052 Vector6{transformed.diagonal()}));
1055 (Vector5{} << -cov(2, 1), cov(0, 1), cov(4, 1), -cov(5, 1), cov(3, 1)).finished(),
1056 (Vector5{} << transformed(1, 0), transformed(2, 0), transformed(3, 0),
1057 transformed(4, 0), transformed(5, 0)).finished()));
1062 auto cov = TwoVariableCovarianceFromSigmas<Pose3>(1, 2, 0.7, 0.3);
1076 auto cov = SingleVariableCovarianceFromSigma<Pose3>(0, 0.1);
1084 auto cov = SingleVariableCovarianceFromSigma<Pose3>(1, 0.1);
1088 (Vector6{} << 0., 0., 0.1 * 0.1, 0., 0.1 * 0.1 * 20. * 20., 0.).finished(),
1089 Vector6{transformed.diagonal()}));
1104 Pose3 expected0(Rot3::Rz(M_PI_4),
Point3(0.5, 0, 0));
1131 Pose3 X = Pose3::Identity();
1134 Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4),
Point3(0.5, -0.207107, 0));
1135 Matrix actualJacobianX, actualJacobianY;
1145 Pose3 X = Pose3::Identity();
1148 Pose3 expectedPoseInterp(Rot3::Identity(),
Point3(0.3, 0, 0));
1149 Matrix actualJacobianX, actualJacobianY;
1159 Pose3 X = Pose3::Identity();
1162 Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4),
Point3(0, 0, 0));
1163 Matrix actualJacobianX, actualJacobianY;
1176 Pose3 expectedPoseInterp(Rot3::Rz(M_PI_4),
Point3(0, 0, 0));
1177 Matrix actualJacobianX, actualJacobianY;
1178 interpolate(X, Y, t, actualJacobianX, actualJacobianY);
1190 Matrix63 actualH1, actualH2;
1191 Pose3 actual = Pose3::Create(R,
P2, actualH1, actualH2);
1194 return Pose3::Create(R,
t);
1205 std::string
expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 1 2 3\n";
Provides additional testing facilities for common data structures.
#define EQUALITY(expected, actual)
Point3 translation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Jet< T, N > cos(const Jet< T, N > &f)
Point3 transformFrom_(const Pose3 &pose, const Point3 &point)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
void adjoint(const MatrixType &m)
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
Provides convenient mappings of common member functions for testing.
static int runAllTests(TestResult &result)
T between(const T &t1, const T &t2)
Pose3 xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4))
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Jet< T, N > sin(const Jet< T, N > &f)
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HaTb={}) const
Pose2_ Expmap(const Vector3_ &xi)
Vector6 testDerivAdjoint(const Vector6 &xi, const Vector6 &v)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Pose3 expected(expectedR, expectedT)
Pose3_ transformPoseTo(const Pose3_ &p, const Pose3_ &q)
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
EIGEN_DEVICE_FUNC const LogReturnType log() const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Pose3 xl2(Rot3::Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0))
#define GTSAM_CONCEPT_LIE_INST(T)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
static const Similarity3 id
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Rot3 expectedR(c, -s, 0, s, c, 0, 0, 0, 1)
Unit3 bearing_proxy(const Pose3 &pose, const Point3 &point)
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Pose3 inverse() const
inverse transformation with derivatives
T compose(const T &t1, const T &t2)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Pose3 Agrawal06iros(const Vector &xi)
static void normalize(Signature::Row &row)
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Pose3 xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0))
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Represents a 3D point on a unit sphere.
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
double range_proxy(const Pose3 &pose, const Point3 &point)
#define EXPECT(condition)
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 3 > Hpoint={}) const
Vector6 AdjointTranspose(const Vector6 &x, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_x={}) const
The dual version of Adjoint.
Array< int, Dynamic, 1 > v
Point3 expectedT(0.29552, 0.0446635, 1)
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
Vector6 testDerivAdjointTranspose(const Vector6 &xi, const Vector6 &v)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Matrix wedge< Pose3 >(const Vector &xi)
Support utilities for using AdjointMap for transforming Pose2 and Pose3 covariance matrices...
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
#define ROT3_DEFAULT_COORDINATES_MODE
Class compose(const Class &g) const
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
Pose3 xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0))
static const Pose3 T(R, P2)
static const Point3 P2(3.5,-8.2, 4.2)
Matrix3 skewSymmetric(double wx, double wy, double wz)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Pose3 transformPoseFrom_(const Pose3 &wTa, const Pose3 &aTb)
ADT create(const Signature &signature)
ofstream os("timeSchurFactors.csv")
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
Double_ range(const Point2_ &p, const Point2_ &q)
Class between(const Class &g) const
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in world coordinates and transforms it to Pose coordinates
static EIGEN_DEPRECATED const end_t end
#define CHECK_CHART_DERIVATIVES(t1, t2)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Similarity3 T5(R, P, 10)
Class expmap(const TangentVector &v) const
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Pose3 interpolateRt(const Pose3 &T, double t) const
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Jet< T, N > sqrt(const Jet< T, N > &f)
Matrix6 AdjointMap() const
Pose3 testing_interpolate(const Pose3 &t1, const Pose3 &t2, double gamma)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
TangentVector logmap(const Class &g) const
double range_pose_proxy(const Pose3 &pose, const Pose3 &point)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HwTb={}) const
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
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={})
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Pose3 transformPoseTo_(const Pose3 &pose, const Pose3 &pose2)
Point3 transform_to_(const Pose3 &pose, const Point3 &point)
Vector6 Adjoint(const Vector6 &xi_b, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_xib={}) const
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
#define GTSAM_CONCEPT_TESTABLE_INST(T)
static const Point3 P(0.2, 0.7,-2)
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
static Similarity2 Align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair ¢roids)
This method estimates the similarity transform from differences point pairs, given a known or estimat...
std::pair< Point3, Point3 > Point3Pair