26 #include <boost/assign/std/vector.hpp> 27 #include <boost/optional.hpp> 32 using namespace gtsam;
71 #ifdef SLOW_BUT_CORRECT_EXPMAP 103 0.0, 0.0, 0.0).finished();
104 Matrix A2 = A*A/2.0, A3 = A2*A/3.0, A4=A3*A/4.0;
200 Matrix3 expected2 = T.
matrix() * hat(xi2) * T.
matrix().inverse();
201 Matrix3 xiprime2 = hat(T.
Adjoint(xi2));
209 #ifdef SLOW_BUT_CORRECT_EXPMAP 281 (
Matrix(2, 3) << -1.0, 0.0, 2.0, 0.0, -1.0, -2.0).finished();
282 Matrix expectedH2 = (
Matrix(2, 2) << 0.0, 1.0, -1.0, 0.0).finished();
285 Matrix actualH1, actualH2;
312 Matrix H1_expected = (
Matrix(2, 3) << 0., -1., -2., 1., 0., -1.).finished();
313 Matrix H2_expected = (
Matrix(2, 2) << 0., -1., 1., 0.).finished();
332 Pose2 actual = pose1.
compose(pose2, actualDcompose1, actualDcompose2);
342 Matrix expectedH2 = I_3x3;
351 Point2 expected_point(-1.0, -1.0);
367 Matrix actualDcompose1, actualDcompose2;
368 Pose2 pose_actual_fcn = pose1.
compose(pose2, actualDcompose1, actualDcompose2);
388 Matrix actualDcompose1, actualDcompose2;
389 Pose2 pose_actual_fcn = pose1.
compose(pose2, actualDcompose1, actualDcompose2);
424 return (
Vector(3) << p.x(), p.y(), 1.0).finished();
432 gRl(0, 0), gRl(0, 1), gt.x(),
433 gRl(1, 0), gRl(1, 1), gt.y(),
434 0.0, 0.0, 1.0).finished();
447 0.0, 0.0, 1.0).finished(),
451 Point2 x_axis(1,0), y_axis(0,1);
454 1.0, 0.0).finished(),
466 0.0, 0.0, 1.0).finished(),
527 p1.
between(p2,actualH1,actualH2);
542 p1.
between(p2,actualH1,actualH2);
572 Matrix expectedH1, actualH1, expectedH2, actualH2;
610 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);
612 Matrix expectedH1, actualH1, expectedH2, actualH2;
644 return pose.
range(point);
649 Matrix expectedH1, actualH1, expectedH2, actualH2;
658 double actual23 =
x2.
range(
l3, actualH1, actualH2);
668 double actual34 =
x3.
range(
l4, actualH1, actualH2);
681 return pose.
range(point);
686 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);
688 Matrix expectedH1, actualH1, expectedH2, actualH2;
697 double actual23 =
x2.
range(
xl3, actualH1, actualH2);
707 double actual34 =
x3.
range(xl4, actualH1, actualH2);
722 vector<Point2Pair> correspondences;
725 correspondences += pq1, pq2;
727 boost::optional<Pose2> actual =
align(correspondences);
736 vector<Point2Pair> correspondences;
743 correspondences += pq1, pq2;
745 boost::optional<Pose2> actual =
align(correspondences);
759 vector<Point2Pair> correspondences;
763 correspondences += pq1, pq2, pq3;
765 boost::optional<Pose2> actual =
align(correspondences);
773 struct Triangle {
size_t i_,j_,k_;};
776 const pair<Triangle, Triangle>& trianglePair) {
777 const Triangle& t1 = trianglePair.first, t2 = trianglePair.second;
778 vector<Point2Pair> correspondences;
779 correspondences += make_pair(ps[t1.i_],qs[t2.i_]), make_pair(ps[t1.j_],qs[t2.j_]), make_pair(ps[t1.k_],qs[t2.k_]);
780 return align(correspondences);
791 Triangle t1; t1.i_=0; t1.j_=1; t1.k_=2;
792 Triangle t2; t2.i_=1; t2.j_=2; t2.k_=0;
794 boost::optional<Pose2> actual = align2(ps, qs, make_pair(t1,t2));
806 EXPECT(check_group_invariants(
id,
id));
807 EXPECT(check_group_invariants(
id,T1));
808 EXPECT(check_group_invariants(T2,
id));
809 EXPECT(check_group_invariants(T2,T1));
811 EXPECT(check_manifold_invariants(
id,
id));
812 EXPECT(check_manifold_invariants(
id,T1));
813 EXPECT(check_manifold_invariants(T2,
id));
814 EXPECT(check_manifold_invariants(T2,T1));
849 auto cov = FullCovarianceFromSigmas<Pose2>({0.1, 0.3, 0.7});
853 Vector3{cov(1, 1), cov(0, 0), cov(2, 2)},
854 Vector3{transformed.diagonal()}));
856 Vector3{-cov(1, 0), -cov(2, 1), cov(2, 0)},
857 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
862 auto cov = SingleVariableCovarianceFromSigma<Pose2>(0, 0.1);
870 auto cov = SingleVariableCovarianceFromSigma<Pose2>(1, 0.1);
878 auto cov = SingleVariableCovarianceFromSigma<Pose2>(2, 0.1);
881 Vector3{0., 0.1 * 0.1 * 20. * 20., 0.1 * 0.1},
882 Vector3{transformed.diagonal()}));
884 Vector3{0., 0., -0.1 * 0.1 * 20.},
885 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
890 auto cov = SingleVariableCovarianceFromSigma<Pose2>(0, 0.1);
894 Vector3{cov(1, 1), cov(0, 0), cov(2, 2)},
895 Vector3{transformed.diagonal()}));
898 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
903 auto cov = SingleVariableCovarianceFromSigma<Pose2>(2, 0.1);
906 Vector3{0., 0.1 * 0.1 * 20. * 20., 0.1 * 0.1},
907 Vector3{transformed.diagonal()}));
909 Vector3{0., 0., -0.1 * 0.1 * 20.},
910 Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
919 string s =
"Planar Pose";
920 string expected_stdout =
"(1, 2, 0)";
921 string expected1 = expected_stdout +
"\n";
922 string expected2 = s +
" " + expected1;
bool assert_stdout_equal(const std::string &expected, const V &actual)
Provides additional testing facilities for common data structures.
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself=boost::none, OptionalJacobian< 2, 3 > Hpoint=boost::none) const
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
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))
GTSAM_EXPORT Matrix3 matrix() 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 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="")
std::pair< Point2, Point2 > Point2Pair
const Point2 & t() const
translation
Q id(Eigen::AngleAxisd(0, Q_z_axis))
Point2 odo(const Point2 &x1, const Point2 &x2)
odometry between two poses
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Point3 pt(1.0, 2.0, 3.0)
const Rot2 & r() const
rotation
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)
void g(const string &key, int i)
int RealScalar int RealScalar int RealScalar RealScalar * ps
Unit3 bearing_proxy(const Pose3 &pose, const Point3 &point)
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
T compose(const T &t1, const T &t2)
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))
static const Line3 l(Rot3(), 1, 1)
Class compose(const Class &g) const
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
double range_proxy(const Pose3 &pose, const Point3 &point)
#define EXPECT(condition)
Matrix wedge< Pose2 >(const Vector &xi)
Eigen::Triplet< double > T
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
static const Symbol l3('l', 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...
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))
boost::optional< Pose2 > align(const vector< Point2Pair > &pairs)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
static Point2 transformTo_(const Pose2 &pose, const Point2 &point)
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
GTSAM_EXPORT Matrix3 AdjointMap() const
#define CHECK_CHART_DERIVATIVES(t1, t2)
Class between(const Class &g) const
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
GTSAM_EXPORT Pose2 inverse() const
inverse
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
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)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
#define GTSAM_CONCEPT_TESTABLE_INST(T)
GTSAM_EXPORT Point2 transformTo(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
Pose2 expected(expectedR, expectedT)
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...