testSmartStereoProjectionPoseFactor.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 
28 #include <iostream>
29 
30 using namespace std;
31 using namespace gtsam;
32 
33 namespace {
34 // make a realistic calibration matrix
35 static double b = 1;
36 
38 static Cal3_S2Stereo::shared_ptr K2(new Cal3_S2Stereo(1500, 1200, 0, 640, 480,
39  b));
40 
42 
43 // static bool manageDegeneracy = true;
44 // Create a noise model for the pixel error
45 static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.1));
46 
47 // Convenience for named keys
50 
51 // tests data
52 static Symbol x1('X', 1);
53 static Symbol x2('X', 2);
54 static Symbol x3('X', 3);
55 
56 static Key poseKey1(x1);
58  323.0, 300.0, 240.0); // potentially use more reasonable measurement value?
59 static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
60  Point3(0.25, -0.10, 1.0));
61 
62 static double missing_uR = std::numeric_limits<double>::quiet_NaN();
63 
64 vector<StereoPoint2> stereo_projectToMultipleCameras(const StereoCamera& cam1,
65  const StereoCamera& cam2,
66  const StereoCamera& cam3,
67  Point3 landmark) {
68  vector<StereoPoint2> measurements_cam;
69 
70  StereoPoint2 cam1_uv1 = cam1.project(landmark);
71  StereoPoint2 cam2_uv1 = cam2.project(landmark);
72  StereoPoint2 cam3_uv1 = cam3.project(landmark);
73  measurements_cam.push_back(cam1_uv1);
74  measurements_cam.push_back(cam2_uv1);
75  measurements_cam.push_back(cam3_uv1);
76 
77  return measurements_cam;
78 }
79 
80 LevenbergMarquardtParams lm_params;
81 } // namespace
82 
83 /* ************************************************************************* */
86 
87  // check default values and "get"
91  EXPECT(p.getVerboseCheirality() == false);
92  EXPECT(p.getThrowCheirality() == false);
93 
94  // check "set"
97  p.setRankTolerance(100);
98  p.setEnableEPI(true);
102 
110 }
111 
112 /* ************************************************************************* */
115 }
116 
117 /* ************************************************************************* */
120 }
121 
122 /* ************************************************************************* */
125  factor1->add(measurement1, poseKey1, K);
126 }
127 
128 /* ************************************************************************* */
131  factor1.add(measurement1, poseKey1, K);
132 }
133 
134 /* ************************************************************************* */
137  factor1->add(measurement1, poseKey1, K);
138 
140  factor2->add(measurement1, poseKey1, K);
141 
142  CHECK(assert_equal(*factor1, *factor2));
143 }
144 
145 /* *************************************************************************/
147  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
148  Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2),
149  Point3(0, 0, 1));
150  StereoCamera level_camera(level_pose, K2);
151 
152  // create second camera 1 meter to the right of first camera
153  Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0));
154  StereoCamera level_camera_right(level_pose_right, K2);
155 
156  // landmark ~5 meters infront of camera
157  Point3 landmark(5, 0.5, 1.2);
158 
159  // 1. Project two landmarks into two cameras and triangulate
160  StereoPoint2 level_uv = level_camera.project(landmark);
161  StereoPoint2 level_uv_right = level_camera_right.project(landmark);
162 
163  Values values;
164  values.insert(x1, level_pose);
165  values.insert(x2, level_pose_right);
166 
168  factor1.add(level_uv, x1, K2);
169  factor1.add(level_uv_right, x2, K2);
170 
171  double actualError = factor1.error(values);
172  double expectedError = 0.0;
173  EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7);
174 
175  SmartStereoProjectionPoseFactor::Cameras cameras = factor1.cameras(values);
176  double actualError2 = factor1.totalReprojectionError(cameras);
177  EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7);
178 
179  // test vector of errors
180  //Vector actual = factor1.unwhitenedError(values);
181  //EXPECT(assert_equal(zero(4),actual,1e-8));
182 }
183 
184 /* *************************************************************************/
185 TEST( SmartProjectionPoseFactor, noiselessWithMissingMeasurements ) {
186 
187  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
188  Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2),
189  Point3(0, 0, 1));
190  StereoCamera level_camera(level_pose, K2);
191 
192  // create second camera 1 meter to the right of first camera
193  Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0));
194  StereoCamera level_camera_right(level_pose_right, K2);
195 
196  // landmark ~5 meters in front of camera
197  Point3 landmark(5, 0.5, 1.2);
198 
199  // 1. Project two landmarks into two cameras and triangulate
200  StereoPoint2 level_uv = level_camera.project(landmark);
201  StereoPoint2 level_uv_right = level_camera_right.project(landmark);
202  StereoPoint2 level_uv_right_missing(level_uv_right.uL(),missing_uR,level_uv_right.v());
203 
204  Values values;
205  values.insert(x1, level_pose);
206  values.insert(x2, level_pose_right);
207 
209  factor1.add(level_uv, x1, K2);
210  factor1.add(level_uv_right_missing, x2, K2);
211 
212  double actualError = factor1.error(values);
213  double expectedError = 0.0;
214  EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7);
215 
216  // TEST TRIANGULATION WITH MISSING VALUES: i) right pixel of second camera is missing:
217  SmartStereoProjectionPoseFactor::Cameras cameras = factor1.cameras(values);
218  double actualError2 = factor1.totalReprojectionError(cameras);
219  EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7);
220 
221  CameraSet<StereoCamera> cams{level_camera, level_camera_right};
223  CHECK(result);
224  EXPECT(assert_equal(landmark, *result, 1e-7));
225 
226  // TEST TRIANGULATION WITH MISSING VALUES: ii) right pixels of both cameras are missing:
228  StereoPoint2 level_uv_missing(level_uv.uL(),missing_uR,level_uv.v());
229  factor2.add(level_uv_missing, x1, K2);
230  factor2.add(level_uv_right_missing, x2, K2);
231  result = factor2.triangulateSafe(cams);
232  CHECK(result);
233  EXPECT(assert_equal(landmark, *result, 1e-7));
234 }
235 
236 /* *************************************************************************/
238  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
239  Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2),
240  Point3(0, 0, 1));
241  StereoCamera level_camera(level_pose, K2);
242 
243  // create second camera 1 meter to the right of first camera
244  Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0));
245  StereoCamera level_camera_right(level_pose_right, K2);
246 
247  // landmark ~5 meters infront of camera
248  Point3 landmark(5, 0.5, 1.2);
249 
250  // 1. Project two landmarks into two cameras and triangulate
251  StereoPoint2 pixelError(0.2, 0.2, 0);
252  StereoPoint2 level_uv = level_camera.project(landmark) + pixelError;
253  StereoPoint2 level_uv_right = level_camera_right.project(landmark);
254 
255  Values values;
256  values.insert(x1, level_pose);
257  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10),
258  Point3(0.5, 0.1, 0.3));
259  values.insert(x2, level_pose_right.compose(noise_pose));
260 
262  factor1->add(level_uv, x1, K);
263  factor1->add(level_uv_right, x2, K);
264 
265  double actualError1 = factor1->error(values);
266 
268  vector<StereoPoint2> measurements;
269  measurements.push_back(level_uv);
270  measurements.push_back(level_uv_right);
271 
272  vector<std::shared_ptr<Cal3_S2Stereo> > Ks;
273  Ks.push_back(K);
274  Ks.push_back(K);
275 
276  KeyVector views;
277  views.push_back(x1);
278  views.push_back(x2);
279 
280  factor2->add(measurements, views, Ks);
281 
282  double actualError2 = factor2->error(values);
283 
284  DOUBLES_EQUAL(actualError1, actualError2, 1e-7);
285 }
286 
287 /* *************************************************************************/
288 TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) {
289 
290  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
291  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
292  StereoCamera cam1(pose1, K2);
293 
294  // create second camera 1 meter to the right of first camera
295  Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0));
296  StereoCamera cam2(pose2, K2);
297 
298  // create third camera 1 meter above the first camera
299  Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0));
300  StereoCamera cam3(pose3, K2);
301 
302  // three landmarks ~5 meters infront of camera
303  Point3 landmark1(5, 0.5, 1.2);
304  Point3 landmark2(5, -0.5, 1.2);
305  Point3 landmark3(3, 0, 3.0);
306 
307  // 1. Project three landmarks into three cameras and triangulate
308  vector<StereoPoint2> measurements_l1 = stereo_projectToMultipleCameras(cam1,
309  cam2, cam3, landmark1);
310  vector<StereoPoint2> measurements_l2 = stereo_projectToMultipleCameras(cam1,
311  cam2, cam3, landmark2);
312  vector<StereoPoint2> measurements_l3 = stereo_projectToMultipleCameras(cam1,
313  cam2, cam3, landmark3);
314 
315  KeyVector views;
316  views.push_back(x1);
317  views.push_back(x2);
318  views.push_back(x3);
319 
320  SmartStereoProjectionParams smart_params;
321  smart_params.triangulation.enableEPI = true;
323  smartFactor1->add(measurements_l1, views, K2);
324 
326  smartFactor2->add(measurements_l2, views, K2);
327 
329  smartFactor3->add(measurements_l3, views, K2);
330 
331  const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
332 
334  graph.push_back(smartFactor1);
335  graph.push_back(smartFactor2);
336  graph.push_back(smartFactor3);
337  graph.addPrior(x1, pose1, noisePrior);
338  graph.addPrior(x2, pose2, noisePrior);
339 
340  // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
341  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100),
342  Point3(0.1, 0.1, 0.1)); // smaller noise
343  Values values;
344  values.insert(x1, pose1);
345  values.insert(x2, pose2);
346  // initialize third pose with some noise, we expect it to move back to original pose3
347  values.insert(x3, pose3 * noise_pose);
348  EXPECT(
349  assert_equal(
350  Pose3(
351  Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598,
352  -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598),
353  Point3(0.1, -0.1, 1.9)), values.at<Pose3>(x3)));
354 
355  // cout << std::setprecision(10) << "\n----SmartStereoFactor graph initial error: " << graph.error(values) << endl;
356  EXPECT_DOUBLES_EQUAL(833953.92789459578, graph.error(values), 1e-7); // initial error
357 
358  // get triangulated landmarks from smart factors
359  Point3 landmark1_smart = *smartFactor1->point();
360  Point3 landmark2_smart = *smartFactor2->point();
361  Point3 landmark3_smart = *smartFactor3->point();
362 
363  Values result;
365  LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
366  result = optimizer.optimize();
369 
370  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-5);
371 
372 // cout << std::setprecision(10) << "SmartStereoFactor graph optimized error: " << graph.error(result) << endl;
373 
374  GaussianFactorGraph::shared_ptr GFG = graph.linearize(result);
375  VectorValues delta = GFG->optimize();
376  VectorValues expected = VectorValues::Zero(delta);
377  EXPECT(assert_equal(expected, delta, 1e-6));
378 
379  // result.print("results of 3 camera, 3 landmark optimization \n");
380  EXPECT(assert_equal(pose3, result.at<Pose3>(x3)));
381 
382  /* ***************************************************************
383  * Same problem with regular Stereo factors, expect same error!
384  * ****************************************************************/
385 
386 // landmark1_smart.print("landmark1_smart");
387 // landmark2_smart.print("landmark2_smart");
388 // landmark3_smart.print("landmark3_smart");
389 
390  // add landmarks to values
391  values.insert(L(1), landmark1_smart);
392  values.insert(L(2), landmark2_smart);
393  values.insert(L(3), landmark3_smart);
394 
395  // add factors
397 
398  graph2.addPrior(x1, pose1, noisePrior);
399  graph2.addPrior(x2, pose2, noisePrior);
400 
401  typedef GenericStereoFactor<Pose3, Point3> ProjectionFactor;
402 
403  bool verboseCheirality = true;
404 
405  graph2.push_back(ProjectionFactor(measurements_l1[0], model, x1, L(1), K2, false, verboseCheirality));
406  graph2.push_back(ProjectionFactor(measurements_l1[1], model, x2, L(1), K2, false, verboseCheirality));
407  graph2.push_back(ProjectionFactor(measurements_l1[2], model, x3, L(1), K2, false, verboseCheirality));
408 
409  graph2.push_back(ProjectionFactor(measurements_l2[0], model, x1, L(2), K2, false, verboseCheirality));
410  graph2.push_back(ProjectionFactor(measurements_l2[1], model, x2, L(2), K2, false, verboseCheirality));
411  graph2.push_back(ProjectionFactor(measurements_l2[2], model, x3, L(2), K2, false, verboseCheirality));
412 
413  graph2.push_back(ProjectionFactor(measurements_l3[0], model, x1, L(3), K2, false, verboseCheirality));
414  graph2.push_back(ProjectionFactor(measurements_l3[1], model, x2, L(3), K2, false, verboseCheirality));
415  graph2.push_back(ProjectionFactor(measurements_l3[2], model, x3, L(3), K2, false, verboseCheirality));
416 
417 // cout << std::setprecision(10) << "\n----StereoFactor graph initial error: " << graph2.error(values) << endl;
418  EXPECT_DOUBLES_EQUAL(833953.92789459578, graph2.error(values), 1e-7);
419 
420  LevenbergMarquardtOptimizer optimizer2(graph2, values, lm_params);
421  Values result2 = optimizer2.optimize();
422  EXPECT_DOUBLES_EQUAL(0, graph2.error(result2), 1e-5);
423 
424 // cout << std::setprecision(10) << "StereoFactor graph optimized error: " << graph2.error(result2) << endl;
425 
426 }
427 /* *************************************************************************/
429 
430  // camera has some displacement
431  Pose3 body_P_sensor = Pose3(Rot3::Ypr(-0.01, 0., -0.05), Point3(0.1, 0, 0.1));
432  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
433  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
434  StereoCamera cam1(pose1.compose(body_P_sensor), K2);
435 
436  // create second camera 1 meter to the right of first camera
437  Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0));
438  StereoCamera cam2(pose2.compose(body_P_sensor), K2);
439 
440  // create third camera 1 meter above the first camera
441  Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0));
442  StereoCamera cam3(pose3.compose(body_P_sensor), K2);
443 
444  // three landmarks ~5 meters infront of camera
445  Point3 landmark1(5, 0.5, 1.2);
446  Point3 landmark2(5, -0.5, 1.2);
447  Point3 landmark3(3, 0, 3.0);
448 
449  // 1. Project three landmarks into three cameras and triangulate
450  vector<StereoPoint2> measurements_l1 = stereo_projectToMultipleCameras(cam1,
451  cam2, cam3, landmark1);
452  vector<StereoPoint2> measurements_l2 = stereo_projectToMultipleCameras(cam1,
453  cam2, cam3, landmark2);
454  vector<StereoPoint2> measurements_l3 = stereo_projectToMultipleCameras(cam1,
455  cam2, cam3, landmark3);
456 
457  KeyVector views;
458  views.push_back(x1);
459  views.push_back(x2);
460  views.push_back(x3);
461 
462  SmartStereoProjectionParams smart_params;
463  smart_params.triangulation.enableEPI = true;
464  SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(model, smart_params, body_P_sensor));
465  smartFactor1->add(measurements_l1, views, K2);
466 
467  SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(model, smart_params, body_P_sensor));
468  smartFactor2->add(measurements_l2, views, K2);
469 
470  SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(model, smart_params, body_P_sensor));
471  smartFactor3->add(measurements_l3, views, K2);
472 
473  const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
474 
476  graph.push_back(smartFactor1);
477  graph.push_back(smartFactor2);
478  graph.push_back(smartFactor3);
479  graph.addPrior(x1, pose1, noisePrior);
480  graph.addPrior(x2, pose2, noisePrior);
481 
482  // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
483  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100),
484  Point3(0.1, 0.1, 0.1)); // smaller noise
485  Values values;
486  values.insert(x1, pose1);
487  values.insert(x2, pose2);
488  // initialize third pose with some noise, we expect it to move back to original pose3
489  values.insert(x3, pose3 * noise_pose);
490  EXPECT(
491  assert_equal(
492  Pose3(
493  Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598,
494  -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598),
495  Point3(0.1, -0.1, 1.9)), values.at<Pose3>(x3)));
496 
497  // cout << std::setprecision(10) << "\n----SmartStereoFactor graph initial error: " << graph.error(values) << endl;
498  EXPECT_DOUBLES_EQUAL(953392.32838422502, graph.error(values), 1e-7); // initial error
499 
500  Values result;
502  LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
503  result = optimizer.optimize();
506 
507  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-5);
508 
509  // result.print("results of 3 camera, 3 landmark optimization \n");
510  EXPECT(assert_equal(pose3, result.at<Pose3>(x3)));
511 }
512 /* *************************************************************************/
513 TEST( SmartStereoProjectionPoseFactor, body_P_sensor_monocular ){
514  // make a realistic calibration matrix
515  double fov = 60; // degrees
516  size_t w=640,h=480;
517 
518  Cal3_S2::shared_ptr K(new Cal3_S2(fov,w,h));
519 
520  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
521  Pose3 cameraPose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); // body poses
522  Pose3 cameraPose2 = cameraPose1 * Pose3(Rot3(), Point3(1,0,0));
523  Pose3 cameraPose3 = cameraPose1 * Pose3(Rot3(), Point3(0,-1,0));
524 
525  PinholeCamera<Cal3_S2> cam1(cameraPose1, *K); // with camera poses
526  PinholeCamera<Cal3_S2> cam2(cameraPose2, *K);
527  PinholeCamera<Cal3_S2> cam3(cameraPose3, *K);
528 
529  // create arbitrary body_Pose_sensor (transforms from sensor to body)
530  Pose3 sensor_to_body = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(1, 1, 1)); // Pose3(); //
531 
532  // These are the poses we want to estimate, from camera measurements
533  Pose3 bodyPose1 = cameraPose1.compose(sensor_to_body.inverse());
534  Pose3 bodyPose2 = cameraPose2.compose(sensor_to_body.inverse());
535  Pose3 bodyPose3 = cameraPose3.compose(sensor_to_body.inverse());
536 
537  // three landmarks ~5 meters infront of camera
538  Point3 landmark1(5, 0.5, 1.2);
539  Point3 landmark2(5, -0.5, 1.2);
540  Point3 landmark3(5, 0, 3.0);
541 
542  Point2Vector measurements_cam1, measurements_cam2, measurements_cam3;
543 
544  // Project three landmarks into three cameras
545  projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1);
546  projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2);
547  projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3);
548 
549  // Create smart factors
550  KeyVector views;
551  views.push_back(x1);
552  views.push_back(x2);
553  views.push_back(x3);
554 
555  // convert measurement to (degenerate) stereoPoint2 (with right pixel being NaN)
556  vector<StereoPoint2> measurements_cam1_stereo, measurements_cam2_stereo, measurements_cam3_stereo;
557  for(size_t k=0; k<measurements_cam1.size();k++)
558  measurements_cam1_stereo.push_back(StereoPoint2(measurements_cam1[k].x() , missing_uR , measurements_cam1[k].y()));
559 
560  for(size_t k=0; k<measurements_cam2.size();k++)
561  measurements_cam2_stereo.push_back(StereoPoint2(measurements_cam2[k].x() , missing_uR , measurements_cam2[k].y()));
562 
563  for(size_t k=0; k<measurements_cam3.size();k++)
564  measurements_cam3_stereo.push_back(StereoPoint2(measurements_cam3[k].x() , missing_uR , measurements_cam3[k].y()));
565 
567  params.setRankTolerance(1.0);
569  params.setEnableEPI(false);
570 
571  Cal3_S2Stereo::shared_ptr Kmono(new Cal3_S2Stereo(fov,w,h,b));
572  SmartStereoProjectionPoseFactor smartFactor1(model, params, sensor_to_body);
573  smartFactor1.add(measurements_cam1_stereo, views, Kmono);
574 
575  SmartStereoProjectionPoseFactor smartFactor2(model, params, sensor_to_body);
576  smartFactor2.add(measurements_cam2_stereo, views, Kmono);
577 
578  SmartStereoProjectionPoseFactor smartFactor3(model, params, sensor_to_body);
579  smartFactor3.add(measurements_cam3_stereo, views, Kmono);
580 
581  const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
582 
583  // Put all factors in factor graph, adding priors
585  graph.push_back(smartFactor1);
586  graph.push_back(smartFactor2);
587  graph.push_back(smartFactor3);
588  graph.addPrior(x1, bodyPose1, noisePrior);
589  graph.addPrior(x2, bodyPose2, noisePrior);
590 
591  // Check errors at ground truth poses
592  Values gtValues;
593  gtValues.insert(x1, bodyPose1);
594  gtValues.insert(x2, bodyPose2);
595  gtValues.insert(x3, bodyPose3);
596  double actualError = graph.error(gtValues);
597  double expectedError = 0.0;
598  DOUBLES_EQUAL(expectedError, actualError, 1e-7)
599 
600  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1));
601  Values values;
602  values.insert(x1, bodyPose1);
603  values.insert(x2, bodyPose2);
604  // initialize third pose with some noise, we expect it to move back to original pose3
605  values.insert(x3, bodyPose3*noise_pose);
606 
608  Values result;
609  LevenbergMarquardtOptimizer optimizer(graph, values, lmParams);
610  result = optimizer.optimize();
611  EXPECT(assert_equal(bodyPose3,result.at<Pose3>(x3)));
612 }
613 /* *************************************************************************/
615 
616  KeyVector views;
617  views.push_back(x1);
618  views.push_back(x2);
619  views.push_back(x3);
620 
621  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
622  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
623  StereoCamera cam1(pose1, K);
624  // create second camera 1 meter to the right of first camera
625  Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0));
626  StereoCamera cam2(pose2, K);
627  // create third camera 1 meter above the first camera
628  Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0));
629  StereoCamera cam3(pose3, K);
630 
631  // three landmarks ~5 meters infront of camera
632  Point3 landmark1(5, 0.5, 1.2);
633  Point3 landmark2(5, -0.5, 1.2);
634  Point3 landmark3(3, 0, 3.0);
635 
636  // 1. Project three landmarks into three cameras and triangulate
637  vector<StereoPoint2> measurements_cam1 = stereo_projectToMultipleCameras(cam1,
638  cam2, cam3, landmark1);
639  vector<StereoPoint2> measurements_cam2 = stereo_projectToMultipleCameras(cam1,
640  cam2, cam3, landmark2);
641  vector<StereoPoint2> measurements_cam3 = stereo_projectToMultipleCameras(cam1,
642  cam2, cam3, landmark3);
643 
646 
648  smartFactor1->add(measurements_cam1, views, K);
649 
651  smartFactor2->add(measurements_cam2, views, K);
652 
654  smartFactor3->add(measurements_cam3, views, K);
655 
656  const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
657 
659  graph.push_back(smartFactor1);
660  graph.push_back(smartFactor2);
661  graph.push_back(smartFactor3);
662  graph.addPrior(x1, pose1, noisePrior);
663  graph.addPrior(x2, pose2, noisePrior);
664 
665  // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
666  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100),
667  Point3(0.1, 0.1, 0.1)); // smaller noise
668  Values values;
669  values.insert(x1, pose1);
670  values.insert(x2, pose2);
671  values.insert(x3, pose3 * noise_pose);
672 
673  Values result;
674  LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
675  result = optimizer.optimize();
676  EXPECT(assert_equal(pose3, result.at<Pose3>(x3)));
677 }
678 
679 /* *************************************************************************/
680 TEST( SmartStereoProjectionPoseFactor, jacobianSVDwithMissingValues ) {
681 
682  KeyVector views;
683  views.push_back(x1);
684  views.push_back(x2);
685  views.push_back(x3);
686 
687  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
688  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
689  StereoCamera cam1(pose1, K);
690  // create second camera 1 meter to the right of first camera
691  Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0));
692  StereoCamera cam2(pose2, K);
693  // create third camera 1 meter above the first camera
694  Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0));
695  StereoCamera cam3(pose3, K);
696 
697  // three landmarks ~5 meters infront of camera
698  Point3 landmark1(5, 0.5, 1.2);
699  Point3 landmark2(5, -0.5, 1.2);
700  Point3 landmark3(3, 0, 3.0);
701 
702  // 1. Project three landmarks into three cameras and triangulate
703  vector<StereoPoint2> measurements_cam1 = stereo_projectToMultipleCameras(cam1,
704  cam2, cam3, landmark1);
705  vector<StereoPoint2> measurements_cam2 = stereo_projectToMultipleCameras(cam1,
706  cam2, cam3, landmark2);
707  vector<StereoPoint2> measurements_cam3 = stereo_projectToMultipleCameras(cam1,
708  cam2, cam3, landmark3);
709 
710  // DELETE SOME MEASUREMENTS
711  StereoPoint2 sp = measurements_cam1[1];
712  measurements_cam1[1] = StereoPoint2(sp.uL(), missing_uR, sp.v());
713  sp = measurements_cam2[2];
714  measurements_cam2[2] = StereoPoint2(sp.uL(), missing_uR, sp.v());
715 
718 
720  smartFactor1->add(measurements_cam1, views, K);
721 
723  smartFactor2->add(measurements_cam2, views, K);
724 
726  smartFactor3->add(measurements_cam3, views, K);
727 
728  const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
729 
731  graph.push_back(smartFactor1);
732  graph.push_back(smartFactor2);
733  graph.push_back(smartFactor3);
734  graph.addPrior(x1, pose1, noisePrior);
735  graph.addPrior(x2, pose2, noisePrior);
736 
737  // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
738  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100),
739  Point3(0.1, 0.1, 0.1)); // smaller noise
740  Values values;
741  values.insert(x1, pose1);
742  values.insert(x2, pose2);
743  values.insert(x3, pose3 * noise_pose);
744 
745  Values result;
746  LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
747  result = optimizer.optimize();
748  EXPECT(assert_equal(pose3, result.at<Pose3>(x3),1e-7));
749 }
750 
751 /* *************************************************************************/
752 TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) {
753 
754 // double excludeLandmarksFutherThanDist = 2;
755 
756  KeyVector views;
757  views.push_back(x1);
758  views.push_back(x2);
759  views.push_back(x3);
760 
761  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
762  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
763  StereoCamera cam1(pose1, K);
764  // create second camera 1 meter to the right of first camera
765  Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0));
766  StereoCamera cam2(pose2, K);
767  // create third camera 1 meter above the first camera
768  Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0));
769  StereoCamera cam3(pose3, K);
770 
771  // three landmarks ~5 meters infront of camera
772  Point3 landmark1(5, 0.5, 1.2);
773  Point3 landmark2(5, -0.5, 1.2);
774  Point3 landmark3(3, 0, 3.0);
775 
776  // 1. Project three landmarks into three cameras and triangulate
777  vector<StereoPoint2> measurements_cam1 = stereo_projectToMultipleCameras(cam1,
778  cam2, cam3, landmark1);
779  vector<StereoPoint2> measurements_cam2 = stereo_projectToMultipleCameras(cam1,
780  cam2, cam3, landmark2);
781  vector<StereoPoint2> measurements_cam3 = stereo_projectToMultipleCameras(cam1,
782  cam2, cam3, landmark3);
783 
787 
789  smartFactor1->add(measurements_cam1, views, K);
790 
792  smartFactor2->add(measurements_cam2, views, K);
793 
795  smartFactor3->add(measurements_cam3, views, K);
796 
797  const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
798 
800  graph.push_back(smartFactor1);
801  graph.push_back(smartFactor2);
802  graph.push_back(smartFactor3);
803  graph.addPrior(x1, pose1, noisePrior);
804  graph.addPrior(x2, pose2, noisePrior);
805 
806  // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
807  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100),
808  Point3(0.1, 0.1, 0.1)); // smaller noise
809  Values values;
810  values.insert(x1, pose1);
811  values.insert(x2, pose2);
812  values.insert(x3, pose3 * noise_pose);
813 
814  // All factors are disabled and pose should remain where it is
815  Values result;
816  LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
817  result = optimizer.optimize();
818  EXPECT(assert_equal(values.at<Pose3>(x3), result.at<Pose3>(x3)));
819 }
820 
821 /* *************************************************************************/
822 TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) {
823 
824  KeyVector views;
825  views.push_back(x1);
826  views.push_back(x2);
827  views.push_back(x3);
828 
829  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
830  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
831  StereoCamera cam1(pose1, K);
832  // create second camera 1 meter to the right of first camera
833  Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0));
834  StereoCamera cam2(pose2, K);
835  // create third camera 1 meter above the first camera
836  Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0));
837  StereoCamera cam3(pose3, K);
838 
839  // three landmarks ~5 meters infront of camera
840  Point3 landmark1(5, 0.5, 1.2);
841  Point3 landmark2(5, -0.5, 1.2);
842  Point3 landmark3(3, 0, 3.0);
843  Point3 landmark4(5, -0.5, 1);
844 
845  // 1. Project four landmarks into three cameras and triangulate
846  vector<StereoPoint2> measurements_cam1 = stereo_projectToMultipleCameras(cam1,
847  cam2, cam3, landmark1);
848  vector<StereoPoint2> measurements_cam2 = stereo_projectToMultipleCameras(cam1,
849  cam2, cam3, landmark2);
850  vector<StereoPoint2> measurements_cam3 = stereo_projectToMultipleCameras(cam1,
851  cam2, cam3, landmark3);
852  vector<StereoPoint2> measurements_cam4 = stereo_projectToMultipleCameras(cam1,
853  cam2, cam3, landmark4);
854 
855  measurements_cam4.at(0) = measurements_cam4.at(0) + StereoPoint2(10, 10, 1); // add outlier
856 
860 
861 
863  smartFactor1->add(measurements_cam1, views, K);
864 
866  smartFactor2->add(measurements_cam2, views, K);
867 
869  smartFactor3->add(measurements_cam3, views, K);
870 
872  smartFactor4->add(measurements_cam4, views, K);
873 
874  // same as factor 4, but dynamic outlier rejection is off
876  smartFactor4b->add(measurements_cam4, views, K);
877 
878  const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
879 
881  graph.push_back(smartFactor1);
882  graph.push_back(smartFactor2);
883  graph.push_back(smartFactor3);
884  graph.push_back(smartFactor4);
885  graph.addPrior(x1, pose1, noisePrior);
886  graph.addPrior(x2, pose2, noisePrior);
887 
888  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100),
889  Point3(0.1, 0.1, 0.1)); // smaller noise
890  Values values;
891  values.insert(x1, pose1);
892  values.insert(x2, pose2);
893  values.insert(x3, pose3);
894 
895  EXPECT_DOUBLES_EQUAL(0, smartFactor1->error(values), 1e-9);
896  EXPECT_DOUBLES_EQUAL(0, smartFactor2->error(values), 1e-9);
897  EXPECT_DOUBLES_EQUAL(0, smartFactor3->error(values), 1e-9);
898  // zero error due to dynamic outlier rejection
899  EXPECT_DOUBLES_EQUAL(0, smartFactor4->error(values), 1e-9);
900 
901  // dynamic outlier rejection is off
902  EXPECT_DOUBLES_EQUAL(6147.3947317473921, smartFactor4b->error(values), 1e-9);
903 
904  // Factors 1-3 should have valid point, factor 4 should not
905  EXPECT(smartFactor1->point());
906  EXPECT(smartFactor2->point());
907  EXPECT(smartFactor3->point());
908  EXPECT(smartFactor4->point().outlier());
909  EXPECT(smartFactor4b->point());
910 
911  // Factor 4 is disabled, pose 3 stays put
912  Values result;
913  LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
914  result = optimizer.optimize();
915  EXPECT(assert_equal(pose3, result.at<Pose3>(x3)));
916 }
917 //
919 //TEST( SmartStereoProjectionPoseFactor, jacobianQ ){
920 //
921 // KeyVector views;
922 // views.push_back(x1);
923 // views.push_back(x2);
924 // views.push_back(x3);
925 //
926 // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
927 // Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1));
928 // StereoCamera cam1(pose1, K);
929 // // create second camera 1 meter to the right of first camera
930 // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0));
931 // StereoCamera cam2(pose2, K);
932 // // create third camera 1 meter above the first camera
933 // Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0));
934 // StereoCamera cam3(pose3, K);
935 //
936 // // three landmarks ~5 meters infront of camera
937 // Point3 landmark1(5, 0.5, 1.2);
938 // Point3 landmark2(5, -0.5, 1.2);
939 // Point3 landmark3(3, 0, 3.0);
940 //
941 // vector<StereoPoint2> measurements_cam1, measurements_cam2, measurements_cam3;
942 //
943 // // 1. Project three landmarks into three cameras and triangulate
944 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1);
945 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2);
946 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3);
947 //
948 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q));
949 // smartFactor1->add(measurements_cam1, views, model, K);
950 //
951 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q));
952 // smartFactor2->add(measurements_cam2, views, model, K);
953 //
954 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q));
955 // smartFactor3->add(measurements_cam3, views, model, K);
956 //
957 // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
958 //
959 // NonlinearFactorGraph graph;
960 // graph.push_back(smartFactor1);
961 // graph.push_back(smartFactor2);
962 // graph.push_back(smartFactor3);
963 // graph.push_back(PriorFactor<Pose3>(x1, pose1, noisePrior));
964 // graph.push_back(PriorFactor<Pose3>(x2, pose2, noisePrior));
965 //
966 // // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
967 // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise
968 // Values values;
969 // values.insert(x1, pose1);
970 // values.insert(x2, pose2);
971 // values.insert(x3, pose3*noise_pose);
972 //
974 // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
975 // result = optimizer.optimize();
976 // EXPECT(assert_equal(pose3,result.at<Pose3>(x3)));
977 //}
978 //
980 //TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){
981 //
982 // KeyVector views;
983 // views.push_back(x1);
984 // views.push_back(x2);
985 // views.push_back(x3);
986 //
987 // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
988 // Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1));
989 // StereoCamera cam1(pose1, K2);
990 //
991 // // create second camera 1 meter to the right of first camera
992 // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0));
993 // StereoCamera cam2(pose2, K2);
994 //
995 // // create third camera 1 meter above the first camera
996 // Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0));
997 // StereoCamera cam3(pose3, K2);
998 //
999 // // three landmarks ~5 meters infront of camera
1000 // Point3 landmark1(5, 0.5, 1.2);
1001 // Point3 landmark2(5, -0.5, 1.2);
1002 // Point3 landmark3(3, 0, 3.0);
1003 //
1004 // typedef GenericStereoFactor<Pose3, Point3> ProjectionFactor;
1005 // NonlinearFactorGraph graph;
1006 //
1007 // // 1. Project three landmarks into three cameras and triangulate
1008 // graph.push_back(ProjectionFactor(cam1.project(landmark1), model, x1, L(1), K2));
1009 // graph.push_back(ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2));
1010 // graph.push_back(ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2));
1011 //
1012 // graph.push_back(ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2));
1013 // graph.push_back(ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2));
1014 // graph.push_back(ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2));
1015 //
1016 // graph.push_back(ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2));
1017 // graph.push_back(ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2));
1018 // graph.push_back(ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2));
1019 //
1020 // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
1021 // graph.push_back(PriorFactor<Pose3>(x1, pose1, noisePrior));
1022 // graph.push_back(PriorFactor<Pose3>(x2, pose2, noisePrior));
1023 //
1024 // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3));
1025 // Values values;
1026 // values.insert(x1, pose1);
1027 // values.insert(x2, pose2);
1028 // values.insert(x3, pose3* noise_pose);
1029 // values.insert(L(1), landmark1);
1030 // values.insert(L(2), landmark2);
1031 // values.insert(L(3), landmark3);
1032 //
1033 // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
1034 // Values result = optimizer.optimize();
1035 //
1036 // EXPECT(assert_equal(pose3,result.at<Pose3>(x3)));
1037 //}
1038 //
1039 /* *************************************************************************/
1041 
1042  KeyVector views;
1043  views.push_back(x1);
1044  views.push_back(x2);
1045  views.push_back(x3);
1046 
1047  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
1048  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
1049  StereoCamera cam1(pose1, K);
1050 
1051  // create second camera
1052  Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0));
1053  StereoCamera cam2(pose2, K);
1054 
1055  // create third camera
1056  Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0));
1057  StereoCamera cam3(pose3, K);
1058 
1059  // three landmarks ~5 meters infront of camera
1060  Point3 landmark1(5, 0.5, 1.2);
1061  Point3 landmark2(5, -0.5, 1.2);
1062  Point3 landmark3(3, 0, 3.0);
1063 
1064  // Project three landmarks into three cameras and triangulate
1065  vector<StereoPoint2> measurements_cam1 = stereo_projectToMultipleCameras(cam1,
1066  cam2, cam3, landmark1);
1067  vector<StereoPoint2> measurements_cam2 = stereo_projectToMultipleCameras(cam1,
1068  cam2, cam3, landmark2);
1069  vector<StereoPoint2> measurements_cam3 = stereo_projectToMultipleCameras(cam1,
1070  cam2, cam3, landmark3);
1071 
1073  params.setRankTolerance(10);
1074 
1076  smartFactor1->add(measurements_cam1, views, K);
1077 
1079  smartFactor2->add(measurements_cam2, views, K);
1080 
1082  smartFactor3->add(measurements_cam3, views, K);
1083 
1084  // Create graph to optimize
1086  graph.push_back(smartFactor1);
1087  graph.push_back(smartFactor2);
1088  graph.push_back(smartFactor3);
1089 
1090  Values values;
1091  values.insert(x1, pose1);
1092  values.insert(x2, pose2);
1093  // initialize third pose with some noise, we expect it to move back to original pose3
1094  Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100),
1095  Point3(0.1, 0.1, 0.1)); // smaller noise
1096  values.insert(x3, pose3 * noise_pose);
1097 
1098  // TODO: next line throws Cheirality exception on Mac
1099  std::shared_ptr<GaussianFactor> hessianFactor1 = smartFactor1->linearize(
1100  values);
1101  std::shared_ptr<GaussianFactor> hessianFactor2 = smartFactor2->linearize(
1102  values);
1103  std::shared_ptr<GaussianFactor> hessianFactor3 = smartFactor3->linearize(
1104  values);
1105 
1106  Matrix CumulativeInformation = hessianFactor1->information()
1107  + hessianFactor2->information() + hessianFactor3->information();
1108 
1109  std::shared_ptr<GaussianFactorGraph> GaussianGraph = graph.linearize(
1110  values);
1111  Matrix GraphInformation = GaussianGraph->hessian().first;
1112 
1113  // Check Hessian
1114  EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8));
1115 
1116  Matrix AugInformationMatrix = hessianFactor1->augmentedInformation()
1117  + hessianFactor2->augmentedInformation()
1118  + hessianFactor3->augmentedInformation();
1119 
1120  // Check Information vector
1121  Vector InfoVector = AugInformationMatrix.block(0, 18, 18, 1); // 18x18 Hessian + information vector
1122 
1123  // Check Hessian
1124  EXPECT(assert_equal(InfoVector, GaussianGraph->hessian().second, 1e-8));
1125 }
1126 //
1128 //TEST( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){
1129 //
1130 // KeyVector views;
1131 // views.push_back(x1);
1132 // views.push_back(x2);
1133 // views.push_back(x3);
1134 //
1135 // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
1136 // Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1));
1137 // StereoCamera cam1(pose1, K2);
1138 //
1139 // // create second camera 1 meter to the right of first camera
1140 // Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0));
1141 // StereoCamera cam2(pose2, K2);
1142 //
1143 // // create third camera 1 meter above the first camera
1144 // Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0));
1145 // StereoCamera cam3(pose3, K2);
1146 //
1147 // // three landmarks ~5 meters infront of camera
1148 // Point3 landmark1(5, 0.5, 1.2);
1149 // Point3 landmark2(5, -0.5, 1.2);
1150 //
1151 // vector<StereoPoint2> measurements_cam1, measurements_cam2, measurements_cam3;
1152 //
1153 // // 1. Project three landmarks into three cameras and triangulate
1154 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1);
1155 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2);
1156 //
1157 // double rankTol = 50;
1158 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy));
1159 // smartFactor1->add(measurements_cam1, views, model, K2);
1160 //
1161 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy));
1162 // smartFactor2->add(measurements_cam2, views, model, K2);
1163 //
1164 // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
1165 // const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10);
1166 // Point3 positionPrior = Point3(0,0,1);
1167 //
1168 // NonlinearFactorGraph graph;
1169 // graph.push_back(smartFactor1);
1170 // graph.push_back(smartFactor2);
1171 // graph.push_back(PriorFactor<Pose3>(x1, pose1, noisePrior));
1172 // graph.push_back(PoseTranslationPrior<Pose3>(x2, positionPrior, noisePriorTranslation));
1173 // graph.push_back(PoseTranslationPrior<Pose3>(x3, positionPrior, noisePriorTranslation));
1174 //
1175 // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.1,0.1,0.1)); // smaller noise
1176 // Values values;
1177 // values.insert(x1, pose1);
1178 // values.insert(x2, pose2*noise_pose);
1179 // // initialize third pose with some noise, we expect it to move back to original pose3
1180 // values.insert(x3, pose3*noise_pose*noise_pose);
1181 //
1182 // Values result;
1183 // gttic_(SmartStereoProjectionPoseFactor);
1184 // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
1185 // result = optimizer.optimize();
1186 // gttoc_(SmartStereoProjectionPoseFactor);
1187 // tictoc_finishedIteration_();
1188 //
1189 // // result.print("results of 3 camera, 3 landmark optimization \n");
1190 // // EXPECT(assert_equal(pose3,result.at<Pose3>(x3)));
1191 //}
1192 //
1194 //TEST( SmartStereoProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ){
1195 //
1196 // KeyVector views;
1197 // views.push_back(x1);
1198 // views.push_back(x2);
1199 // views.push_back(x3);
1200 //
1201 // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
1202 // Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1));
1203 // StereoCamera cam1(pose1, K);
1204 //
1205 // // create second camera 1 meter to the right of first camera
1206 // Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0));
1207 // StereoCamera cam2(pose2, K);
1208 //
1209 // // create third camera 1 meter above the first camera
1210 // Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0));
1211 // StereoCamera cam3(pose3, K);
1212 //
1213 // // three landmarks ~5 meters infront of camera
1214 // Point3 landmark1(5, 0.5, 1.2);
1215 // Point3 landmark2(5, -0.5, 1.2);
1216 // Point3 landmark3(3, 0, 3.0);
1217 //
1218 // vector<StereoPoint2> measurements_cam1, measurements_cam2, measurements_cam3;
1219 //
1220 // // 1. Project three landmarks into three cameras and triangulate
1221 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1);
1222 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2);
1223 // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3);
1224 //
1225 // double rankTol = 10;
1226 //
1227 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy));
1228 // smartFactor1->add(measurements_cam1, views, model, K);
1229 //
1230 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy));
1231 // smartFactor2->add(measurements_cam2, views, model, K);
1232 //
1233 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy));
1234 // smartFactor3->add(measurements_cam3, views, model, K);
1235 //
1236 // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10);
1237 // const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10);
1238 // Point3 positionPrior = Point3(0,0,1);
1239 //
1240 // NonlinearFactorGraph graph;
1241 // graph.push_back(smartFactor1);
1242 // graph.push_back(smartFactor2);
1243 // graph.push_back(smartFactor3);
1244 // graph.push_back(PriorFactor<Pose3>(x1, pose1, noisePrior));
1245 // graph.push_back(PoseTranslationPrior<Pose3>(x2, positionPrior, noisePriorTranslation));
1246 // graph.push_back(PoseTranslationPrior<Pose3>(x3, positionPrior, noisePriorTranslation));
1247 //
1248 // // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
1249 // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise
1250 // Values values;
1251 // values.insert(x1, pose1);
1252 // values.insert(x2, pose2);
1253 // // initialize third pose with some noise, we expect it to move back to original pose3
1254 // values.insert(x3, pose3*noise_pose);
1255 //
1256 // Values result;
1257 // gttic_(SmartStereoProjectionPoseFactor);
1258 // LevenbergMarquardtOptimizer optimizer(graph, values, lm_params);
1259 // result = optimizer.optimize();
1260 // gttoc_(SmartStereoProjectionPoseFactor);
1261 // tictoc_finishedIteration_();
1262 //
1263 // // result.print("results of 3 camera, 3 landmark optimization \n");
1264 // // EXPECT(assert_equal(pose3,result.at<Pose3>(x3)));
1265 //}
1266 //
1268 //TEST( SmartStereoProjectionPoseFactor, Hessian ){
1269 //
1270 // KeyVector views;
1271 // views.push_back(x1);
1272 // views.push_back(x2);
1273 //
1274 // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
1275 // Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1));
1276 // StereoCamera cam1(pose1, K2);
1277 //
1278 // // create second camera 1 meter to the right of first camera
1279 // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0));
1280 // StereoCamera cam2(pose2, K2);
1281 //
1282 // // three landmarks ~5 meters infront of camera
1283 // Point3 landmark1(5, 0.5, 1.2);
1284 //
1285 // // 1. Project three landmarks into three cameras and triangulate
1286 // StereoPoint2 cam1_uv1 = cam1.project(landmark1);
1287 // StereoPoint2 cam2_uv1 = cam2.project(landmark1);
1288 // vector<StereoPoint2> measurements_cam1;
1289 // measurements_cam1.push_back(cam1_uv1);
1290 // measurements_cam1.push_back(cam2_uv1);
1291 //
1292 // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor());
1293 // smartFactor1->add(measurements_cam1,views, model, K2);
1294 //
1295 // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3));
1296 // Values values;
1297 // values.insert(x1, pose1);
1298 // values.insert(x2, pose2);
1299 //
1300 // std::shared_ptr<GaussianFactor> hessianFactor = smartFactor1->linearize(values);
1301 //
1302 // // compute triangulation from linearization point
1303 // // compute reprojection errors (sum squared)
1304 // // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance)
1305 // // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4]
1306 //}
1307 //
1308 
1309 /* *************************************************************************/
1310 TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) {
1311  KeyVector views;
1312  views.push_back(x1);
1313  views.push_back(x2);
1314  views.push_back(x3);
1315 
1316  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
1317  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
1318  StereoCamera cam1(pose1, K);
1319 
1320  // create second camera 1 meter to the right of first camera
1321  Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0));
1322  StereoCamera cam2(pose2, K);
1323 
1324  // create third camera 1 meter above the first camera
1325  Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0));
1326  StereoCamera cam3(pose3, K);
1327 
1328  Point3 landmark1(5, 0.5, 1.2);
1329 
1330  vector<StereoPoint2> measurements_cam1 = stereo_projectToMultipleCameras(cam1,
1331  cam2, cam3, landmark1);
1332 
1334  smartFactorInstance->add(measurements_cam1, views, K);
1335 
1336  Values values;
1337  values.insert(x1, pose1);
1338  values.insert(x2, pose2);
1339  values.insert(x3, pose3);
1340 
1341  std::shared_ptr<GaussianFactor> hessianFactor =
1342  smartFactorInstance->linearize(values);
1343  // hessianFactor->print("Hessian factor \n");
1344 
1345  Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0));
1346 
1347  Values rotValues;
1348  rotValues.insert(x1, poseDrift.compose(pose1));
1349  rotValues.insert(x2, poseDrift.compose(pose2));
1350  rotValues.insert(x3, poseDrift.compose(pose3));
1351 
1352  std::shared_ptr<GaussianFactor> hessianFactorRot =
1353  smartFactorInstance->linearize(rotValues);
1354  // hessianFactorRot->print("Hessian factor \n");
1355 
1356  // Hessian is invariant to rotations in the nondegenerate case
1357  EXPECT(
1358  assert_equal(hessianFactor->information(),
1359  hessianFactorRot->information(), 1e-7));
1360 
1361  Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2),
1362  Point3(10, -4, 5));
1363 
1364  Values tranValues;
1365  tranValues.insert(x1, poseDrift2.compose(pose1));
1366  tranValues.insert(x2, poseDrift2.compose(pose2));
1367  tranValues.insert(x3, poseDrift2.compose(pose3));
1368 
1369  std::shared_ptr<GaussianFactor> hessianFactorRotTran =
1370  smartFactorInstance->linearize(tranValues);
1371 
1372  // Hessian is invariant to rotations and translations in the nondegenerate case
1373  EXPECT(
1374  assert_equal(hessianFactor->information(),
1375  hessianFactorRotTran->information(), 1e-6));
1376 }
1377 
1378 /* *************************************************************************/
1379 TEST( SmartStereoProjectionPoseFactor, HessianWithRotationNonDegenerate ) {
1380 
1381  KeyVector views;
1382  views.push_back(x1);
1383  views.push_back(x2);
1384  views.push_back(x3);
1385 
1386  // create first camera. Looking along X-axis, 1 meter above ground plane (x-y)
1387  Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1));
1388  StereoCamera cam1(pose1, K2);
1389 
1390  // Second and third cameras in same place, which is a degenerate configuration
1391  Pose3 pose2 = pose1;
1392  Pose3 pose3 = pose1;
1393  StereoCamera cam2(pose2, K2);
1394  StereoCamera cam3(pose3, K2);
1395 
1396  Point3 landmark1(5, 0.5, 1.2);
1397 
1398  vector<StereoPoint2> measurements_cam1 = stereo_projectToMultipleCameras(cam1,
1399  cam2, cam3, landmark1);
1400 
1402  smartFactor->add(measurements_cam1, views, K2);
1403 
1404  Values values;
1405  values.insert(x1, pose1);
1406  values.insert(x2, pose2);
1407  values.insert(x3, pose3);
1408 
1409  std::shared_ptr<GaussianFactor> hessianFactor = smartFactor->linearize(
1410  values);
1411 
1412  // check that it is non degenerate
1413  EXPECT(smartFactor->isValid());
1414 
1415  Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0));
1416 
1417  Values rotValues;
1418  rotValues.insert(x1, poseDrift.compose(pose1));
1419  rotValues.insert(x2, poseDrift.compose(pose2));
1420  rotValues.insert(x3, poseDrift.compose(pose3));
1421 
1422  std::shared_ptr<GaussianFactor> hessianFactorRot = smartFactor->linearize(
1423  rotValues);
1424 
1425  // check that it is non degenerate
1426  EXPECT(smartFactor->isValid());
1427 
1428  // Hessian is invariant to rotations in the nondegenerate case
1429  EXPECT(
1430  assert_equal(hessianFactor->information(),
1431  hessianFactorRot->information(), 1e-6));
1432 
1433  Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2),
1434  Point3(10, -4, 5));
1435 
1436  Values tranValues;
1437  tranValues.insert(x1, poseDrift2.compose(pose1));
1438  tranValues.insert(x2, poseDrift2.compose(pose2));
1439  tranValues.insert(x3, poseDrift2.compose(pose3));
1440 
1441  std::shared_ptr<GaussianFactor> hessianFactorRotTran =
1442  smartFactor->linearize(tranValues);
1443 
1444  // Hessian is invariant to rotations and translations in the degenerate case
1445  EXPECT(
1446  assert_equal(hessianFactor->information(),
1447 #ifdef GTSAM_USE_EIGEN_MKL
1448  hessianFactorRotTran->information(), 1e-5));
1449 #else
1450  hessianFactorRotTran->information(), 1e-6));
1451 #endif
1452 }
1453 
1454 /* ************************************************************************* */
1455 int main() {
1456  TestResult tr;
1457  return TestRegistry::runAllTests(tr);
1458 }
1459 /* ************************************************************************* */
1460 
#define CHECK(condition)
Definition: Test.h:108
static PinholeCamera< Cal3_S2 > cam1(pose3, cal1)
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Scalar * y
virtual const Values & optimize()
Camera cam3(interp_pose3, sharedK)
Scalar * b
Definition: benchVecAdd.cpp:17
#define gttic_(label)
Definition: timing.h:245
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
Definition: Values-inl.h:204
Matrix expected
Definition: testMatrix.cpp:971
void setRetriangulationThreshold(double retriangulationTh)
static StereoCamera cam2(pose3, cal4ptr)
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:190
static const Camera level_camera(level_pose, K2)
void setEnableEPI(bool enableEPI)
CameraSet< Camera > Cameras
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
#define M_PI
Definition: main.h:106
leaf::MyValues values
TriangulationParameters triangulation
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
void add(const StereoPoint2 &measured, const Key &poseKey, const std::shared_ptr< Cal3_S2Stereo > &K)
static const Camera level_camera_right(pose_right, K2)
NonlinearFactorGraph graph
A set of cameras, all with their own calibration.
Definition: CameraSet.h:36
Point2 landmark1(5.0, 1.5)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
DegeneracyMode getDegeneracyMode() const
Smart stereo factor on poses, assuming camera calibration is fixed.
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:49
static const SmartProjectionParams params
static Point3 landmark(0, 0, 5)
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double totalReprojectionError(const Cameras &cameras, std::optional< Point3 > externalPoint={}) const
void setRankTolerance(double rankTol)
Implements a prior on the translation component of a pose.
static const Cal3Bundler K2(625, 1e-3, 1e-3)
Point2 landmark2(7.0, 1.5)
double getRetriangulationThreshold() const
std::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
double error(const Values &values) const override
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
bool enableEPI
if set to true, will refine triangulation using LM
double rankTolerance
(the rank is the number of singular values of the triangulation matrix which are larger than rankTole...
#define EXPECT(condition)
Definition: Test.h:150
static Pose3 pose3(rt3, pt3)
Pose3 level_pose
double v() const
get v
Definition: StereoPoint2.h:116
static Point2 measurement1(323.0, 240.0)
void projectToMultipleCameras(const CAMERA &cam1, const CAMERA &cam2, const CAMERA &cam3, Point3 landmark, typename CAMERA::MeasurementVector &measurements_cam)
LevenbergMarquardtParams lmParams
void setLandmarkDistanceThreshold(double landmarkDistanceThreshold)
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.
Definition: Cal3_S2.h:34
StereoPoint2 project(const Point3 &point) const
Project 3D point to StereoPoint2 (uL,uR,v)
std::shared_ptr< This > shared_ptr
shared_ptr to this class
double error(const Values &values) const
Class compose(const Class &g) const
Definition: Lie.h:48
Reprojection of a LANDMARK to a 2D point.
Base::Cameras cameras(const Values &values) const override
RowVector3d w
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
std::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
A non-linear factor for stereo measurements.
NonlinearFactorGraph graph2()
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
static Key poseKey1(X(1))
traits
Definition: chartTesting.h:28
TriangulationResult triangulateSafe(const Cameras &cameras) const
triangulateSafe
const double h
#define HESSIAN
TEST(SmartStereoProjectionPoseFactor, params)
void setDegeneracyMode(DegeneracyMode degMode)
double uL() const
get uL
Definition: StereoPoint2.h:110
Pose3 x1
Definition: testPose3.cpp:663
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:49
float * p
static const Point2 level_uv_right
static Pose3 pose2
void insert(Key j, const Value &val)
Definition: Values.cpp:155
void setLinearizationMode(LinearizationMode linMode)
void tictoc_finishedIteration_()
Definition: timing.h:264
Vector3 Point3
Definition: Point3.h:38
LinearizationMode getLinearizationMode() const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
#define X
Definition: icosphere.cpp:20
#define gttoc_(label)
Definition: timing.h:250
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
void setDynamicOutlierRejectionThreshold(double dynOutRejectionThreshold)
static const Point2 level_uv
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
static double fov
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
TriangulationParameters getTriangulationParameters() const
TEST_UNSAFE(SmartStereoProjectionPoseFactor, noiseless)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:40