10 using namespace gtsam;
19 const double a = 5,
b = 10;
21 const Line3 line(R, a,
b);
39 Vector4
v1(0, 0, -1, 0);
44 Vector4
v2(0, 0, 0, -1);
50 Vector4
v3(-
M_PI / 4, 0, 0, 0);
56 Vector4 v4(0, -
M_PI / 4, 0, 0);
75 Vector4
v1(0, 0, 0, 1);
80 Vector4
v2(0, 0, 1, 0);
85 Vector4
v3(
M_PI / 4, 0, 0, 0);
92 Vector4 v4(0,
M_PI / 4, 0, 0);
98 Vector4 v5(
M_PI / 3, -
M_PI / 4, -0.4, 1.2);
119 Vector4
r2(2.3, 0.987, -3, 4);
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Rot2 R(Rot2::fromAngle(0.1))
Some functions to compute numerical derivatives.
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Rot3 inverse() const
inverse of a rotation
Represents a 3D point on a unit sphere.
static const Line3 l(Rot3(), 1, 1)
Vector4 localCoordinates(const Line3 &q, OptionalJacobian< 4, 4 > Dp=boost::none, OptionalJacobian< 4, 4 > Dq=boost::none) const
Test harness methods for expressions.
Line3 retract(const Vector4 &v, OptionalJacobian< 4, 4 > Dp=boost::none, OptionalJacobian< 4, 4 > Dv=boost::none) const
#define EXPECT(condition)
Unit3 project(OptionalJacobian< 2, 4 > Dline=boost::none) const
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
static const Symbol l3('l', 3)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
4 dimensional manifold of 3D lines
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
Expression< Point2 > projection(f, p_cam)
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
bool equals(const Line3 &l2, double tol=10e-9) const
TEST(LPInitSolver, InfiniteLoopSingleVar)
static GTSAM_EXPORT Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H=boost::none)
Named constructor from Point3 with optional Jacobian.
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
#define GTSAM_CONCEPT_TESTABLE_INST(T)
noiseModel::Base::shared_ptr SharedNoiseModel
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.