testVisualISAM2.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
21 #include <examples/SFMdata.h>
22 #include <gtsam/geometry/Point2.h>
23 #include <gtsam/inference/Symbol.h>
24 #include <gtsam/nonlinear/ISAM2.h>
26 #include <gtsam/nonlinear/Values.h>
28 
29 #include <vector>
30 
31 using namespace std;
32 using namespace gtsam;
33 
34 /* ************************************************************************* */
35 TEST(testVisualISAM2, all)
36 {
37  Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
38 
39  auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
40 
41  // Create ground truth data
42  vector<Point3> points = createPoints();
43  vector<Pose3> poses = createPoses();
44 
45  // Set the parameters
47  parameters.relinearizeThreshold = 0.01;
48  parameters.relinearizeSkip = 1;
49  ISAM2 isam(parameters);
50 
51  // Create a Factor Graph and Values to hold the new data
53  Values initialEstimate;
54 
55  // Loop over the poses, adding the observations to iSAM incrementally
56  for (size_t i = 0; i < poses.size(); ++i)
57  {
58  // Add factors for each landmark observation
59  for (size_t j = 0; j < points.size(); ++j)
60  {
61  PinholeCamera<Cal3_S2> camera(poses[i], *K);
62  Point2 measurement = camera.project(points[j]);
64  measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K);
65  }
66 
67  // Add an initial guess for the current pose
68  // Intentionally initialize the variables off from the ground truth
69  static Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
70  Point3(0.05, -0.10, 0.20));
71  initialEstimate.insert(Symbol('x', i), poses[i] * kDeltaPose);
72 
73  // Treat first iteration as special case
74  if (i == 0)
75  {
76  // Add a prior on pose x0, 30cm std on x,y,z and 0.1 rad on roll,pitch,yaw
77  static auto kPosePrior = noiseModel::Diagonal::Sigmas(
78  (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
79  .finished());
80  graph.addPrior(Symbol('x', 0), poses[0], kPosePrior);
81 
82  // Add a prior on landmark l0
83  static auto kPointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
84  graph.addPrior(Symbol('l', 0), points[0], kPointPrior);
85 
86  // Add initial guesses to all observed landmarks
87  // Intentionally initialize the variables off from the ground truth
88  static Point3 kDeltaPoint(-0.25, 0.20, 0.15);
89  for (size_t j = 0; j < points.size(); ++j)
90  initialEstimate.insert<Point3>(Symbol('l', j), points[j] + kDeltaPoint);
91  }
92  else
93  {
94  // Update iSAM with the new factors
95  isam.update(graph, initialEstimate);
96 
97  // Do an extra update to converge withing these 8 iterations
98  isam.update();
99 
100  // Optimize
101  Values currentEstimate = isam.calculateEstimate();
102 
103  // reset for next iteration
104  graph.resize(0);
105  initialEstimate.clear();
106  }
107  } // for loop
108 
109  auto result = isam.calculateEstimate();
111  for (size_t j = 0; j < points.size(); ++j)
112  {
113  Symbol key('l', j);
114  EXPECT(assert_equal(points[j], result.at<Point3>(key), 0.01));
115  }
116 }
117 
118 /* ************************************************************************* */
119 int main()
120 {
121  TestResult tr;
122  return TestRegistry::runAllTests(tr);
123 }
124 /* ************************************************************************* */
void clear()
Definition: Values.h:311
static int runAllTests(TestResult &result)
TEST(testVisualISAM2, all)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
double measurement(10.0)
Definition: Half.h:150
int main()
NonlinearFactorGraph graph
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
std::vector< gtsam::Point3 > createPoints()
Definition: SFMdata.h:37
Values calculateEstimate() const
Definition: ISAM2.cpp:763
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
size_t size() const
Definition: Values.h:236
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
#define EXPECT(condition)
Definition: Test.h:151
NonlinearISAM isam(relinearizeInterval)
Basic bearing factor from 2D measurement.
static ConjugateGradientParameters parameters
RelinearizationThreshold relinearizeThreshold
Definition: ISAM2Params.h:168
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
std::vector< gtsam::Pose3 > createPoses(const gtsam::Pose3 &init=gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2, 0,-M_PI/2), gtsam::Point3(30, 0, 0)), const gtsam::Pose3 &delta=gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4, 0), gtsam::Point3(sin(M_PI/4)*30, 0, 30 *(1-sin(M_PI/4)))), int steps=8)
Definition: SFMdata.h:54
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
Simple example for the structure-from-motion problems.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
Definition: ISAM2.cpp:396
void resize(size_t size)
Definition: FactorGraph.h:358
Vector3 Point3
Definition: Point3.h:35
static const CalibratedCamera camera(kDefaultPose)
2D Point
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
boost::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
std::ptrdiff_t j


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:25