diff --git a/gtsam_unstable/examples/SmartProjectionFactorTesting.cpp b/gtsam_unstable/examples/SmartProjectionFactorTesting.cpp new file mode 100644 index 000000000..3421a6d38 --- /dev/null +++ b/gtsam_unstable/examples/SmartProjectionFactorTesting.cpp @@ -0,0 +1,350 @@ +/* ---------------------------------------------------------------------------- + + * 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 SmartProjectionFactorTesting.cpp + * @brief Example usage of SmartProjectionFactor using real datasets + * @date August, 2013 + * @author Luca Carlone + */ + +// Use a map to store landmark/smart factor pairs +#include + +// Both relative poses and recovered trajectory poses will be stored as Pose3 objects +#include +#include +#include + +// Each variable in the system (poses and landmarks) must be identified with a unique key. +// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). +// Here we will use Symbols +#include + +// We want to use iSAM2 to solve the range-SLAM problem incrementally +#include + +// iSAM2 requires as input a set set of new factors to be added stored in a factor graph, +// and initial guesses for any new variables used in the added factors +#include + +// We will use a non-linear solver to batch-initialize from the first 150 frames +#include +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics SLAM problems. +#include +#include +#include + +// Standard headers, added last, so we know headers above work on their own +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; +using namespace boost::assign; +namespace NM = gtsam::noiseModel; + +using symbol_shorthand::X; +using symbol_shorthand::L; + +typedef PriorFactor Pose3Prior; +typedef SmartProjectionFactorsCreator SmartFactorsCreator; +typedef GenericProjectionFactorsCreator ProjectionFactorsCreator; +typedef FastMap OrderingMap; + +bool debug = false; + +// Write key values to file +void writeValues(string directory_, const Values& values){ + string filename = directory_ + "out_camera_poses.txt"; + ofstream fout; + fout.open(filename.c_str()); + fout.precision(20); + + // write out camera poses + BOOST_FOREACH(Values::ConstFiltered::value_type key_value, values.filter()) { + fout << Symbol(key_value.key).index(); + const gtsam::Matrix& matrix= key_value.value.matrix(); + for (size_t row=0; row < 4; ++row) { + for (size_t col=0; col < 4; ++col) { + fout << " " << matrix(row, col); + } + } + fout << endl; + } + fout.close(); + + if(values.filter().size() > 0) { + // write landmarks + filename = directory_ + "landmarks.txt"; + fout.open(filename.c_str()); + + BOOST_FOREACH(Values::ConstFiltered::value_type key_value, values.filter()) { + fout << Symbol(key_value.key).index(); + fout << " " << key_value.value.x(); + fout << " " << key_value.value.y(); + fout << " " << key_value.value.z(); + fout << endl; + } + fout.close(); + + } +} + +void optimizeGraphLM(NonlinearFactorGraph &graph, gtsam::Values::shared_ptr graphValues, Values &result, boost::shared_ptr &ordering) { + // Optimization parameters + LevenbergMarquardtParams params; + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + params.verbosity = NonlinearOptimizerParams::ERROR; + params.lambdaInitial = 1; + params.lambdaFactor = 10; + // Profile a single iteration +// params.maxIterations = 1; + params.maxIterations = 100; + std::cout << " LM max iterations: " << params.maxIterations << std::endl; + // // params.relativeErrorTol = 1e-5; + params.absoluteErrorTol = 1.0; + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + params.verbosity = NonlinearOptimizerParams::ERROR; + params.linearSolverType = SuccessiveLinearizationParams::MULTIFRONTAL_CHOLESKY; + + cout << "Graph size: " << graph.size() << endl; + cout << "Number of variables: " << graphValues->size() << endl; + std::cout << " OPTIMIZATION " << std::endl; + + std::cout << "\n\n=================================================\n\n"; + if (debug) { + graph.print("thegraph"); + } + std::cout << "\n\n=================================================\n\n"; + + if (ordering && ordering->size() > 0) { + if (debug) { + std::cout << "Have an ordering\n" << std::endl; + BOOST_FOREACH(const Key& key, *ordering) { + std::cout << key << " "; + } + std::cout << std::endl; + } + + params.ordering = *ordering; + + //for (int i = 0; i < 3; i++) { + LevenbergMarquardtOptimizer optimizer(graph, *graphValues, params); + gttic_(GenericProjectionFactorExample_kitti); + result = optimizer.optimize(); + gttoc_(GenericProjectionFactorExample_kitti); + tictoc_finishedIteration_(); + //} + } else { + std::cout << "Using COLAMD ordering\n" << std::endl; + //boost::shared_ptr ordering2(new Ordering()); ordering = ordering2; + + //for (int i = 0; i < 3; i++) { + LevenbergMarquardtOptimizer optimizer(graph, *graphValues, params); + params.ordering = Ordering::COLAMD(graph); + gttic_(SmartProjectionFactorExample_kitti); + result = optimizer.optimize(); + gttoc_(SmartProjectionFactorExample_kitti); + tictoc_finishedIteration_(); + //} + + //*ordering = params.ordering; + if (params.ordering) { + std::cout << "Graph size: " << graph.size() << " ORdering: " << params.ordering->size() << std::endl; + ordering = boost::make_shared(*(new Ordering())); + *ordering = *params.ordering; + } else { + std::cout << "WARNING: NULL ordering!" << std::endl; + } + } +} + +void optimizeGraphGN(NonlinearFactorGraph &graph, gtsam::Values::shared_ptr graphValues, Values &result) { + GaussNewtonParams params; + //params.maxIterations = 1; + params.verbosity = NonlinearOptimizerParams::DELTA; + + GaussNewtonOptimizer optimizer(graph, *graphValues, params); + gttic_(SmartProjectionFactorExample_kitti); + result = optimizer.optimize(); + gttoc_(SmartProjectionFactorExample_kitti); + tictoc_finishedIteration_(); + +} + +void optimizeGraphISAM2(NonlinearFactorGraph &graph, gtsam::Values::shared_ptr graphValues, Values &result) { + ISAM2 isam; + gttic_(SmartProjectionFactorExample_kitti); + isam.update(graph, *graphValues); + result = isam.calculateEstimate(); + gttoc_(SmartProjectionFactorExample_kitti); + tictoc_finishedIteration_(); +} + +// main +int main(int argc, char** argv) { + + // unsigned int maxNumLandmarks = 1e+7; + // unsigned int maxNumPoses = 1e+7; + + // Set to true to use SmartProjectionFactor. Otherwise GenericProjectionFactor will be used + bool useSmartProjectionFactor = false; + bool useLM = true; + + double linThreshold = -1.0; // negative is disabled + double rankTolerance = 1.0; + + bool incrementalFlag = false; + int optSkip = 200; // we optimize the graph every optSkip poses + + std::cout << "PARAM SmartFactor: " << useSmartProjectionFactor << std::endl; + std::cout << "PARAM LM: " << useLM << std::endl; + std::cout << "PARAM linThreshold (negative is disabled): " << linThreshold << std::endl; + + // Get home directory and dataset + string HOME = getenv("HOME"); + string input_dir = HOME + "/data/SfM/BAL/Ladybug/"; + string datasetName = "problem-1723-156502-pre.txt"; + + static SharedNoiseModel pixel_sigma(noiseModel::Unit::Create(2)); + NonlinearFactorGraph graphSmart, graphProjection; + + gtsam::Values::shared_ptr graphSmartValues(new gtsam::Values()); + gtsam::Values::shared_ptr graphProjectionValues(new gtsam::Values()); + gtsam::Values::shared_ptr loadedValues(new gtsam::Values()); + + // Read in kitti dataset + ifstream fin; + fin.open((input_dir+datasetName).c_str()); + if(!fin) { + cerr << "Could not open dataset" << endl; + exit(1); + } + + // read all measurements + cout << "Reading dataset... " << endl; + unsigned int numLandmarks = 0, numPoses = 0; + Key r, l; + double u, v; + double x, y, z, rotx, roty, rotz, f, k1, k2; + std::vector landmarkKeys, cameraPoseKeys; + Values result; + bool optimized = false; + boost::shared_ptr ordering(new Ordering()); + + // std::vector< boost::shared_ptr > K_cameras; // TODO: uncomment + Cal3_S2::shared_ptr K(new Cal3_S2(1, 1, 0, 0, 0)); + + // boost::shared_ptr Kbund(new Cal3Bundler());// TODO: uncomment + + SmartFactorsCreator smartCreator(pixel_sigma, K, rankTolerance, linThreshold); + ProjectionFactorsCreator projectionCreator(pixel_sigma, K); + + // main loop: reads measurements and adds factors (also performs optimization if desired) + // r >> pose id + // l >> landmark id + // (u >> u) >> measurement + unsigned int totNumLandmarks=0, totNumPoses=0, totNumMeasurements=0; + fin >> totNumPoses >> totNumPoses >> totNumMeasurements; + + std::vector vector_u; + std::vector vector_v; + std::vector vector_r; + std::vector vector_l; + + // read measurements + for(unsigned int i = 0; i < totNumMeasurements; i++){ + fin >> r >> l >> u >> v; + vector_u.push_back(u); + vector_v.push_back(v); + vector_r.push_back(r); + vector_l.push_back(l); + } + + // create values + for(unsigned int i = 0; i < totNumPoses; i++){ + // R,t,f,k1 and k2. + fin >> x >> y >> z >> rotx >> roty >> rotz >> f >> k1 >> k2; + // boost::shared_ptr Kbundler(new Cal3Bundler(f, k1, k2, 0.0, 0.0)); // TODO: uncomment + // K_cameras.push_back(Kbundler); // TODO: uncomment + Vector3 rotVect(rotx,roty,rotz); + loadedValues->insert(Symbol('x',i), Pose3(Rot3::Expmap(rotVect), Point3(x,y,z) ) ); + } + + // add landmarks in standard projection factors + if(!useSmartProjectionFactor){ + for(unsigned int i = 0; i < totNumLandmarks; i++){ + fin >> x >> y >> z; + loadedValues->insert(Symbol('l',i), Point3(x,y,z) ); + } + } + + // 1: add values and factors to the graph + // 1.1: add factors + // SMART FACTORS .. + for(size_t i = 0; i < vector_u.size(); i++){ + l = vector_l.at(i); + r = vector_r.at(i); + u = vector_u.at(i); + v = vector_v.at(i); + + if (useSmartProjectionFactor) { + + smartCreator.add(L(l), X(r), Point2(u,v), graphSmart); + numLandmarks = smartCreator.getNumLandmarks(); + + // Add initial pose value if pose does not exist + if (!graphSmartValues->exists(X(r)) && loadedValues->exists(X(r))) { + graphSmartValues->insert(X(r), loadedValues->at(X(r))); + numPoses++; + optimized = false; + } + + } else { + // or STANDARD PROJECTION FACTORS + projectionCreator.add(L(l), X(r), Point2(u,v), pixel_sigma, K, graphProjection); + numLandmarks = projectionCreator.getNumLandmarks(); + optimized = false; + } + } + + if (!useSmartProjectionFactor) { + projectionCreator.update(graphProjection, loadedValues, graphProjectionValues); + ordering = projectionCreator.getOrdering(); + } + + if (useSmartProjectionFactor) { + if (useLM) + optimizeGraphLM(graphSmart, graphSmartValues, result, ordering); + else + optimizeGraphISAM2(graphSmart, graphSmartValues, result); + } else { + if (useLM) + optimizeGraphLM(graphProjection, graphProjectionValues, result, ordering); + else + optimizeGraphISAM2(graphSmart, graphSmartValues, result); + } + // *graphSmartValues = result; // we use optimized solution as initial guess for the next one + + optimized = true; + + writeValues("./", result); + + // if (1||debug) fprintf(stderr,"%d: %d > %d, %d > %d\n", count, numLandmarks, maxNumLandmarks, numPoses, maxNumPoses); + exit(0); +} diff --git a/gtsam_unstable/slam/GenericProjectionFactorsCreator.h b/gtsam_unstable/slam/GenericProjectionFactorsCreator.h index e31d513d9..baa79ff82 100644 --- a/gtsam_unstable/slam/GenericProjectionFactorsCreator.h +++ b/gtsam_unstable/slam/GenericProjectionFactorsCreator.h @@ -21,7 +21,7 @@ #include - +#include //#include //#include //#include @@ -80,6 +80,43 @@ namespace gtsam { } } + void add(Key landmarkKey, + Key poseKey, Point2 measurement, + const SharedNoiseModel& model, + const boost::shared_ptr& K, + NonlinearFactorGraph &graph) { + bool debug = false; + + // Create projection factor + ProjectionFactor::shared_ptr projectionFactor(new ProjectionFactor(measurement, model, poseKey, landmarkKey, K)); + + // Check if landmark exists in mapping + ProjectionFactorMap::iterator pfit = projectionFactors.find(landmarkKey); + if (pfit != projectionFactors.end()) { + if (debug) fprintf(stderr,"Adding measurement to existing landmark\n"); + + // Add projection factor to list of projection factors associated with this landmark + (*pfit).second.push_back(projectionFactor); + + } else { + if (debug) fprintf(stderr,"New landmark (%d)\n", pfit != projectionFactors.end()); + + // Create a new vector of projection factors + std::vector projectionFactorVector; + projectionFactorVector.push_back(projectionFactor); + + // Insert projection factor to NEW list of projection factors associated with this landmark + projectionFactors.insert( std::make_pair(landmarkKey, projectionFactorVector) ); + + // Add projection factor to graph + //graph.push_back(projectionFactor); + + // We have a new landmark + numLandmarks++; + landmarkKeys.push_back( landmarkKey ); + } + } + void update(NonlinearFactorGraph &graph, gtsam::Values::shared_ptr inputValues, gtsam::Values::shared_ptr outputValues) { addTriangulatedLandmarks(graph, inputValues, outputValues); updateOrdering(graph); diff --git a/gtsam_unstable/slam/SmartProjectionHessianFactor.h b/gtsam_unstable/slam/SmartProjectionHessianFactor.h index 5e175e307..0d6fe551b 100644 --- a/gtsam_unstable/slam/SmartProjectionHessianFactor.h +++ b/gtsam_unstable/slam/SmartProjectionHessianFactor.h @@ -21,6 +21,7 @@ #include #include +#include #include #include #include diff --git a/gtsam_unstable/slam/tests/testSmartProjectionHessianFactor.cpp b/gtsam_unstable/slam/tests/testSmartProjectionHessianFactor.cpp index 1361033b3..70dd0a4a8 100644 --- a/gtsam_unstable/slam/tests/testSmartProjectionHessianFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartProjectionHessianFactor.cpp @@ -38,7 +38,9 @@ #include #include #include +#include #include +#include #include @@ -70,11 +72,10 @@ Symbol x2('X', 2); Symbol x3('X', 3); static Key poseKey1(x1); -static Key poseKey2(x2); static Point2 measurement1(323.0, 240.0); static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); -typedef SmartProjectionHessianFactor SmartFactor; +typedef SmartProjectionHessianFactor SmartFactor; /* ************************************************************************* */ TEST( SmartProjectionHessianFactor, Constructor) { @@ -836,6 +837,109 @@ TEST( SmartProjectionHessianFactor, HessianWithRotationDegenerate ){ EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); } +/* ************************************************************************* */ +//TEST( SmartProjectionHessianFactor, ConstructorWithCal3Bundler) { +// SmartProjectionHessianFactor factor1(rankTol, linThreshold); +// Cal3Bundler Kbundler(500, 1e-3, 1e-3, 1000, 2000); +// factor1.add(measurement1, poseKey1, model, boost::shared_ptr &Kbundler); +//} + +/* *************************************************************************/ +//TEST( SmartProjectionHessianFactor, Cal3Bundler ){ +// // cout << " ************************ SmartProjectionHessianFactor: Cal3Bundler **********************" << endl; +// +// Cal3Bundler Kbundler(500, 1e-3, 1e-3, 1000, 2000); +// +// // 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)); +// PinholeCamera cam1(pose1, Kbundler); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// PinholeCamera cam2(pose2, Kbundler); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// PinholeCamera cam3(pose3, Kbundler); +// +// // 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); +// +// 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); +// +// 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); +// +// std::vector views; +// views.push_back(x1); +// views.push_back(x2); +// views.push_back(x3); + +// SmartProjectionHessianFactor::shared_ptr smartFactor1(new SmartFactor()); +// smartFactor1->add(measurements_cam1, views, model, &Kbundler); +// +// SmartProjectionHessianFactor::shared_ptr smartFactor2(new SmartFactor()); +// smartFactor2->add(measurements_cam2, views, model, &Kbundler); +// +// SmartProjectionHessianFactor::shared_ptr smartFactor3(new SmartFactor()); +// smartFactor3->add(measurements_cam3, views, model, &Kbundler); +// +// 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); +// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); +// +// LevenbergMarquardtParams params; +// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; +// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; +// +// Values result; +// gttic_(SmartProjectionHessianFactor); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartProjectionHessianFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// EXPECT(assert_equal(pose3,result.at(x3))); +// if(isDebugTest) tictoc_print_(); +// } + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); }