testGeneralSFMFactor.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 #include <gtsam/sam/RangeFactor.h>
21 #include <gtsam/geometry/Cal3_S2.h>
22 #include <gtsam/geometry/Rot2.h>
28 #include <gtsam/inference/Symbol.h>
29 #include <gtsam/base/Testable.h>
30 
31 #include <boost/assign/std/vector.hpp>
32 #include <boost/shared_ptr.hpp>
34 using namespace boost::assign;
35 
36 #include <iostream>
37 #include <vector>
38 
39 using namespace std;
40 using namespace gtsam;
41 
42 // Convenience for named keys
45 
50 
51 class Graph: public NonlinearFactorGraph {
52 public:
53  void addMeasurement(int i, int j, const Point2& z,
54  const SharedNoiseModel& model) {
55  push_back(boost::make_shared<Projection>(z, model, X(i), L(j)));
56  }
57 
58  void addCameraConstraint(int j, const GeneralCamera& p) {
59  boost::shared_ptr<CameraConstraint> factor(new CameraConstraint(X(j), p));
60  push_back(factor);
61  }
62 
63  void addPoint3Constraint(int j, const Point3& p) {
64  boost::shared_ptr<Point3Constraint> factor(new Point3Constraint(L(j), p));
65  push_back(factor);
66  }
67 
68 };
69 
70 static double getGaussian() {
71  double S, V1, V2;
72  // Use Box-Muller method to create gauss noise from uniform noise
73  do {
74  double U1 = rand() / (double) (RAND_MAX);
75  double U2 = rand() / (double) (RAND_MAX);
76  V1 = 2 * U1 - 1; /* V1=[-1,1] */
77  V2 = 2 * U2 - 1; /* V2=[-1,1] */
78  S = V1 * V1 + V2 * V2;
79  } while (S >= 1);
80  return sqrt(-2.f * (double) log(S) / S) * V1;
81 }
82 
83 static const SharedNoiseModel sigma1(noiseModel::Unit::Create(2));
84 static const double baseline = 5.;
85 
86 /* ************************************************************************* */
87 static vector<Point3> genPoint3() {
88  const double z = 5;
89  vector<Point3> landmarks;
90  landmarks.push_back(Point3(-1., -1., z));
91  landmarks.push_back(Point3(-1., 1., z));
92  landmarks.push_back(Point3(1., 1., z));
93  landmarks.push_back(Point3(1., -1., z));
94  landmarks.push_back(Point3(-1.5, -1.5, 1.5 * z));
95  landmarks.push_back(Point3(-1.5, 1.5, 1.5 * z));
96  landmarks.push_back(Point3(1.5, 1.5, 1.5 * z));
97  landmarks.push_back(Point3(1.5, -1.5, 1.5 * z));
98  landmarks.push_back(Point3(-2., -2., 2 * z));
99  landmarks.push_back(Point3(-2., 2., 2 * z));
100  landmarks.push_back(Point3(2., 2., 2 * z));
101  landmarks.push_back(Point3(2., -2., 2 * z));
102  return landmarks;
103 }
104 
105 static vector<GeneralCamera> genCameraDefaultCalibration() {
106  vector<GeneralCamera> X;
107  X.push_back(GeneralCamera(Pose3(Rot3(), Point3(-baseline / 2., 0., 0.))));
108  X.push_back(GeneralCamera(Pose3(Rot3(), Point3(baseline / 2., 0., 0.))));
109  return X;
110 }
111 
112 static vector<GeneralCamera> genCameraVariableCalibration() {
113  const Cal3_S2 K(640, 480, 0.1, 320, 240);
114  vector<GeneralCamera> X;
115  X.push_back(GeneralCamera(Pose3(Rot3(), Point3(-baseline / 2., 0., 0.)), K));
116  X.push_back(GeneralCamera(Pose3(Rot3(), Point3(baseline / 2., 0., 0.)), K));
117  return X;
118 }
119 
120 static boost::shared_ptr<Ordering> getOrdering(
121  const vector<GeneralCamera>& cameras, const vector<Point3>& landmarks) {
122  boost::shared_ptr<Ordering> ordering(new Ordering);
123  for (size_t i = 0; i < landmarks.size(); ++i)
124  ordering->push_back(L(i));
125  for (size_t i = 0; i < cameras.size(); ++i)
126  ordering->push_back(X(i));
127  return ordering;
128 }
129 
130 /* ************************************************************************* */
132  // Create two identical factors and make sure they're equal
133  Point2 z(323., 240.);
134  const Symbol cameraFrameNumber('x', 1), landmarkNumber('l', 1);
135  const SharedNoiseModel sigma(noiseModel::Unit::Create(1));
136  boost::shared_ptr<Projection> factor1(
137  new Projection(z, sigma, cameraFrameNumber, landmarkNumber));
138 
139  boost::shared_ptr<Projection> factor2(
140  new Projection(z, sigma, cameraFrameNumber, landmarkNumber));
141 
142  EXPECT(assert_equal(*factor1, *factor2));
143 }
144 
145 /* ************************************************************************* */
147  Point2 z(3., 0.);
148  const SharedNoiseModel sigma(noiseModel::Unit::Create(2));
149  Projection factor(z, sigma, X(1), L(1));
150  // For the following configuration, the factor predicts 320,240
151  Values values;
152  Rot3 R;
153  Point3 t1(0, 0, -6);
154  Pose3 x1(R, t1);
155  values.insert(X(1), GeneralCamera(x1));
156  Point3 l1(0,0,0);
157  values.insert(L(1), l1);
158  EXPECT(
159  assert_equal(((Vector ) Vector2(-3., 0.)),
160  factor.unwhitenedError(values)));
161 }
162 
163 /* ************************************************************************* */
164 TEST( GeneralSFMFactor, optimize_defaultK ) {
165 
166  vector<Point3> landmarks = genPoint3();
167  vector<GeneralCamera> cameras = genCameraDefaultCalibration();
168 
169  // add measurement with noise
170  Graph graph;
171  for (size_t j = 0; j < cameras.size(); ++j) {
172  for (size_t i = 0; i < landmarks.size(); ++i) {
173  Point2 pt = cameras[j].project(landmarks[i]);
174  graph.addMeasurement(j, i, pt, sigma1);
175  }
176  }
177 
178  const size_t nMeasurements = cameras.size() * landmarks.size();
179 
180  // add initial
181  const double noise = baseline * 0.1;
182  Values values;
183  for (size_t i = 0; i < cameras.size(); ++i)
184  values.insert(X(i), cameras[i]);
185 
186  for (size_t i = 0; i < landmarks.size(); ++i) {
187  Point3 pt(landmarks[i].x() + noise * getGaussian(),
188  landmarks[i].y() + noise * getGaussian(),
189  landmarks[i].z() + noise * getGaussian());
190  values.insert(L(i), pt);
191  }
192 
193  graph.addCameraConstraint(0, cameras[0]);
194 
195  // Create an ordering of the variables
196  Ordering ordering = *getOrdering(cameras, landmarks);
197  LevenbergMarquardtOptimizer optimizer(graph, values, ordering);
198  Values final = optimizer.optimize();
199  EXPECT(optimizer.error() < 0.5 * 1e-5 * nMeasurements);
200 }
201 
202 /* ************************************************************************* */
203 TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) {
204  vector<Point3> landmarks = genPoint3();
205  vector<GeneralCamera> cameras = genCameraVariableCalibration();
206  // add measurement with noise
207  Graph graph;
208  for (size_t j = 0; j < cameras.size(); ++j) {
209  for (size_t i = 0; i < landmarks.size(); ++i) {
210  Point2 pt = cameras[j].project(landmarks[i]);
211  graph.addMeasurement(j, i, pt, sigma1);
212  }
213  }
214 
215  const size_t nMeasurements = cameras.size() * landmarks.size();
216 
217  // add initial
218  const double noise = baseline * 0.1;
219  Values values;
220  for (size_t i = 0; i < cameras.size(); ++i)
221  values.insert(X(i), cameras[i]);
222 
223  // add noise only to the first landmark
224  for (size_t i = 0; i < landmarks.size(); ++i) {
225  if (i == 0) {
226  Point3 pt(landmarks[i].x() + noise * getGaussian(),
227  landmarks[i].y() + noise * getGaussian(),
228  landmarks[i].z() + noise * getGaussian());
229  values.insert(L(i), pt);
230  } else {
231  values.insert(L(i), landmarks[i]);
232  }
233  }
234 
235  graph.addCameraConstraint(0, cameras[0]);
236  const double reproj_error = 1e-5;
237 
238  Ordering ordering = *getOrdering(cameras, landmarks);
239  LevenbergMarquardtOptimizer optimizer(graph, values, ordering);
240  Values final = optimizer.optimize();
241  EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements);
242 }
243 
244 /* ************************************************************************* */
245 TEST( GeneralSFMFactor, optimize_varK_FixCameras ) {
246 
247  vector<Point3> landmarks = genPoint3();
248  vector<GeneralCamera> cameras = genCameraVariableCalibration();
249 
250  // add measurement with noise
251  const double noise = baseline * 0.1;
252  Graph graph;
253  for (size_t i = 0; i < cameras.size(); ++i) {
254  for (size_t j = 0; j < landmarks.size(); ++j) {
255  Point2 z = cameras[i].project(landmarks[j]);
256  graph.addMeasurement(i, j, z, sigma1);
257  }
258  }
259 
260  const size_t nMeasurements = landmarks.size() * cameras.size();
261 
262  Values values;
263  for (size_t i = 0; i < cameras.size(); ++i)
264  values.insert(X(i), cameras[i]);
265 
266  for (size_t j = 0; j < landmarks.size(); ++j) {
267  Point3 pt(landmarks[j].x() + noise * getGaussian(),
268  landmarks[j].y() + noise * getGaussian(),
269  landmarks[j].z() + noise * getGaussian());
270  values.insert(L(j), pt);
271  }
272 
273  for (size_t i = 0; i < cameras.size(); ++i)
274  graph.addCameraConstraint(i, cameras[i]);
275 
276  const double reproj_error = 1e-5;
277 
278  Ordering ordering = *getOrdering(cameras, landmarks);
279  LevenbergMarquardtOptimizer optimizer(graph, values, ordering);
280  Values final = optimizer.optimize();
281  EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements);
282 }
283 
284 /* ************************************************************************* */
285 TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) {
286 
287  vector<Point3> landmarks = genPoint3();
288  vector<GeneralCamera> cameras = genCameraVariableCalibration();
289 
290  // add measurement with noise
291  Graph graph;
292  for (size_t j = 0; j < cameras.size(); ++j) {
293  for (size_t i = 0; i < landmarks.size(); ++i) {
294  Point2 pt = cameras[j].project(landmarks[i]);
295  graph.addMeasurement(j, i, pt, sigma1);
296  }
297  }
298 
299  const size_t nMeasurements = landmarks.size() * cameras.size();
300 
301  Values values;
302  for (size_t i = 0; i < cameras.size(); ++i) {
303  const double rot_noise = 1e-5, trans_noise = 1e-3, focal_noise = 1,
304  skew_noise = 1e-5;
305  if (i == 0) {
306  values.insert(X(i), cameras[i]);
307  } else {
308 
309  Vector delta = (Vector(11) << rot_noise, rot_noise, rot_noise, // rotation
310  trans_noise, trans_noise, trans_noise, // translation
311  focal_noise, focal_noise, // f_x, f_y
312  skew_noise, // s
313  trans_noise, trans_noise // ux, uy
314  ).finished();
315  values.insert(X(i), cameras[i].retract(delta));
316  }
317  }
318 
319  for (size_t i = 0; i < landmarks.size(); ++i) {
320  values.insert(L(i), landmarks[i]);
321  }
322 
323  // fix X0 and all landmarks, allow only the cameras[1] to move
324  graph.addCameraConstraint(0, cameras[0]);
325  for (size_t i = 0; i < landmarks.size(); ++i)
326  graph.addPoint3Constraint(i, landmarks[i]);
327 
328  const double reproj_error = 1e-5;
329 
330  Ordering ordering = *getOrdering(cameras, landmarks);
331  LevenbergMarquardtOptimizer optimizer(graph, values, ordering);
332  Values final = optimizer.optimize();
333  EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements);
334 }
335 
336 /* ************************************************************************* */
337 TEST( GeneralSFMFactor, optimize_varK_BA ) {
338  vector<Point3> landmarks = genPoint3();
339  vector<GeneralCamera> cameras = genCameraVariableCalibration();
340 
341  // add measurement with noise
342  Graph graph;
343  for (size_t j = 0; j < cameras.size(); ++j) {
344  for (size_t i = 0; i < landmarks.size(); ++i) {
345  Point2 pt = cameras[j].project(landmarks[i]);
346  graph.addMeasurement(j, i, pt, sigma1);
347  }
348  }
349 
350  const size_t nMeasurements = cameras.size() * landmarks.size();
351 
352  // add initial
353  const double noise = baseline * 0.1;
354  Values values;
355  for (size_t i = 0; i < cameras.size(); ++i)
356  values.insert(X(i), cameras[i]);
357 
358  // add noise only to the first landmark
359  for (size_t i = 0; i < landmarks.size(); ++i) {
360  Point3 pt(landmarks[i].x() + noise * getGaussian(),
361  landmarks[i].y() + noise * getGaussian(),
362  landmarks[i].z() + noise * getGaussian());
363  values.insert(L(i), pt);
364  }
365 
366  // Constrain position of system with the first camera constrained to the origin
367  graph.addCameraConstraint(0, cameras[0]);
368 
369  // Constrain the scale of the problem with a soft range factor of 1m between the cameras
370  graph.emplace_shared<
372  noiseModel::Isotropic::Sigma(1, 10.));
373 
374  const double reproj_error = 1e-5;
375 
376  Ordering ordering = *getOrdering(cameras, landmarks);
377  LevenbergMarquardtOptimizer optimizer(graph, values, ordering);
378  Values final = optimizer.optimize();
379  EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements);
380 }
381 
382 /* ************************************************************************* */
383 TEST(GeneralSFMFactor, GeneralCameraPoseRange) {
384  // Tests range factor between a GeneralCamera and a Pose3
385  Graph graph;
387  graph.emplace_shared<
389  noiseModel::Isotropic::Sigma(1, 1.));
390  graph.addPrior(X(1), Pose3(Rot3(), Point3(1., 0., 0.)),
391  noiseModel::Isotropic::Sigma(6, 1.));
392 
393  Values init;
394  init.insert(X(0), GeneralCamera());
395  init.insert(X(1), Pose3(Rot3(), Point3(1., 1., 1.)));
396 
397  // The optimal value between the 2m range factor and 1m prior is 1.5m
399  expected.insert(X(0), GeneralCamera());
400  expected.insert(X(1), Pose3(Rot3(), Point3(1.5, 0., 0.)));
401 
403  params.absoluteErrorTol = 1e-9;
404  params.relativeErrorTol = 1e-9;
405  Values actual = LevenbergMarquardtOptimizer(graph, init, params).optimize();
406 
407  EXPECT(assert_equal(expected, actual, 1e-4));
408 }
409 
410 /* ************************************************************************* */
411 TEST(GeneralSFMFactor, CalibratedCameraPoseRange) {
412  // Tests range factor between a CalibratedCamera and a Pose3
414  graph.addPrior(X(0), CalibratedCamera(),
415  noiseModel::Isotropic::Sigma(6, 1.));
416  graph.emplace_shared<
418  noiseModel::Isotropic::Sigma(1, 1.));
419  graph.addPrior(X(1), Pose3(Rot3(), Point3(1., 0., 0.)),
420  noiseModel::Isotropic::Sigma(6, 1.));
421 
422  Values init;
423  init.insert(X(0), CalibratedCamera());
424  init.insert(X(1), Pose3(Rot3(), Point3(1., 1., 1.)));
425 
427  expected.insert(X(0),
428  CalibratedCamera(Pose3(Rot3(), Point3(-0.333333333333, 0, 0))));
429  expected.insert(X(1), Pose3(Rot3(), Point3(1.333333333333, 0, 0)));
430 
432  params.absoluteErrorTol = 1e-9;
433  params.relativeErrorTol = 1e-9;
434  Values actual = LevenbergMarquardtOptimizer(graph, init, params).optimize();
435 
436  EXPECT(assert_equal(expected, actual, 1e-4));
437 }
438 
439 /* ************************************************************************* */
440 // Frank created these tests after switching to a custom LinearizedFactor
442  Point2 measurement(3., -1.);
443 
444  // Create Values
445  Values values;
446  Rot3 R;
447  Point3 t1(0, 0, -6);
448  Pose3 x1(R, t1);
449  values.insert(X(1), GeneralCamera(x1));
450  Point3 l1(0,0,0);
451  values.insert(L(1), l1);
452 
453  vector<SharedNoiseModel> models;
454  {
455  // Create various noise-models to test all cases
456  using namespace noiseModel;
457  Rot2 R = Rot2::fromAngle(0.3);
458  Matrix2 cov = R.matrix() * R.matrix().transpose();
459  models += SharedNoiseModel(), Unit::Create(2), //
460  Isotropic::Sigma(2, 0.5), Constrained::All(2), Gaussian::Covariance(cov);
461  }
462 
463  // Now loop over all these noise models
464  for(SharedNoiseModel model: models) {
465  Projection factor(measurement, model, X(1), L(1));
466 
467  // Test linearize
469  factor.NoiseModelFactor::linearize(values);
470  GaussianFactor::shared_ptr actual = factor.linearize(values);
471  EXPECT(assert_equal(*expected, *actual, 1e-9));
472 
473  // Test methods that rely on updateHessian
474  if (model && !model->isConstrained()) {
475  // Construct HessianFactor from single JacobianFactor
476  HessianFactor expectedHessian(*expected), actualHessian(*actual);
477  EXPECT(assert_equal(expectedHessian, actualHessian, 1e-9));
478 
479  // Convert back
480  JacobianFactor actualJacobian(actualHessian);
481  // Note we do not expect the actualJacobian to match *expected
482  // Just that they have the same information on the variable.
483  EXPECT(
484  assert_equal(expected->augmentedInformation(),
485  actualJacobian.augmentedInformation(), 1e-9));
486 
487  // Construct from GaussianFactorGraph
488  GaussianFactorGraph gfg1;
489  gfg1 += expected;
490  GaussianFactorGraph gfg2;
491  gfg2 += actual;
492  HessianFactor hessian1(gfg1), hessian2(gfg2);
493  EXPECT(assert_equal(hessian1, hessian2, 1e-9));
494  }
495  }
496 }
497 
498 /* ************************************************************************* */
499 // Do a thorough test of BinaryJacobianFactor
500 TEST( GeneralSFMFactor, BinaryJacobianFactor2 ) {
501 
502  vector<Point3> landmarks = genPoint3();
503  vector<GeneralCamera> cameras = genCameraVariableCalibration();
504 
505  Values values;
506  for (size_t i = 0; i < cameras.size(); ++i)
507  values.insert(X(i), cameras[i]);
508  for (size_t j = 0; j < landmarks.size(); ++j)
509  values.insert(L(j), landmarks[j]);
510 
511  for (size_t i = 0; i < cameras.size(); ++i) {
512  for (size_t j = 0; j < landmarks.size(); ++j) {
513  Point2 z = cameras[i].project(landmarks[j]);
514  Projection::shared_ptr nonlinear = //
515  boost::make_shared<Projection>(z, sigma1, X(i), L(j));
516  GaussianFactor::shared_ptr factor = nonlinear->linearize(values);
517  HessianFactor hessian(*factor);
518  JacobianFactor jacobian(hessian);
519  EXPECT(
520  assert_equal(factor->augmentedInformation(),
521  jacobian.augmentedInformation(), 1e-9));
522  }
523  }
524 }
525 
526 /* ************************************************************************* */
527 int main() {
528  TestResult tr;
529  return TestRegistry::runAllTests(tr);
530 }
531 /* ************************************************************************* */
NonlinearEquality< Point3 > Point3Constraint
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override
Linearize using fixed-size matrices.
NonlinearEquality< GeneralCamera > CameraConstraint
Scalar * y
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
static enum @843 ordering
Matrix expected
Definition: testMatrix.cpp:974
Vector2 Point2
Definition: Point2.h:27
static const double sigma
Rot2 R(Rot2::fromAngle(0.1))
leaf::MyValues values
EIGEN_DEVICE_FUNC const LogReturnType log() const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
static vector< Point3 > genPoint3()
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
boost::shared_ptr< This > shared_ptr
MatrixXd L
Definition: LLT_example.cpp:6
double measurement(10.0)
Definition: Half.h:150
static boost::shared_ptr< Ordering > getOrdering(const vector< GeneralCamera > &cameras, const vector< Point3 > &landmarks)
static const SharedNoiseModel sigma1(noiseModel::Unit::Create(2))
static const Point3 pt(1.0, 2.0, 3.0)
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
Base class for all pinhole cameras.
TEST(GeneralSFMFactor, equals)
Factor Graph Values.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Eigen::VectorXd Vector
Definition: Vector.h:38
Key S(std::uint64_t j)
void addPoint3Constraint(int j, const Point3 &p)
#define EXPECT(condition)
Definition: Test.h:151
GeneralSFMFactor< GeneralCamera, Point3 > Projection
Matrix2 matrix() const
Definition: Rot2.cpp:89
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.)
int main()
static SmartStereoProjectionParams params
double error() const
return error in current optimizer state
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
gtsam::Key l1
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
static const double baseline
Eigen::Vector2d Vector2
Definition: Vector.h:42
void addMeasurement(int i, int j, const Point2 &z, const SharedNoiseModel &model)
Matrix augmentedInformation() const override
void addCameraConstraint(int j, const GeneralCamera &p)
static vector< GeneralCamera > genCameraVariableCalibration()
Pose3 x1
Definition: testPose3.cpp:588
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1460
float * p
A Gaussian factor using the canonical parameters (information form)
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
static double getGaussian()
static double error
Definition: testRot3.cpp:39
Vector3 Point3
Definition: Point3.h:35
static vector< GeneralCamera > genCameraDefaultCalibration()
#define X
Definition: icosphere.cpp:20
a general SFM factor with an unknown calibration
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
PinholeCamera< Cal3_S2 > GeneralCamera
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::ptrdiff_t j
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
2D rotation
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
The most common 5DOF 3D->2D calibration.
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:56