23 #include <boost/assign/std/vector.hpp> 30 using namespace gtsam;
35 static const
Point3 P(0.2,0.7,-2);
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);
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;
175 Matrix A = I_3x3 + ((1 -
cos(t)) / t) * W + ((t -
sin(t)) / t) * (W *
W);
184 xi = (
Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
190 xi = (
Vector(6) << 0.1, -0.2, 0.3, -0.4, 0.5, -0.6).finished();
202 xi = (
Vector(6) << 0.2, 0.3, -0.8, 100.0, 120.0, -60.0).finished();
215 Matrix numericalH = numericalDerivative11<Point3, Pose3>(
216 boost::bind(&Pose3::translation, _1, boost::none),
T);
226 Matrix numericalH = numericalDerivative11<Rot3, Pose3>(
237 Vector x = (
Vector(6) << 0.1, 0.1, 0.1, 0.4, 0.2, 0.8).finished();
239 Vector y = T2.inverse().Adjoint(x);
253 Matrix actualDcompose1, actualDcompose2;
273 Matrix actualDcompose1, actualDcompose2;
274 T1.
compose(
T2, actualDcompose1, actualDcompose2);
288 Matrix actual =
T.inverse(actualDinverse).matrix();
300 Rot3 R = Rot3::Rodrigues(0.3,0.4,-0.5);
324 Matrix actualDtransform_from1;
325 T.transformFrom(
P, actualDtransform_from1, boost::none);
332 Matrix actualDtransform_from1;
341 Matrix actualDtransform_from1;
351 Matrix actualDtransform_from1;
361 Matrix actualDtransform_from2;
362 T.transformFrom(
P, boost::none, actualDtransform_from2);
373 T.transformTo(
P, computed, boost::none);
381 T.transformTo(
P, boost::none, computed);
389 T.transformTo(
P, actH1, actH2);
399 T.transformFrom(
P, actH1, actH2);
505 d << 1,2,3,4,5,6; d/=10;
506 const Rot3 R = Rot3::Retract(d.head<3>());
507 Pose3 t = Pose3::Retract(d);
514 d12 << 1,2,3,4,5,6; d12/=10;
521 Vector d12 = Vector6::Constant(0.1);
559 Vector d = (
Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
574 Matrix actualDBetween1,actualDBetween2;
587 Point3 l1(1, 0, 0),
l2(1, 1, 0),
l3(2, 2, 0),
l4(1, 4,-4);
590 xl1(Rot3::Ypr(0.0, 0.0, 0.0),
Point3(1, 0, 0)),
591 xl2(Rot3::Ypr(0.0, 1.0, 0.0),
Point3(1, 1, 0)),
592 xl3(Rot3::Ypr(1.0, 0.0, 0.0),
Point3(2, 2, 0)),
593 xl4(Rot3::Ypr(0.0, 0.0, 1.0),
Point3(1, 4,-4));
597 return pose.
range(point);
601 Matrix expectedH1, actualH1, expectedH2, actualH2;
610 double actual23 =
x2.
range(
l3, actualH1, actualH2);
620 double actual34 =
x3.
range(l4, actualH1, actualH2);
632 return pose.
range(point);
636 Matrix expectedH1, actualH1, expectedH2, actualH2;
645 double actual23 =
x2.
range(
xl3, actualH1, actualH2);
655 double actual34 =
x3.
range(
xl4, actualH1, actualH2);
670 Matrix expectedH1, actualH1, expectedH2, actualH2;
681 Matrix expectedH1, actualH1, expectedH2, actualH2;
692 Matrix expectedH1, actualH1, expectedH2, actualH2, H2block;
704 expectedH2 =
Matrix(2, 6);
705 expectedH2.setZero();
706 expectedH2.block<2, 3>(0, 3) = H2block;
716 Vector x_step = Vector::Unit(6,3)*1.0;
728 expected << wh, Z_3x3, vh, wh;
736 vector<Point3Pair> correspondences;
740 correspondences += ab1, ab2, ab3;
742 boost::optional<Pose3> actual = Pose3::Align(correspondences);
749 Rot3 R = Rot3::RzRyRx(0.3, 0.2, 0.1);
752 vector<Point3Pair> correspondences;
760 correspondences += ab1, ab2, ab3;
762 boost::optional<Pose3> actual = Pose3::Align(correspondences);
769 Vector6
w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0;
790 auto xi = [](
double t) {
792 v << 2 *
t,
sin(t), 4 * t *
t, 2 *
t,
sin(t), 4 * t *
t;
795 auto xi_dot = [](
double t) {
804 for (
double t = -2.0;
t < 2.0;
t += 0.3) {
806 const Matrix actual = Pose3::ExpmapDerivative(
xi(
t)) * xi_dot(
t);
812 Vector6 w = Vector6::Random();
814 w.head<3>() = w.head<3>() * 0.9e-2;
815 Matrix3 actualQr = Pose3::ComputeQforExpmapDerivative(w, 0.01);
818 Matrix3 expectedQr = expectedH.bottomLeftCorner<3, 3>();
825 Vector6
w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0;
835 return Pose3::adjointMap(xi) *
v;
844 Matrix numericalH = numericalDerivative21<Vector6, Vector6, Vector6>(
853 return Pose3::adjointMap(xi).transpose() *
v;
857 Vector xi = (
Vector(6) << 0.01, 0.02, 0.03, 1.0, 2.0, 3.0).finished();
858 Vector v = (
Vector(6) << 0.04, 0.05, 0.06, 4.0, 5.0, 6.0).finished();
862 Vector actual = Pose3::adjointTranspose(xi, v, actualH);
864 Matrix numericalH = numericalDerivative21<Vector6, Vector6, Vector6>(
873 std::ostringstream
os;
876 string expected =
"R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0 0 0";
884 EXPECT(check_group_invariants(
id,
id));
885 EXPECT(check_group_invariants(
id,
T3));
886 EXPECT(check_group_invariants(
T2,
id));
889 EXPECT(check_manifold_invariants(
id,
id));
890 EXPECT(check_manifold_invariants(
id,
T3));
891 EXPECT(check_manifold_invariants(
T2,
id));
925 auto cov2 = FullCovarianceFromSigmas<Pose2>(s2);
928 auto match_cov3_to_cov2 = [&](
int spatial_axis0,
int spatial_axis1,
int r_axis,
929 const Pose2::Jacobian &cov2,
const Pose3::Jacobian &cov3) ->
void 933 Vector3{cov3(spatial_axis0, spatial_axis0), cov3(spatial_axis1, spatial_axis1), cov3(r_axis, r_axis)}));
935 Vector3{cov2(1, 0), cov2(2, 0), cov2(2, 1)},
936 Vector3{cov3(spatial_axis1, spatial_axis0), cov3(r_axis, spatial_axis0), cov3(r_axis, spatial_axis1)}));
941 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << s2(2), 0., 0., 0., s2(0), s2(1)).finished());
943 match_cov3_to_cov2(4, 5, 0, transformed2, transformed3);
948 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., s2(2), 0., s2(1), 0., s2(0)).finished());
950 match_cov3_to_cov2(5, 3, 1, transformed2, transformed3);
955 auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., 0., s2(2), s2(0), s2(1), 0.).finished());
957 match_cov3_to_cov2(3, 4, 2, transformed2, transformed3);
969 auto cov = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0.1, 0.2, 0.3, 0.5, 0.7, 1.1).finished());
973 (Vector6{} << cov(1, 1), cov(2, 2), cov(0, 0), cov(4, 4), cov(5, 5), cov(3, 3)).finished(),
974 Vector6{transformed.diagonal()}));
977 (Vector5{} << -cov(2, 1), cov(0, 1), cov(4, 1), -cov(5, 1), cov(3, 1)).finished(),
978 (Vector5{} << transformed(1, 0), transformed(2, 0), transformed(3, 0),
979 transformed(4, 0), transformed(5, 0)).finished()));
984 auto cov = TwoVariableCovarianceFromSigmas<Pose3>(1, 2, 0.7, 0.3);
998 auto cov = SingleVariableCovarianceFromSigma<Pose3>(0, 0.1);
1006 auto cov = SingleVariableCovarianceFromSigma<Pose3>(1, 0.1);
1010 (Vector6{} << 0., 0., 0.1 * 0.1, 0., 0.1 * 0.1 * 20. * 20., 0.).finished(),
1011 Vector6{transformed.diagonal()}));
1026 Pose3 expected0(Rot3::Rz(M_PI_4),
Point3(0.5, 0, 0));
1050 Matrix63 actualH1, actualH2;
1051 Pose3 actual = Pose3::Create(
R,
P2, actualH1, actualH2);
1053 boost::function<Pose3(Rot3,Point3)>
create = boost::bind(Pose3::Create,_1,_2,boost::none,boost::none);
1063 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.
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself=boost::none, OptionalJacobian< 2, 3 > Hpoint=boost::none) const
Point3 transformFrom_(const Pose3 &pose, const Point3 &point)
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Pose3 interpolateRt(const Pose3 &T, double t) const
Matrix6 AdjointMap() const
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))
Vector6 Adjoint(const Vector6 &xi_b) const
FIXME Not tested - marked as incorrect.
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="")
Q id(Eigen::AngleAxisd(0, Q_z_axis))
EIGEN_DEVICE_FUNC const LogReturnType log() const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() 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)
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)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Pose3 expected(expectedR, expectedT)
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)
Unit3 bearing_proxy(const Pose3 &pose, const Point3 &point)
T compose(const T &t1, const T &t2)
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself=boost::none, OptionalJacobian< 6, 6 > HaTb=boost::none) const
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
Represents a 3D point on a unit sphere.
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
T interpolate(const T &X, const T &Y, double t)
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in world coordinates and transforms it to Pose coordinates
Class compose(const Class &g) const
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Pose3 inverse() const
inverse transformation with derivatives
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Class expmap(const TangentVector &v) const
double range_proxy(const Pose3 &pose, const Point3 &point)
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself=boost::none, OptionalJacobian< 6, 6 > HwTb=boost::none) const
#define EXPECT(condition)
Point3 expectedT(0.29552, 0.0446635, 1)
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Rot3 expectedR(c,-s, 0, s, c, 0, 0, 0, 1)
Vector6 testDerivAdjointTranspose(const Vector6 &xi, const Vector6 &v)
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
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)
TangentVector logmap(const Class &g) const
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
Matrix3 skewSymmetric(double wx, double wy, double wz)
Pose3 transformPoseFrom_(const Pose3 &wTa, const Pose3 &aTb)
ADT create(const Signature &signature)
ofstream os("timeSchurFactors.csv")
#define CHECK_CHART_DERIVATIVES(t1, t2)
Class between(const Class &g) const
static const Similarity3 T5(R, P, 10)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(boost::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
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)
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
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
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Pose3 transformPoseTo_(const Pose3 &pose, const Pose3 &pose2)
Point3 transform_to_(const Pose3 &pose, const Point3 &point)
EIGEN_DEVICE_FUNC const InverseReturnType inverse() 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)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
std::pair< Point3, Point3 > Point3Pair