30 using namespace gtsam;
69 #ifdef GTSAM_SLOW_BUT_CORRECT_EXPMAP 101 0.0, 0.0, 0.0).finished();
102 Matrix A2 = A*A/2.0, A3 = A2*A/3.0, A4=A3*A/4.0;
198 Matrix3 expected2 = T.
matrix() * hat(xi2) * T.
matrix().inverse();
199 Matrix3 xiprime2 = hat(T.
Adjoint(xi2));
207 #ifdef GTSAM_SLOW_BUT_CORRECT_EXPMAP 279 (
Matrix(2, 3) << -1.0, 0.0, 2.0, 0.0, -1.0, -2.0).finished();
280 Matrix expectedH2 = (
Matrix(2, 2) << 0.0, 1.0, -1.0, 0.0).finished();
283 Matrix actualH1, actualH2;
310 Matrix H1_expected = (
Matrix(2, 3) << 0., -1., -2., 1., 0., -1.).finished();
311 Matrix H2_expected = (
Matrix(2, 2) << 0., -1., 1., 0.).finished();
330 Pose2 actual = pose1.
compose(pose2, actualDcompose1, actualDcompose2);
340 Matrix expectedH2 = I_3x3;
349 Point2 expected_point(-1.0, -1.0);
365 Matrix actualDcompose1, actualDcompose2;
366 Pose2 pose_actual_fcn = pose1.
compose(pose2, actualDcompose1, actualDcompose2);
386 Matrix actualDcompose1, actualDcompose2;
387 Pose2 pose_actual_fcn = pose1.
compose(pose2, actualDcompose1, actualDcompose2);
422 return (
Vector(3) << p.x(), p.y(), 1.0).finished();
430 gRl(0, 0), gRl(0, 1), gt.x(),
431 gRl(1, 0), gRl(1, 1), gt.y(),
432 0.0, 0.0, 1.0).finished();
445 0.0, 0.0, 1.0).finished(),
449 Point2 x_axis(1,0), y_axis(0,1);
452 1.0, 0.0).finished(),
464 0.0, 0.0, 1.0).finished(),
486 std::function<Point2(const Pose2&)>
f = [](
const Pose2&
T) {
return T.translation(); };
487 Matrix numericalH = numericalDerivative11<Point2, Pose2>(
f,
pose);
498 std::function<Rot2(const Pose2&)>
f = [](
const Pose2&
T) {
return T.rotation(); };
499 Matrix numericalH = numericalDerivative11<Rot2, Pose2>(
f,
pose);
552 p1.
between(p2,actualH1,actualH2);
567 p1.
between(p2,actualH1,actualH2);
597 Matrix expectedH1, actualH1, expectedH2, actualH2;
635 Pose2 xl1(1, 0,
M_PI/2.0),
xl2(1, 1,
M_PI),
xl3(2.0, 2.0,-
M_PI/2.0),
xl4(1, 3, 0);
637 Matrix expectedH1, actualH1, expectedH2, actualH2;
669 return pose.
range(point);
674 Matrix expectedH1, actualH1, expectedH2, actualH2;
683 double actual23 =
x2.
range(
l3, actualH1, actualH2);
693 double actual34 =
x3.
range(
l4, actualH1, actualH2);
706 return pose.
range(point);
711 Pose2 xl1(1, 0,
M_PI/2.0),
xl2(1, 1,
M_PI),
xl3(2.0, 2.0,-
M_PI/2.0),
xl4(1, 3, 0);
713 Matrix expectedH1, actualH1, expectedH2, actualH2;
722 double actual23 =
x2.
range(
xl3, actualH1, actualH2);
732 double actual34 =
x3.
range(xl4, actualH1, actualH2);
790 struct Triangle {
size_t i_, j_, k_;};
793 const pair<Triangle, Triangle>& trianglePair) {
794 const Triangle& t1 = trianglePair.first, t2 = trianglePair.second;
796 {as[t1.j_], bs[t2.j_]},
797 {as[t1.k_], bs[t2.k_]}};
807 Triangle t1; t1.i_=0; t1.j_=1; t1.k_=2;
808 Triangle t2; t2.i_=1; t2.j_=2; t2.k_=0;
810 std::optional<Pose2> actual = align2(as, bs, {t1, t2});
823 EXPECT(check_group_invariants(
id,
id));
824 EXPECT(check_group_invariants(
id,
T1));
825 EXPECT(check_group_invariants(
T2,
id));
828 EXPECT(check_manifold_invariants(
id,
id));
829 EXPECT(check_manifold_invariants(
id,
T1));
830 EXPECT(check_manifold_invariants(
T2,
id));
860 auto cov = FullCovarianceFromSigmas<Pose2>({0.1, 0.3, 0.7});
864 Vector3{cov(1, 1), cov(0, 0), cov(2, 2)},
865 Vector3{transformed.diagonal()}));
867 Vector3{-cov(1, 0), -cov(2, 1), cov(2, 0)},
868 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
873 auto cov = SingleVariableCovarianceFromSigma<Pose2>(0, 0.1);
881 auto cov = SingleVariableCovarianceFromSigma<Pose2>(1, 0.1);
889 auto cov = SingleVariableCovarianceFromSigma<Pose2>(2, 0.1);
892 Vector3{0., 0.1 * 0.1 * 20. * 20., 0.1 * 0.1},
893 Vector3{transformed.diagonal()}));
895 Vector3{0., 0., -0.1 * 0.1 * 20.},
896 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
901 auto cov = SingleVariableCovarianceFromSigma<Pose2>(0, 0.1);
905 Vector3{cov(1, 1), cov(0, 0), cov(2, 2)},
906 Vector3{transformed.diagonal()}));
909 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
914 auto cov = SingleVariableCovarianceFromSigma<Pose2>(2, 0.1);
917 Vector3{0., 0.1 * 0.1 * 20. * 20., 0.1 * 0.1},
918 Vector3{transformed.diagonal()}));
920 Vector3{0., 0., -0.1 * 0.1 * 20.},
921 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
930 string s =
"Planar Pose";
931 string expected_stdout =
"(1, 2, 0)";
932 string expected1 = expected_stdout +
"\n";
933 string expected2 = s +
" " + expected1;
bool assert_stdout_equal(const std::string &expected, const V &actual)
Provides additional testing facilities for common data structures.
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
#define GTSAM_CONCEPT_ASSERT(concept)
Rot3_ rotation(const Pose3_ &pose)
Concept check for values that can be used in unit tests.
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="")
Point2 odo(const Point2 &x1, const Point2 &x2)
odometry between two poses
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Rot2 R(Rot2::fromAngle(0.1))
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
static const Point3 pt(1.0, 2.0, 3.0)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
const Point2 & t() const
translation
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
Pose2 expected(Rot2::fromAngle(2 *M_PI/3), t)
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
void g(const string &key, int i)
Unit3 bearing_proxy(const Pose3 &pose, const Point3 &point)
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)
Point2 expectedT(-0.0446635, 0.29552)
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Pose3 xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0))
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
std::vector< Point2Pair > Point2Pairs
static const Line3 l(Rot3(), 1, 1)
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
static GTSAM_EXPORT Vector3 Logmap(const Pose2 &p, ChartJacobian H={})
Log map at identity - return the canonical coordinates of this rotation.
gtsam::Expression< typename gtsam::traits< T >::TangentVector > logmap(const gtsam::Expression< T > &x1, const gtsam::Expression< T > &x2)
logmap
GTSAM_EXPORT Matrix3 matrix() const
Point3_ translation(const Pose3_ &pose)
double range_proxy(const Pose3 &pose, const Point3 &point)
const Rot2 & r() const
rotation
#define EXPECT(condition)
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 3 > Hpoint={}) const
Array< int, Dynamic, 1 > v
Matrix wedge< Pose2 >(const Vector &xi)
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
static Point2 transformFrom_(const Pose2 &pose, const Point2 &point)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Support utilities for using AdjointMap for transforming Pose2 and Pose3 covariance matrices...
Class compose(const Class &g) const
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Pose3 xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0))
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
static Point2 transformTo_(const Pose2 &pose, const Point2 &point)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
static std::optional< Pose2 > Align(const Point2Pairs &abPointPairs)
std::pair< Point2, Point2 > Point2Pair
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
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
#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 Rot2 fromAngle(double theta)
Named constructor from angle in radians.
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)
TEST(SmartFactorBase, Pinhole)
GTSAM_EXPORT Pose2 inverse() const
inverse
static GTSAM_EXPORT Pose2 Expmap(const Vector3 &xi, ChartJacobian H={})
Exponential map at identity - create a rotation from canonical coordinates .
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)
GTSAM_EXPORT Point2 transformTo(const Point2 &point, OptionalJacobian< 2, 3 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
GTSAM_EXPORT Matrix3 AdjointMap() const
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
rotation
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
#define GTSAM_CONCEPT_TESTABLE_INST(T)
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
const Point2 & translation(OptionalJacobian< 2, 3 > Hself={}) const
translation
Pose2 expected(expectedR, expectedT)