From 6c59273a1829e0b7fd3bcad9cf7269ae48129832 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 4 Jan 2019 15:10:47 -0500 Subject: [PATCH 1/8] Clear and functional --- gtsam/slam/SmartProjectionPoseFactor.h | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index bb261a9c4e..be15841957 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -123,18 +123,16 @@ class SmartProjectionPoseFactor: public SmartProjectionFactor< */ typename Base::Cameras cameras(const Values& values) const { typename Base::Cameras cameras; - for(const Key& k: this->keys_) { - Pose3 pose = values.at(k); - if (Base::body_P_sensor_) - pose = pose.compose(*(Base::body_P_sensor_)); - - Camera camera(pose, K_); - cameras.push_back(camera); + for (const Key& k : this->keys_) { + const Pose3 world_P_sensor_k = + Base::body_P_sensor_ ? values.at(k) * *Base::body_P_sensor_ + : values.at(k); + cameras.emplace_back(world_P_sensor_k, K_); } return cameras; } -private: + private: /// Serialization function friend class boost::serialization::access; From 968c0c0d4b496535f21aeceffade14c40863d494 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 4 Jan 2019 15:11:07 -0500 Subject: [PATCH 2/8] Use test namespace --- .../tests/testSmartProjectionPoseFactor.cpp | 60 ++++++++----------- 1 file changed, 25 insertions(+), 35 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 080046dd4b..8b435b5659 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -199,29 +199,17 @@ TEST( SmartProjectionPoseFactor, noisy ) { } /* *************************************************************************/ -TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ - // make a realistic calibration matrix - double fov = 60; // degrees - size_t w=640,h=480; - - Cal3_S2::shared_ptr K(new Cal3_S2(fov,w,h)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 cameraPose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); // body poses - Pose3 cameraPose2 = cameraPose1 * Pose3(Rot3(), Point3(1,0,0)); - Pose3 cameraPose3 = cameraPose1 * Pose3(Rot3(), Point3(0,-1,0)); - - SimpleCamera cam1(cameraPose1, *K); // with camera poses - SimpleCamera cam2(cameraPose2, *K); - SimpleCamera cam3(cameraPose3, *K); +TEST(SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform) { + using namespace vanillaPose; - // create arbitrary body_Pose_sensor (transforms from sensor to body) - Pose3 sensor_to_body = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(1, 1, 1)); // Pose3(); // + // create arbitrary body_T_sensor (transforms from sensor to body) + Pose3 body_T_sensor = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(1, 1, 1)); // These are the poses we want to estimate, from camera measurements - Pose3 bodyPose1 = cameraPose1.compose(sensor_to_body.inverse()); - Pose3 bodyPose2 = cameraPose2.compose(sensor_to_body.inverse()); - Pose3 bodyPose3 = cameraPose3.compose(sensor_to_body.inverse()); + const Pose3 sensor_T_body = body_T_sensor.inverse(); + Pose3 wTb1 = cam1.pose() * sensor_T_body; + Pose3 wTb2 = cam2.pose() * sensor_T_body; + Pose3 wTb3 = cam3.pose() * sensor_T_body; // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); @@ -243,16 +231,16 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ SmartProjectionParams params; params.setRankTolerance(1.0); - params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setDegeneracyMode(IGNORE_DEGENERACY); params.setEnableEPI(false); - SmartProjectionPoseFactor smartFactor1(model, K, sensor_to_body, params); + SmartFactor smartFactor1(model, sharedK, body_T_sensor, params); smartFactor1.add(measurements_cam1, views); - SmartProjectionPoseFactor smartFactor2(model, K, sensor_to_body, params); + SmartFactor smartFactor2(model, sharedK, body_T_sensor, params); smartFactor2.add(measurements_cam2, views); - SmartProjectionPoseFactor smartFactor3(model, K, sensor_to_body, params); + SmartFactor smartFactor3(model, sharedK, body_T_sensor, params); smartFactor3.add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -262,30 +250,32 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.emplace_shared >(x1, bodyPose1, noisePrior); - graph.emplace_shared >(x2, bodyPose2, noisePrior); + graph.emplace_shared >(x1, wTb1, noisePrior); + graph.emplace_shared >(x2, wTb2, noisePrior); // Check errors at ground truth poses Values gtValues; - gtValues.insert(x1, bodyPose1); - gtValues.insert(x2, bodyPose2); - gtValues.insert(x3, bodyPose3); + gtValues.insert(x1, wTb1); + gtValues.insert(x2, wTb2); + gtValues.insert(x3, wTb3); double actualError = graph.error(gtValues); double expectedError = 0.0; DOUBLES_EQUAL(expectedError, actualError, 1e-7) - Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), + Point3(0.1, 0.1, 0.1)); Values values; - values.insert(x1, bodyPose1); - values.insert(x2, bodyPose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, bodyPose3*noise_pose); + values.insert(x1, wTb1); + values.insert(x2, wTb2); + // initialize third pose with some noise, we expect it to move back to + // original pose3 + values.insert(x3, wTb3 * noise_pose); LevenbergMarquardtParams lmParams; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - EXPECT(assert_equal(bodyPose3,result.at(x3))); + EXPECT(assert_equal(wTb3, result.at(x3))); } /* *************************************************************************/ From 80a42fe2cd5303b4c132d4988368d4377acc90e2 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 4 Jan 2019 15:11:58 -0500 Subject: [PATCH 3/8] Reflect name of actual Factor --- ...rtProjectionCameraFactor.cpp => testSmartProjectionFactor.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename gtsam/slam/tests/{testSmartProjectionCameraFactor.cpp => testSmartProjectionFactor.cpp} (100%) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionFactor.cpp similarity index 100% rename from gtsam/slam/tests/testSmartProjectionCameraFactor.cpp rename to gtsam/slam/tests/testSmartProjectionFactor.cpp From 67f3b51ab2266a3a94c5d97947ef71793b6b23d3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 4 Jan 2019 15:50:12 -0500 Subject: [PATCH 4/8] Clean up --- .../slam/tests/testSmartProjectionFactor.cpp | 70 +++++++-------- .../tests/testSmartProjectionPoseFactor.cpp | 86 ++++--------------- 2 files changed, 49 insertions(+), 107 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionFactor.cpp b/gtsam/slam/tests/testSmartProjectionFactor.cpp index aaffbf0e66..16eca65848 100644 --- a/gtsam/slam/tests/testSmartProjectionFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionFactor.cpp @@ -10,8 +10,8 @@ * -------------------------------------------------------------------------- */ /** - * @file testSmartProjectionCameraFactor.cpp - * @brief Unit tests for SmartProjectionCameraFactor Class + * @file testSmartProjectionFactor.cpp + * @brief Unit tests for SmartProjectionFactor Class * @author Chris Beall * @author Luca Carlone * @author Zsolt Kira @@ -29,19 +29,11 @@ using namespace boost::assign; -static bool isDebugTest = false; - -// Convenience for named keys -using symbol_shorthand::X; -using symbol_shorthand::L; - -static Key x1(1); -Symbol l1('l', 1), l2('l', 2), l3('l', 3); -Key c1 = 1, c2 = 2, c3 = 3; - -static Point2 measurement1(323.0, 240.0); - -static double rankTol = 1.0; +static const bool isDebugTest = false; +static const Symbol l1('l', 1), l2('l', 2), l3('l', 3); +static const Key c1 = 1, c2 = 2, c3 = 3; +static const Point2 measurement1(323.0, 240.0); +static const double rankTol = 1.0; template PinholeCamera perturbCameraPoseAndCalibration( @@ -59,7 +51,7 @@ PinholeCamera perturbCameraPoseAndCalibration( } /* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, perturbCameraPose) { +TEST(SmartProjectionFactor, perturbCameraPose) { using namespace vanilla; Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); @@ -71,45 +63,45 @@ TEST( SmartProjectionCameraFactor, perturbCameraPose) { } /* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, Constructor) { +TEST(SmartProjectionFactor, Constructor) { using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); } /* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, Constructor2) { +TEST(SmartProjectionFactor, Constructor2) { using namespace vanilla; params.setRankTolerance(rankTol); SmartFactor factor1(unit2, boost::none, params); } /* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, Constructor3) { +TEST(SmartProjectionFactor, Constructor3) { using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); - factor1->add(measurement1, x1); + factor1->add(measurement1, c1); } /* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, Constructor4) { +TEST(SmartProjectionFactor, Constructor4) { using namespace vanilla; params.setRankTolerance(rankTol); SmartFactor factor1(unit2, boost::none, params); - factor1.add(measurement1, x1); + factor1.add(measurement1, c1); } /* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, Equals ) { +TEST(SmartProjectionFactor, Equals ) { using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); - factor1->add(measurement1, x1); + factor1->add(measurement1, c1); SmartFactor::shared_ptr factor2(new SmartFactor(unit2)); - factor2->add(measurement1, x1); + factor2->add(measurement1, c1); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, noiseless ) { +TEST(SmartProjectionFactor, noiseless ) { using namespace vanilla; Values values; @@ -128,7 +120,7 @@ TEST( SmartProjectionCameraFactor, noiseless ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, noisy ) { +TEST(SmartProjectionFactor, noisy ) { using namespace vanilla; @@ -179,7 +171,7 @@ TEST( SmartProjectionCameraFactor, noisy ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { +TEST(SmartProjectionFactor, perturbPoseAndOptimize ) { using namespace vanilla; @@ -278,7 +270,7 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { +TEST(SmartProjectionFactor, perturbPoseAndOptimizeFromSfM_tracks ) { using namespace vanilla; @@ -348,7 +340,7 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { +TEST(SmartProjectionFactor, perturbCamerasAndOptimize ) { using namespace vanilla; @@ -425,7 +417,7 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, Cal3Bundler ) { +TEST(SmartProjectionFactor, Cal3Bundler ) { using namespace bundler; @@ -498,7 +490,7 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { +TEST(SmartProjectionFactor, Cal3Bundler2 ) { using namespace bundler; @@ -571,7 +563,7 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, noiselessBundler ) { +TEST(SmartProjectionFactor, noiselessBundler ) { using namespace bundler; Values values; @@ -599,7 +591,7 @@ TEST( SmartProjectionCameraFactor, noiselessBundler ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { +TEST(SmartProjectionFactor, comparisonGeneralSfMFactor ) { using namespace bundler; Values values; @@ -638,7 +630,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { +TEST(SmartProjectionFactor, comparisonGeneralSfMFactor1 ) { using namespace bundler; Values values; @@ -682,7 +674,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { /* *************************************************************************/ // Have to think about how to compare multiplyHessianAdd in generalSfMFactor and smartFactors -//TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor2 ){ +//TEST(SmartProjectionFactor, comparisonGeneralSfMFactor2 ){ // // Values values; // values.insert(c1, level_camera); @@ -730,7 +722,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { // EXPECT(assert_equal(yActual,yExpected, 1e-7)); //} /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { +TEST(SmartProjectionFactor, computeImplicitJacobian ) { using namespace bundler; Values values; @@ -768,7 +760,7 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { +TEST(SmartProjectionFactor, implicitJacobianFactor ) { using namespace bundler; @@ -829,7 +821,7 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropi BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); -TEST( SmartProjectionCameraFactor, serialize) { +TEST(SmartProjectionFactor, serialize) { using namespace vanilla; using namespace gtsam::serializationTestHelpers; SmartFactor factor(unit2); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 8b435b5659..0197ba1b07 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -189,9 +189,7 @@ TEST( SmartProjectionPoseFactor, noisy ) { measurements.push_back(level_uv); measurements.push_back(level_uv_right); - KeyVector views; - views.push_back(x1); - views.push_back(x2); + KeyVector views {x1, x2}; factor2->add(measurements, views); double actualError2 = factor2->error(values); @@ -212,9 +210,7 @@ TEST(SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform) { Pose3 wTb3 = cam3.pose() * sensor_T_body; // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(5, 0, 3.0); + Point3 landmark1(5, 0.5, 1.2), landmark2(5, -0.5, 1.2), landmark3(5, 0, 3.0); Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -224,10 +220,7 @@ TEST(SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); // Create smart factors - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; SmartProjectionParams params; params.setRankTolerance(1.0); @@ -360,9 +353,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { measurements_cam1.push_back(cam2.project(landmark1)); // Create smart factors - KeyVector views; - views.push_back(x1); - views.push_back(x2); + KeyVector views {x1, x2}; SmartFactor::shared_ptr smartFactor1 = boost::make_shared(model, sharedK); smartFactor1->add(measurements_cam1, views); @@ -510,10 +501,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { using namespace vanillaPose; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -567,10 +555,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { using namespace vanillaPose; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -628,10 +613,7 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { double excludeLandmarksFutherThanDist = 2; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -691,10 +673,7 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { double excludeLandmarksFutherThanDist = 1e10; double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; // add fourth landmark Point3 landmark4(5, -0.5, 1); @@ -757,10 +736,7 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { using namespace vanillaPose; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -811,10 +787,7 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { using namespace vanillaPose2; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; typedef GenericProjectionFactor ProjectionFactor; NonlinearFactorGraph graph; @@ -859,10 +832,7 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, CheckHessian) { - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; using namespace vanillaPose; @@ -945,10 +915,7 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ) { using namespace vanillaPose2; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; // Two different cameras, at the same position, but different rotations Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); @@ -1004,10 +971,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) // this test considers a condition in which the cheirality constraint is triggered using namespace vanillaPose; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; // Two different cameras, at the same position, but different rotations Pose3 pose2 = level_pose @@ -1089,9 +1053,7 @@ TEST( SmartProjectionPoseFactor, Hessian ) { using namespace vanillaPose2; - KeyVector views; - views.push_back(x1); - views.push_back(x2); + KeyVector views {x1, x2}; // Project three landmarks into 2 cameras Point2 cam1_uv1 = cam1.project(landmark1); @@ -1123,10 +1085,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { using namespace vanillaPose; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -1176,10 +1135,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { using namespace vanillaPose2; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; // All cameras have the same pose so will be degenerate ! Camera cam2(level_pose, sharedK2); @@ -1250,10 +1206,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; SmartFactor::shared_ptr smartFactor1(new SmartFactor(model, sharedBundlerK)); smartFactor1->add(measurements_cam1, views); @@ -1299,10 +1252,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { using namespace bundlerPose; - KeyVector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); + KeyVector views {x1, x2, x3}; // Two different cameras Pose3 pose2 = level_pose From 737d369ecf516c09d502984bb5486a436100e9f4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 6 Jan 2019 18:18:23 -0500 Subject: [PATCH 5/8] Added test with transform --- .../slam/tests/testSmartProjectionFactor.cpp | 58 +++++++++++++++++++ 1 file changed, 58 insertions(+) diff --git a/gtsam/slam/tests/testSmartProjectionFactor.cpp b/gtsam/slam/tests/testSmartProjectionFactor.cpp index 16eca65848..6455db31b8 100644 --- a/gtsam/slam/tests/testSmartProjectionFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionFactor.cpp @@ -812,6 +812,64 @@ TEST(SmartProjectionFactor, implicitJacobianFactor ) { } +/* *************************************************************************/ +TEST(SmartProjectionFactor, smartFactorWithSensorBodyTransform) { + using namespace vanilla; + + // create arbitrary body_T_sensor (transforms from sensor to body) + Pose3 body_T_sensor = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(1, 1, 1)); + + // These are the poses we want to estimate, from camera measurements + const Pose3 sensor_T_body = body_T_sensor.inverse(); + Pose3 wTb1 = cam1.pose() * sensor_T_body; + Pose3 wTb2 = cam2.pose() * sensor_T_body; + Pose3 wTb3 = cam3.pose() * sensor_T_body; + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2), landmark2(5, -0.5, 1.2), landmark3(5, 0, 3.0); + + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; + + // Project three landmarks into three cameras + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + // Create smart factors + KeyVector views {1, 2, 3}; + + SmartProjectionParams params; + params.setRankTolerance(1.0); + params.setDegeneracyMode(IGNORE_DEGENERACY); + params.setEnableEPI(false); + + SmartFactor smartFactor1(unit2, body_T_sensor, params); + smartFactor1.add(measurements_cam1, views); + + SmartFactor smartFactor2(unit2, body_T_sensor, params); + smartFactor2.add(measurements_cam2, views); + + SmartFactor smartFactor3(unit2, body_T_sensor, params); + smartFactor3.add(measurements_cam3, views); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + // Put all factors in factor graph, adding priors + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + + // Check errors at ground truth poses + Values gtValues; + gtValues.insert(1, cam1); + gtValues.insert(2, cam2); + gtValues.insert(3, cam3); + double actualError = graph.error(gtValues); + double expectedError = 0.0; + DOUBLES_EQUAL(expectedError, actualError, 1e-7); +} + /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); From 214dca3aa5233313dd6f38b57e796f299ed7f1ca Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 7 Aug 2019 13:36:39 -0400 Subject: [PATCH 6/8] Fixed warning --- gtsam/navigation/AHRSFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 02384e23dc..1418ab687d 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -71,8 +71,8 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation const Rot3& deltaRij, const Matrix3& delRdelBiasOmega, const Matrix3& preint_meas_cov) : - biasHat_(bias_hat), PreintegratedRotation(p, deltaTij, deltaRij, delRdelBiasOmega), + biasHat_(bias_hat), preintMeasCov_(preint_meas_cov) {} const Params& p() const { return *boost::static_pointer_cast(p_);} From 0eef77ff368ddc30e37aa1f3a7a97f526ba1fa92 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 8 Aug 2019 11:52:33 -0400 Subject: [PATCH 7/8] Made code a bit more efficient in case of offset --- gtsam/slam/SmartFactorBase.h | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 6e55eb50cf..34f9b9e9f1 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -75,15 +75,12 @@ class SmartFactorBase: public NonlinearFactor { */ ZVector measured_; - /// @name Pose of the camera in the body frame - boost::optional body_P_sensor_; ///< Pose of the camera in the body frame - /// @} + boost::optional body_P_sensor_; ///< Pose of the camera in the body frame // Cache for Fblocks, to avoid a malloc ever time we re-linearize mutable FBlocks Fs; -public: - + public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for a smart pointer to a factor @@ -200,17 +197,20 @@ class SmartFactorBase: public NonlinearFactor { return e && Base::equals(p, tol) && areMeasurementsEqual; } - /// Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives - template - Vector unwhitenedError(const Cameras& cameras, const POINT& point, - boost::optional Fs = boost::none, // + /// Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and + /// derivatives + template + Vector unwhitenedError( + const Cameras& cameras, const POINT& point, + boost::optional Fs = boost::none, // boost::optional E = boost::none) const { Vector ue = cameras.reprojectionError(point, measured_, Fs, E); - if(body_P_sensor_ && Fs){ - for(size_t i=0; i < Fs->size(); i++){ - Pose3 w_Pose_body = (cameras[i].pose()).compose(body_P_sensor_->inverse()); + if (body_P_sensor_ && Fs) { + const Pose3 sensor_P_body = body_P_sensor_->inverse(); + for (size_t i = 0; i < Fs->size(); i++) { + const Pose3 w_Pose_body = cameras[i].pose() * sensor_P_body; Matrix J(6, 6); - Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); + const Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); Fs->at(i) = Fs->at(i) * J; } } From 20736b6f14ad0245d36efdc7784b72955dd1a468 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 8 Aug 2019 11:53:05 -0400 Subject: [PATCH 8/8] deprecated SmartProjectionFactor constructor with offset --- gtsam.h | 3 + gtsam/slam/SmartProjectionFactor.h | 37 +++++++--- gtsam/slam/SmartProjectionPoseFactor.h | 29 ++++++-- .../slam/tests/testSmartProjectionFactor.cpp | 67 ++----------------- .../tests/testSmartProjectionPoseFactor.cpp | 58 ++++++++-------- 5 files changed, 86 insertions(+), 108 deletions(-) diff --git a/gtsam.h b/gtsam.h index 826f8472ec..0ac2d4ad12 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2499,6 +2499,9 @@ virtual class SmartProjectionPoseFactor: gtsam::NonlinearFactor { SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, const CALIBRATION* K, const gtsam::Pose3& body_P_sensor); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K, + const gtsam::SmartProjectionParams& params); SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, const CALIBRATION* K, const gtsam::Pose3& body_P_sensor, diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index cbeed77c50..15d632cda2 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -79,15 +79,15 @@ class SmartProjectionFactor: public SmartFactorBase { /** * Constructor - * @param body_P_sensor pose of the camera in the body frame - * @param params internal parameters of the smart factors + * @param sharedNoiseModel isotropic noise model for the 2D feature measurements + * @param params parameters for the smart projection factors */ - SmartProjectionFactor(const SharedNoiseModel& sharedNoiseModel, - const boost::optional body_P_sensor = boost::none, - const SmartProjectionParams& params = SmartProjectionParams()) : - Base(sharedNoiseModel, body_P_sensor), params_(params), // - result_(TriangulationResult::Degenerate()) { - } + SmartProjectionFactor( + const SharedNoiseModel& sharedNoiseModel, + const SmartProjectionParams& params = SmartProjectionParams()) + : Base(sharedNoiseModel), + params_(params), + result_(TriangulationResult::Degenerate()) {} /** Virtual destructor */ virtual ~SmartProjectionFactor() { @@ -443,7 +443,26 @@ class SmartProjectionFactor: public SmartFactorBase { /** return the farPoint state */ bool isFarPoint() const { return result_.farPoint(); } -private: +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// @name Deprecated + /// @{ + // It does not make sense to optimize for a camera where the pose would not be + // the actual pose of the camera. An unfortunate consequence of deprecating + // this constructor means that we cannot optimize for calibration when the + // camera is offset from the body pose. That would need a new factor with + // (body) pose and calibration as variables. However, that use case is + // unlikely: when a global offset is know, calibration is typically known. + SmartProjectionFactor( + const SharedNoiseModel& sharedNoiseModel, + const boost::optional body_P_sensor, + const SmartProjectionParams& params = SmartProjectionParams()) + : Base(sharedNoiseModel, body_P_sensor), + params_(params), + result_(TriangulationResult::Degenerate()) {} + /// @} +#endif + + private: /// Serialization function friend class boost::serialization::access; diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index be15841957..b5be46258a 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -66,16 +66,31 @@ class SmartProjectionPoseFactor: public SmartProjectionFactor< /** * Constructor - * @param Isotropic measurement noise + * @param sharedNoiseModel isotropic noise model for the 2D feature measurements * @param K (fixed) calibration, assumed to be the same for all cameras - * @param body_P_sensor pose of the camera in the body frame - * @param params internal parameters of the smart factors + * @param params parameters for the smart projection factors */ - SmartProjectionPoseFactor(const SharedNoiseModel& sharedNoiseModel, + SmartProjectionPoseFactor( + const SharedNoiseModel& sharedNoiseModel, const boost::shared_ptr K, - const boost::optional body_P_sensor = boost::none, - const SmartProjectionParams& params = SmartProjectionParams()) : - Base(sharedNoiseModel, body_P_sensor, params), K_(K) { + const SmartProjectionParams& params = SmartProjectionParams()) + : Base(sharedNoiseModel, params), K_(K) { + } + + /** + * Constructor + * @param sharedNoiseModel isotropic noise model for the 2D feature measurements + * @param K (fixed) calibration, assumed to be the same for all cameras + * @param body_P_sensor pose of the camera in the body frame (optional) + * @param params parameters for the smart projection factors + */ + SmartProjectionPoseFactor( + const SharedNoiseModel& sharedNoiseModel, + const boost::shared_ptr K, + const boost::optional body_P_sensor, + const SmartProjectionParams& params = SmartProjectionParams()) + : SmartProjectionPoseFactor(sharedNoiseModel, K, params) { + this->body_P_sensor_ = body_P_sensor; } /** Virtual destructor */ diff --git a/gtsam/slam/tests/testSmartProjectionFactor.cpp b/gtsam/slam/tests/testSmartProjectionFactor.cpp index 336c7d2ea4..c6d1a5b2cf 100644 --- a/gtsam/slam/tests/testSmartProjectionFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionFactor.cpp @@ -71,7 +71,7 @@ TEST(SmartProjectionFactor, Constructor) { TEST(SmartProjectionFactor, Constructor2) { using namespace vanilla; params.setRankTolerance(rankTol); - SmartFactor factor1(unit2, boost::none, params); + SmartFactor factor1(unit2, params); } /* ************************************************************************* */ @@ -85,7 +85,7 @@ TEST(SmartProjectionFactor, Constructor3) { TEST(SmartProjectionFactor, Constructor4) { using namespace vanilla; params.setRankTolerance(rankTol); - SmartFactor factor1(unit2, boost::none, params); + SmartFactor factor1(unit2, params); factor1.add(measurement1, c1); } @@ -777,7 +777,7 @@ TEST(SmartProjectionFactor, implicitJacobianFactor ) { params.setEnableEPI(useEPI); SmartFactor::shared_ptr explicitFactor( - new SmartFactor(unit2, boost::none, params)); + new SmartFactor(unit2, params)); explicitFactor->add(level_uv, c1); explicitFactor->add(level_uv_right, c2); @@ -789,7 +789,7 @@ TEST(SmartProjectionFactor, implicitJacobianFactor ) { // Implicit Schur version params.setLinearizationMode(gtsam::IMPLICIT_SCHUR); SmartFactor::shared_ptr implicitFactor( - new SmartFactor(unit2, boost::none, params)); + new SmartFactor(unit2, params)); implicitFactor->add(level_uv, c1); implicitFactor->add(level_uv_right, c2); GaussianFactor::shared_ptr gaussianImplicitSchurFactor = @@ -810,65 +810,6 @@ TEST(SmartProjectionFactor, implicitJacobianFactor ) { EXPECT(assert_equal(yActual, yExpected, 1e-7)); } - -/* *************************************************************************/ -TEST(SmartProjectionFactor, smartFactorWithSensorBodyTransform) { - using namespace vanilla; - - // create arbitrary body_T_sensor (transforms from sensor to body) - Pose3 body_T_sensor = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(1, 1, 1)); - - // These are the poses we want to estimate, from camera measurements - const Pose3 sensor_T_body = body_T_sensor.inverse(); - Pose3 wTb1 = cam1.pose() * sensor_T_body; - Pose3 wTb2 = cam2.pose() * sensor_T_body; - Pose3 wTb3 = cam3.pose() * sensor_T_body; - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2), landmark2(5, -0.5, 1.2), landmark3(5, 0, 3.0); - - Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; - - // Project three landmarks into three cameras - projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - - // Create smart factors - KeyVector views {1, 2, 3}; - - SmartProjectionParams params; - params.setRankTolerance(1.0); - params.setDegeneracyMode(IGNORE_DEGENERACY); - params.setEnableEPI(false); - - SmartFactor smartFactor1(unit2, body_T_sensor, params); - smartFactor1.add(measurements_cam1, views); - - SmartFactor smartFactor2(unit2, body_T_sensor, params); - smartFactor2.add(measurements_cam2, views); - - SmartFactor smartFactor3(unit2, body_T_sensor, params); - smartFactor3.add(measurements_cam3, views); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - // Put all factors in factor graph, adding priors - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - - // Check errors at ground truth poses - Values gtValues; - gtValues.insert(1, cam1); - gtValues.insert(2, cam2); - gtValues.insert(3, cam3); - double actualError = graph.error(gtValues); - double expectedError = 0.0; - DOUBLES_EQUAL(expectedError, actualError, 1e-7); -} - /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 0197ba1b07..f833941bcc 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -62,7 +62,7 @@ TEST( SmartProjectionPoseFactor, Constructor2) { using namespace vanillaPose; SmartProjectionParams params; params.setRankTolerance(rankTol); - SmartFactor factor1(model, sharedK, boost::none, params); + SmartFactor factor1(model, sharedK, params); } /* ************************************************************************* */ @@ -77,7 +77,7 @@ TEST( SmartProjectionPoseFactor, Constructor4) { using namespace vanillaPose; SmartProjectionParams params; params.setRankTolerance(rankTol); - SmartFactor factor1(model, sharedK, boost::none, params); + SmartFactor factor1(model, sharedK, params); factor1.add(measurement1, x1); } @@ -569,18 +569,18 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { params.setLinearizationMode(gtsam::JACOBIAN_SVD); params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); params.setEnableEPI(false); - SmartFactor factor1(model, sharedK, boost::none, params); + SmartFactor factor1(model, sharedK, params); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -630,15 +630,15 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { params.setEnableEPI(false); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -694,19 +694,19 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { params.setDynamicOutlierRejectionThreshold(dynamicOutlierRejectionThreshold); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor3->add(measurements_cam3, views); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor4->add(measurements_cam4, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -749,15 +749,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { params.setLinearizationMode(gtsam::JACOBIAN_Q); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -854,15 +854,15 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { params.setRankTolerance(10); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedK, boost::none, params)); // HESSIAN, by default + new SmartFactor(model, sharedK, params)); // HESSIAN, by default smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedK, boost::none, params)); // HESSIAN, by default + new SmartFactor(model, sharedK, params)); // HESSIAN, by default smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(model, sharedK, boost::none, params)); // HESSIAN, by default + new SmartFactor(model, sharedK, params)); // HESSIAN, by default smartFactor3->add(measurements_cam3, views); NonlinearFactorGraph graph; @@ -934,11 +934,11 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac params.setDegeneracyMode(gtsam::HANDLE_INFINITY); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedK2, boost::none, params)); + new SmartFactor(model, sharedK2, params)); smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedK2, boost::none, params)); + new SmartFactor(model, sharedK2, params)); smartFactor2->add(measurements_cam2, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -992,15 +992,15 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(model, sharedK, boost::none, params)); + new SmartFactor(model, sharedK, params)); smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1187,7 +1187,7 @@ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { using namespace bundlerPose; SmartProjectionParams params; params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); - SmartFactor factor(model, sharedBundlerK, boost::none, params); + SmartFactor factor(model, sharedBundlerK, params); factor.add(measurement1, x1); } @@ -1276,15 +1276,15 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(model, sharedBundlerK, boost::none, params)); + new SmartFactor(model, sharedBundlerK, params)); smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(model, sharedBundlerK, boost::none, params)); + new SmartFactor(model, sharedBundlerK, params)); smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(model, sharedBundlerK, boost::none, params)); + new SmartFactor(model, sharedBundlerK, params)); smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1345,7 +1345,7 @@ TEST(SmartProjectionPoseFactor, serialize) { using namespace gtsam::serializationTestHelpers; SmartProjectionParams params; params.setRankTolerance(rankTol); - SmartFactor factor(model, sharedK, boost::none, params); + SmartFactor factor(model, sharedK, params); EXPECT(equalsObj(factor)); EXPECT(equalsXML(factor));