33 #include <boost/function.hpp> 34 #include <boost/bind.hpp> 36 using namespace gtsam;
42 static const
Point3 P(0.2, 0.7, -2);
44 static const
double s = 4;
48 Point3(3.5, -8.2, 4.2), 1);
89 delta << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7;
99 Re << -0.2248, 0.9024, -0.3676, -0.3502, -0.4269, -0.8337, -0.9093, -0.0587, 0.4120;
100 Vector3 te(-9.8472, 59.7640, 10.2125);
116 re << 0.0688, 0.9863, -0.1496, -0.5665, -0.0848, -0.8197, -0.8211, 0.1412, 0.5530;
117 Vector3 te(-13.6797, 3.2441, -5.7794);
129 Vector7
v = Vector7::Zero();
138 v3 << 0, 0, 0, 1, 2, 3, 0;
171 Vector7 d12 = Vector7::Constant(0.1);
192 expected << 1, 0, 0, 1, 0, 1, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0.5;
201 delta << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7;
206 zeros << 0, 0, 0, 0, 0, 0, 0;
245 boost::function<Point3(Similarity3, Point3)>
f = boost::bind(
251 Matrix H1 = numericalDerivative21<Point3, Similarity3, Point3>(
f,
T,
q);
252 Matrix H2 = numericalDerivative22<Point3, Similarity3, Point3>(
f,
T,
q);
253 Matrix actualH1, actualH2;
254 T.transformFrom(q, actualH1, actualH2);
273 Pose3 eTo2(
Rot3(-1, 0, 0, 0, -1, 0, 0, 0, 1),
Point3(4, 0, 0));
277 Pose3 expected_wTo1(
Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1),
Point3(4, 6, 10));
278 Pose3 expected_wTo2(
Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1),
Point3(-4, 6, 10));
294 Pose3 Ta2(
Rot3(-1, 0, 0, 0, -1, 0, 0, 0, 1),
Point3(4, 0, 0));
295 Pose3 Tb1(
Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1),
Point3(4, 6, 10));
296 Pose3 Tb2(
Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1),
Point3(-4, 6, 10));
297 Pose3 Tc1(
Rot3(0, 0, -1, 0, 1, 0, 1, 0, 0),
Point3(0, 6, -12));
298 Pose3 Tc2(
Rot3(0, 0, -1, 0, -1, 0, -1, 0, 0),
Point3(0, 6, 12));
318 vector<Point3Pair> correspondences{ab1, ab2, ab3};
333 vector<Point3Pair> correspondences{ab1, ab2, ab3};
348 vector<Point3Pair> correspondences{ab1, ab2, ab3};
362 Pose3 eTo2(
Rot3(-1, 0, 0, 0, -1, 0, 0, 0, 1),
Point3(4, 0, 0));
365 Pose3 wTo1(
Rot3(-1, 0, 0, 0, 1, 0, 0, 0, -1),
Point3(4, 6, 10));
366 Pose3 wTo2(
Rot3(1, 0, 0, 0, -1, 0, 0, 0, -1),
Point3(-4, 6, 10));
371 vector<Pose3Pair> correspondences{wTe1, wTe2};
375 #ifdef GTSAM_ROT3_EXPMAP 419 Point3(6 * 0.7, 0, 0), 1.0);
426 (
Vector(7) << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10).finished());
428 (
Vector(7) << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0).finished());
509 EXPECT(check_group_invariants(
id,
id));
510 EXPECT(check_group_invariants(
id,
T3));
511 EXPECT(check_group_invariants(
T2,
id));
514 EXPECT(check_manifold_invariants(
id,
id));
515 EXPECT(check_manifold_invariants(
id,
T3));
516 EXPECT(check_manifold_invariants(
T2,
id));
static const Similarity3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3), 1)
GTSAM_EXPORT const Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
static const Similarity3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), Point3(3.5,-8.2, 4.2), 1)
static size_t Dim()
Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
static GTSAM_EXPORT Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
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
static GTSAM_EXPORT Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 identity()
Return an identity transform.
Point2 prior(const Point2 &x)
Prior on a single pose.
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
double scale() const
Return the scale.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Some functions to compute numerical derivatives.
static GTSAM_EXPORT Matrix4 wedge(const Vector7 &xi)
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx=boost::none, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hz=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
static const Similarity3 id
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hp=boost::none, OptionalJacobian< 3, 1 > Hr=boost::none)
static const Similarity3 T4(R, P, s)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
static Rot3 Rodrigues(const Vector3 &w)
static const Point3 P(0.2, 0.7,-2)
Factor graph that supports adding ExpressionFactors directly.
#define EXPECT(condition)
static const Similarity3 T6(Rot3(), Point3(1, 1, 0), 2)
const Point3 & translation() const
Return a GTSAM translation.
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
static GTSAM_EXPORT Similarity3 Align(const std::vector< Point3Pair > &abPointPairs)
static SmartStereoProjectionParams params
noiseModel::Diagonal::shared_ptr SharedDiagonal
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
GTSAM_EXPORT Similarity3 inverse() const
Return the inverse.
const Rot3 & rotation() const
Return a GTSAM rotation.
#define EXPECT_LONGS_EQUAL(expected, actual)
GTSAM_EXPORT Point3 transformFrom(const Point3 &p, OptionalJacobian< 3, 7 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Action on a point p is s*(R*p+t)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
static Rot3 Rz(double t)
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
TEST(LPInitSolver, InfiniteLoopSingleVar)
void setVerbosityLM(const std::string &s)
static const Similarity3 T5(R, P, 10)
boost::shared_ptr< Isotropic > shared_ptr
static const Similarity3 T1(R, Point3(3.5,-8.2, 4.2), 1)
std::pair< Pose3, Pose3 > Pose3Pair
Implementation of Similarity3 transform.
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
#define GTSAM_CONCEPT_TESTABLE_INST(T)
static Rot3 Ry(double t)
Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
GTSAM_EXPORT Matrix7 AdjointMap() const
Project from one tangent space to another.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
std::pair< Point3, Point3 > Point3Pair
void test2(OptionalJacobian<-1,-1 > H=boost::none)