diff --git a/gtsam_unstable/slam/tests/testSmartProjectionFactor.cpp b/gtsam_unstable/slam/tests/testSmartProjectionFactor.cpp deleted file mode 100644 index 8a025e277..000000000 --- a/gtsam_unstable/slam/tests/testSmartProjectionFactor.cpp +++ /dev/null @@ -1,1047 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file TestSmartProjectionFactor.cpp - * @brief Unit tests for ProjectionFactor Class - * @author Frank Dellaert - * @date Nov 2009 - */ - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -using namespace std; -using namespace boost::assign; -using namespace gtsam; - -// make a realistic calibration matrix -static double fov = 60; // degrees -static size_t w=640,h=480; -static Cal3_S2::shared_ptr K(new Cal3_S2(fov,w,h)); - -// Create a noise model for the pixel error -static SharedNoiseModel model(noiseModel::Unit::Create(2)); - -// Convenience for named keys -using symbol_shorthand::X; -using symbol_shorthand::L; - -typedef SmartProjectionFactor TestSmartProjectionFactor; - -#ifdef DEVELOP - -/* ************************************************************************* */ -TEST( SmartProjectionFactor, Constructor) { - Key poseKey(X(1)); - - std::vector views; - views.push_back(poseKey); - - std::vector measurements; - measurements.push_back(Point2(323.0, 240.0)); - - TestSmartProjectionFactor factor(views, measurements, model, K); -} - -/* ************************************************************************* */ -TEST( SmartProjectionFactor, ConstructorWithTransform) { - Key poseKey(X(1)); - - std::vector views; - views.push_back(poseKey); - - std::vector measurements; - measurements.push_back(Point2(323.0, 240.0)); - Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); - - TestSmartProjectionFactor factor(views, measurements, model, K, body_P_sensor); -} - -/* ************************************************************************* */ -TEST( SmartProjectionFactor, Equals ) { - // Create two identical factors and make sure they're equal - std::vector measurements; - measurements.push_back(Point2(323.0, 240.0)); - - std::vector views; - views.push_back(X(1)); - TestSmartProjectionFactor factor1(views, measurements, model, K); - TestSmartProjectionFactor factor2(views, measurements, model, K); - - CHECK(assert_equal(factor1, factor2)); -} - -/* ************************************************************************* */ -TEST( SmartProjectionFactor, EqualsWithTransform ) { - // Create two identical factors and make sure they're equal - std::vector measurements; - measurements.push_back(Point2(323.0, 240.0)); - Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); - - std::vector views; - views.push_back(X(1)); - TestSmartProjectionFactor factor1(views, measurements, model, K, body_P_sensor); - TestSmartProjectionFactor factor2(views, measurements, model, K, body_P_sensor); - - CHECK(assert_equal(factor1, factor2)); -} - - -/* *************************************************************************/ -TEST( SmartProjectionFactor, noisy ){ - // cout << " ************************ SmartProjectionFactor: noisy ****************************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 level_pose = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera level_camera(level_pose, *K); - - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - SimpleCamera level_camera_right(level_pose_right, *K); - - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - - // 1. Project two landmarks into two cameras and triangulate - Point2 pixelError(0.2,0.2); - Point2 level_uv = level_camera.project(landmark) + pixelError; - Point2 level_uv_right = level_camera_right.project(landmark); - - Values values; - values.insert(x1, level_pose); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); - values.insert(x2, level_pose_right.compose(noise_pose)); - - vector measurements; - measurements.push_back(level_uv); - measurements.push_back(level_uv_right); - - SmartProjectionFactor::shared_ptr - smartFactor(new SmartProjectionFactor(views, measurements, noiseProjection, K)); - - double actualError = smartFactor->error(values); - // std::cout << "Error: " << actualError << std::endl; - - // we do not expect to be able to predict the error, since the error on the pixel will change - // the triangulation of the landmark which is internal to the factor. - // DOUBLES_EQUAL(expectedError, actualError, 1e-7); -} - -/* ************************************************************************** -TEST( SmartProjectionFactor, 3poses_1iteration_projection_factor_comparison ){ - cout << " ************************ SmartProjectionFactor: 3 cams + 3 landmarks, 1 iteration, comparison b/w Generic and Smart Projection Factors **********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1 += cam1_uv1, cam2_uv1, cam3_uv1; // TODO: change to push_back - - // - Point2 cam1_uv2 = cam1.project(landmark2); - Point2 cam2_uv2 = cam2.project(landmark2); - Point2 cam3_uv2 = cam3.project(landmark2); - measurements_cam2 += cam1_uv2, cam2_uv2, cam3_uv2; TODO: change to push_back - - - Point2 cam1_uv3 = cam1.project(landmark3); - Point2 cam2_uv3 = cam2.project(landmark3); - Point2 cam3_uv3 = cam3.project(landmark3); - measurements_cam3 += cam1_uv3, cam2_uv3, cam3_uv3; TODO: change to push_back - - typedef SmartProjectionFactor SmartFactor; - typedef GenericProjectionFactor ProjectionFactor; - - SmartFactor::shared_ptr smartFactor1(new SmartFactor(views, measurements_cam1, noiseProjection, K, boost::make_optional(landmark1) )); - SmartFactor::shared_ptr smartFactor2(new SmartFactor(views, measurements_cam2, noiseProjection, K, boost::make_optional(landmark2) )); - SmartFactor::shared_ptr smartFactor3(new SmartFactor(views, measurements_cam3, noiseProjection, K, boost::make_optional(landmark3) )); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graphWithOriginalFactor; - graphWithOriginalFactor.push_back(ProjectionFactor(cam1.project(landmark1), noiseProjection, x1, L(1), K)); - graphWithOriginalFactor.push_back(ProjectionFactor(cam2.project(landmark1), noiseProjection, x2, L(1), K)); - graphWithOriginalFactor.push_back(ProjectionFactor(cam3.project(landmark1), noiseProjection, x3, L(1), K)); - - graphWithOriginalFactor.push_back(ProjectionFactor(cam1.project(landmark2), noiseProjection, x1, L(2), K)); - graphWithOriginalFactor.push_back(ProjectionFactor(cam2.project(landmark2), noiseProjection, x2, L(2), K)); - graphWithOriginalFactor.push_back(ProjectionFactor(cam3.project(landmark2), noiseProjection, x3, L(2), K)); - - graphWithOriginalFactor.push_back(ProjectionFactor(cam1.project(landmark3), noiseProjection, x1, L(3), K)); - graphWithOriginalFactor.push_back(ProjectionFactor(cam2.project(landmark3), noiseProjection, x2, L(3), K)); - graphWithOriginalFactor.push_back(ProjectionFactor(cam3.project(landmark3), noiseProjection, x3, L(3), K)); - - graphWithOriginalFactor.push_back(PriorFactor(x1, pose1, noisePrior)); - graphWithOriginalFactor.push_back(PriorFactor(x2, pose2, noisePrior)); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); - Values valuesOriginalFactor; - valuesOriginalFactor.insert(x1, pose1); - valuesOriginalFactor.insert(x2, pose2); - valuesOriginalFactor.insert(x3, pose3* noise_pose); - valuesOriginalFactor.insert(L(1), landmark1); - valuesOriginalFactor.insert(L(2), landmark2); - valuesOriginalFactor.insert(L(3), landmark3); - - NonlinearFactorGraph graphWithSmartFactor; - graphWithSmartFactor.push_back(smartFactor1); - graphWithSmartFactor.push_back(smartFactor2); - graphWithSmartFactor.push_back(smartFactor3); - graphWithSmartFactor.push_back(PriorFactor(x1, pose1, noisePrior)); - graphWithSmartFactor.push_back(PriorFactor(x2, pose2, noisePrior)); - - Values valuesSmartFactor; - valuesSmartFactor.insert(x1, pose1); - valuesSmartFactor.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - valuesSmartFactor.insert(x3, pose3*noise_pose); - valuesSmartFactor.at(x3).print("Pose3 before optimization: "); - pose3.print("Pose3 ground truth: "); - - LevenbergMarquardtParams params; - params.maxIterations = 1; - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - params.verbosity = NonlinearOptimizerParams::ERROR; - - Values resultWithOriginalFactor; - std::cout << "\n=========================================" << std::endl; - std::cout << "Optimizing GenericProjectionFactor" << std::endl; - LevenbergMarquardtOptimizer optimizerForOriginalFactor(graphWithOriginalFactor, valuesOriginalFactor, params); - resultWithOriginalFactor = optimizerForOriginalFactor.optimize(); - - Values resultWithSmartFactor; - std::cout << "\n=========================================" << std::endl; - std::cout << "Optimizing SmartProjectionfactor" << std::endl; - LevenbergMarquardtOptimizer optimizerForSmartFactor(graphWithSmartFactor, valuesSmartFactor, params); - resultWithSmartFactor = optimizerForSmartFactor.optimize(); - - std::cout << "\n=========================================" << std::endl; - // result.print("results of 3 camera, 3 landmark optimization \n"); - resultWithOriginalFactor.at(x3).print("Original: Pose3 after optimization: "); - resultWithSmartFactor.at(x3).print("\nSmart: Pose3 after optimization: "); - EXPECT(assert_equal(resultWithOriginalFactor.at(x3),resultWithSmartFactor.at(x3))); - - std::cout << "\n================= STARTING GN ITERATION ========================" << std::endl; - GaussNewtonParams params2; - params2.maxIterations = 1; - Values resultWithOriginalFactor2; - params2.verbosity = NonlinearOptimizerParams::DELTA; - GaussNewtonOptimizer optimizerForOriginalFactor2(graphWithOriginalFactor, valuesOriginalFactor, params2); - resultWithOriginalFactor2 = optimizerForOriginalFactor2.optimize(); - - Values resultWithSmartFactor2; - GaussNewtonOptimizer optimizerForSmartFactor2(graphWithSmartFactor, valuesSmartFactor, params2); - resultWithSmartFactor2 = optimizerForSmartFactor2.optimize(); - - std::cout << "\n=========================================" << std::endl; - resultWithOriginalFactor2.at(x3).print("Original: Pose3 after optimization (GaussNewton): "); - resultWithSmartFactor2.at(x3).print("\nSmart: Pose3 after optimization (GaussNewton): "); - -} - -/* *************************************************************************/ -TEST( SmartProjectionFactor, 3poses_smart_projection_factor ){ - // cout << " ************************ SmartProjectionFactor: 3 cams + 3 landmarks **********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); - // measurements_cam1 += cam1_uv1, cam2_uv1, cam3_uv1; - - // - Point2 cam1_uv2 = cam1.project(landmark2); - Point2 cam2_uv2 = cam2.project(landmark2); - Point2 cam3_uv2 = cam3.project(landmark2); - measurements_cam2.push_back(cam1_uv2); - measurements_cam2.push_back(cam2_uv2); - measurements_cam2.push_back(cam3_uv2); - // measurements_cam2 += cam1_uv2, cam2_uv2, cam3_uv2; - - - Point2 cam1_uv3 = cam1.project(landmark3); - Point2 cam2_uv3 = cam2.project(landmark3); - Point2 cam3_uv3 = cam3.project(landmark3); - measurements_cam3.push_back(cam1_uv3); - measurements_cam3.push_back(cam2_uv3); - measurements_cam3.push_back(cam3_uv3); - // measurements_cam3 += cam1_uv3, cam2_uv3, cam3_uv3; - - typedef SmartProjectionFactor SmartFactor; - - SmartFactor::shared_ptr smartFactor1(new SmartFactor(views, measurements_cam1, noiseProjection, K)); - SmartFactor::shared_ptr smartFactor2(new SmartFactor(views, measurements_cam2, noiseProjection, K)); - SmartFactor::shared_ptr smartFactor3(new SmartFactor(views, measurements_cam3, noiseProjection, K)); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose); - values.at(x3).print("Smart: Pose3 before optimization: "); - - LevenbergMarquardtParams params; - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - params.verbosity = NonlinearOptimizerParams::ERROR; - - Values result; - gttic_(SmartProjectionFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose3,result.at(x3))); - tictoc_print_(); - -} - -/* *************************************************************************/ -TEST( SmartProjectionFactor, 3poses_iterative_smart_projection_factor ){ - // cout << " ************************ SmartProjectionFactor: 3 cams + 3 landmarks **********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - // views += x1, x2, x3; - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); - // measurements_cam1 += cam1_uv1, cam2_uv1, cam3_uv1; - - // - Point2 cam1_uv2 = cam1.project(landmark2); - Point2 cam2_uv2 = cam2.project(landmark2); - Point2 cam3_uv2 = cam3.project(landmark2); - measurements_cam2.push_back(cam1_uv2); - measurements_cam2.push_back(cam2_uv2); - measurements_cam2.push_back(cam3_uv2); - // measurements_cam2 += cam1_uv2, cam2_uv2, cam3_uv2; - - - Point2 cam1_uv3 = cam1.project(landmark3); - Point2 cam2_uv3 = cam2.project(landmark3); - Point2 cam3_uv3 = cam3.project(landmark3); - measurements_cam3.push_back(cam1_uv3); - measurements_cam3.push_back(cam2_uv3); - measurements_cam3.push_back(cam3_uv3); - // measurements_cam3 += cam1_uv3, cam2_uv3, cam3_uv3; - - typedef SmartProjectionFactor SmartFactor; - - SmartFactor::shared_ptr smartFactor1(new SmartFactor(noiseProjection, K)); - smartFactor1->add(cam1_uv1, views[0]); - smartFactor1->add(cam2_uv1, views[1]); - smartFactor1->add(cam3_uv1, views[2]); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(noiseProjection, K)); - smartFactor2->add(cam1_uv2, views[0]); - smartFactor2->add(cam2_uv2, views[1]); - smartFactor2->add(cam3_uv2, views[2]); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor(noiseProjection, K)); - smartFactor3->add(cam1_uv3, views[0]); - smartFactor3->add(cam2_uv3, views[1]); - smartFactor3->add(cam3_uv3, views[2]); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose); - values.at(x3).print("Smart: Pose3 before optimization: "); - - LevenbergMarquardtParams params; - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - params.verbosity = NonlinearOptimizerParams::ERROR; - - Values result; - gttic_(SmartProjectionFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose3,result.at(x3))); - tictoc_print_(); - -} - -/* *************************************************************************/ -TEST( SmartProjectionFactor, 3poses_projection_factor ){ - // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - typedef GenericProjectionFactor ProjectionFactor; - NonlinearFactorGraph graph; - - // 1. Project three landmarks into three cameras and triangulate - graph.push_back(ProjectionFactor(cam1.project(landmark1), noiseProjection, x1, L(1), K)); - graph.push_back(ProjectionFactor(cam2.project(landmark1), noiseProjection, x2, L(1), K)); - graph.push_back(ProjectionFactor(cam3.project(landmark1), noiseProjection, x3, L(1), K)); - - // - graph.push_back(ProjectionFactor(cam1.project(landmark2), noiseProjection, x1, L(2), K)); - graph.push_back(ProjectionFactor(cam2.project(landmark2), noiseProjection, x2, L(2), K)); - graph.push_back(ProjectionFactor(cam3.project(landmark2), noiseProjection, x3, L(2), K)); - - graph.push_back(ProjectionFactor(cam1.project(landmark3), noiseProjection, x1, L(3), K)); - graph.push_back(ProjectionFactor(cam2.project(landmark3), noiseProjection, x2, L(3), K)); - graph.push_back(ProjectionFactor(cam3.project(landmark3), noiseProjection, x3, L(3), K)); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3* noise_pose); - values.insert(L(1), landmark1); - values.insert(L(2), landmark2); - values.insert(L(3), landmark3); - // values.at(x3).print("Pose3 before optimization: "); - - LevenbergMarquardtParams params; - // params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - // params.verbosity = NonlinearOptimizerParams::ERROR; - LevenbergMarquardtOptimizer optimizer(graph, values, params); - Values result = optimizer.optimize(); - - // result.at(x3).print("Pose3 after optimization: "); - EXPECT(assert_equal(pose3,result.at(x3))); - -} - -/* *************************************************************************/ -TEST( SmartProjectionFactor, 3poses_2land_rotation_only_smart_projection_factor ){ - // cout << " ************************ SmartProjectionFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); - // measurements_cam1 += cam1_uv1, cam2_uv1, cam3_uv1; - - // - Point2 cam1_uv2 = cam1.project(landmark2); - Point2 cam2_uv2 = cam2.project(landmark2); - Point2 cam3_uv2 = cam3.project(landmark2); - measurements_cam2.push_back(cam1_uv2); - measurements_cam2.push_back(cam2_uv2); - measurements_cam2.push_back(cam3_uv2); - // measurements_cam2 += cam1_uv2, cam2_uv2, cam3_uv2; - - typedef SmartProjectionFactor SmartFactor; - - double rankTol = 50; - - SmartFactor::shared_ptr smartFactor1(new SmartFactor(views, measurements_cam1, noiseProjection, K, rankTol)); - SmartFactor::shared_ptr smartFactor2(new SmartFactor(views, measurements_cam2, noiseProjection, K, rankTol)); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); - Point3 positionPrior = gtsam::Point3(0,0,1); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); - graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2*noise_pose); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose*noise_pose); - values.at(x3).print("Smart: Pose3 before optimization: "); - - LevenbergMarquardtParams params; - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - params.verbosity = NonlinearOptimizerParams::ERROR; - - Values result; - gttic_(SmartProjectionFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose3,result.at(x3))); - tictoc_print_(); -} - -/* *************************************************************************/ -TEST( SmartProjectionFactor, 3poses_rotation_only_smart_projection_factor ){ - // cout << " ************************ SmartProjectionFactor: 3 cams + 3 landmarks: Rotation Only**********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - // views += x1, x2, x3; - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); - // measurements_cam1 += cam1_uv1, cam2_uv1, cam3_uv1; - - Point2 cam1_uv2 = cam1.project(landmark2); - Point2 cam2_uv2 = cam2.project(landmark2); - Point2 cam3_uv2 = cam3.project(landmark2); - measurements_cam2.push_back(cam1_uv2); - measurements_cam2.push_back(cam2_uv2); - measurements_cam2.push_back(cam3_uv2); - // measurements_cam2 += cam1_uv2, cam2_uv2, cam3_uv2; - - Point2 cam1_uv3 = cam1.project(landmark3); - Point2 cam2_uv3 = cam2.project(landmark3); - Point2 cam3_uv3 = cam3.project(landmark3); - measurements_cam3.push_back(cam1_uv3); - measurements_cam3.push_back(cam2_uv3); - measurements_cam3.push_back(cam3_uv3); - // measurements_cam3 += cam1_uv3, cam2_uv3, cam3_uv3; - - typedef SmartProjectionFactor SmartFactor; - - double rankTol = 10; - - SmartFactor::shared_ptr smartFactor1(new SmartFactor(views, measurements_cam1, noiseProjection, K, rankTol)); - SmartFactor::shared_ptr smartFactor2(new SmartFactor(views, measurements_cam2, noiseProjection, K, rankTol)); - SmartFactor::shared_ptr smartFactor3(new SmartFactor(views, measurements_cam3, noiseProjection, K, rankTol)); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); - Point3 positionPrior = gtsam::Point3(0,0,1); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); - graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose); - values.at(x3).print("Smart: Pose3 before optimization: "); - - LevenbergMarquardtParams params; - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - params.verbosity = NonlinearOptimizerParams::ERROR; - - Values result; - gttic_(SmartProjectionFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose3,result.at(x3))); - tictoc_print_(); -} - - -/* *************************************************************************/ -TEST( SmartProjectionFactor, Hessian ){ - // cout << " ************************ SmartProjectionFactor: Hessian **********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - // views += x1, x2; - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - SimpleCamera cam2(pose2, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - vector measurements_cam1; - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - // measurements_cam1 += cam1_uv1, cam2_uv1; - - SmartProjectionFactor smartFactor(views, measurements_cam1, noiseProjection, K); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // values.insert(L(1), landmark1); - - boost::shared_ptr hessianFactor = smartFactor.linearize(values); - // hessianFactor->print("Hessian factor \n"); - - // compute triangulation from linearization point - // compute reprojection errors (sum squared) - // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) - // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] - -} - - -/* *************************************************************************/ -TEST( SmartProjectionFactor, HessianWithRotation ){ - // cout << " ************************ SmartProjectionFactor: rotated Hessian **********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - // views += x1, x2, x3; - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - SimpleCamera cam3(pose3, *K); - - Point3 landmark1(5, 0.5, 1.2); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); - // measurements_cam1 += cam1_uv1, cam2_uv1, cam3_uv1; - - typedef SmartProjectionFactor SmartFactor; - - SmartFactor::shared_ptr smartFactor(new SmartFactor(noiseProjection, K)); - smartFactor->add(cam1_uv1, views[0]); - smartFactor->add(cam2_uv1, views[1]); - smartFactor->add(cam3_uv1, views[2]); - - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); - - boost::shared_ptr hessianFactor = smartFactor->linearize(values); - // hessianFactor->print("Hessian factor \n"); - - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); - - Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); - - boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); - // hessianFactorRot->print("Hessian factor \n"); - - // Hessian is invariant to rotations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); - - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); - - Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); - - boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); - - // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -} - -/* *************************************************************************/ -TEST( SmartProjectionFactor, HessianWithRotationDegenerate ){ - // cout << " ************************ SmartProjectionFactor: rotated Hessian (degenerate) **********************" << endl; - - Symbol x1('X', 1); - Symbol x2('X', 2); - Symbol x3('X', 3); - - const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - - std::vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - // views += x1, x2, x3; - - Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0,0,0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,0,0)); - SimpleCamera cam3(pose3, *K); - - Point3 landmark1(5, 0.5, 1.2); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); - // measurements_cam1 += cam1_uv1, cam2_uv1, cam3_uv1; - - typedef SmartProjectionFactor SmartFactor; - - SmartFactor::shared_ptr smartFactor(new SmartFactor(noiseProjection, K)); - smartFactor->add(cam1_uv1, views[0]); - smartFactor->add(cam2_uv1, views[1]); - smartFactor->add(cam3_uv1, views[2]); - - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); - - boost::shared_ptr hessianFactor = smartFactor->linearize(values); - // hessianFactor->print("Hessian factor \n"); - - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); - - Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); - - boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); - // hessianFactorRot->print("Hessian factor \n"); - - // Hessian is invariant to rotations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); - - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); - - Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); - - boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); - - // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -} - -#endif - -/* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ - -