36 using namespace gtsam;
40 static const double tol = 1
e-5;
60 GaussianFactor::shared_ptr actualLF = nle->linearize(linearize);
75 GaussianFactor::shared_ptr actualLF = nle->linearize(config);
97 Pose2 value(2.0, 1.0, 2.0), wrong(2.0, 3.0, 4.0);
99 bad_linearize.
insert(key, wrong);
114 bad_linearize.
insert(key, wrong);
127 Values feasible, bad_linearize;
135 Vector actual = nle->unwhitenedError(feasible);
138 actual = nle->unwhitenedError(bad_linearize);
140 assert_equal(actual, Vector::Constant(3, std::numeric_limits<double>::infinity())));
154 EXPECT(nle1->equals(*nle2));
156 EXPECT(nle2->equals(*nle1));
158 EXPECT(!nle1->equals(*nle3));
165 Pose2 feasible1(1.0, 2.0, 3.0);
166 double error_gain = 500.0;
167 PoseNLE nle(key1, feasible1, error_gain);
170 Pose2 badPoint1(0.0, 2.0, 3.0);
177 config.
insert(key1, badPoint1);
178 double actError = nle.
error(config);
182 GaussianFactor::shared_ptr actLinFactor = nle.
linearize(config);
186 GaussianFactor::shared_ptr expLinFactor(
194 Pose2 feasible1(1.0, 2.0, 3.0);
195 double error_gain = 500.0;
202 Pose2 initPose(0.0, 2.0, 3.0);
204 init.
insert(key1, initPose);
208 ordering.push_back(key1);
213 expected.
insert(key1, feasible1);
222 Pose2 feasible1(1.0, 2.0, 3.0);
226 Pose2 initPose(0.0, 2.0, 3.0);
227 init.
insert(key1, initPose);
230 double error_gain = 500.0;
239 ordering.push_back(key1);
244 expected.
insert(key1, feasible1);
253 TEST( testNonlinearEqualityConstraint, unary_basics ) {
268 config2.insert(
key, ptBad1);
278 TEST( testNonlinearEqualityConstraint, unary_linearization ) {
286 GaussianFactor::shared_ptr actual1 = constraint.
linearize(config1);
287 GaussianFactor::shared_ptr expected1(
294 GaussianFactor::shared_ptr actual2 = constraint.
linearize(config2);
295 GaussianFactor::shared_ptr expected2(
301 TEST( testNonlinearEqualityConstraint, unary_simple_optimization ) {
304 Point2 truth_pt(1.0, 2.0);
310 Point2 badPt(100.0, -200.0);
319 initValues.
insert(key, badPt);
322 EXPECT(constraint->active(initValues));
325 expected.insert(key, truth_pt);
326 EXPECT(constraint->active(expected));
334 TEST( testNonlinearEqualityConstraint, odo_basics ) {
335 Point2 x1(1.0, 2.0),
x2(2.0, 3.0), odom(1.0, 1.0);
351 config2.insert(
key1, x1bad);
352 config2.insert(key2, x2bad);
362 TEST( testNonlinearEqualityConstraint, odo_linearization ) {
363 Point2 x1(1.0, 2.0),
x2(2.0, 3.0), odom(1.0, 1.0);
371 GaussianFactor::shared_ptr actual1 = constraint.
linearize(config1);
372 GaussianFactor::shared_ptr expected1(
381 config2.
insert(key2, x2bad);
382 GaussianFactor::shared_ptr actual2 = constraint.
linearize(config2);
383 GaussianFactor::shared_ptr expected2(
390 TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) {
394 Point2 truth_pt1(1.0, 2.0), truth_pt2(3.0, 2.0);
402 Point2 badPt(100.0, -200.0);
417 initValues.
insert(key2, badPt);
422 expected.
insert(key2, truth_pt2);
427 TEST (testNonlinearEqualityConstraint, two_pose ) {
438 Point2 pt_x1(1.0, 1.0), pt_x2(5.0, 6.0);
452 initialEstimate.
insert(x1, pt_x1);
453 initialEstimate.insert(x2,
Point2(0,0));
454 initialEstimate.insert(l1,
Point2(1.0, 6.0));
455 initialEstimate.insert(l2,
Point2(-4.0, 0.0));
461 expected.
insert(x1, pt_x1);
469 TEST (testNonlinearEqualityConstraint, map_warp ) {
497 initialEstimate.insert(l1,
Point2(1.0, 6.0));
498 initialEstimate.insert(l2,
Point2(-4.0, 0.0));
499 initialEstimate.insert(x2,
Point2(0.0, 0.0));
514 TEST (testNonlinearEqualityConstraint, stereo_constrained ) {
517 static double fov = 60;
518 static int w = 640,
h = 480;
520 static std::shared_ptr<Cal3_S2> shK(
new Cal3_S2(K));
534 Symbol key_x1(
'x', 1), key_x2(
'x', 2);
535 Symbol key_l1(
'l', 1), key_l2(
'l', 2);
547 leftCamera.
project(landmark), vmodel, key_x1, key_l1, shK);
549 rightCamera.
project(landmark), vmodel, key_x2, key_l2, shK);
559 initValues.
insert(key_x1, poseLeft);
560 initValues.
insert(key_x2, poseRight);
561 initValues.
insert(key_l1, landmark1);
562 initValues.
insert(key_l2, landmark2);
569 truthValues.
insert(key_x1, leftCamera.
pose());
570 truthValues.
insert(key_x2, rightCamera.
pose());
571 truthValues.
insert(key_l1, landmark);
572 truthValues.
insert(key_l2, landmark);
iq2D::PoseXInequality constraint1(key, 1.0, true, mu)
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
virtual const Values & optimize()
NonlinearEquality< Pose2 > PoseNLE
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
This is the base class for all measurement types.
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
#define DOUBLES_EQUAL(expected, actual, threshold)
iq2D::PoseYInequality constraint2(key, 2.0, true, mu)
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static SharedDiagonal soft_model
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
static const Point3 pt(1.0, 2.0, 3.0)
#define CHECK_EXCEPTION(condition, exception_name)
NonlinearFactorGraph graph
Point2 landmark1(5.0, 1.5)
TEST(NonlinearEquality, linearization)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static enum @1107 ordering
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
static Point3 landmark(0, 0, 5)
static Symbol key('x', 1)
const Pose3 & pose() const
return pose
GaussianFactor::shared_ptr linearize(const Values &x) const override
Linearize is over-written, because base linearization tries to whiten.
Base class for all pinhole cameras.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Point2 landmark2(7.0, 1.5)
const Symbol key1('v', 1)
Vector evaluateError(const T &p1, const T &p2, OptionalMatrixType H1, OptionalMatrixType H2) const override
evaluate error, returns vector of errors size of tangent space
#define EXPECT(condition)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
The most common 5DOF 3D->2D calibration.
std::shared_ptr< BetweenConstraint< VALUE > > shared_ptr
Reprojection of a LANDMARK to a 2D point.
std::shared_ptr< NonlinearEquality1< VALUE > > shared_ptr
fixed value for variable
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Vector evaluateError(const T &xj, OptionalMatrixType H) const override
Error function.
noiseModel::Diagonal::shared_ptr SharedDiagonal
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
std::shared_ptr< PoseNLE > shared_poseNLE
double error(const Values &c) const override
std::shared_ptr< GenericPrior< VALUE > > shared_ptr
virtual bool active(const Values &) const
Vector evaluateError(const X &x1, OptionalMatrixType H) const override
g(x) with optional derivative
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
PriorFactor< Pose2 > PosePrior
Chordal Bayes Net, the result of eliminating a factor graph.
static const double sigma
void insert(Key j, const Value &val)
double error(const Values &c) const override
Actual error function calculation.
static SharedDiagonal hard_model
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
const Symbol key2('v', 2)
measurement functions and constraint definitions for simulated 2D robot