From 6365dbaba58bcfb59011af3334543417ec94d915 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 14:03:13 +0100 Subject: [PATCH 001/173] Moved from smartfactors_ceres --- timing/DummyFactor.h | 56 +++++++++++++ timing/timeSchurFactors.cpp | 152 ++++++++++++++++++++++++++++++++++++ 2 files changed, 208 insertions(+) create mode 100644 timing/DummyFactor.h create mode 100644 timing/timeSchurFactors.cpp diff --git a/timing/DummyFactor.h b/timing/DummyFactor.h new file mode 100644 index 000000000..ff9732909 --- /dev/null +++ b/timing/DummyFactor.h @@ -0,0 +1,56 @@ +/** + * @file DummyFactor.h + * @brief Just to help in timing overhead + * @author Frank Dellaert + */ + +#pragma once + +#include + +namespace gtsam { + +/** + * DummyFactor + */ +template // +class DummyFactor: public RegularImplicitSchurFactor { + +public: + + typedef Eigen::Matrix Matrix2D; + typedef std::pair KeyMatrix2D; + + DummyFactor() { + } + + DummyFactor(const std::vector& Fblocks, const Matrix& E, + const Matrix3& P, const Vector& b) :RegularImplicitSchurFactor(Fblocks,E,P,b) + { + } + + virtual ~DummyFactor() { + } + +public: + + /** + * @brief Dummy version to measure overhead of key access + */ + void multiplyHessian(double alpha, const VectorValues& x, + VectorValues& y) const { + + BOOST_FOREACH(const KeyMatrix2D& Fi, this->Fblocks_) { + static const Vector empty; + Key key = Fi.first; + std::pair it = y.tryInsert(key, empty); + Vector& yi = it.first->second; + yi = x.at(key); + } + } + +}; +// DummyFactor + +} + diff --git a/timing/timeSchurFactors.cpp b/timing/timeSchurFactors.cpp new file mode 100644 index 000000000..06a526567 --- /dev/null +++ b/timing/timeSchurFactors.cpp @@ -0,0 +1,152 @@ +/** + * @file timeSchurFactors.cpp + * @brief Time various Schur-complement Jacobian factors + * @author Frank Dellaert + * @date Oct 27, 2013 + */ + +#include "DummyFactor.h" +#include + +#include +#include "gtsam/slam/JacobianFactorQR.h" +#include + +#include +#include +#include + +using namespace std; +using namespace boost::assign; +using namespace gtsam; + +#define SLOW +#define RAW +#define HESSIAN +#define NUM_ITERATIONS 1000 + +// Create CSV file for results +ofstream os("timeSchurFactors.csv"); + +/*************************************************************************************/ +template +void timeAll(size_t m, size_t N) { + + cout << m << endl; + + // create F + typedef Eigen::Matrix Matrix2D; + typedef pair KeyMatrix2D; + vector < pair > Fblocks; + for (size_t i = 0; i < m; i++) + Fblocks.push_back(KeyMatrix2D(i, (i + 1) * Matrix::Ones(2, D))); + + // create E + Matrix E(2 * m, 3); + for (size_t i = 0; i < m; i++) + E.block < 2, 3 > (2 * i, 0) = Matrix::Ones(2, 3); + + // Calculate point covariance + Matrix P = (E.transpose() * E).inverse(); + + // RHS and sigmas + const Vector b = gtsam::repeat(2 * m, 1); + const SharedDiagonal model; + + // parameters for multiplyHessianAdd + double alpha = 0.5; + VectorValues xvalues, yvalues; + for (size_t i = 0; i < m; i++) + xvalues.insert(i, gtsam::repeat(D, 2)); + + // Implicit + RegularImplicitSchurFactor implicitFactor(Fblocks, E, P, b); + // JacobianFactor with same error + JacobianFactorQ jf(Fblocks, E, P, b, model); + // JacobianFactorQR with same error + JacobianFactorQR jqr(Fblocks, E, P, b, model); + // Hessian + HessianFactor hessianFactor(jqr); + +#define TIME(label,factor,xx,yy) {\ + for (size_t t = 0; t < N; t++) \ + factor.multiplyHessianAdd(alpha, xx, yy);\ + gttic_(label);\ + for (size_t t = 0; t < N; t++) {\ + factor.multiplyHessianAdd(alpha, xx, yy);\ + }\ + gttoc_(label);\ + tictoc_getNode(timer, label)\ + os << timer->secs()/NUM_ITERATIONS << ", ";\ + } + +#ifdef SLOW + TIME(Implicit, implicitFactor, xvalues, yvalues) + TIME(Jacobian, jf, xvalues, yvalues) + TIME(JacobianQR, jqr, xvalues, yvalues) +#endif + +#ifdef HESSIAN + TIME(Hessian, hessianFactor, xvalues, yvalues) +#endif + +#ifdef OVERHEAD + DummyFactor dummy(Fblocks, E, P, b); + TIME(Overhead,dummy,xvalues,yvalues) +#endif + +#ifdef RAW + { // Raw memory Version + FastVector < Key > keys; + for (size_t i = 0; i < m; i++) + keys += i; + Vector x = xvalues.vector(keys); + double* xdata = x.data(); + + // create a y + Vector y = zero(m * D); + TIME(RawImplicit, implicitFactor, xdata, y.data()) + TIME(RawJacobianQ, jf, xdata, y.data()) + TIME(RawJacobianQR, jqr, xdata, y.data()) + } +#endif + + os << m << endl; + +} // timeAll + +/*************************************************************************************/ +int main(void) { +#ifdef SLOW + os << "Implicit,"; + os << "JacobianQ,"; + os << "JacobianQR,"; +#endif +#ifdef HESSIAN + os << "Hessian,"; +#endif +#ifdef OVERHEAD + os << "Overhead,"; +#endif +#ifdef RAW + os << "RawImplicit,"; + os << "RawJacobianQ,"; + os << "RawJacobianQR,"; +#endif + os << "m" << endl; + // define images + vector < size_t > ms; + // ms += 2; + // ms += 3, 4, 5, 6, 7, 8, 9, 10; + // ms += 11,12,13,14,15,16,17,18,19; + // ms += 20, 30, 40, 50; + // ms += 20,30,40,50,60,70,80,90,100; + for (size_t m = 2; m <= 50; m += 2) + ms += m; + //for (size_t m=10;m<=100;m+=10) ms += m; + // loop over number of images + BOOST_FOREACH(size_t m,ms) + timeAll<6>(m, NUM_ITERATIONS); +} + +//************************************************************************************* From 7bc0a9df5ba65a2cbbf8bf2a3ebea14779d2bc21 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 15:32:05 +0100 Subject: [PATCH 002/173] Moved regular factors (except implicit) to linear (they are not SLAM-specific) --- .cproject | 24 +++++++++++++++++++ gtsam/{slam => linear}/RegularHessianFactor.h | 0 .../{slam => linear}/RegularJacobianFactor.h | 0 .../tests/testRegularHessianFactor.cpp | 2 +- .../tests/testRegularJacobianFactor.cpp | 2 +- gtsam/slam/JacobianFactorQ.h | 2 +- gtsam/slam/JacobianFactorQR.h | 2 +- gtsam/slam/JacobianFactorSVD.h | 2 +- gtsam/slam/SmartFactorBase.h | 3 ++- 9 files changed, 31 insertions(+), 6 deletions(-) rename gtsam/{slam => linear}/RegularHessianFactor.h (100%) rename gtsam/{slam => linear}/RegularJacobianFactor.h (100%) rename gtsam/{slam => linear}/tests/testRegularHessianFactor.cpp (98%) rename gtsam/{slam => linear}/tests/testRegularJacobianFactor.cpp (99%) diff --git a/.cproject b/.cproject index 19d3912b0..acb0ea910 100644 --- a/.cproject +++ b/.cproject @@ -2455,6 +2455,14 @@ true true + + make + -j4 + SFMExample_SmartFactorPCG.run + true + true + true + make -j2 @@ -3047,6 +3055,22 @@ true true + + make + -j4 + testRegularHessianFactor.run + true + true + true + + + make + -j4 + testRegularJacobianFactor.run + true + true + true + make -j5 diff --git a/gtsam/slam/RegularHessianFactor.h b/gtsam/linear/RegularHessianFactor.h similarity index 100% rename from gtsam/slam/RegularHessianFactor.h rename to gtsam/linear/RegularHessianFactor.h diff --git a/gtsam/slam/RegularJacobianFactor.h b/gtsam/linear/RegularJacobianFactor.h similarity index 100% rename from gtsam/slam/RegularJacobianFactor.h rename to gtsam/linear/RegularJacobianFactor.h diff --git a/gtsam/slam/tests/testRegularHessianFactor.cpp b/gtsam/linear/tests/testRegularHessianFactor.cpp similarity index 98% rename from gtsam/slam/tests/testRegularHessianFactor.cpp rename to gtsam/linear/tests/testRegularHessianFactor.cpp index e2b8ac3cf..07f5b5e42 100644 --- a/gtsam/slam/tests/testRegularHessianFactor.cpp +++ b/gtsam/linear/tests/testRegularHessianFactor.cpp @@ -15,7 +15,7 @@ * @date March 4, 2014 */ -#include +#include #include #include diff --git a/gtsam/slam/tests/testRegularJacobianFactor.cpp b/gtsam/linear/tests/testRegularJacobianFactor.cpp similarity index 99% rename from gtsam/slam/tests/testRegularJacobianFactor.cpp rename to gtsam/linear/tests/testRegularJacobianFactor.cpp index 5803516a1..b8c4aa689 100644 --- a/gtsam/slam/tests/testRegularJacobianFactor.cpp +++ b/gtsam/linear/tests/testRegularJacobianFactor.cpp @@ -16,7 +16,7 @@ * @date Nov 12, 2014 */ -#include +#include #include #include #include diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index ed6213058..5e8693541 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -17,7 +17,7 @@ #pragma once -#include "RegularJacobianFactor.h" +#include namespace gtsam { /** diff --git a/gtsam/slam/JacobianFactorQR.h b/gtsam/slam/JacobianFactorQR.h index 4c1b0ff14..9c3f8be4a 100644 --- a/gtsam/slam/JacobianFactorQR.h +++ b/gtsam/slam/JacobianFactorQR.h @@ -6,9 +6,9 @@ */ #pragma once -#include #include #include +#include namespace gtsam { diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index b4389d681..255c799a6 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -5,7 +5,7 @@ */ #pragma once -#include "gtsam/slam/RegularJacobianFactor.h" +#include namespace gtsam { /** diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a2bdfc059..8cbc2f73c 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -22,9 +22,9 @@ #include #include #include -#include #include +#include #include #include @@ -55,6 +55,7 @@ protected: */ std::vector measured_; + //SharedIsotropic noiseModel_; std::vector noise_; ///< noise model used boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) From ad6293848e6112577621366a436bc375cc563b25 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 17:09:05 +0100 Subject: [PATCH 003/173] Moved from smartfactors_ceres --- .cproject | 16 + gtsam/slam/SmartProjectionCameraFactor.h | 164 +++ .../tests/testSmartProjectionCameraFactor.cpp | 1009 +++++++++++++++++ 3 files changed, 1189 insertions(+) create mode 100644 gtsam/slam/SmartProjectionCameraFactor.h create mode 100644 gtsam/slam/tests/testSmartProjectionCameraFactor.cpp diff --git a/.cproject b/.cproject index acb0ea910..8783ebc31 100644 --- a/.cproject +++ b/.cproject @@ -1554,6 +1554,22 @@ true true + + make + -j4 + testSmartProjectionCameraFactor.run + true + true + true + + + make + -j4 + testSmartFactorBase.run + true + true + true + make -j3 diff --git a/gtsam/slam/SmartProjectionCameraFactor.h b/gtsam/slam/SmartProjectionCameraFactor.h new file mode 100644 index 000000000..d5bdc2e84 --- /dev/null +++ b/gtsam/slam/SmartProjectionCameraFactor.h @@ -0,0 +1,164 @@ +/* ---------------------------------------------------------------------------- + + * 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 SmartProjectionCameraFactor.h + * @brief Produces an Hessian factors on CAMERAS (Pose3+CALIBRATION) from monocular measurements of a landmark + * @author Luca Carlone + * @author Chris Beall + * @author Zsolt Kira + */ + +#pragma once +#include + +namespace gtsam { + +/** + * @addtogroup SLAM + */ +template +class SmartProjectionCameraFactor: public SmartProjectionFactor { +protected: + + bool isImplicit_; + +public: + + /// shorthand for base class type + typedef SmartProjectionFactor Base; + + /// shorthand for this class + typedef SmartProjectionCameraFactor This; + + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** + * Constructor + * @param rankTol tolerance used to check if point triangulation is degenerate + * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) + * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, + * otherwise the factor is simply neglected + * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations + * @param isImplicit if set to true linearize the factor to an implicit Schur factor + * @param body_P_sensor is the transform from body to sensor frame (default identity) + */ + SmartProjectionCameraFactor(const double rankTol = 1, + const double linThreshold = -1, const bool manageDegeneracy = false, + const bool enableEPI = false, const bool isImplicit = false, + boost::optional body_P_sensor = boost::none) : + Base(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor), isImplicit_( + isImplicit) { + if (linThreshold != -1) { + std::cout << "SmartProjectionCameraFactor: linThreshold " + << linThreshold << std::endl; + } + } + + /** Virtual destructor */ + virtual ~SmartProjectionCameraFactor() { + } + + /** + * print + * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols + */ + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const { + std::cout << s << "SmartProjectionCameraFactor, z = \n "; + Base::print("", keyFormatter); + } + + /// equals + virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + const This *e = dynamic_cast(&p); + + return e && Base::equals(p, tol); + } + + /// get the dimension of the factor (number of rows on linearization) + virtual size_t dim() const { + return D * this->keys_.size(); // 6 for the pose and 3 for the calibration + } + + /// Collect all cameras: important that in key order + typename Base::Cameras cameras(const Values& values) const { + typename Base::Cameras cameras; + BOOST_FOREACH(const Key& k, this->keys_) + cameras.push_back(values.at(k)); + return cameras; + } + + /// linearize and adds damping on the points + boost::shared_ptr linearizeDamped(const Values& values, + const double lambda=0.0) const { + if (!isImplicit_) + return Base::createHessianFactor(cameras(values), lambda); + else + return Base::createRegularImplicitSchurFactor(cameras(values)); + } + + /// linearize returns a Hessianfactor that is an approximation of error(p) + virtual boost::shared_ptr > linearizeToHessian( + const Values& values, double lambda=0.0) const { + return Base::createHessianFactor(cameras(values),lambda); + } + + /// linearize returns a Hessianfactor that is an approximation of error(p) + virtual boost::shared_ptr > linearizeToImplicit( + const Values& values, double lambda=0.0) const { + return Base::createRegularImplicitSchurFactor(cameras(values),lambda); + } + + /// linearize returns a Jacobianfactor that is an approximation of error(p) + virtual boost::shared_ptr > linearizeToJacobian( + const Values& values, double lambda=0.0) const { + return Base::createJacobianQFactor(cameras(values),lambda); + } + + /// linearize returns a Hessianfactor that is an approximation of error(p) + virtual boost::shared_ptr linearizeWithLambda( + const Values& values, double lambda) const { + if (isImplicit_) + return linearizeToImplicit(values,lambda); + else + return linearizeToHessian(values,lambda); + } + + /// linearize returns a Hessianfactor that is an approximation of error(p) + virtual boost::shared_ptr linearize( + const Values& values) const { + return linearizeWithLambda(values,0.0); + } + + /// Calculare total reprojection error + virtual double error(const Values& values) const { + if (this->active(values)) { + return Base::totalReprojectionError(cameras(values)); + } else { // else of active flag + return 0.0; + } + } + +private: + + /// Serialization function + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + } + +}; + +} // \ namespace gtsam diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp new file mode 100644 index 000000000..88a0c0521 --- /dev/null +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -0,0 +1,1009 @@ +/* ---------------------------------------------------------------------------- + + * 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 testSmartProjectionCameraFactor.cpp + * @brief Unit tests for SmartProjectionCameraFactor Class + * @author Chris Beall + * @author Luca Carlone + * @author Zsolt Kira + * @date Sept 2013 + */ + +//#include "BundlerDefinitions.h" +#include +//#include "../SmartFactorsTestProblems.h" +//#include "../LevenbergMarquardtOptimizerCERES.h" + +#include +#include +#include +#include +#include +#include + +//#include "../SmartNonlinearFactorGraph.h" +#undef CHECK +#include +#include + +using namespace std; +using namespace boost::assign; +using namespace gtsam; + +typedef PinholeCamera Camera; + +static bool isDebugTest = false; + +// 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)); +static Cal3_S2::shared_ptr K2(new Cal3_S2(1500, 1200, 0, 640, 480)); +static boost::shared_ptr Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 0, 0)); + +static double rankTol = 1.0; +static double linThreshold = -1.0; + +// 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; + +// tests data +Key x1 = 1; + +Symbol l1('l', 1), l2('l', 2), l3('l', 3); +Key c1 = 1, c2 = 2, c3 = 3; + +static Key poseKey1(x1); +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 PinholeCamera CameraCal3_S2; +typedef SmartProjectionCameraFactor SmartFactor; +typedef SmartProjectionCameraFactor SmartFactorBundler; +typedef GeneralSFMFactor SFMFactor; + +template +PinholeCamera perturbCameraPose( + const PinholeCamera& camera) { + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 cameraPose = camera.pose(); + Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); + return PinholeCamera(perturbedCameraPose, camera.calibration()); +} + +template +PinholeCamera perturbCameraPoseAndCalibration( + const PinholeCamera& camera) { + GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 cameraPose = camera.pose(); + Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); + typename gtsam::traits::TangentVector d; + d.setRandom(); d*=0.1; + CALIBRATION perturbedCalibration = camera.calibration().retract(d); + return PinholeCamera(perturbedCameraPose, perturbedCalibration); +} + +template +void projectToMultipleCameras(const PinholeCamera& cam1, + const PinholeCamera& cam2, + const PinholeCamera& cam3, Point3 landmark, + vector& measurements_cam) { + Point2 cam1_uv1 = cam1.project(landmark); + Point2 cam2_uv1 = cam2.project(landmark); + Point2 cam3_uv1 = cam3.project(landmark); + measurements_cam.push_back(cam1_uv1); + measurements_cam.push_back(cam2_uv1); + measurements_cam.push_back(cam3_uv1); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, perturbCameraPose) { + // 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), Point3(0,0,1)); + CameraCal3_S2 level_camera(level_pose, *K2); + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); + Pose3 perturbed_level_pose = level_pose.compose(noise_pose); + CameraCal3_S2 actualCamera(perturbed_level_pose, *K2); + + CameraCal3_S2 expectedCamera = perturbCameraPose(level_camera); + CHECK(assert_equal(expectedCamera, actualCamera)); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor) { + SmartFactor::shared_ptr factor1(new SmartFactor()); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor2) { + SmartFactor factor1(rankTol, linThreshold); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor3) { + SmartFactor::shared_ptr factor1(new SmartFactor()); + factor1->add(measurement1, poseKey1, model); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor4) { + SmartFactor factor1(rankTol, linThreshold); + factor1.add(measurement1, poseKey1, model); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, ConstructorWithTransform) { + bool manageDegeneracy = true; + bool isImplicit = false; + bool enableEPI = false; + SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, isImplicit, enableEPI, body_P_sensor1); + factor1.add(measurement1, poseKey1, model); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Equals ) { + SmartFactor::shared_ptr factor1(new SmartFactor()); + factor1->add(measurement1, poseKey1, model); + + SmartFactor::shared_ptr factor2(new SmartFactor()); + factor2->add(measurement1, poseKey1, model); + //CHECK(assert_equal(*factor1, *factor2)); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, noiseless ){ + // cout << " ************************ SmartProjectionCameraFactor: noisy ****************************" << endl; + + // 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), Point3(0,0,1)); + CameraCal3_S2 level_camera(level_pose, *K2); + + // create second camera 1 meter to the right of first camera + Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); + CameraCal3_S2 level_camera_right(level_pose_right, *K2); + + // landmark ~5 meters infront of camera + Point3 landmark(5, 0.5, 1.2); + + // 1. Project two landmarks into two cameras and triangulate + Point2 level_uv = level_camera.project(landmark); + Point2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + SmartFactor::shared_ptr factor1(new SmartFactor()); + factor1->add(level_uv, c1, model); + factor1->add(level_uv_right, c2, model); + + double actualError = factor1->error(values); + + double expectedError = 0.0; + DOUBLES_EQUAL(expectedError, actualError, 1e-7); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, noiselessBundler ){ + + // 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), Point3(0,0,1)); + Camera level_camera(level_pose, *Kbundler); + + // create second camera 1 meter to the right of first camera + Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); + Camera level_camera_right(level_pose_right, *Kbundler); + + // landmark ~5 meters infront of camera + Point3 landmark(5, 0.5, 1.2); + + // 1. Project two landmarks into two cameras and triangulate + Point2 level_uv = level_camera.project(landmark); + Point2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + factor1->add(level_uv, c1, model); + factor1->add(level_uv_right, c2, model); + + double actualError = factor1->error(values); + + double expectedError = 0.0; + DOUBLES_EQUAL(expectedError, actualError, 1e-3); + + Point3 oldPoint; // this takes the point stored in the factor (we are not interested in this) + if(factor1->point()) + oldPoint = *(factor1->point()); + + Point3 expectedPoint; + if(factor1->point(values)) + expectedPoint = *(factor1->point(values)); + + EXPECT(assert_equal(expectedPoint,landmark, 1e-3)); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, noisy ){ + + // 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), Point3(0,0,1)); + CameraCal3_S2 level_camera(level_pose, *K2); + + // create second camera 1 meter to the right of first camera + Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); + CameraCal3_S2 level_camera_right(level_pose_right, *K2); + + // 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(c1, level_camera); + CameraCal3_S2 perturbed_level_camera_right = perturbCameraPose(level_camera_right); + values.insert(c2, perturbed_level_camera_right); + + SmartFactor::shared_ptr factor1(new SmartFactor()); + factor1->add(level_uv, c1, model); + factor1->add(level_uv_right, c2, model); + + double actualError1= factor1->error(values); + + SmartFactor::shared_ptr factor2(new SmartFactor()); + vector measurements; + measurements.push_back(level_uv); + measurements.push_back(level_uv_right); + + vector< SharedNoiseModel > noises; + noises.push_back(model); + noises.push_back(model); + + vector views; + views.push_back(c1); + views.push_back(c2); + + factor2->add(measurements, views, noises); + + double actualError2= factor2->error(values); + + DOUBLES_EQUAL(actualError1, actualError2, 1e-7); +} + + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ){ + + // 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), Point3(0,0,1)); + CameraCal3_S2 cam1(pose1, *K2); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + CameraCal3_S2 cam2(pose2, *K2); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + CameraCal3_S2 cam3(pose3, *K2); + + // 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 + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + smartFactor1->add(measurements_cam1, views, model); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + smartFactor2->add(measurements_cam2, views, model); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + smartFactor3->add(measurements_cam3, views, model); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6+5, 1e-5); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + values.insert(c3, perturbCameraPose(cam3)); + if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams params; + if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + gttic_(SmartProjectionCameraFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartProjectionCameraFactor); + tictoc_finishedIteration_(); + + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + // VectorValues delta = GFG->optimize(); + + if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1,result.at(c1))); + EXPECT(assert_equal(cam2,result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if(isDebugTest) tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ){ + + // 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), Point3(0,0,1)); + CameraCal3_S2 cam1(pose1, *K2); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + CameraCal3_S2 cam2(pose2, *K2); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + CameraCal3_S2 cam3(pose3, *K2); + + // 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 + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SfM_Track track1; + for(size_t i=0;i<3;++i){ + SfM_Measurement measures; + measures.first = i+1;// cameras are from 1 to 3 + measures.second = measurements_cam1.at(i); + track1.measurements.push_back(measures); + } + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + smartFactor1->add(track1, model); + + SfM_Track track2; + for(size_t i=0;i<3;++i){ + SfM_Measurement measures; + measures.first = i+1;// cameras are from 1 to 3 + measures.second = measurements_cam2.at(i); + track2.measurements.push_back(measures); + } + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + smartFactor2->add(track2, model); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + smartFactor3->add(measurements_cam3, views, model); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6+5, 1e-5); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + values.insert(c3, perturbCameraPose(cam3)); + if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams params; + if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + gttic_(SmartProjectionCameraFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartProjectionCameraFactor); + tictoc_finishedIteration_(); + + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + // VectorValues delta = GFG->optimize(); + + if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1,result.at(c1))); + EXPECT(assert_equal(cam2,result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if(isDebugTest) tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ){ + + // 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), Point3(0,0,1)); + CameraCal3_S2 cam1(pose1, *K2); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + CameraCal3_S2 cam2(pose2, *K2); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + CameraCal3_S2 cam3(pose3, *K2); + + // 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); + Point3 landmark4(10, 0.5, 1.2); + Point3 landmark5(10, -0.5, 1.2); + + vector measurements_cam1, measurements_cam2, measurements_cam3, + measurements_cam4, measurements_cam5; + + // 1. Project three landmarks into three cameras and triangulate + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); + projectToMultipleCameras(cam1, cam2, cam3, landmark5, measurements_cam5); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + smartFactor1->add(measurements_cam1, views, model); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + smartFactor2->add(measurements_cam2, views, model); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + smartFactor3->add(measurements_cam3, views, model); + + SmartFactor::shared_ptr smartFactor4(new SmartFactor()); + smartFactor4->add(measurements_cam4, views, model); + + SmartFactor::shared_ptr smartFactor5(new SmartFactor()); + smartFactor5->add(measurements_cam5, views, model); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6+5, 1e-5); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(smartFactor4); + graph.push_back(smartFactor5); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + values.insert(c3, perturbCameraPoseAndCalibration(cam3)); + if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams params; + params.relativeErrorTol = 1e-8; + params.absoluteErrorTol = 0; + params.maxIterations = 20; + if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + gttic_(SmartProjectionCameraFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartProjectionCameraFactor); + tictoc_finishedIteration_(); + + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + // VectorValues delta = GFG->optimize(); + + if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1,result.at(c1))); + EXPECT(assert_equal(cam2,result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 20)); + if(isDebugTest) tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, Cal3Bundler ){ + + // 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), Point3(0,0,1)); + Camera cam1(pose1, *Kbundler); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + Camera cam2(pose2, *Kbundler); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + Camera 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); + Point3 landmark4(10, 0.5, 1.2); + Point3 landmark5(10, -0.5, 1.2); + + vector measurements_cam1, measurements_cam2, measurements_cam3, + measurements_cam4, measurements_cam5; + + // 1. Project three landmarks into three cameras and triangulate + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); + projectToMultipleCameras(cam1, cam2, cam3, landmark5, measurements_cam5); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); + smartFactor1->add(measurements_cam1, views, model); + + SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); + smartFactor2->add(measurements_cam2, views, model); + + SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); + smartFactor3->add(measurements_cam3, views, model); + + SmartFactorBundler::shared_ptr smartFactor4(new SmartFactorBundler()); + smartFactor4->add(measurements_cam4, views, model); + + SmartFactorBundler::shared_ptr smartFactor5(new SmartFactorBundler()); + smartFactor5->add(measurements_cam5, views, model); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(c3, perturbCameraPose(cam3)); + if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams params; + params.relativeErrorTol = 1e-8; + params.absoluteErrorTol = 0; + params.maxIterations = 20; + if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + gttic_(SmartProjectionCameraFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartProjectionCameraFactor); + tictoc_finishedIteration_(); + + if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1,result.at(c1), 1e-4)); + EXPECT(assert_equal(cam2,result.at(c2), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 1)); + if(isDebugTest) tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, Cal3Bundler2 ){ + + // 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), Point3(0,0,1)); + Camera cam1(pose1, *Kbundler); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + Camera cam2(pose2, *Kbundler); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + Camera 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); + Point3 landmark4(10, 0.5, 1.2); + Point3 landmark5(10, -0.5, 1.2); + + vector measurements_cam1, measurements_cam2, measurements_cam3, + measurements_cam4, measurements_cam5; + + // 1. Project three landmarks into three cameras and triangulate + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); + projectToMultipleCameras(cam1, cam2, cam3, landmark5, measurements_cam5); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); + smartFactor1->add(measurements_cam1, views, model); + + SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); + smartFactor2->add(measurements_cam2, views, model); + + SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); + smartFactor3->add(measurements_cam3, views, model); + + SmartFactorBundler::shared_ptr smartFactor4(new SmartFactorBundler()); + smartFactor4->add(measurements_cam4, views, model); + + SmartFactorBundler::shared_ptr smartFactor5(new SmartFactorBundler()); + smartFactor5->add(measurements_cam5, views, model); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(c3, perturbCameraPoseAndCalibration(cam3)); + if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams params; + params.relativeErrorTol = 1e-8; + params.absoluteErrorTol = 0; + params.maxIterations = 20; + if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + gttic_(SmartProjectionCameraFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartProjectionCameraFactor); + tictoc_finishedIteration_(); + + if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1,result.at(c1), 1e-4)); + EXPECT(assert_equal(cam2,result.at(c2), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if(isDebugTest) tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ){ + + // 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), Point3(0,0,1)); + Camera level_camera(level_pose, *Kbundler); + + // create second camera 1 meter to the right of first camera + Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); + Camera level_camera_right(level_pose_right, *Kbundler); + + // landmark ~5 meters infront of camera + Point3 landmark(5, 0.5, 1.2); + + // 1. Project two landmarks into two cameras and triangulate + Point2 level_uv = level_camera.project(landmark); + Point2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + NonlinearFactorGraph smartGraph; + SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + factor1->add(level_uv, c1, model); + factor1->add(level_uv_right, c2, model); + smartGraph.push_back(factor1); + double expectedError = factor1->error(values); + double expectedErrorGraph = smartGraph.error(values); + Point3 expectedPoint; + if(factor1->point()) + expectedPoint = *(factor1->point()); + // cout << "expectedPoint " << expectedPoint.vector() << endl; + + // COMMENTS: + // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as + // value in the generalGrap + NonlinearFactorGraph generalGraph; + SFMFactor sfm1(level_uv, model, c1, l1); + SFMFactor sfm2(level_uv_right, model, c2, l1); + generalGraph.push_back(sfm1); + generalGraph.push_back(sfm2); + values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation + Vector e1 = sfm1.evaluateError(values.at< Camera >(c1), values.at< Point3 >(l1)); + Vector e2 = sfm2.evaluateError(values.at< Camera >(c2), values.at< Point3 >(l1)); + double actualError = 0.5 * (norm_2(e1)*norm_2(e1) + norm_2(e2)*norm_2(e2)); + double actualErrorGraph = generalGraph.error(values); + + DOUBLES_EQUAL(expectedErrorGraph, actualErrorGraph, 1e-7); + DOUBLES_EQUAL(expectedErrorGraph, expectedError, 1e-7); + DOUBLES_EQUAL(actualErrorGraph, actualError, 1e-7); + DOUBLES_EQUAL(expectedError, actualError, 1e-7); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ){ + + // 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), Point3(0,0,1)); + Camera level_camera(level_pose, *Kbundler); + // create second camera 1 meter to the right of first camera + Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); + Camera level_camera_right(level_pose_right, *Kbundler); + // landmark ~5 meters infront of camera + Point3 landmark(5, 0.5, 1.2); + // 1. Project two landmarks into two cameras and triangulate + Point2 level_uv = level_camera.project(landmark); + Point2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + NonlinearFactorGraph smartGraph; + SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + factor1->add(level_uv, c1, model); + factor1->add(level_uv_right, c2, model); + smartGraph.push_back(factor1); + Matrix expectedHessian = smartGraph.linearize(values)->hessian().first; + Vector expectedInfoVector = smartGraph.linearize(values)->hessian().second; + Point3 expectedPoint; + if(factor1->point()) + expectedPoint = *(factor1->point()); + + // COMMENTS: + // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as + // value in the generalGrap + NonlinearFactorGraph generalGraph; + SFMFactor sfm1(level_uv, model, c1, l1); + SFMFactor sfm2(level_uv_right, model, c2, l1); + generalGraph.push_back(sfm1); + generalGraph.push_back(sfm2); + values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation + Matrix actualFullHessian = generalGraph.linearize(values)->hessian().first; + Matrix actualFullInfoVector = generalGraph.linearize(values)->hessian().second; + Matrix actualHessian = actualFullHessian.block(0,0,18,18) - + actualFullHessian.block(0,18,18,3) * (actualFullHessian.block(18,18,3,3)).inverse() * actualFullHessian.block(18,0,3,18); + Vector actualInfoVector = actualFullInfoVector.block(0,0,18,1) - + actualFullHessian.block(0,18,18,3) * (actualFullHessian.block(18,18,3,3)).inverse() * actualFullInfoVector.block(18,0,3,1); + + EXPECT(assert_equal(expectedHessian,actualHessian, 1e-7)); + EXPECT(assert_equal(expectedInfoVector,actualInfoVector, 1e-7)); +} + +/* *************************************************************************/ +// Have to think about how to compare multiplyHessianAdd in generalSfMFactor and smartFactors +//TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor2 ){ +// +// // 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), Point3(0,0,1)); +// cameraObjectBundler level_camera(level_pose, *Kbundler); +// // create second camera 1 meter to the right of first camera +// Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); +// cameraObjectBundler level_camera_right(level_pose_right, *Kbundler); +// // landmark ~5 meters infront of camera +// Point3 landmark(5, 0.5, 1.2); +// // 1. Project two landmarks into two cameras +// Point2 level_uv = level_camera.project(landmark); +// Point2 level_uv_right = level_camera_right.project(landmark); +// +// Values values; +// values.insert(c1, level_camera); +// values.insert(c2, level_camera_right); +// +// NonlinearFactorGraph smartGraph; +// SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); +// factor1->add(level_uv, c1, model); +// factor1->add(level_uv_right, c2, model); +// smartGraph.push_back(factor1); +// GaussianFactorGraph::shared_ptr gfgSmart = smartGraph.linearize(values); +// +// Point3 expectedPoint; +// if(factor1->point()) +// expectedPoint = *(factor1->point()); +// +// // COMMENTS: +// // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as +// // value in the generalGrap +// NonlinearFactorGraph generalGraph; +// SFMFactor sfm1(level_uv, model, c1, l1); +// SFMFactor sfm2(level_uv_right, model, c2, l1); +// generalGraph.push_back(sfm1); +// generalGraph.push_back(sfm2); +// values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation +// GaussianFactorGraph::shared_ptr gfg = generalGraph.linearize(values); +// +// double alpha = 1.0; +// +// VectorValues yExpected, yActual, ytmp; +// VectorValues xtmp = map_list_of +// (c1, (Vec(9) << 0,0,0,0,0,0,0,0,0)) +// (c2, (Vec(9) << 0,0,0,0,0,0,0,0,0)) +// (l1, (Vec(3) << 5.5, 0.5, 1.2)); +// gfg ->multiplyHessianAdd(alpha, xtmp, ytmp); +// +// VectorValues x = map_list_of +// (c1, (Vec(9) << 1,2,3,4,5,6,7,8,9)) +// (c2, (Vec(9) << 11,12,13,14,15,16,17,18,19)) +// (l1, (Vec(3) << 5.5, 0.5, 1.2)); +// +// gfgSmart->multiplyHessianAdd(alpha, ytmp + x, yActual); +// gfg ->multiplyHessianAdd(alpha, x, yExpected); +// +// EXPECT(assert_equal(yActual,yExpected, 1e-7)); +//} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, computeImplicitJacobian ){ + + // 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), Point3(0,0,1)); + Camera level_camera(level_pose, *Kbundler); + // create second camera 1 meter to the right of first camera + Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); + Camera level_camera_right(level_pose_right, *Kbundler); + // landmark ~5 meters infront of camera + Point3 landmark(5, 0.5, 1.2); + // 1. Project two landmarks into two cameras and triangulate + Point2 level_uv = level_camera.project(landmark); + Point2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + factor1->add(level_uv, c1, model); + factor1->add(level_uv_right, c2, model); + Matrix expectedF, expectedE; + Vector expectedb; + + CameraSet< Camera > cameras; + cameras.push_back(level_camera); + cameras.push_back(level_camera_right); + + factor1->error(values); // this is important to have a triangulation of the point + Point3 expectedPoint; + if(factor1->point()) + expectedPoint = *(factor1->point()); + factor1->computeJacobians(expectedF, expectedE, expectedb, cameras); + + NonlinearFactorGraph generalGraph; + SFMFactor sfm1(level_uv, model, c1, l1); + SFMFactor sfm2(level_uv_right, model, c2, l1); + generalGraph.push_back(sfm1); + generalGraph.push_back(sfm2); + values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation + Matrix actualFullHessian = generalGraph.linearize(values)->hessian().first; + Matrix actualVinv = (actualFullHessian.block(18,18,3,3)).inverse(); + + Matrix3 expectedVinv = factor1->PointCov(expectedE); + EXPECT(assert_equal(expectedVinv,actualVinv, 1e-7)); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, implicitJacobianFactor ){ + + // 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), Point3(0,0,1)); + Camera level_camera(level_pose, *Kbundler); + // create second camera 1 meter to the right of first camera + Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); + Camera level_camera_right(level_pose_right, *Kbundler); + // landmark ~5 meters infront of camera + Point3 landmark(5, 0.5, 1.2); + // 1. Project two landmarks into two cameras and triangulate + Point2 level_uv = level_camera.project(landmark); + Point2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + double rankTol = 1; + double linThreshold = -1; + bool manageDegeneracy = false; + bool useEPI = false; + bool isImplicit = false; + + // Hessian version + SmartFactorBundler::shared_ptr explicitFactor(new SmartFactorBundler(rankTol,linThreshold, manageDegeneracy, useEPI, isImplicit)); + explicitFactor->add(level_uv, c1, model); + explicitFactor->add(level_uv_right, c2, model); + + GaussianFactor::shared_ptr gaussianHessianFactor = explicitFactor->linearize(values); + HessianFactor& hessianFactor = dynamic_cast(*gaussianHessianFactor); + + // Implicit Schur version + isImplicit = true; + SmartFactorBundler::shared_ptr implicitFactor(new SmartFactorBundler(rankTol,linThreshold, manageDegeneracy, useEPI, isImplicit)); + implicitFactor->add(level_uv, c1, model); + implicitFactor->add(level_uv_right, c2, model); + GaussianFactor::shared_ptr gaussianImplicitSchurFactor = implicitFactor->linearize(values); + typedef RegularImplicitSchurFactor<9> Implicit9; + Implicit9& implicitSchurFactor = dynamic_cast(*gaussianImplicitSchurFactor); + + VectorValues x = map_list_of + (c1, (Vector(9) << 1,2,3,4,5,6,7,8,9).finished()) + (c2, (Vector(9) << 11,12,13,14,15,16,17,18,19).finished()); + + VectorValues yExpected, yActual; + double alpha = 1.0; + hessianFactor.multiplyHessianAdd(alpha, x, yActual); + implicitSchurFactor.multiplyHessianAdd(alpha, x, yExpected); + EXPECT(assert_equal(yActual,yExpected, 1e-7)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ + + From c271874bc25f3a9ff6cb36a5509b03be55879c55 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 17:20:03 +0100 Subject: [PATCH 004/173] Starting the change to isotropic --- gtsam/slam/SmartFactorBase.h | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 8cbc2f73c..e66b6ca6a 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -55,8 +55,7 @@ protected: */ std::vector measured_; - //SharedIsotropic noiseModel_; - std::vector noise_; ///< noise model used + SharedIsotropic noiseModel_; boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) @@ -159,8 +158,8 @@ public: } /** return the noise models */ - const std::vector& noise() const { - return noise_; + const SharedIsotropic& noise() const { + return noiseModel_; } /** @@ -173,7 +172,7 @@ public: std::cout << s << "SmartFactorBase, z = \n"; for (size_t k = 0; k < measured_.size(); ++k) { std::cout << "measurement, p = " << measured_[k] << "\t"; - noise_[k]->print("noise model = "); + noiseModel_->print("noise model = "); } if (this->body_P_sensor_) this->body_P_sensor_->print(" sensor pose in body frame: "); From 241366a6e6d4ad343f195ce01c766ae8a913b159 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 17:30:08 +0100 Subject: [PATCH 005/173] Check augmented information matrices --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 474009cfb..939743cd7 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -502,7 +502,7 @@ TEST( SmartProjectionPoseFactor, Factors ){ boost::shared_ptr > actual = smartFactor1->createHessianFactor(cameras, 0.0); - CHECK(assert_equal(expected.information(), actual->information(), 1e-8)); + CHECK(assert_equal(expected.augmentedInformation(), actual->augmentedInformation(), 1e-8)); CHECK(assert_equal(expected, *actual, 1e-8)); } @@ -529,6 +529,7 @@ TEST( SmartProjectionPoseFactor, Factors ){ boost::shared_ptr > actualQ = smartFactor1->createJacobianQFactor(cameras, 0.0); CHECK(actual); + CHECK(assert_equal(expectedQ.augmentedInformation(), actualQ->augmentedInformation(), 1e-8)); CHECK(assert_equal(expectedQ, *actualQ)); } @@ -541,6 +542,7 @@ TEST( SmartProjectionPoseFactor, Factors ){ boost::shared_ptr actual = smartFactor1->createJacobianSVDFactor(cameras, 0.0); CHECK(actual); + CHECK(assert_equal(expected.augmentedInformation(), actual->augmentedInformation(), 1e-8)); CHECK(assert_equal(expected, *actual)); } } From ac16b7e1d457f72e232bc608f0c934c5e2c91cb1 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 17:50:10 +0100 Subject: [PATCH 006/173] Switched to isotropic --- gtsam/slam/SmartFactorBase.h | 43 ++++++++++++++++++++---------- gtsam/slam/SmartProjectionFactor.h | 4 +-- 2 files changed, 31 insertions(+), 16 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index e66b6ca6a..a247832e2 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -97,17 +97,32 @@ public: virtual ~SmartFactorBase() { } + // check that noise model is isotropic and the same + void maybeSetNoiseModel(const SharedNoiseModel& sharedNoiseModel) { + if (!sharedNoiseModel) + return; + SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast< + noiseModel::Isotropic>(sharedNoiseModel); + if (!sharedIsotropic) + throw std::runtime_error("SmartFactorBase: needs isotropic"); + if (!noiseModel_) + noiseModel_ = sharedIsotropic; + else if (!sharedIsotropic->equals(*noiseModel_)) + throw std::runtime_error( + "SmartFactorBase: cannot add measurements with different noise model"); + } + /** * Add a new measurement and pose key * @param measured_i is the 2m dimensional projection of a single landmark * @param poseKey is the index corresponding to the camera observing the landmark - * @param noise_i is the measurement noise + * @param sharedNoiseModel is the measurement noise */ void add(const Z& measured_i, const Key& poseKey_i, - const SharedNoiseModel& noise_i) { + const SharedNoiseModel& sharedNoiseModel) { this->measured_.push_back(measured_i); this->keys_.push_back(poseKey_i); - this->noise_.push_back(noise_i); + maybeSetNoiseModel(sharedNoiseModel); } /** @@ -118,7 +133,7 @@ public: for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); this->keys_.push_back(poseKeys.at(i)); - this->noise_.push_back(noises.at(i)); + maybeSetNoiseModel(noises.at(i)); } } @@ -130,7 +145,7 @@ public: for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); this->keys_.push_back(poseKeys.at(i)); - this->noise_.push_back(noise); + maybeSetNoiseModel(noise); } } @@ -143,7 +158,7 @@ public: for (size_t k = 0; k < trackToAdd.number_measurements(); k++) { this->measured_.push_back(trackToAdd.measurements[k].second); this->keys_.push_back(trackToAdd.measurements[k].first); - this->noise_.push_back(noise); + maybeSetNoiseModel(noise); } } @@ -223,7 +238,7 @@ public: Vector b = reprojectionError(cameras, point); size_t nrCameras = cameras.size(); for (size_t i = 0, row = 0; i < nrCameras; i++, row += ZDim) - b.segment(row) = noise_.at(i)->whiten(b.segment(row)); + b.segment(row) = noiseModel_->whiten(b.segment(row)); return b; } @@ -240,7 +255,7 @@ public: double overallError = 0; size_t nrCameras = cameras.size(); for (size_t i = 0; i < nrCameras; i++) - overallError += noise_.at(i)->distance(b.segment(i * ZDim)); + overallError += noiseModel_->distance(b.segment(i * ZDim)); return 0.5 * overallError; } @@ -272,7 +287,7 @@ public: Vector bi = (zi - predicted[i]).vector(); // if needed, whiten - SharedNoiseModel model = noise_.at(i); + SharedNoiseModel model = noiseModel_; if (model) { // TODO: re-factor noiseModel to take any block/fixed vector/matrix Vector dummy; @@ -325,16 +340,15 @@ public: } // if needed, whiten - SharedNoiseModel model = noise_.at(i); - if (model) { + if (noiseModel_) { // TODO, refactor noiseModel so we can take blocks Matrix Fi = F.block(row, 0); Matrix Ei = E.block(row, 0); if (!G) - model->WhitenSystem(Fi, Ei, bi); + noiseModel_->WhitenSystem(Fi, Ei, bi); else { Matrix Gi = G->block(row, 0); - model->WhitenSystem(Fi, Ei, Gi, bi); + noiseModel_->WhitenSystem(Fi, Ei, Gi, bi); G->block(row, 0) = Gi; } F.block(row, 0) = Fi; @@ -413,7 +427,8 @@ public: } /// Create BIG block-diagonal matrix F from Fblocks - static void FillDiagonalF(const std::vector& Fblocks, Matrix& F) { + static void FillDiagonalF(const std::vector& Fblocks, + Matrix& F) { size_t m = Fblocks.size(); F.resize(ZDim * m, D * m); F.setZero(); diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 7fb43152a..ca49272ec 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -533,7 +533,7 @@ public: Vector bi = -(cameras[i].projectPointAtInfinity(this->point_, Fi, Ei) - this->measured_.at(i)).vector(); - this->noise_.at(i)->WhitenSystem(Fi, Ei, bi); + this->noiseModel_->WhitenSystem(Fi, Ei, bi); f += bi.squaredNorm(); Fblocks.push_back(typename Base::KeyMatrix2D(this->keys_[i], Fi)); E.block<2, 2>(2 * i, 0) = Ei; @@ -639,7 +639,7 @@ public: Point2 reprojectionError( camera.projectPointAtInfinity(this->point_) - zi); overallError += 0.5 - * this->noise_.at(i)->distance(reprojectionError.vector()); + * this->noiseModel_->distance(reprojectionError.vector()); i += 1; } return overallError; From c9536523bfd07816290472b2d9e09a14c2e8cb34 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 20:10:18 +0100 Subject: [PATCH 007/173] Some header refactoring --- gtsam/slam/SmartFactorBase.h | 72 ++++++++++++++++++++---------------- 1 file changed, 40 insertions(+), 32 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a247832e2..3e813a691 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -46,22 +46,17 @@ class SmartFactorBase: public NonlinearFactor { protected: + /// shorthand for base class type + typedef NonlinearFactor Base; + + /// shorthand for this class + typedef SmartFactorBase This; + + // Figure out the measurement type and dimension typedef typename CAMERA::Measurement Z; - - /** - * 2D measurement and noise model for each of the m views - * We keep a copy of measurements for I/O and computing the error. - * The order is kept the same as the keys that we use to create the factor. - */ - std::vector measured_; - - SharedIsotropic noiseModel_; - - boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) - static const int ZDim = traits::dimension; ///< Measurement dimension - /// Definitions for blocks of F + // Definitions for blocks of F typedef Eigen::Matrix Matrix2D; // F typedef Eigen::Matrix MatrixD2; // F' typedef std::pair KeyMatrix2D; // Fblocks @@ -70,11 +65,39 @@ protected: typedef Eigen::Matrix VectorD; typedef Eigen::Matrix Matrix2; - /// shorthand for base class type - typedef NonlinearFactor Base; + /** + * 2D measurement and noise model for each of the m views + * We keep a copy of measurements for I/O and computing the error. + * The order is kept the same as the keys that we use to create the factor. + */ + std::vector measured_; - /// shorthand for this class - typedef SmartFactorBase This; + /** + * As of Feb 22, 2015, the noise model is the same for all measurements and + * is isotropic. This allows for moving most calculations of Schur complement + * etc to be moved to CameraSet very easily, and also agrees pragmatically + * with what is normally done. + */ + SharedIsotropic noiseModel_; + + /// An optional sensor pose, in the body frame (one for all cameras) + /// This seems to make sense for a CameraTrack, not for a CameraSet + boost::optional body_P_sensor_; + + // check that noise model is isotropic and the same + void maybeSetNoiseModel(const SharedNoiseModel& sharedNoiseModel) { + if (!sharedNoiseModel) + return; + SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast< + noiseModel::Isotropic>(sharedNoiseModel); + if (!sharedIsotropic) + throw std::runtime_error("SmartFactorBase: needs isotropic"); + if (!noiseModel_) + noiseModel_ = sharedIsotropic; + else if (!sharedIsotropic->equals(*noiseModel_)) + throw std::runtime_error( + "SmartFactorBase: cannot add measurements with different noise model"); + } public: @@ -97,21 +120,6 @@ public: virtual ~SmartFactorBase() { } - // check that noise model is isotropic and the same - void maybeSetNoiseModel(const SharedNoiseModel& sharedNoiseModel) { - if (!sharedNoiseModel) - return; - SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast< - noiseModel::Isotropic>(sharedNoiseModel); - if (!sharedIsotropic) - throw std::runtime_error("SmartFactorBase: needs isotropic"); - if (!noiseModel_) - noiseModel_ = sharedIsotropic; - else if (!sharedIsotropic->equals(*noiseModel_)) - throw std::runtime_error( - "SmartFactorBase: cannot add measurements with different noise model"); - } - /** * Add a new measurement and pose key * @param measured_i is the 2m dimensional projection of a single landmark From 81538aac55ea9974dd1c0f42bd648dc23412cd41 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 21:48:21 +0100 Subject: [PATCH 008/173] reprojectionErrors --- gtsam/geometry/CameraSet.h | 89 ++++++++++++++++++++++---- gtsam/geometry/tests/testCameraSet.cpp | 40 ++++++++---- 2 files changed, 104 insertions(+), 25 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 3a34ca1fd..9d678181b 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -43,6 +43,24 @@ protected: static const int ZDim = traits::dimension; ///< Measurement dimension static const int Dim = traits::dimension; ///< Camera dimension + /// Make a vector of re-projection errors + static Vector ErrorVector(const std::vector& predicted, + const std::vector& measured) { + + // Check size + size_t m = predicted.size(); + if (measured.size() != m) + throw std::runtime_error("CameraSet::errors: size mismatch"); + + // Project and fill derivatives + Vector b(ZDim * m); + for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { + Z e = predicted[i] - measured[i]; + b.segment(row) = e.vector(); + } + return b; + } + public: /// Definitions for blocks of F @@ -77,28 +95,71 @@ public: * Project a point, with derivatives in this, point, and calibration * throws CheiralityException */ - std::vector project(const Point3& point, boost::optional F = - boost::none, boost::optional E = boost::none, + std::vector project(const Point3& point, // + boost::optional F = boost::none, // + boost::optional E = boost::none, // boost::optional H = boost::none) const { - size_t nrCameras = this->size(); - if (F) F->resize(ZDim * nrCameras, 6); - if (E) E->resize(ZDim * nrCameras, 3); - if (H && Dim > 6) H->resize(ZDim * nrCameras, Dim - 6); - std::vector z(nrCameras); + // Allocate result + size_t m = this->size(); + std::vector z(m); - for (size_t i = 0; i < nrCameras; i++) { - Eigen::Matrix Fi; - Eigen::Matrix Ei; - Eigen::Matrix Hi; + // Allocate derivatives + if (F) + F->resize(ZDim * m, 6); + if (E) + E->resize(ZDim * m, 3); + if (H && Dim > 6) + H->resize(ZDim * m, Dim - 6); + + Eigen::Matrix Fi; + Eigen::Matrix Ei; + Eigen::Matrix Hi; + + // Project and fill derivatives + for (size_t i = 0; i < m; i++) { z[i] = this->at(i).project(point, F ? &Fi : 0, E ? &Ei : 0, H ? &Hi : 0); - if (F) F->block(ZDim * i, 0) = Fi; - if (E) E->block(ZDim * i, 0) = Ei; - if (H) H->block(ZDim * i, 0) = Hi; + if (F) + F->block(ZDim * i, 0) = Fi; + if (E) + E->block(ZDim * i, 0) = Ei; + if (H) + H->block(ZDim * i, 0) = Hi; } + return z; } + /** + * Project a point, with derivatives in this, point, and calibration + * throws CheiralityException + */ + std::vector projectAtInfinity(const Point3& point) const { + + // Allocate result + size_t m = this->size(); + std::vector z(m); + + // Project and fill derivatives + for (size_t i = 0; i < m; i++) + z[i] = this->at(i).projectPointAtInfinity(point); + + return z; + } + + /// Calculate vector of re-projection errors + Vector reprojectionErrors(const Point3& point, + const std::vector& measured) const { + return ErrorVector(project(point), measured); + } + + /// Calculate vector of re-projection errors, from point at infinity + // TODO: take Unit3 instead + Vector reprojectionErrorsAtInfinity(const Point3& point, + const std::vector& measured) const { + return ErrorVector(projectAtInfinity(point), measured); + } + private: /// Serialization function diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 42cf0f299..4ed9f2f07 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -37,16 +37,16 @@ TEST(CameraSet, Pinhole) { set.push_back(camera); set.push_back(camera); Point3 p(0, 0, 1); - CHECK(assert_equal(set, set)); + EXPECT(assert_equal(set, set)); CameraSet set2 = set; set2.push_back(camera); - CHECK(!set.equals(set2)); + EXPECT(!set.equals(set2)); // Check measurements Point2 expected; ZZ z = set.project(p); - CHECK(assert_equal(expected, z[0])); - CHECK(assert_equal(expected, z[1])); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole Matrix46 actualF; @@ -65,9 +65,27 @@ TEST(CameraSet, Pinhole) { // Check computed derivatives Matrix F, E, H; set.project(p, F, E, H); - CHECK(assert_equal(actualF, F)); - CHECK(assert_equal(actualE, E)); - CHECK(assert_equal(actualH, H)); + EXPECT(assert_equal(actualF, F)); + EXPECT(assert_equal(actualE, E)); + EXPECT(assert_equal(actualH, H)); + + // Check errors + ZZ measured; + measured.push_back(Point2(1, 2)); + measured.push_back(Point2(3, 4)); + Vector4 expectedV; + + // reprojectionErrors + expectedV << -1, -2, -3, -4; + Vector actualV = set.reprojectionErrors(p, measured); + EXPECT(assert_equal(expectedV, actualV)); + + // reprojectionErrorsAtInfinity + EXPECT( + assert_equal(Point3(0, 0, 1), + camera.backprojectPointAtInfinity(Point2()))); + actualV = set.reprojectionErrorsAtInfinity(p, measured); + EXPECT(assert_equal(expectedV, actualV)); } /* ************************************************************************* */ @@ -84,8 +102,8 @@ TEST(CameraSet, Stereo) { // Check measurements StereoPoint2 expected(0, -1, 0); ZZ z = set.project(p); - CHECK(assert_equal(expected, z[0])); - CHECK(assert_equal(expected, z[1])); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole Matrix66 actualF; @@ -101,8 +119,8 @@ TEST(CameraSet, Stereo) { // Check computed derivatives Matrix F, E; set.project(p, F, E); - CHECK(assert_equal(actualF, F)); - CHECK(assert_equal(actualE, E)); + EXPECT(assert_equal(actualF, F)); + EXPECT(assert_equal(actualE, E)); } /* ************************************************************************* */ From c2feb239fb0cf23b9146c7fe00701d3a1595f206 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 21:50:58 +0100 Subject: [PATCH 009/173] whitenInPlace --- gtsam/linear/NoiseModel.cpp | 5 +++++ gtsam/linear/NoiseModel.h | 1 + 2 files changed, 6 insertions(+) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 2031a4b73..6ab26474a 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -514,6 +514,11 @@ void Isotropic::WhitenInPlace(Matrix& H) const { H *= invsigma_; } +/* ************************************************************************* */ +void Isotropic::whitenInPlace(Vector& v) const { + v *= invsigma_; +} + /* ************************************************************************* */ void Isotropic::WhitenInPlace(Eigen::Block H) const { H *= invsigma_; diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 098af8b6d..94012c7c2 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -545,6 +545,7 @@ namespace gtsam { virtual Vector unwhiten(const Vector& v) const; virtual Matrix Whiten(const Matrix& H) const; virtual void WhitenInPlace(Matrix& H) const; + virtual void whitenInPlace(Vector& v) const; virtual void WhitenInPlace(Eigen::Block H) const; /** From 484facef834b5477586a10ace23be7364102e7f4 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 22:03:45 +0100 Subject: [PATCH 010/173] testCameraSet --- .cproject | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.cproject b/.cproject index 8783ebc31..1aa6ab5e1 100644 --- a/.cproject +++ b/.cproject @@ -1027,6 +1027,14 @@ true true + + make + -j4 + testCameraSet.run + true + true + true + make -j2 From cdaaee6fce72a5cfc42a5d9e426bc619c7beaf19 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 22:05:26 +0100 Subject: [PATCH 011/173] Move Errors to CameraSet --- gtsam/slam/SmartFactorBase.h | 106 ++++++++---------- .../tests/testSmartProjectionPoseFactor.cpp | 4 +- 2 files changed, 51 insertions(+), 59 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 3e813a691..fe88b5401 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -44,17 +44,36 @@ namespace gtsam { template class SmartFactorBase: public NonlinearFactor { +private: + + /** + * As of Feb 22, 2015, the noise model is the same for all measurements and + * is isotropic. This allows for moving most calculations of Schur complement + * etc to be moved to CameraSet very easily, and also agrees pragmatically + * with what is normally done. + */ + SharedIsotropic noiseModel_; + protected: + // Figure out the measurement type + typedef typename CAMERA::Measurement Z; + + /** + * 2D measurement and noise model for each of the m views + * We keep a copy of measurements for I/O and computing the error. + * The order is kept the same as the keys that we use to create the factor. + */ + std::vector measured_; + /// shorthand for base class type typedef NonlinearFactor Base; /// shorthand for this class typedef SmartFactorBase This; - // Figure out the measurement type and dimension - typedef typename CAMERA::Measurement Z; - static const int ZDim = traits::dimension; ///< Measurement dimension + // Figure out the measurement dimension + static const int ZDim = traits::dimension; // Definitions for blocks of F typedef Eigen::Matrix Matrix2D; // F @@ -65,21 +84,6 @@ protected: typedef Eigen::Matrix VectorD; typedef Eigen::Matrix Matrix2; - /** - * 2D measurement and noise model for each of the m views - * We keep a copy of measurements for I/O and computing the error. - * The order is kept the same as the keys that we use to create the factor. - */ - std::vector measured_; - - /** - * As of Feb 22, 2015, the noise model is the same for all measurements and - * is isotropic. This allows for moving most calculations of Schur complement - * etc to be moved to CameraSet very easily, and also agrees pragmatically - * with what is normally done. - */ - SharedIsotropic noiseModel_; - /// An optional sensor pose, in the body frame (one for all cameras) /// This seems to make sense for a CameraTrack, not for a CameraSet boost::optional body_P_sensor_; @@ -180,11 +184,6 @@ public: return measured_; } - /** return the noise models */ - const SharedIsotropic& noise() const { - return noiseModel_; - } - /** * print * @param s optional string naming the factor @@ -219,39 +218,34 @@ public: } /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionError(const Cameras& cameras, const Point3& point) const { - - // Project into CameraSet - std::vector predicted; + Vector reprojectionErrors(const Cameras& cameras, const Point3& point) const { try { - predicted = cameras.project(point); + return cameras.reprojectionErrors(point, measured_); } catch (CheiralityException&) { std::cout << "reprojectionError: Cheirality exception " << std::endl; exit(EXIT_FAILURE); // TODO: throw exception } + } - // Calculate vector of errors - size_t nrCameras = cameras.size(); - Vector b(ZDim * nrCameras); - for (size_t i = 0, row = 0; i < nrCameras; i++, row += ZDim) { - Z e = predicted[i] - measured_.at(i); - b.segment(row) = e.vector(); - } - + /// Calculate vector of re-projection errors, noise model applied + Vector whitenedErrors(const Cameras& cameras, const Point3& point) const { + Vector b = reprojectionErrors(cameras, point); + if (noiseModel_) + noiseModel_->whitenInPlace(b); return b; } /// Calculate vector of re-projection errors, noise model applied - Vector whitenedError(const Cameras& cameras, const Point3& point) const { - Vector b = reprojectionError(cameras, point); - size_t nrCameras = cameras.size(); - for (size_t i = 0, row = 0; i < nrCameras; i++, row += ZDim) - b.segment(row) = noiseModel_->whiten(b.segment(row)); + // TODO: Unit3 + Vector whitenedErrorsAtInfinity(const Cameras& cameras, + const Point3& point) const { + Vector b = cameras.reprojectionErrorsAtInfinity(point, measured_); + if (noiseModel_) + noiseModel_->whitenInPlace(b); return b; } - /** - * Calculate the error of the factor. + /** Calculate the error of the factor. * This is the log-likelihood, e.g. \f$ 0.5(h(x)-z)^2/\sigma^2 \f$ in case of Gaussian. * In this class, we take the raw prediction error \f$ h(x)-z \f$, ask the noise model * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. @@ -259,12 +253,16 @@ public: */ double totalReprojectionError(const Cameras& cameras, const Point3& point) const { - Vector b = reprojectionError(cameras, point); - double overallError = 0; - size_t nrCameras = cameras.size(); - for (size_t i = 0; i < nrCameras; i++) - overallError += noiseModel_->distance(b.segment(i * ZDim)); - return 0.5 * overallError; + Vector b = whitenedErrors(cameras, point); + return 0.5 * b.dot(b); + } + + /// Version for infinity + // TODO: Unit3 + double totalReprojectionErrorAtInfinity(const Cameras& cameras, + const Point3& point) const { + Vector b = whitenedErrorsAtInfinity(cameras, point); + return 0.5 * b.dot(b); } /** @@ -295,14 +293,8 @@ public: Vector bi = (zi - predicted[i]).vector(); // if needed, whiten - SharedNoiseModel model = noiseModel_; - if (model) { - // TODO: re-factor noiseModel to take any block/fixed vector/matrix - Vector dummy; - Matrix Ei = E.block(row, 0); - model->WhitenSystem(Ei, dummy); - E.block(row, 0) = Ei; - } + if (noiseModel_) + E.block(row, 0) /= noiseModel_->sigma(); b.segment(row) = bi; } return b; diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 939743cd7..9b36b645a 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -163,7 +163,7 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // Calculate expected derivative for point (easiest to check) boost::function f = // - boost::bind(&SmartFactor::whitenedError, factor, cameras, _1); + boost::bind(&SmartFactor::whitenedErrors, factor, cameras, _1); boost::optional point = factor.point(); CHECK(point); Matrix expectedE = numericalDerivative11(f, *point); @@ -425,7 +425,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { // Calculate expected derivative for point (easiest to check) SmartFactor::Cameras cameras = smartFactor1->cameras(values); boost::function f = // - boost::bind(&SmartFactor::whitenedError, *smartFactor1, cameras, _1); + boost::bind(&SmartFactor::whitenedErrors, *smartFactor1, cameras, _1); boost::optional point = smartFactor1->point(); CHECK(point); Matrix expectedE = numericalDerivative11(f, *point); From 66d12a1c30fe854ccc1e9b26eb8eaaddbbc816d8 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 22:05:58 +0100 Subject: [PATCH 012/173] noiseModel_ is now private -> just call Errors --- gtsam/slam/SmartProjectionFactor.h | 17 ++++------------- 1 file changed, 4 insertions(+), 13 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index ca49272ec..8c11d7ec4 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -630,19 +630,10 @@ public: std::cout << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" << std::endl; - size_t i = 0; - double overallError = 0; - BOOST_FOREACH(const Camera& camera, cameras) { - const Point2& zi = this->measured_.at(i); - if (i == 0) // first pose - this->point_ = camera.backprojectPointAtInfinity(zi); // 3D parametrization of point at infinity - Point2 reprojectionError( - camera.projectPointAtInfinity(this->point_) - zi); - overallError += 0.5 - * this->noiseModel_->distance(reprojectionError.vector()); - i += 1; - } - return overallError; + // 3D parameterization of point at infinity + const Point2& zi = this->measured_.at(0); + this->point_ = cameras.front().backprojectPointAtInfinity(zi); + return Base::totalReprojectionErrorAtInfinity(cameras,this->point_); } else { // Just use version in base class return Base::totalReprojectionError(cameras, point_); From 1e62f310646746a534c56cd5426302146be3605b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 22:32:25 +0100 Subject: [PATCH 013/173] Now return FBlocks as derivatives --- gtsam/geometry/CameraSet.h | 12 ++++++------ gtsam/geometry/tests/testCameraSet.cpp | 22 ++++++++++++---------- 2 files changed, 18 insertions(+), 16 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 9d678181b..43b806857 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -64,8 +64,8 @@ protected: public: /// Definitions for blocks of F - typedef Eigen::Matrix MatrixZD; // F - typedef std::pair FBlock; // Fblocks + typedef Eigen::Matrix MatrixZ6; // F + typedef std::vector FBlocks; /** * print @@ -93,10 +93,12 @@ public: /** * Project a point, with derivatives in this, point, and calibration + * Note that F is a sparse block-diagonal matrix, so instead of a large dense + * matrix this function returns the diagonal blocks. * throws CheiralityException */ std::vector project(const Point3& point, // - boost::optional F = boost::none, // + boost::optional F = boost::none, // boost::optional E = boost::none, // boost::optional H = boost::none) const { @@ -105,8 +107,6 @@ public: std::vector z(m); // Allocate derivatives - if (F) - F->resize(ZDim * m, 6); if (E) E->resize(ZDim * m, 3); if (H && Dim > 6) @@ -120,7 +120,7 @@ public: for (size_t i = 0; i < m; i++) { z[i] = this->at(i).project(point, F ? &Fi : 0, E ? &Ei : 0, H ? &Hi : 0); if (F) - F->block(ZDim * i, 0) = Fi; + F->push_back(Fi); if (E) E->block(ZDim * i, 0) = Ei; if (H) diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 4ed9f2f07..b4f8a75ef 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -49,23 +49,24 @@ TEST(CameraSet, Pinhole) { EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole - Matrix46 actualF; Matrix43 actualE; Matrix43 actualH; + Matrix F1; { - Matrix26 F1; Matrix23 E1; Matrix23 H1; camera.project(p, F1, E1, H1); actualE << E1, E1; - actualF << F1, F1; actualH << H1, H1; } // Check computed derivatives - Matrix F, E, H; + CameraSet::FBlocks F; + Matrix E, H; set.project(p, F, E, H); - EXPECT(assert_equal(actualF, F)); + LONGS_EQUAL(2,F.size()); + EXPECT(assert_equal(F1, F[0])); + EXPECT(assert_equal(F1, F[1])); EXPECT(assert_equal(actualE, E)); EXPECT(assert_equal(actualH, H)); @@ -106,20 +107,21 @@ TEST(CameraSet, Stereo) { EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole - Matrix66 actualF; Matrix63 actualE; + Matrix F1; { - Matrix36 F1; Matrix33 E1; camera.project(p, F1, E1); actualE << E1, E1; - actualF << F1, F1; } // Check computed derivatives - Matrix F, E; + CameraSet::FBlocks F; + Matrix E; set.project(p, F, E); - EXPECT(assert_equal(actualF, F)); + LONGS_EQUAL(2,F.size()); + EXPECT(assert_equal(F1, F[0])); + EXPECT(assert_equal(F1, F[1])); EXPECT(assert_equal(actualE, E)); } From bc0bddf7c6897df8c2ddb6fd6f5b8a57b5b84273 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 22:50:11 +0100 Subject: [PATCH 014/173] Removed whitening in Jacobians (which will move). Also, cheirality no longer caught -> will exit by itself if uncaught. --- gtsam/slam/SmartFactorBase.h | 29 +---------------------------- 1 file changed, 1 insertion(+), 28 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index fe88b5401..5b6b4ec3f 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -217,19 +217,9 @@ public: && body_P_sensor_->equals(*e->body_P_sensor_))); } - /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionErrors(const Cameras& cameras, const Point3& point) const { - try { - return cameras.reprojectionErrors(point, measured_); - } catch (CheiralityException&) { - std::cout << "reprojectionError: Cheirality exception " << std::endl; - exit(EXIT_FAILURE); // TODO: throw exception - } - } - /// Calculate vector of re-projection errors, noise model applied Vector whitenedErrors(const Cameras& cameras, const Point3& point) const { - Vector b = reprojectionErrors(cameras, point); + Vector b = cameras.reprojectionErrors(point, measured_); if (noiseModel_) noiseModel_->whitenInPlace(b); return b; @@ -338,23 +328,6 @@ public: Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); F.block(row, 0) *= J; } - - // if needed, whiten - if (noiseModel_) { - // TODO, refactor noiseModel so we can take blocks - Matrix Fi = F.block(row, 0); - Matrix Ei = E.block(row, 0); - if (!G) - noiseModel_->WhitenSystem(Fi, Ei, bi); - else { - Matrix Gi = G->block(row, 0); - noiseModel_->WhitenSystem(Fi, Ei, Gi, bi); - G->block(row, 0) = Gi; - } - F.block(row, 0) = Fi; - E.block(row, 0) = Ei; - } - b.segment(row) = bi; } return b; } From 8619b04cd7b01ebab658aef10a231d78db62e0a6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 22 Feb 2015 22:52:31 +0100 Subject: [PATCH 015/173] Now switched to full ZDim*Dim blocks, no more hacky calibration splitting... --- gtsam/geometry/CameraSet.h | 26 +++++++++----------------- gtsam/geometry/tests/testCameraSet.cpp | 15 ++++++--------- 2 files changed, 15 insertions(+), 26 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 43b806857..d0c2d04d0 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -27,7 +27,6 @@ namespace gtsam { /** * @brief A set of cameras, all with their own calibration - * Assumes that a camera is laid out as 6 Pose3 parameters then calibration */ template class CameraSet: public std::vector { @@ -64,8 +63,8 @@ protected: public: /// Definitions for blocks of F - typedef Eigen::Matrix MatrixZ6; // F - typedef std::vector FBlocks; + typedef Eigen::Matrix MatrixZD; // F + typedef std::vector FBlocks; /** * print @@ -92,15 +91,14 @@ public: } /** - * Project a point, with derivatives in this, point, and calibration + * Project a point, with derivatives in CameraSet and Point3 * Note that F is a sparse block-diagonal matrix, so instead of a large dense * matrix this function returns the diagonal blocks. * throws CheiralityException */ - std::vector project(const Point3& point, // + std::vector project2(const Point3& point, // boost::optional F = boost::none, // - boost::optional E = boost::none, // - boost::optional H = boost::none) const { + boost::optional E = boost::none) const { // Allocate result size_t m = this->size(); @@ -109,22 +107,16 @@ public: // Allocate derivatives if (E) E->resize(ZDim * m, 3); - if (H && Dim > 6) - H->resize(ZDim * m, Dim - 6); - - Eigen::Matrix Fi; - Eigen::Matrix Ei; - Eigen::Matrix Hi; // Project and fill derivatives for (size_t i = 0; i < m; i++) { - z[i] = this->at(i).project(point, F ? &Fi : 0, E ? &Ei : 0, H ? &Hi : 0); + Eigen::Matrix Fi; + Eigen::Matrix Ei; + z[i] = this->at(i).project2(point, F ? &Fi : 0, E ? &Ei : 0); if (F) F->push_back(Fi); if (E) E->block(ZDim * i, 0) = Ei; - if (H) - H->block(ZDim * i, 0) = Hi; } return z; @@ -150,7 +142,7 @@ public: /// Calculate vector of re-projection errors Vector reprojectionErrors(const Point3& point, const std::vector& measured) const { - return ErrorVector(project(point), measured); + return ErrorVector(project2(point), measured); } /// Calculate vector of re-projection errors, from point at infinity diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index b4f8a75ef..a003b6bce 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -44,31 +44,28 @@ TEST(CameraSet, Pinhole) { // Check measurements Point2 expected; - ZZ z = set.project(p); + ZZ z = set.project2(p); EXPECT(assert_equal(expected, z[0])); EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole Matrix43 actualE; - Matrix43 actualH; Matrix F1; { Matrix23 E1; Matrix23 H1; - camera.project(p, F1, E1, H1); + camera.project2(p, F1, E1); actualE << E1, E1; - actualH << H1, H1; } // Check computed derivatives CameraSet::FBlocks F; Matrix E, H; - set.project(p, F, E, H); + set.project2(p, F, E); LONGS_EQUAL(2,F.size()); EXPECT(assert_equal(F1, F[0])); EXPECT(assert_equal(F1, F[1])); EXPECT(assert_equal(actualE, E)); - EXPECT(assert_equal(actualH, H)); // Check errors ZZ measured; @@ -102,7 +99,7 @@ TEST(CameraSet, Stereo) { // Check measurements StereoPoint2 expected(0, -1, 0); - ZZ z = set.project(p); + ZZ z = set.project2(p); EXPECT(assert_equal(expected, z[0])); EXPECT(assert_equal(expected, z[1])); @@ -111,14 +108,14 @@ TEST(CameraSet, Stereo) { Matrix F1; { Matrix33 E1; - camera.project(p, F1, E1); + camera.project2(p, F1, E1); actualE << E1, E1; } // Check computed derivatives CameraSet::FBlocks F; Matrix E; - set.project(p, F, E); + set.project2(p, F, E); LONGS_EQUAL(2,F.size()); EXPECT(assert_equal(F1, F[0])); EXPECT(assert_equal(F1, F[1])); From fdbff461f386930a483f325b90812c72d6bb2327 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 00:08:02 +0100 Subject: [PATCH 016/173] Removed D argument from SmartFactorBase - note, branch does not compile now. --- gtsam/slam/SmartFactorBase.h | 130 +++++++++-------------- gtsam/slam/tests/testSmartFactorBase.cpp | 4 +- 2 files changed, 55 insertions(+), 79 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 5b6b4ec3f..10352405a 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -41,7 +41,7 @@ namespace gtsam { * The methods take a Cameras argument, which should behave like PinholeCamera, and * the value of a point, which is kept in the base class. */ -template +template class SmartFactorBase: public NonlinearFactor { private: @@ -70,18 +70,18 @@ protected: typedef NonlinearFactor Base; /// shorthand for this class - typedef SmartFactorBase This; + typedef SmartFactorBase This; - // Figure out the measurement dimension - static const int ZDim = traits::dimension; + static const int ZDim = traits::dimension; ///< Measurement dimension + static const int Dim = traits::dimension; ///< Camera dimension // Definitions for blocks of F - typedef Eigen::Matrix Matrix2D; // F - typedef Eigen::Matrix MatrixD2; // F' + typedef Eigen::Matrix Matrix2D; // F + typedef Eigen::Matrix MatrixD2; // F' typedef std::pair KeyMatrix2D; // Fblocks - typedef Eigen::Matrix MatrixDD; // camera hessian block + typedef Eigen::Matrix MatrixDD; // camera hessian block typedef Eigen::Matrix Matrix23; - typedef Eigen::Matrix VectorD; + typedef Eigen::Matrix VectorD; typedef Eigen::Matrix Matrix2; /// An optional sensor pose, in the body frame (one for all cameras) @@ -260,18 +260,12 @@ public: * the stacked ZDim*3 derivatives of project with respect to the point. * Assumes non-degenerate ! TODO explain this */ - Vector whitenedError(const Cameras& cameras, const Point3& point, + Vector reprojectionErrors(const Cameras& cameras, const Point3& point, Matrix& E) const { // Project into CameraSet, calculating derivatives std::vector predicted; - try { - using boost::none; - predicted = cameras.project(point, none, E, none); - } catch (CheiralityException&) { - std::cout << "whitenedError(E): Cheirality exception " << std::endl; - exit(EXIT_FAILURE); // TODO: throw exception - } + predicted = cameras.project2(point, boost::none, E); // if needed, whiten size_t m = keys_.size(); @@ -281,10 +275,6 @@ public: // Calculate error const Z& zi = measured_.at(i); Vector bi = (zi - predicted[i]).vector(); - - // if needed, whiten - if (noiseModel_) - E.block(row, 0) /= noiseModel_->sigma(); b.segment(row) = bi; } return b; @@ -298,22 +288,17 @@ public: * TODO: the treatment of body_P_sensor_ is weird: the transformation * is applied in the caller, but the derivatives are computed here. */ - Vector whitenedError(const Cameras& cameras, const Point3& point, Matrix& F, - Matrix& E, boost::optional G = boost::none) const { + Vector reprojectionErrors(const Cameras& cameras, const Point3& point, + typename Cameras::FBlocks& F, Matrix& E) const { // Project into CameraSet, calculating derivatives std::vector predicted; - try { - predicted = cameras.project(point, F, E, G); - } catch (CheiralityException&) { - std::cout << "whitenedError(E,F): Cheirality exception " << std::endl; - exit(EXIT_FAILURE); // TODO: throw exception - } + predicted = cameras.project2(point, F, E); // Calculate error and whiten derivatives if needed size_t m = keys_.size(); Vector b(ZDim * m); - for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { + for (size_t i = 0; i < m; i++) { // Calculate error const Z& zi = measured_.at(i); @@ -326,7 +311,7 @@ public: Pose3 w_Pose_body = pose_i.compose(body_P_sensor_->inverse()); Matrix66 J; Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); - F.block(row, 0) *= J; + F[i].leftCols(6) *= J; } } return b; @@ -359,7 +344,7 @@ public: /// Assumes non-degenerate ! void computeEP(Matrix& E, Matrix& P, const Cameras& cameras, const Point3& point) const { - whitenedError(cameras, point, E); + reprojectionErrors(cameras, point, E); P = PointCov(E); } @@ -372,11 +357,8 @@ public: Vector& b, const Cameras& cameras, const Point3& point) const { // Project into Camera set and calculate derivatives - // TODO: if D==6 we optimize only camera pose. That is fairly hacky! - Matrix F, G; - using boost::none; - boost::optional optionalG(G); - b = whitenedError(cameras, point, F, E, D == 6 ? none : optionalG); + typename Cameras::FBlocks F; + b = reprojectionErrors(cameras, point, F, E); // Now calculate f and divide up the F derivatives into Fblocks double f = 0.0; @@ -386,15 +368,8 @@ public: // Accumulate normalized error f += b.segment(row).squaredNorm(); - // Get piece of F and possibly G - Matrix2D Fi; - if (D == 6) - Fi << F.block(row, 0); - else - Fi << F.block(row, 0), G.block(row, 0); - - // Push it onto Fblocks - Fblocks.push_back(KeyMatrix2D(keys_[i], Fi)); + // Push piece of F onto Fblocks with associated key + Fblocks.push_back(KeyMatrix2D(keys_[i], F[i])); } return f; } @@ -403,10 +378,10 @@ public: static void FillDiagonalF(const std::vector& Fblocks, Matrix& F) { size_t m = Fblocks.size(); - F.resize(ZDim * m, D * m); + F.resize(ZDim * m, Dim * m); F.setZero(); for (size_t i = 0; i < m; ++i) - F.block(This::ZDim * i, D * i) = Fblocks.at(i).second; + F.block(This::ZDim * i, Dim * i) = Fblocks.at(i).second; } /** @@ -451,7 +426,7 @@ public: /** * Linearize returns a Hessianfactor that is an approximation of error(p) */ - boost::shared_ptr > createHessianFactor( + boost::shared_ptr > createHessianFactor( const Cameras& cameras, const Point3& point, const double lambda = 0.0, bool diagonalDamping = false) const { @@ -475,17 +450,17 @@ public: //std::vector < Matrix > Gs2(Gs.begin(), Gs.end()); //std::vector < Vector > gs2(gs.begin(), gs.end()); - return boost::make_shared < RegularHessianFactor > (this->keys_, Gs, gs, f); + return boost::make_shared < RegularHessianFactor > (this->keys_, Gs, gs, f); #else // we create directly a SymmetricBlockMatrix - size_t n1 = D * numKeys + 1; + size_t n1 = Dim * numKeys + 1; std::vector dims(numKeys + 1); // this also includes the b term - std::fill(dims.begin(), dims.end() - 1, D); + std::fill(dims.begin(), dims.end() - 1, Dim); dims.back() = 1; - SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(n1, n1)); // for 10 cameras, size should be (10*D+1 x 10*D+1) - sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... + SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(n1, n1)); // for 10 cameras, size should be (10*Dim+1 x 10*Dim+1) + sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... augmentedHessian(numKeys, numKeys)(0, 0) = f; - return boost::make_shared >(this->keys_, + return boost::make_shared >(this->keys_, augmentedHessian); #endif } @@ -508,7 +483,7 @@ public: Matrix F; FillDiagonalF(Fblocks, F); - Matrix H(D * numKeys, D * numKeys); + Matrix H(Dim * numKeys, Dim * numKeys); Vector gs_vector; H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); @@ -517,11 +492,11 @@ public: // Populate Gs and gs int GsCount2 = 0; for (DenseIndex i1 = 0; i1 < numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * D; - gs.at(i1) = gs_vector.segment(i1D); + DenseIndex i1D = i1 * Dim; + gs.at(i1) = gs_vector.segment(i1D); for (DenseIndex i2 = 0; i2 < numKeys; i2++) { if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * D); + Gs.at(GsCount2) = H.block(i1D, i2 * Dim); GsCount2++; } } @@ -548,11 +523,11 @@ public: const Matrix2D& Fi1 = Fblocks.at(i1).second; const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; - // D = (Dx2) * (2) - // (augmentedHessian.matrix()).block (i1,numKeys+1) = Fi1.transpose() * b.segment < 2 > (2 * i1); // F' * b + // Dim = (Dx2) * (2) + // (augmentedHessian.matrix()).block (i1,numKeys+1) = Fi1.transpose() * b.segment < 2 > (2 * i1); // F' * b augmentedHessian(i1, numKeys) = Fi1.transpose() * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) augmentedHessian(i1, i1) = Fi1.transpose() @@ -597,9 +572,9 @@ public: const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; { // for i1 = i2 - // D = (Dx2) * (2) + // Dim = (Dx2) * (2) gs.at(i1) = Fi1.transpose() * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) Gs.at(GsIndex) = Fi1.transpose() @@ -639,7 +614,7 @@ public: // a single point is observed in numKeys cameras size_t numKeys = this->keys_.size(); // cameras observing current point - size_t aug_numKeys = (augmentedHessian.rows() - 1) / D; // all cameras in the group + size_t aug_numKeys = (augmentedHessian.rows() - 1) / Dim; // all cameras in the group // Blockwise Schur complement for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera in the current factor @@ -647,7 +622,7 @@ public: const Matrix2D& Fi1 = Fblocks.at(i1).second; const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; - // D = (DxZDim) * (ZDim) + // Dim = (DxZDim) * (ZDim) // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) // Key cameraKey_i1 = this->keys_[i1]; @@ -659,7 +634,7 @@ public: augmentedHessian(aug_i1, aug_numKeys) = augmentedHessian(aug_i1, aug_numKeys).knownOffDiagonal() + Fi1.transpose() * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) // main block diagonal - store previous block @@ -709,17 +684,17 @@ public: Vector b; double f = computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - updateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... + updateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... } /** * Return Jacobians as RegularImplicitSchurFactor with raw access */ - boost::shared_ptr > createRegularImplicitSchurFactor( + boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - typename boost::shared_ptr > f( - new RegularImplicitSchurFactor()); + typename boost::shared_ptr > f( + new RegularImplicitSchurFactor()); computeJacobians(f->Fblocks(), f->E(), f->b(), cameras, point); f->PointCovariance() = PointCov(f->E(), lambda, diagonalDamping); f->initKeys(); @@ -729,7 +704,7 @@ public: /** * Return Jacobians as JacobianFactorQ */ - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { std::vector Fblocks; @@ -737,7 +712,7 @@ public: Vector b; computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - return boost::make_shared >(Fblocks, E, P, b); + return boost::make_shared >(Fblocks, E, P, b); } /** @@ -751,7 +726,7 @@ public: Vector b; Matrix Enull(ZDim * numKeys, ZDim * numKeys - 3); computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - return boost::make_shared >(Fblocks, Enull, b); + return boost::make_shared >(Fblocks, Enull, b); } private: @@ -764,10 +739,11 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } -} -; +}; +// end class SmartFactorBase -template -const int SmartFactorBase::ZDim; +// TODO: Why is this here? +template +const int SmartFactorBase::ZDim; } // \ namespace gtsam diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index b5ef18842..373d482fe 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -26,7 +26,7 @@ using namespace gtsam; /* ************************************************************************* */ #include #include -class PinholeFactor: public SmartFactorBase, 9> { +class PinholeFactor: public SmartFactorBase > { virtual double error(const Values& values) const { return 0.0; } @@ -45,7 +45,7 @@ TEST(SmartFactorBase, Pinhole) { /* ************************************************************************* */ #include -class StereoFactor: public SmartFactorBase { +class StereoFactor: public SmartFactorBase { virtual double error(const Values& values) const { return 0.0; } From 0fee8f37a6d22b7271d4e5f1198dd87a51e9144c Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 12:37:06 +0100 Subject: [PATCH 017/173] Added derivatives to Errors --- gtsam/geometry/CameraSet.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index d0c2d04d0..eb58d1658 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -140,9 +140,10 @@ public: } /// Calculate vector of re-projection errors - Vector reprojectionErrors(const Point3& point, - const std::vector& measured) const { - return ErrorVector(project2(point), measured); + Vector reprojectionErrors(const Point3& point, const std::vector& measured, + boost::optional F = boost::none, // + boost::optional E = boost::none) const { + return ErrorVector(project2(point,F,E), measured); } /// Calculate vector of re-projection errors, from point at infinity From fb47cf89614507172182826e6ca98400f9c7e46c Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 12:37:55 +0100 Subject: [PATCH 018/173] moved projectPointAtInfinity down --- gtsam/geometry/PinholeCamera.h | 49 --------------------------- gtsam/geometry/PinholePose.h | 60 ++++++++++++++++++++++++++++++++-- 2 files changed, 58 insertions(+), 51 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index bfc2bbb93..632f6de86 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -31,14 +31,6 @@ namespace gtsam { template class GTSAM_EXPORT PinholeCamera: public PinholeBaseK { -public: - - /** - * Some classes template on either PinholeCamera or StereoCamera, - * and this typedef informs those classes what "project" returns. - */ - typedef Point2 Measurement; - private: typedef PinholeBaseK Base; ///< base class has 3D pose as private member @@ -235,47 +227,6 @@ public: return pi; } - /** project a point at infinity from world coordinate to the image - * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) - * @param Dpose is the Jacobian w.r.t. pose3 - * @param Dpoint is the Jacobian w.r.t. point3 - * @param Dcal is the Jacobian w.r.t. calibration - */ - Point2 projectPointAtInfinity(const Point3& pw, OptionalJacobian<2, 6> Dpose = - boost::none, OptionalJacobian<2, 2> Dpoint = boost::none, - OptionalJacobian<2, DimK> Dcal = boost::none) const { - - if (!Dpose && !Dpoint && !Dcal) { - const Point3 pc = this->pose().rotation().unrotate(pw); // get direction in camera frame (translation does not matter) - const Point2 pn = Base::project_to_camera(pc); // project the point to the camera - return K_.uncalibrate(pn); - } - - // world to camera coordinate - Matrix3 Dpc_rot, Dpc_point; - const Point3 pc = this->pose().rotation().unrotate(pw, Dpc_rot, Dpc_point); - - Matrix36 Dpc_pose; - Dpc_pose.setZero(); - Dpc_pose.leftCols<3>() = Dpc_rot; - - // camera to normalized image coordinate - Matrix23 Dpn_pc; // 2*3 - const Point2 pn = Base::project_to_camera(pc, Dpn_pc); - - // uncalibration - Matrix2 Dpi_pn; // 2*2 - const Point2 pi = K_.uncalibrate(pn, Dcal, Dpi_pn); - - // chain the Jacobian matrices - const Matrix23 Dpi_pc = Dpi_pn * Dpn_pc; - if (Dpose) - *Dpose = Dpi_pc * Dpc_pose; - if (Dpoint) - *Dpoint = (Dpi_pc * Dpc_point).leftCols<2>(); // only 2dof are important for the point (direction-only) - return pi; - } - /** project a point from world coordinate to the image, fixed Jacobians * @param pw is a point in the world coordinate */ diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 7588f517e..6f2f7dca0 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -35,7 +35,10 @@ class GTSAM_EXPORT PinholeBaseK: public PinholeBase { GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration) -public : + // Get dimensions of calibration type at compile time +static const int DimK = FixedDimension::value; + +public : /// @name Standard Constructors /// @{ @@ -78,7 +81,19 @@ public : return pn; } - /** project a point from world coordinate to the image, fixed Jacobians + /** project a point from world coordinate to the image + * @param pw is a point in the world coordinates + */ + Point2 project(const Point3& pw) const { + + // project to normalized coordinates + const Point2 pn = PinholeBase::project2(pw); + + // uncalibrate to pixel coordinates + return calibration().uncalibrate(pn); + } + + /** project a point from world coordinate to the image, w 2 derivatives * @param pw is a point in the world coordinates */ Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, @@ -99,6 +114,47 @@ public : return pi; } + /** project a point at infinity from world coordinate to the image + * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) + * @param Dpose is the Jacobian w.r.t. pose3 + * @param Dpoint is the Jacobian w.r.t. point3 + * @param Dcal is the Jacobian w.r.t. calibration + */ + Point2 projectPointAtInfinity(const Point3& pw, OptionalJacobian<2, 6> Dpose = + boost::none, OptionalJacobian<2, 2> Dpoint = boost::none, + OptionalJacobian<2, DimK> Dcal = boost::none) const { + + if (!Dpose && !Dpoint && !Dcal) { + const Point3 pc = this->pose().rotation().unrotate(pw); // get direction in camera frame (translation does not matter) + const Point2 pn = PinholeBase::project_to_camera(pc);// project the point to the camera + return calibration().uncalibrate(pn); + } + + // world to camera coordinate + Matrix3 Dpc_rot, Dpc_point; + const Point3 pc = this->pose().rotation().unrotate(pw, Dpc_rot, Dpc_point); + + Matrix36 Dpc_pose; + Dpc_pose.setZero(); + Dpc_pose.leftCols<3>() = Dpc_rot; + + // camera to normalized image coordinate + Matrix23 Dpn_pc;// 2*3 + const Point2 pn = PinholeBase::project_to_camera(pc, Dpn_pc); + + // uncalibration + Matrix2 Dpi_pn;// 2*2 + const Point2 pi = calibration().uncalibrate(pn, Dcal, Dpi_pn); + + // chain the Jacobian matrices + const Matrix23 Dpi_pc = Dpi_pn * Dpn_pc; + if (Dpose) + *Dpose = Dpi_pc * Dpc_pose; + if (Dpoint) + *Dpoint = (Dpi_pc * Dpc_point).leftCols<2>();// only 2dof are important for the point (direction-only) + return pi; + } + /// backproject a 2-dimensional point to a 3-dimensional point at given depth Point3 backproject(const Point2& p, double depth) const { const Point2 pn = calibration().calibrate(p); From 4c7f0eba004eaf6e527d08096745ba7eea6fb62b Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 12:41:14 +0100 Subject: [PATCH 019/173] Added some templates with whole cameras --- gtsam/geometry/triangulation.h | 58 ++++++++++++++++++++++---------- gtsam/slam/TriangulationFactor.h | 20 +++++------ 2 files changed, 50 insertions(+), 28 deletions(-) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index ce83f780b..164bfa881 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -54,7 +54,6 @@ GTSAM_EXPORT Point3 triangulateDLT( const std::vector& projection_matrices, const std::vector& measurements, double rank_tol); -/// /** * Create a factor graph with projection factors from poses and one calibration * @param poses Camera poses @@ -76,8 +75,8 @@ std::pair triangulationGraph( static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); for (size_t i = 0; i < measurements.size(); i++) { const Pose3& pose_i = poses[i]; - PinholeCamera camera_i(pose_i, *sharedCal); - graph.push_back(TriangulationFactor // + PinholePose camera_i(pose_i, sharedCal); + graph.push_back(TriangulationFactor > // (camera_i, measurements[i], unit2, landmarkKey)); } return std::make_pair(graph, values); @@ -92,25 +91,32 @@ std::pair triangulationGraph( * @param initialEstimate * @return graph and initial values */ -template +template std::pair triangulationGraph( - const std::vector >& cameras, - const std::vector& measurements, Key landmarkKey, - const Point3& initialEstimate) { + const std::vector& cameras, const std::vector& measurements, + Key landmarkKey, const Point3& initialEstimate) { Values values; values.insert(landmarkKey, initialEstimate); // Initial landmark value NonlinearFactorGraph graph; static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); for (size_t i = 0; i < measurements.size(); i++) { - const PinholeCamera& camera_i = cameras[i]; - graph.push_back(TriangulationFactor // + const CAMERA& camera_i = cameras[i]; + graph.push_back(TriangulationFactor // (camera_i, measurements[i], unit2, landmarkKey)); } return std::make_pair(graph, values); } -/// +/// PinholeCamera specific version +template +std::pair triangulationGraph( + const std::vector >& cameras, + const std::vector& measurements, Key landmarkKey, + const Point3& initialEstimate) { + return triangulationGraph(cameras, measurements, landmarkKey, initialEstimate); +} + /** * Optimize for triangulation * @param graph nonlinear factors for projection @@ -150,9 +156,8 @@ Point3 triangulateNonlinear(const std::vector& poses, * @param initialEstimate * @return refined Point3 */ -template -Point3 triangulateNonlinear( - const std::vector >& cameras, +template +Point3 triangulateNonlinear(const std::vector& cameras, const std::vector& measurements, const Point3& initialEstimate) { // Create a factor graph and initial values @@ -164,6 +169,14 @@ Point3 triangulateNonlinear( return optimize(graph, values, Symbol('p', 0)); } +/// PinholeCamera specific version +template +Point3 triangulateNonlinear( + const std::vector >& cameras, + const std::vector& measurements, const Point3& initialEstimate) { + return triangulateNonlinear(cameras, measurements, initialEstimate); +} + /** * Function to triangulate 3D landmark point from an arbitrary number * of poses (at least 2) using the DLT. The function checks that the @@ -223,9 +236,9 @@ Point3 triangulatePoint3(const std::vector& poses, * @param optimize Flag to turn on nonlinear refinement of triangulation * @return Returns a Point3 */ -template +template Point3 triangulatePoint3( - const std::vector >& cameras, + const std::vector& cameras, const std::vector& measurements, double rank_tol = 1e-9, bool optimize = false) { @@ -236,9 +249,8 @@ Point3 triangulatePoint3( throw(TriangulationUnderconstrainedException()); // construct projection matrices from poses & calibration - typedef PinholeCamera Camera; std::vector projection_matrices; - BOOST_FOREACH(const Camera& camera, cameras) { + BOOST_FOREACH(const CAMERA& camera, cameras) { Matrix P_ = (camera.pose().inverse().matrix()); projection_matrices.push_back(camera.calibration().K()* (P_.block<3,4>(0,0)) ); } @@ -250,7 +262,7 @@ Point3 triangulatePoint3( #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION // verify that the triangulated point lies infront of all cameras - BOOST_FOREACH(const Camera& camera, cameras) { + BOOST_FOREACH(const CAMERA& camera, cameras) { const Point3& p_local = camera.pose().transform_to(point); if (p_local.z() <= 0) throw(TriangulationCheiralityException()); @@ -260,5 +272,15 @@ Point3 triangulatePoint3( return point; } +/// Pinhole-specific version +template +Point3 triangulatePoint3( + const std::vector >& cameras, + const std::vector& measurements, double rank_tol = 1e-9, + bool optimize = false) { + return triangulatePoint3 >(cameras, measurements, + rank_tol, optimize); +} + } // \namespace gtsam diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index b7f6a20dc..895d00f4c 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -27,16 +27,22 @@ namespace gtsam { * The calibration and pose are assumed known. * @addtogroup SLAM */ -template +template > class TriangulationFactor: public NoiseModelFactor1 { public: /// Camera type - typedef PinholeCamera Camera; + typedef CAMERA Camera; protected: + /// shorthand for base class type + typedef NoiseModelFactor1 Base; + + /// shorthand for this class + typedef TriangulationFactor This; + // Keep a copy of measurement and calibration for I/O const Camera camera_; ///< Camera in which this landmark was seen const Point2 measured_; ///< 2D measurement @@ -47,12 +53,6 @@ protected: public: - /// shorthand for base class type - typedef NoiseModelFactor1 Base; - - /// shorthand for this class - typedef TriangulationFactor This; - /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -114,7 +114,7 @@ public: Vector evaluateError(const Point3& point, boost::optional H2 = boost::none) const { try { - Point2 error(camera_.project(point, boost::none, H2, boost::none) - measured_); + Point2 error(camera_.project2(point, boost::none, H2) - measured_); return error.vector(); } catch (CheiralityException& e) { if (H2) @@ -154,7 +154,7 @@ public: // Would be even better if we could pass blocks to project const Point3& point = x.at(key()); - b = -(camera_.project(point, boost::none, A, boost::none) - measured_).vector(); + b = -(camera_.project2(point, boost::none, A) - measured_).vector(); if (noiseModel_) this->noiseModel_->WhitenSystem(A, b); From 59e6a636f2f144672033a4cb8f948d9d26faa703 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 12:41:33 +0100 Subject: [PATCH 020/173] Added Measurement type --- gtsam/geometry/CalibratedCamera.h | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 0e6f83fdf..6d08f2160 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -42,6 +42,14 @@ public: */ class GTSAM_EXPORT PinholeBase { +public: + + /** + * Some classes template on either PinholeCamera or StereoCamera, + * and this typedef informs those classes what "project" returns. + */ + typedef Point2 Measurement; + private: Pose3 pose_; ///< 3D pose of camera @@ -263,8 +271,8 @@ public: } /* ************************************************************************* */ - Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose, - OptionalJacobian<2, 3> Dpoint) const { + Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 3> Dpoint = boost::none) const { Matrix3 Rt; // calculated by transform_to if needed const Point3 q = pose().transform_to(point, boost::none, Dpoint ? &Rt : 0); From d5261e2e8dca75196b9f19c52f8bb2d7b1980443 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 12:41:45 +0100 Subject: [PATCH 021/173] triangulation targets --- .cproject | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/.cproject b/.cproject index 1aa6ab5e1..79cb93f93 100644 --- a/.cproject +++ b/.cproject @@ -1035,6 +1035,14 @@ true true + + make + -j4 + testTriangulation.run + true + true + true + make -j2 @@ -1578,6 +1586,14 @@ true true + + make + -j4 + testTriangulationFactor.run + true + true + true + make -j3 From d6f54475c3cbe41006cceed5685a8288a3f889bc Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 12:43:43 +0100 Subject: [PATCH 022/173] BIG change: SmartFactorBase and SmartProjectionFactor now templated on CAMERA --- gtsam/slam/SmartFactorBase.h | 73 +-- gtsam/slam/SmartProjectionCameraFactor.h | 36 +- gtsam/slam/SmartProjectionFactor.h | 108 ++-- gtsam/slam/SmartProjectionPoseFactor.h | 33 +- .../tests/testSmartProjectionCameraFactor.cpp | 4 +- .../tests/testSmartProjectionPoseFactor.cpp | 488 ++++++++---------- .../slam/SmartStereoProjectionFactor.h | 48 +- 7 files changed, 352 insertions(+), 438 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 10352405a..a184a7956 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -45,6 +45,9 @@ template class SmartFactorBase: public NonlinearFactor { private: + typedef NonlinearFactor Base; + typedef SmartFactorBase This; + typedef typename CAMERA::Measurement Z; /** * As of Feb 22, 2015, the noise model is the same for all measurements and @@ -56,9 +59,6 @@ private: protected: - // Figure out the measurement type - typedef typename CAMERA::Measurement Z; - /** * 2D measurement and noise model for each of the m views * We keep a copy of measurements for I/O and computing the error. @@ -66,19 +66,11 @@ protected: */ std::vector measured_; - /// shorthand for base class type - typedef NonlinearFactor Base; - - /// shorthand for this class - typedef SmartFactorBase This; - static const int ZDim = traits::dimension; ///< Measurement dimension static const int Dim = traits::dimension; ///< Camera dimension - // Definitions for blocks of F - typedef Eigen::Matrix Matrix2D; // F + // Definitions for block matrices used internally typedef Eigen::Matrix MatrixD2; // F' - typedef std::pair KeyMatrix2D; // Fblocks typedef Eigen::Matrix MatrixDD; // camera hessian block typedef Eigen::Matrix Matrix23; typedef Eigen::Matrix VectorD; @@ -105,6 +97,10 @@ protected: public: + // Definitions for blocks of F, externally visible + typedef Eigen::Matrix Matrix2D; // F + typedef std::pair KeyMatrix2D; // Fblocks + EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for a smart pointer to a factor @@ -256,57 +252,19 @@ public: } /** - * Compute whitenedError, returning only the derivative E, i.e., - * the stacked ZDim*3 derivatives of project with respect to the point. - * Assumes non-degenerate ! TODO explain this - */ - Vector reprojectionErrors(const Cameras& cameras, const Point3& point, - Matrix& E) const { - - // Project into CameraSet, calculating derivatives - std::vector predicted; - predicted = cameras.project2(point, boost::none, E); - - // if needed, whiten - size_t m = keys_.size(); - Vector b(ZDim * m); - for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { - - // Calculate error - const Z& zi = measured_.at(i); - Vector bi = (zi - predicted[i]).vector(); - b.segment(row) = bi; - } - return b; - } - - /** - * Compute F, E, and optionally H, where F and E are the stacked derivatives - * with respect to the cameras, point, and calibration, respectively. - * The value of cameras/point are passed as parameters. - * Returns error vector b + * Compute reprojection errors and derivatives * TODO: the treatment of body_P_sensor_ is weird: the transformation * is applied in the caller, but the derivatives are computed here. */ Vector reprojectionErrors(const Cameras& cameras, const Point3& point, typename Cameras::FBlocks& F, Matrix& E) const { - // Project into CameraSet, calculating derivatives - std::vector predicted; - predicted = cameras.project2(point, F, E); + Vector b = cameras.reprojectionErrors(point, measured_, F, E); - // Calculate error and whiten derivatives if needed - size_t m = keys_.size(); - Vector b(ZDim * m); - for (size_t i = 0; i < m; i++) { - - // Calculate error - const Z& zi = measured_.at(i); - Vector bi = (zi - predicted[i]).vector(); - - // if we have a sensor offset, correct camera derivatives - if (body_P_sensor_) { - // TODO: no simpler way ?? + // Apply sensor chain rule if needed TODO: no simpler way ?? + if (body_P_sensor_) { + size_t m = keys_.size(); + for (size_t i = 0; i < m; i++) { const Pose3& pose_i = cameras[i].pose(); Pose3 w_Pose_body = pose_i.compose(body_P_sensor_->inverse()); Matrix66 J; @@ -314,6 +272,7 @@ public: F[i].leftCols(6) *= J; } } + return b; } @@ -344,7 +303,7 @@ public: /// Assumes non-degenerate ! void computeEP(Matrix& E, Matrix& P, const Cameras& cameras, const Point3& point) const { - reprojectionErrors(cameras, point, E); + cameras.reprojectionErrors(point, measured_, boost::none, E); P = PointCov(E); } diff --git a/gtsam/slam/SmartProjectionCameraFactor.h b/gtsam/slam/SmartProjectionCameraFactor.h index d5bdc2e84..8381c847e 100644 --- a/gtsam/slam/SmartProjectionCameraFactor.h +++ b/gtsam/slam/SmartProjectionCameraFactor.h @@ -25,23 +25,29 @@ namespace gtsam { /** * @addtogroup SLAM */ -template -class SmartProjectionCameraFactor: public SmartProjectionFactor { +template +class SmartProjectionCameraFactor: public SmartProjectionFactor< + PinholeCamera > { + +private: + typedef PinholeCamera Camera; + typedef SmartProjectionFactor Base; + typedef SmartProjectionCameraFactor This; + protected: + static const int Dim = traits::dimension; ///< CAMERA dimension + bool isImplicit_; public: - /// shorthand for base class type - typedef SmartProjectionFactor Base; - - /// shorthand for this class - typedef SmartProjectionCameraFactor This; - /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; + // A set of cameras + typedef CameraSet Cameras; + /** * Constructor * @param rankTol tolerance used to check if point triangulation is degenerate @@ -88,14 +94,14 @@ public: /// get the dimension of the factor (number of rows on linearization) virtual size_t dim() const { - return D * this->keys_.size(); // 6 for the pose and 3 for the calibration + return Dim * this->keys_.size(); // 6 for the pose and 3 for the calibration } /// Collect all cameras: important that in key order - typename Base::Cameras cameras(const Values& values) const { - typename Base::Cameras cameras; + Cameras cameras(const Values& values) const { + Cameras cameras; BOOST_FOREACH(const Key& k, this->keys_) - cameras.push_back(values.at(k)); + cameras.push_back(values.at(k)); return cameras; } @@ -109,19 +115,19 @@ public: } /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr > linearizeToHessian( + virtual boost::shared_ptr > linearizeToHessian( const Values& values, double lambda=0.0) const { return Base::createHessianFactor(cameras(values),lambda); } /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr > linearizeToImplicit( + virtual boost::shared_ptr > linearizeToImplicit( const Values& values, double lambda=0.0) const { return Base::createRegularImplicitSchurFactor(cameras(values),lambda); } /// linearize returns a Jacobianfactor that is an approximation of error(p) - virtual boost::shared_ptr > linearizeToJacobian( + virtual boost::shared_ptr > linearizeToJacobian( const Values& values, double lambda=0.0) const { return Base::createJacobianQFactor(cameras(values),lambda); } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 8c11d7ec4..7a73a0c49 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -60,11 +60,17 @@ enum LinearizationMode { /** * SmartProjectionFactor: triangulates point and keeps an estimate of it around. */ -template -class SmartProjectionFactor: public SmartFactorBase, - D> { +template +class SmartProjectionFactor: public SmartFactorBase { + +private: + typedef SmartFactorBase Base; + typedef SmartProjectionFactor This; + protected: + static const int Dim = traits::dimension; ///< CAMERA dimension + // Some triangulation parameters const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate @@ -91,9 +97,6 @@ protected: /// shorthand for smart projection factor state variable typedef boost::shared_ptr SmartFactorStatePtr; - /// shorthand for base class type - typedef SmartFactorBase, D> Base; - double landmarkDistanceThreshold_; // if the landmark is triangulated at a // distance larger than that the factor is considered degenerate @@ -101,17 +104,13 @@ protected: // average reprojection error is smaller than this threshold after triangulation, // and the factor is disregarded if the error is large - /// shorthand for this class - typedef SmartProjectionFactor This; - public: /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; - /// shorthand for a pinhole camera - typedef PinholeCamera Camera; - typedef CameraSet Cameras; + /// shorthand for a set of cameras + typedef CameraSet Cameras; /** * Constructor @@ -243,7 +242,7 @@ public: // We triangulate the 3D position of the landmark try { // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - point_ = triangulatePoint3(cameras, this->measured_, + point_ = triangulatePoint3(cameras, this->measured_, rankTolerance_, enableEPI_); degenerate_ = false; cheiralityException_ = false; @@ -251,7 +250,7 @@ public: // Check landmark distance and reprojection errors to avoid outliers double totalReprojError = 0.0; size_t i = 0; - BOOST_FOREACH(const Camera& camera, cameras) { + BOOST_FOREACH(const CAMERA& camera, cameras) { Point3 cameraTranslation = camera.pose().translation(); // we discard smart factors corresponding to points that are far away if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { @@ -314,7 +313,7 @@ public: } /// linearize returns a Hessianfactor that is an approximation of error(p) - boost::shared_ptr > createHessianFactor( + boost::shared_ptr > createHessianFactor( const Cameras& cameras, const double lambda = 0.0) const { bool isDebug = false; @@ -338,10 +337,10 @@ public: && (this->cheiralityException_ || this->degenerate_))) { // std::cout << "In linearize: exception" << std::endl; BOOST_FOREACH(Matrix& m, Gs) - m = zeros(D, D); + m = zeros(Dim, Dim); BOOST_FOREACH(Vector& v, gs) - v = zero(D); - return boost::make_shared >(this->keys_, Gs, gs, + v = zero(Dim); + return boost::make_shared >(this->keys_, Gs, gs, 0.0); } @@ -366,7 +365,7 @@ public: << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" << std::endl; exit(1); - return boost::make_shared >(this->keys_, + return boost::make_shared >(this->keys_, this->state_->Gs, this->state_->gs, this->state_->f); } @@ -378,7 +377,7 @@ public: // Schur complement trick // Frank says: should be possible to do this more efficiently? // And we care, as in grouped factors this is called repeatedly - Matrix H(D * numKeys, D * numKeys); + Matrix H(Dim * numKeys, Dim * numKeys); Vector gs_vector; Matrix3 P = Base::PointCov(E, lambda); @@ -390,11 +389,11 @@ public: // Populate Gs and gs int GsCount2 = 0; for (DenseIndex i1 = 0; i1 < (DenseIndex) numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * D; - gs.at(i1) = gs_vector.segment(i1D); + DenseIndex i1D = i1 * Dim; + gs.at(i1) = gs_vector.segment(i1D); for (DenseIndex i2 = 0; i2 < (DenseIndex) numKeys; i2++) { if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * D); + Gs.at(GsCount2) = H.block(i1D, i2 * Dim); GsCount2++; } } @@ -405,37 +404,37 @@ public: this->state_->gs = gs; this->state_->f = f; } - return boost::make_shared >(this->keys_, Gs, gs, f); + return boost::make_shared >(this->keys_, Gs, gs, f); } // create factor - boost::shared_ptr > createRegularImplicitSchurFactor( + boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) return Base::createRegularImplicitSchurFactor(cameras, point_, lambda); else - return boost::shared_ptr >(); + return boost::shared_ptr >(); } /// create factor - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) return Base::createJacobianQFactor(cameras, point_, lambda); else - return boost::make_shared >(this->keys_); + return boost::make_shared >(this->keys_); } /// Create a factor, takes values - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Values& values, double lambda) const { - Cameras myCameras; + Cameras cameras; // TODO triangulate twice ?? - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return createJacobianQFactor(myCameras, lambda); + return createJacobianQFactor(cameras, lambda); else - return boost::make_shared >(this->keys_); + return boost::make_shared >(this->keys_); } /// different (faster) way to compute Jacobian factor @@ -444,20 +443,20 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared >(this->keys_); + return boost::make_shared >(this->keys_); } /// Returns true if nonDegenerate bool computeCamerasAndTriangulate(const Values& values, - Cameras& myCameras) const { + Cameras& cameras) const { Values valuesFactor; // Select only the cameras BOOST_FOREACH(const Key key, this->keys_) valuesFactor.insert(key, values.at(key)); - myCameras = this->cameras(valuesFactor); - size_t nrCameras = this->triangulateSafe(myCameras); + cameras = this->cameras(valuesFactor); + size_t nrCameras = this->triangulateSafe(cameras); if (nrCameras < 2 || (!this->manageDegeneracy_ @@ -477,27 +476,22 @@ public: return true; } - /// Assumes non-degenerate ! - void computeEP(Matrix& E, Matrix& P, const Cameras& cameras) const { - return Base::computeEP(E, P, cameras, point_); - } - /// Takes values bool computeEP(Matrix& E, Matrix& P, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - computeEP(E, P, myCameras); + Base::computeEP(E, P, cameras, point_); return nonDegenerate; } /// Version that takes values, and creates the point bool computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - computeJacobians(Fblocks, E, b, myCameras); + computeJacobians(Fblocks, E, b, cameras); return nonDegenerate; } @@ -513,12 +507,13 @@ public: std::cout << "SmartProjectionFactor: Management of degeneracy is disabled - not ready to be used" << std::endl; - if (D > 6) { + if (Dim > 6) { std::cout << "Management of degeneracy is not yet ready when one also optimizes for the calibration " << std::endl; } + // TODO replace all this by Call to CameraSet int numKeys = this->keys_.size(); E = zeros(2 * numKeys, 2); b = zero(2 * numKeys); @@ -533,7 +528,6 @@ public: Vector bi = -(cameras[i].projectPointAtInfinity(this->point_, Fi, Ei) - this->measured_.at(i)).vector(); - this->noiseModel_->WhitenSystem(Fi, Ei, bi); f += bi.squaredNorm(); Fblocks.push_back(typename Base::KeyMatrix2D(this->keys_[i], Fi)); E.block<2, 2>(2 * i, 0) = Ei; @@ -549,10 +543,10 @@ public: /// takes values bool computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, Vector& b, const Values& values) const { - typename Base::Cameras myCameras; - double good = computeCamerasAndTriangulate(values, myCameras); + typename Base::Cameras cameras; + double good = computeCamerasAndTriangulate(values, cameras); if (good) - computeJacobiansSVD(Fblocks, Enull, b, myCameras); + computeJacobiansSVD(Fblocks, Enull, b, cameras); return true; } @@ -583,12 +577,12 @@ public: /// Calculate vector of re-projection errors, before applying noise model Vector reprojectionError(const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return reprojectionError(myCameras); + return reprojectionError(cameras); else - return zero(myCameras.size() * 2); + return zero(cameras.size() * 2); } /** diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 70476ba3e..5cfd74913 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -38,21 +38,22 @@ namespace gtsam { * @addtogroup SLAM */ template -class SmartProjectionPoseFactor: public SmartProjectionFactor { +class SmartProjectionPoseFactor: public SmartProjectionFactor< + PinholePose > { + +private: + typedef PinholePose Camera; + typedef SmartProjectionFactor Base; + typedef SmartProjectionPoseFactor This; + protected: LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) - std::vector > K_all_; ///< shared pointer to calibration object (one for each camera) + std::vector > sharedKs_; ///< shared pointer to calibration object (one for each camera) public: - /// shorthand for base class type - typedef SmartProjectionFactor Base; - - /// shorthand for this class - typedef SmartProjectionPoseFactor This; - /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -87,7 +88,7 @@ public: const SharedNoiseModel noise_i, const boost::shared_ptr K_i) { Base::add(measured_i, poseKey_i, noise_i); - K_all_.push_back(K_i); + sharedKs_.push_back(K_i); } /** @@ -102,7 +103,7 @@ public: std::vector > Ks) { Base::add(measurements, poseKeys, noises); for (size_t i = 0; i < measurements.size(); i++) { - K_all_.push_back(Ks.at(i)); + sharedKs_.push_back(Ks.at(i)); } } @@ -117,7 +118,7 @@ public: const SharedNoiseModel noise, const boost::shared_ptr K) { for (size_t i = 0; i < measurements.size(); i++) { Base::add(measurements.at(i), poseKeys.at(i), noise); - K_all_.push_back(K); + sharedKs_.push_back(K); } } @@ -129,7 +130,7 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionPoseFactor, z = \n "; - BOOST_FOREACH(const boost::shared_ptr& K, K_all_) + BOOST_FOREACH(const boost::shared_ptr& K, sharedKs_) K->print("calibration = "); Base::print("", keyFormatter); } @@ -155,7 +156,7 @@ public: if(Base::body_P_sensor_) pose = pose.compose(*(Base::body_P_sensor_)); - typename Base::Camera camera(pose, *K_all_[i++]); + Camera camera(pose, sharedKs_[i++]); cameras.push_back(camera); } return cameras; @@ -193,9 +194,9 @@ public: } } - /** return the calibration object */ + /** return calibration shared pointers */ inline const std::vector > calibration() const { - return K_all_; + return sharedKs_; } private: @@ -205,7 +206,7 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(K_all_); + ar & BOOST_SERIALIZATION_NVP(sharedKs_); } }; // end of class declaration diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 88a0c0521..b9634025b 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -72,8 +72,8 @@ 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 PinholeCamera CameraCal3_S2; -typedef SmartProjectionCameraFactor SmartFactor; -typedef SmartProjectionCameraFactor SmartFactorBundler; +typedef SmartProjectionCameraFactor SmartFactor; +typedef SmartProjectionCameraFactor SmartFactorBundler; typedef GeneralSFMFactor SFMFactor; template diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 9b36b645a..e1ef82b82 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -32,22 +32,23 @@ using namespace std; using namespace boost::assign; using namespace gtsam; -static bool isDebugTest = false; +static bool isDebugTest = true; // 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)); -static Cal3_S2::shared_ptr K2(new Cal3_S2(1500, 1200, 0, 640, 480)); -static boost::shared_ptr Kbundler( +static Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); +static Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); +static boost::shared_ptr sharedBundlerK( new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); -static double rankTol = 1.0; -static double linThreshold = -1.0; -static bool manageDegeneracy = true; +static const double rankTol = 1.0; +static const double linThreshold = -1.0; +static const bool manageDegeneracy = true; // Create a noise model for the pixel error -static SharedNoiseModel model(noiseModel::Isotropic::Sigma(2, 0.1)); +static const double sigma = 0.1; +static SharedNoiseModel model(noiseModel::Isotropic::Sigma(2, sigma)); // Convenience for named keys using symbol_shorthand::X; @@ -63,11 +64,28 @@ 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 PinholePose Camera; typedef SmartProjectionPoseFactor SmartFactor; + +typedef PinholePose CameraBundler; typedef SmartProjectionPoseFactor SmartFactorBundler; -void projectToMultipleCameras(SimpleCamera cam1, SimpleCamera cam2, - SimpleCamera cam3, Point3 landmark, vector& measurements_cam) { +// 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), + Point3(0, 0, 1)); +Camera level_camera(level_pose, sharedK2); + +// create second camera 1 meter to the right of first camera +Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); +Camera level_camera_right(level_pose_right, sharedK2); + +// landmarks ~5 meters in front of camera +Point3 landmark1(5, 0.5, 1.2); +Point3 landmark2(5, -0.5, 1.2); +Point3 landmark3(5, 0, 3.0); + +void projectToMultipleCameras(Camera cam1, Camera cam2, Camera cam3, + Point3 landmark, vector& measurements_cam) { Point2 cam1_uv1 = cam1.project(landmark); Point2 cam2_uv1 = cam2.project(landmark); @@ -90,13 +108,13 @@ TEST( SmartProjectionPoseFactor, Constructor2) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor3) { SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, K); + factor1->add(measurement1, poseKey1, model, sharedK); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { SmartFactor factor1(rankTol, linThreshold); - factor1.add(measurement1, poseKey1, model, K); + factor1.add(measurement1, poseKey1, model, sharedK); } /* ************************************************************************* */ @@ -105,16 +123,16 @@ TEST( SmartProjectionPoseFactor, ConstructorWithTransform) { bool enableEPI = false; SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor1); - factor1.add(measurement1, poseKey1, model, K); + factor1.add(measurement1, poseKey1, model, sharedK); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Equals ) { SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, K); + factor1->add(measurement1, poseKey1, model, sharedK); SmartFactor::shared_ptr factor2(new SmartFactor()); - factor2->add(measurement1, poseKey1, model, K); + factor2->add(measurement1, poseKey1, model, sharedK); CHECK(assert_equal(*factor1, *factor2)); } @@ -123,30 +141,18 @@ TEST( SmartProjectionPoseFactor, Equals ) { TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; - // 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), - Point3(0, 0, 1)); - SimpleCamera level_camera(level_pose, *K2); - - // 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, *K2); - - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - // Project two landmarks into two cameras - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); + Point2 level_uv = level_camera.project(landmark1); + Point2 level_uv_right = level_camera_right.project(landmark1); + + SmartFactor factor; + factor.add(level_uv, x1, model, sharedK); + factor.add(level_uv_right, x2, model, sharedK); Values values; values.insert(x1, level_pose); values.insert(x2, level_pose_right); - SmartFactor factor; - factor.add(level_uv, x1, model, K); - factor.add(level_uv_right, x2, model, K); - double actualError = factor.error(values); double expectedError = 0.0; EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7); @@ -155,51 +161,44 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { double actualError2 = factor.totalReprojectionError(cameras); EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); - // test vector of errors - //Vector actual = factor.unwhitenedError(values); - //EXPECT(assert_equal(zero(4),actual,1e-8)); - - // Check derivatives - // Calculate expected derivative for point (easiest to check) boost::function f = // boost::bind(&SmartFactor::whitenedErrors, factor, cameras, _1); boost::optional point = factor.point(); CHECK(point); - Matrix expectedE = numericalDerivative11(f, *point); + + // Note ! After refactor the noiseModel is only in the factors, not these matrices + Matrix expectedE = sigma * numericalDerivative11(f, *point); // Calculate using computeEP Matrix actualE, PointCov; - factor.computeEP(actualE, PointCov, cameras); + factor.computeEP(actualE, PointCov, values); EXPECT(assert_equal(expectedE, actualE, 1e-7)); - // Calculate using whitenedError - Matrix F, actualE2; - Vector actualErrors = factor.whitenedError(cameras, *point, F, actualE2); - EXPECT(assert_equal(expectedE, actualE2, 1e-7)); - EXPECT(assert_equal(f(*point), actualErrors, 1e-7)); + // Calculate using reprojectionErrors, note not yet divided by sigma ! + SmartFactor::Cameras::FBlocks F; + Matrix E; + Vector actualErrors = factor.reprojectionErrors(cameras, *point, F, E); + EXPECT(assert_equal(expectedE, E, 1e-7)); + + EXPECT(assert_equal(zero(4), actualErrors, 1e-7)); + + // Calculate using computeJacobians + Vector b; + vector Fblocks; + double actualError3 = factor.computeJacobians(Fblocks, E, b, cameras); + EXPECT(assert_equal(expectedE, E, 1e-7)); + EXPECT_DOUBLES_EQUAL(expectedError, actualError3, 1e-8); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, noisy ) { // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; - // 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), - Point3(0, 0, 1)); - SimpleCamera level_camera(level_pose, *K2); - - // 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, *K2); - - // 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); + Point2 level_uv = level_camera.project(landmark1) + pixelError; + Point2 level_uv_right = level_camera_right.project(landmark1); Values values; values.insert(x1, level_pose); @@ -208,8 +207,8 @@ TEST( SmartProjectionPoseFactor, noisy ) { values.insert(x2, level_pose_right.compose(noise_pose)); SmartFactor::shared_ptr factor(new SmartFactor()); - factor->add(level_uv, x1, model, K); - factor->add(level_uv_right, x2, model, K); + factor->add(level_uv, x1, model, sharedK); + factor->add(level_uv_right, x2, model, sharedK); double actualError1 = factor->error(values); @@ -223,8 +222,8 @@ TEST( SmartProjectionPoseFactor, noisy ) { noises.push_back(model); vector > Ks; ///< shared pointer to calibration object (one for each camera) - Ks.push_back(K); - Ks.push_back(K); + Ks.push_back(sharedK); + Ks.push_back(sharedK); vector views; views.push_back(x1); @@ -243,20 +242,15 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); + Camera cam1(pose1, sharedK2); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K2); + Camera cam2(pose2, sharedK2); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K2); - - // 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); + Camera cam3(pose3, sharedK2); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -271,13 +265,13 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { views.push_back(x3); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K2); + smartFactor1->add(measurements_cam1, views, model, sharedK2); SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, K2); + smartFactor2->add(measurements_cam2, views, model, sharedK2); SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, K2); + smartFactor3->add(measurements_cam3, views, model, sharedK2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -312,8 +306,8 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { gttoc_(SmartProjectionPoseFactor); tictoc_finishedIteration_(); -// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); -// VectorValues delta = GFG->optimize(); + GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + VectorValues delta = GFG->optimize(); // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) @@ -332,9 +326,9 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { 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); + Camera cam1(cameraPose1, sharedK); // with camera poses + Camera cam2(cameraPose2, sharedK); + Camera cam3(cameraPose3, sharedK); // create arbitrary body_Pose_sensor (transforms from sensor to body) Pose3 sensor_to_body = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), @@ -345,11 +339,6 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { Pose3 bodyPose2 = cameraPose2.compose(sensor_to_body.inverse()); Pose3 bodyPose3 = cameraPose3.compose(sensor_to_body.inverse()); - // 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); - vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras @@ -371,17 +360,17 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, sensor_to_body)); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, sensor_to_body)); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, sensor_to_body)); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -428,34 +417,36 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { boost::bind(&SmartFactor::whitenedErrors, *smartFactor1, cameras, _1); boost::optional point = smartFactor1->point(); CHECK(point); - Matrix expectedE = numericalDerivative11(f, *point); + + // Note ! After refactor the noiseModel is only in the factors, not these matrices + Matrix expectedE = sigma * numericalDerivative11(f, *point); // Calculate using computeEP Matrix actualE, PointCov; - smartFactor1->computeEP(actualE, PointCov, cameras); + smartFactor1->computeEP(actualE, PointCov, values); EXPECT(assert_equal(expectedE, actualE, 1e-7)); // Calculate using whitenedError - Matrix F, actualE2; - Vector actualErrors = smartFactor1->whitenedError(cameras, *point, F, - actualE2); - EXPECT(assert_equal(expectedE, actualE2, 1e-7)); + Matrix E; + SmartFactor::Cameras::FBlocks F; + Vector actualErrors = smartFactor1->reprojectionErrors(cameras, *point, F, E); + EXPECT(assert_equal(expectedE, E, 1e-7)); - // TODO the derivatives agree with f, but returned errors are -f :-( - // TODO We should merge the two whitenedErrors functions and make derivatives optional - EXPECT(assert_equal(-f(*point), actualErrors, 1e-7)); + // Success ! The derivatives of reprojectionErrors now agree with f ! + EXPECT(assert_equal(f(*point) * sigma, actualErrors, 1e-7)); } /* *************************************************************************/ -TEST( SmartProjectionPoseFactor, Factors ){ +TEST( SmartProjectionPoseFactor, Factors ) { // Default cameras for simple derivatives Rot3 R; - static Cal3_S2::shared_ptr K(new Cal3_S2(100, 100, 0, 0, 0)); - SimpleCamera cam1(Pose3(R,Point3(0,0,0)),*K), cam2(Pose3(R,Point3(1,0,0)),*K); + static Cal3_S2::shared_ptr sharedK(new Cal3_S2(100, 100, 0, 0, 0)); + PinholePose cam1(Pose3(R, Point3(0, 0, 0)), sharedK), cam2( + Pose3(R, Point3(1, 0, 0)), sharedK); // one landmarks 1m in front of camera - Point3 landmark1(0,0,10); + Point3 landmark1(0, 0, 10); vector measurements_cam1; @@ -464,24 +455,24 @@ TEST( SmartProjectionPoseFactor, Factors ){ measurements_cam1.push_back(cam2.project(landmark1)); // Create smart factors - std::vector views; + vector views; views.push_back(x1); views.push_back(x2); SmartFactor::shared_ptr smartFactor1 = boost::make_shared(); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::Cameras cameras; cameras.push_back(cam1); cameras.push_back(cam2); // Make sure triangulation works - LONGS_EQUAL(2,smartFactor1->triangulateSafe(cameras)); + LONGS_EQUAL(2, smartFactor1->triangulateSafe(cameras)); CHECK(!smartFactor1->isDegenerate()); CHECK(!smartFactor1->isPointBehindCamera()); boost::optional p = smartFactor1->point(); CHECK(p); - EXPECT(assert_equal(landmark1,*p)); + EXPECT(assert_equal(landmark1, *p)); // After eliminating the point, A1 and A2 contain 2-rank information on cameras: Matrix16 A1, A2; @@ -489,12 +480,14 @@ TEST( SmartProjectionPoseFactor, Factors ){ A2 << 1000, 0, 100, 0, -100, 0; { // createHessianFactor - Matrix66 G11 = 0.5*A1.transpose()*A1; - Matrix66 G12 = 0.5*A1.transpose()*A2; - Matrix66 G22 = 0.5*A2.transpose()*A2; + Matrix66 G11 = 0.5 * A1.transpose() * A1; + Matrix66 G12 = 0.5 * A1.transpose() * A2; + Matrix66 G22 = 0.5 * A2.transpose() * A2; - Vector6 g1; g1.setZero(); - Vector6 g2; g2.setZero(); + Vector6 g1; + g1.setZero(); + Vector6 g2; + g2.setZero(); double f = 0; @@ -502,18 +495,37 @@ TEST( SmartProjectionPoseFactor, Factors ){ boost::shared_ptr > actual = smartFactor1->createHessianFactor(cameras, 0.0); - CHECK(assert_equal(expected.augmentedInformation(), actual->augmentedInformation(), 1e-8)); - CHECK(assert_equal(expected, *actual, 1e-8)); + EXPECT(assert_equal(expected.information(), actual->information(), 1e-8)); + EXPECT(assert_equal(expected, *actual, 1e-8)); } { - Matrix26 F1; F1.setZero(); F1(0,1)=-100; F1(0,3)=-10; F1(1,0)=100; F1(1,4)=-10; - Matrix26 F2; F2.setZero(); F2(0,1)=-101; F2(0,3)=-10; F2(0,5)=-1; F2(1,0)=100; F2(1,2)=10; F2(1,4)=-10; - Matrix43 E; E.setZero(); E(0,0)=100; E(1,1)=100; E(2,0)=100; E(2,2)=10;E(3,1)=100; + Matrix26 F1; + F1.setZero(); + F1(0, 1) = -100; + F1(0, 3) = -10; + F1(1, 0) = 100; + F1(1, 4) = -10; + Matrix26 F2; + F2.setZero(); + F2(0, 1) = -101; + F2(0, 3) = -10; + F2(0, 5) = -1; + F2(1, 0) = 100; + F2(1, 2) = 10; + F2(1, 4) = -10; + Matrix43 E; + E.setZero(); + E(0, 0) = 100; + E(1, 1) = 100; + E(2, 0) = 100; + E(2, 2) = 10; + E(3, 1) = 100; const vector > Fblocks = list_of > // - (make_pair(x1, 10*F1))(make_pair(x2, 10*F2)); + (make_pair(x1, 10 * F1))(make_pair(x2, 10 * F2)); Matrix3 P = (E.transpose() * E).inverse(); - Vector4 b; b.setZero(); + Vector4 b; + b.setZero(); // createRegularImplicitSchurFactor RegularImplicitSchurFactor<6> expected(Fblocks, E, P, b); @@ -524,26 +536,27 @@ TEST( SmartProjectionPoseFactor, Factors ){ CHECK(assert_equal(expected, *actual)); // createJacobianQFactor - JacobianFactorQ < 6, 2 > expectedQ(Fblocks, E, P, b); + JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b); boost::shared_ptr > actualQ = smartFactor1->createJacobianQFactor(cameras, 0.0); CHECK(actual); - CHECK(assert_equal(expectedQ.augmentedInformation(), actualQ->augmentedInformation(), 1e-8)); - CHECK(assert_equal(expectedQ, *actualQ)); + EXPECT(assert_equal(expectedQ.information(), actualQ->information(), 1e-8)); + EXPECT(assert_equal(expectedQ, *actualQ)); } { // createJacobianSVDFactor - Vector1 b; b.setZero(); + Vector1 b; + b.setZero(); double s = sin(M_PI_4); - JacobianFactor expected(x1, s*A1, x2, s*A2, b); + JacobianFactor expected(x1, s * A1, x2, s * A2, b); boost::shared_ptr actual = smartFactor1->createJacobianSVDFactor(cameras, 0.0); CHECK(actual); - CHECK(assert_equal(expected.augmentedInformation(), actual->augmentedInformation(), 1e-8)); - CHECK(assert_equal(expected, *actual)); + EXPECT(assert_equal(expected.information(), actual->information(), 1e-8)); + EXPECT(assert_equal(expected, *actual)); } } @@ -558,20 +571,15 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); + Camera cam2(pose2, sharedK); // 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); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -581,13 +589,13 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -640,18 +648,13 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); + Camera cam2(pose2, sharedK); // 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); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -662,15 +665,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -708,18 +711,13 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); + Camera cam2(pose2, sharedK); // 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); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -731,17 +729,17 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -781,18 +779,15 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); + Camera cam2(pose2, sharedK); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K); + Camera cam3(pose3, sharedK); - // 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); + // add fourth landmark Point3 landmark4(5, -0.5, 1); vector measurements_cam1, measurements_cam2, measurements_cam3, @@ -808,22 +803,22 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); SmartFactor::shared_ptr smartFactor4( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor4->add(measurements_cam4, views, model, K); + smartFactor4->add(measurements_cam4, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -860,18 +855,13 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); + Camera cam2(pose2, sharedK); // 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); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -882,15 +872,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -927,45 +917,40 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); + Camera cam1(pose1, sharedK2); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K2); + Camera cam2(pose2, sharedK2); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K2); - - // 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); + Camera cam3(pose3, sharedK2); typedef GenericProjectionFactor ProjectionFactor; NonlinearFactorGraph graph; // 1. Project three landmarks into three cameras and triangulate graph.push_back( - ProjectionFactor(cam1.project(landmark1), model, x1, L(1), K2)); + ProjectionFactor(cam1.project(landmark1), model, x1, L(1), sharedK2)); graph.push_back( - ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); + ProjectionFactor(cam2.project(landmark1), model, x2, L(1), sharedK2)); graph.push_back( - ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); + ProjectionFactor(cam3.project(landmark1), model, x3, L(1), sharedK2)); graph.push_back( - ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); + ProjectionFactor(cam1.project(landmark2), model, x1, L(2), sharedK2)); graph.push_back( - ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); + ProjectionFactor(cam2.project(landmark2), model, x2, L(2), sharedK2)); graph.push_back( - ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); + ProjectionFactor(cam3.project(landmark2), model, x3, L(2), sharedK2)); graph.push_back( - ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); + ProjectionFactor(cam1.project(landmark3), model, x1, L(3), sharedK2)); graph.push_back( - ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); + ProjectionFactor(cam2.project(landmark3), model, x2, L(3), sharedK2)); graph.push_back( - ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); + ProjectionFactor(cam3.project(landmark3), model, x3, L(3), sharedK2)); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); graph.push_back(PriorFactor(x1, pose1, noisePrior)); @@ -1006,20 +991,15 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // 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); + Camera cam2(pose2, sharedK); // 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); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -1031,13 +1011,13 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); NonlinearFactorGraph graph; graph.push_back(smartFactor1); @@ -1095,19 +1075,15 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); + Camera cam1(pose1, sharedK2); // 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, *K2); + Camera cam2(pose2, sharedK2); // 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, *K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); + Camera cam3(pose3, sharedK2); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -1118,11 +1094,11 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, K2); + smartFactor1->add(measurements_cam1, views, model, sharedK2); SmartFactor::shared_ptr smartFactor2( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, K2); + smartFactor2->add(measurements_cam2, views, model, sharedK2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, @@ -1183,20 +1159,15 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // 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); + Camera cam2(pose2, sharedK); // 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); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -1209,15 +1180,15 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) SmartFactor::shared_ptr smartFactor1( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, K); + smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, K); + smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor3->add(measurements_cam3, views, model, K); + smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, @@ -1279,14 +1250,11 @@ TEST( SmartProjectionPoseFactor, Hessian ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); + Camera cam1(pose1, sharedK2); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); + Camera cam2(pose2, sharedK2); // 1. Project three landmarks into three cameras and triangulate Point2 cam1_uv1 = cam1.project(landmark1); @@ -1296,7 +1264,7 @@ TEST( SmartProjectionPoseFactor, Hessian ) { measurements_cam1.push_back(cam2_uv1); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K2); + smartFactor1->add(measurements_cam1, views, model, sharedK2); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); @@ -1326,24 +1294,22 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + Camera cam1(pose1, sharedK); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); + Camera cam2(pose2, sharedK); // 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); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); - smartFactorInstance->add(measurements_cam1, views, model, K); + smartFactorInstance->add(measurements_cam1, views, model, sharedK); Values values; values.insert(x1, pose1); @@ -1398,24 +1364,22 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { // 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), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); + Camera cam1(pose1, sharedK2); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0, 0, 0)); - SimpleCamera cam2(pose2, *K2); + Camera cam2(pose2, sharedK2); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, 0, 0)); - SimpleCamera cam3(pose3, *K2); - - Point3 landmark1(5, 0.5, 1.2); + Camera cam3(pose3, sharedK2); vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); SmartFactor::shared_ptr smartFactor(new SmartFactor()); - smartFactor->add(measurements_cam1, views, model, K2); + smartFactor->add(measurements_cam1, views, model, sharedK2); Values values; values.insert(x1, pose1); @@ -1464,9 +1428,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { SmartFactorBundler factor(rankTol, linThreshold); - boost::shared_ptr Kbundler( + boost::shared_ptr sharedBundlerK( new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); - factor.add(measurement1, poseKey1, model, Kbundler); + factor.add(measurement1, poseKey1, model, sharedBundlerK); } /* *************************************************************************/ @@ -1475,19 +1439,17 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { // 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), Point3(0, 0, 1)); - PinholeCamera cam1(pose1, *Kbundler); + CameraBundler cam1(pose1, sharedBundlerK); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - PinholeCamera cam2(pose2, *Kbundler); + CameraBundler cam2(pose2, sharedBundlerK); // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - PinholeCamera cam3(pose3, *Kbundler); + CameraBundler cam3(pose3, sharedBundlerK); // 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; @@ -1520,13 +1482,13 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { views.push_back(x3); SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); - smartFactor1->add(measurements_cam1, views, model, Kbundler); + smartFactor1->add(measurements_cam1, views, model, sharedBundlerK); SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); - smartFactor2->add(measurements_cam2, views, model, Kbundler); + smartFactor2->add(measurements_cam2, views, model, sharedBundlerK); SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); - smartFactor3->add(measurements_cam3, views, model, Kbundler); + smartFactor3->add(measurements_cam3, views, model, sharedBundlerK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1579,19 +1541,17 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { // 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), Point3(0, 0, 1)); - PinholeCamera cam1(pose1, *Kbundler); + CameraBundler cam1(pose1, sharedBundlerK); // 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)); - PinholeCamera cam2(pose2, *Kbundler); + CameraBundler cam2(pose2, sharedBundlerK); // 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)); - PinholeCamera cam3(pose3, *Kbundler); + CameraBundler cam3(pose3, sharedBundlerK); - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); + // landmark3 at 3 meters now Point3 landmark3(3, 0, 3.0); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -1622,15 +1582,15 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { SmartFactorBundler::shared_ptr smartFactor1( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, Kbundler); + smartFactor1->add(measurements_cam1, views, model, sharedBundlerK); SmartFactorBundler::shared_ptr smartFactor2( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, Kbundler); + smartFactor2->add(measurements_cam2, views, model, sharedBundlerK); SmartFactorBundler::shared_ptr smartFactor3( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor3->add(measurements_cam3, views, model, Kbundler); + smartFactor3->add(measurements_cam3, views, model, sharedBundlerK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 11513d19f..0e70add9f 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -64,7 +64,7 @@ enum LinearizationMode { * SmartStereoProjectionFactor: triangulates point */ template -class SmartStereoProjectionFactor: public SmartFactorBase { +class SmartStereoProjectionFactor: public SmartFactorBase { protected: // Some triangulation parameters @@ -94,7 +94,7 @@ protected: typedef boost::shared_ptr SmartFactorStatePtr; /// shorthand for base class type - typedef SmartFactorBase Base; + typedef SmartFactorBase Base; double landmarkDistanceThreshold_; // if the landmark is triangulated at a // distance larger than that the factor is considered degenerate @@ -465,11 +465,11 @@ public: // /// Create a factor, takes values // boost::shared_ptr > createJacobianQFactor( // const Values& values, double lambda) const { -// Cameras myCameras; +// Cameras cameras; // // TODO triangulate twice ?? -// bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); +// bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); // if (nonDegenerate) -// return createJacobianQFactor(myCameras, lambda); +// return createJacobianQFactor(cameras, lambda); // else // return boost::make_shared< JacobianFactorQ >(this->keys_); // } @@ -485,15 +485,15 @@ public: /// Returns true if nonDegenerate bool computeCamerasAndTriangulate(const Values& values, - Cameras& myCameras) const { + Cameras& cameras) const { Values valuesFactor; // Select only the cameras BOOST_FOREACH(const Key key, this->keys_) valuesFactor.insert(key, values.at(key)); - myCameras = this->cameras(valuesFactor); - size_t nrCameras = this->triangulateSafe(myCameras); + cameras = this->cameras(valuesFactor); + size_t nrCameras = this->triangulateSafe(cameras); if (nrCameras < 2 || (!this->manageDegeneracy_ @@ -520,20 +520,20 @@ public: /// Takes values bool computeEP(Matrix& E, Matrix& PointCov, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - computeEP(E, PointCov, myCameras); + computeEP(E, PointCov, cameras); return nonDegenerate; } /// Version that takes values, and creates the point bool computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - computeJacobians(Fblocks, E, b, myCameras, 0.0); + computeJacobians(Fblocks, E, b, cameras, 0.0); return nonDegenerate; } @@ -598,10 +598,10 @@ public: // /// takes values // bool computeJacobiansSVD(std::vector& Fblocks, // Matrix& Enull, Vector& b, const Values& values) const { -// typename Base::Cameras myCameras; -// double good = computeCamerasAndTriangulate(values, myCameras); +// typename Base::Cameras cameras; +// double good = computeCamerasAndTriangulate(values, cameras); // if (good) -// computeJacobiansSVD(Fblocks, Enull, b, myCameras); +// computeJacobiansSVD(Fblocks, Enull, b, cameras); // return true; // } // @@ -624,20 +624,14 @@ public: return Base::computeJacobians(F, E, b, cameras, point_); } - /// Calculate vector of re-projection errors, before applying noise model - /// Assumes triangulation was done and degeneracy handled - Vector reprojectionError(const Cameras& cameras) const { - return Base::reprojectionError(cameras, point_); - } - /// Calculate vector of re-projection errors, before applying noise model Vector reprojectionError(const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return reprojectionError(myCameras); + return cameras.reprojectionErrors(point_); else - return zero(myCameras.size() * 3); + return zero(cameras.size() * 3); } /** From 8e615c0ce73ada59f0e980316252cff135ab1664 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 14:45:45 +0100 Subject: [PATCH 023/173] Fixed infinite recursion --- gtsam/geometry/triangulation.h | 40 ++++++++++++++++++---------------- 1 file changed, 21 insertions(+), 19 deletions(-) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 164bfa881..0a0508efc 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -18,7 +18,6 @@ #pragma once - #include #include #include @@ -114,7 +113,8 @@ std::pair triangulationGraph( const std::vector >& cameras, const std::vector& measurements, Key landmarkKey, const Point3& initialEstimate) { - return triangulationGraph(cameras, measurements, landmarkKey, initialEstimate); + return triangulationGraph > // + (cameras, measurements, landmarkKey, initialEstimate); } /** @@ -143,8 +143,8 @@ Point3 triangulateNonlinear(const std::vector& poses, // Create a factor graph and initial values Values values; NonlinearFactorGraph graph; - boost::tie(graph, values) = triangulationGraph(poses, sharedCal, measurements, - Symbol('p', 0), initialEstimate); + boost::tie(graph, values) = triangulationGraph // + (poses, sharedCal, measurements, Symbol('p', 0), initialEstimate); return optimize(graph, values, Symbol('p', 0)); } @@ -163,8 +163,8 @@ Point3 triangulateNonlinear(const std::vector& cameras, // Create a factor graph and initial values Values values; NonlinearFactorGraph graph; - boost::tie(graph, values) = triangulationGraph(cameras, measurements, - Symbol('p', 0), initialEstimate); + boost::tie(graph, values) = triangulationGraph // + (cameras, measurements, Symbol('p', 0), initialEstimate); return optimize(graph, values, Symbol('p', 0)); } @@ -174,7 +174,8 @@ template Point3 triangulateNonlinear( const std::vector >& cameras, const std::vector& measurements, const Point3& initialEstimate) { - return triangulateNonlinear(cameras, measurements, initialEstimate); + return triangulateNonlinear > // + (cameras, measurements, initialEstimate); } /** @@ -203,21 +204,22 @@ Point3 triangulatePoint3(const std::vector& poses, std::vector projection_matrices; BOOST_FOREACH(const Pose3& pose, poses) { projection_matrices.push_back( - sharedCal->K() * (pose.inverse().matrix()).block<3,4>(0,0)); + sharedCal->K() * (pose.inverse().matrix()).block<3, 4>(0, 0)); } // Triangulate linearly Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); // The n refine using non-linear optimization if (optimize) - point = triangulateNonlinear(poses, sharedCal, measurements, point); + point = triangulateNonlinear // + (poses, sharedCal, measurements, point); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION // verify that the triangulated point lies infront of all cameras BOOST_FOREACH(const Pose3& pose, poses) { const Point3& p_local = pose.transform_to(point); if (p_local.z() <= 0) - throw(TriangulationCheiralityException()); + throw(TriangulationCheiralityException()); } #endif @@ -237,8 +239,7 @@ Point3 triangulatePoint3(const std::vector& poses, * @return Returns a Point3 */ template -Point3 triangulatePoint3( - const std::vector& cameras, +Point3 triangulatePoint3(const std::vector& cameras, const std::vector& measurements, double rank_tol = 1e-9, bool optimize = false) { @@ -251,21 +252,22 @@ Point3 triangulatePoint3( // construct projection matrices from poses & calibration std::vector projection_matrices; BOOST_FOREACH(const CAMERA& camera, cameras) { - Matrix P_ = (camera.pose().inverse().matrix()); - projection_matrices.push_back(camera.calibration().K()* (P_.block<3,4>(0,0)) ); - } + Matrix P_ = (camera.pose().inverse().matrix()); + projection_matrices.push_back( + camera.calibration().K() * (P_.block<3, 4>(0, 0))); + } Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); // The n refine using non-linear optimization if (optimize) - point = triangulateNonlinear(cameras, measurements, point); + point = triangulateNonlinear(cameras, measurements, point); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION // verify that the triangulated point lies infront of all cameras BOOST_FOREACH(const CAMERA& camera, cameras) { const Point3& p_local = camera.pose().transform_to(point); if (p_local.z() <= 0) - throw(TriangulationCheiralityException()); + throw(TriangulationCheiralityException()); } #endif @@ -278,8 +280,8 @@ Point3 triangulatePoint3( const std::vector >& cameras, const std::vector& measurements, double rank_tol = 1e-9, bool optimize = false) { - return triangulatePoint3 >(cameras, measurements, - rank_tol, optimize); + return triangulatePoint3 > // + (cameras, measurements, rank_tol, optimize); } } // \namespace gtsam From d091ed3e834bb3d40652dbb2318fbd0b2212386f Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 20:42:48 +0100 Subject: [PATCH 024/173] Added reprojectionErrors back in --- gtsam/slam/SmartFactorBase.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a184a7956..6a33eeb6e 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -251,6 +251,11 @@ public: return 0.5 * b.dot(b); } + /// Compute reprojection errors + Vector reprojectionErrors(const Cameras& cameras, const Point3& point) const { + return cameras.reprojectionErrors(point, measured_); + } + /** * Compute reprojection errors and derivatives * TODO: the treatment of body_P_sensor_ is weird: the transformation From f21ba0567967df2d45fd7b818cc9f2670e12727d Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 20:43:10 +0100 Subject: [PATCH 025/173] Get Dim from base --- gtsam/slam/SmartProjectionFactor.h | 52 ++++++++++++++++-------------- 1 file changed, 27 insertions(+), 25 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 7a73a0c49..df78894e9 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -69,8 +69,6 @@ private: protected: - static const int Dim = traits::dimension; ///< CAMERA dimension - // Some triangulation parameters const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate @@ -313,10 +311,9 @@ public: } /// linearize returns a Hessianfactor that is an approximation of error(p) - boost::shared_ptr > createHessianFactor( + boost::shared_ptr > createHessianFactor( const Cameras& cameras, const double lambda = 0.0) const { - bool isDebug = false; size_t numKeys = this->keys_.size(); // Create structures for Hessian Factors std::vector js; @@ -337,10 +334,10 @@ public: && (this->cheiralityException_ || this->degenerate_))) { // std::cout << "In linearize: exception" << std::endl; BOOST_FOREACH(Matrix& m, Gs) - m = zeros(Dim, Dim); + m = zeros(Base::Dim, Base::Dim); BOOST_FOREACH(Vector& v, gs) - v = zero(Dim); - return boost::make_shared >(this->keys_, Gs, gs, + v = zero(Base::Dim); + return boost::make_shared >(this->keys_, Gs, gs, 0.0); } @@ -365,7 +362,7 @@ public: << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" << std::endl; exit(1); - return boost::make_shared >(this->keys_, + return boost::make_shared >(this->keys_, this->state_->Gs, this->state_->gs, this->state_->f); } @@ -377,23 +374,28 @@ public: // Schur complement trick // Frank says: should be possible to do this more efficiently? // And we care, as in grouped factors this is called repeatedly - Matrix H(Dim * numKeys, Dim * numKeys); + Matrix H(Base::Dim * numKeys, Base::Dim * numKeys); Vector gs_vector; Matrix3 P = Base::PointCov(E, lambda); + + // Create reduced Hessian matrix via Schur complement F'*F - F'*E*P*E'*F H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); - if (isDebug) - std::cout << "gs_vector size " << gs_vector.size() << std::endl; + + // Create reduced gradient - (F'*b - F'*E*P*E'*b) + // Note the minus sign above! g has negative b. + // Informal reasoning: when we write the error as 0.5*|Ax-b|^2 + // the derivative is A'*(Ax-b), and at x=0, this becomes -A'*b + gs_vector.noalias() = - F.transpose() * (b - (E * (P * (E.transpose() * b)))); // Populate Gs and gs int GsCount2 = 0; for (DenseIndex i1 = 0; i1 < (DenseIndex) numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * Dim; - gs.at(i1) = gs_vector.segment(i1D); + DenseIndex i1D = i1 * Base::Dim; + gs.at(i1) = gs_vector.segment(i1D); for (DenseIndex i2 = 0; i2 < (DenseIndex) numKeys; i2++) { if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * Dim); + Gs.at(GsCount2) = H.block(i1D, i2 * Base::Dim); GsCount2++; } } @@ -404,29 +406,29 @@ public: this->state_->gs = gs; this->state_->f = f; } - return boost::make_shared >(this->keys_, Gs, gs, f); + return boost::make_shared >(this->keys_, Gs, gs, f); } // create factor - boost::shared_ptr > createRegularImplicitSchurFactor( + boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) return Base::createRegularImplicitSchurFactor(cameras, point_, lambda); else - return boost::shared_ptr >(); + return boost::shared_ptr >(); } /// create factor - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) return Base::createJacobianQFactor(cameras, point_, lambda); else - return boost::make_shared >(this->keys_); + return boost::make_shared >(this->keys_); } /// Create a factor, takes values - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Values& values, double lambda) const { Cameras cameras; // TODO triangulate twice ?? @@ -434,7 +436,7 @@ public: if (nonDegenerate) return createJacobianQFactor(cameras, lambda); else - return boost::make_shared >(this->keys_); + return boost::make_shared >(this->keys_); } /// different (faster) way to compute Jacobian factor @@ -443,7 +445,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared >(this->keys_); + return boost::make_shared >(this->keys_); } /// Returns true if nonDegenerate @@ -507,7 +509,7 @@ public: std::cout << "SmartProjectionFactor: Management of degeneracy is disabled - not ready to be used" << std::endl; - if (Dim > 6) { + if (Base::Dim > 6) { std::cout << "Management of degeneracy is not yet ready when one also optimizes for the calibration " << std::endl; @@ -572,7 +574,7 @@ public: /// Calculate vector of re-projection errors, before applying noise model /// Assumes triangulation was done and degeneracy handled Vector reprojectionError(const Cameras& cameras) const { - return Base::reprojectionError(cameras, point_); + return cameras.reprojectionErrors(point_,this->measured_); } /// Calculate vector of re-projection errors, before applying noise model From a60e13dd094c8ed8fa0c94d4a5739c0f74e07a98 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 20:43:31 +0100 Subject: [PATCH 026/173] Remove a whole lot of copy/paste --- .../tests/testSmartProjectionCameraFactor.cpp | 540 +++++++++--------- 1 file changed, 256 insertions(+), 284 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index b9634025b..993cefea8 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -18,10 +18,7 @@ * @date Sept 2013 */ -//#include "BundlerDefinitions.h" #include -//#include "../SmartFactorsTestProblems.h" -//#include "../LevenbergMarquardtOptimizerCERES.h" #include #include @@ -39,17 +36,11 @@ using namespace std; using namespace boost::assign; using namespace gtsam; -typedef PinholeCamera Camera; - static bool isDebugTest = false; // 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)); -static Cal3_S2::shared_ptr K2(new Cal3_S2(1500, 1200, 0, 640, 480)); -static boost::shared_ptr Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 0, 0)); +static size_t w = 640, h = 480; static double rankTol = 1.0; static double linThreshold = -1.0; @@ -61,20 +52,20 @@ static SharedNoiseModel model(noiseModel::Unit::Create(2)); using symbol_shorthand::X; using symbol_shorthand::L; -// tests data -Key x1 = 1; - +static Key x1(1); Symbol l1('l', 1), l2('l', 2), l3('l', 3); Key c1 = 1, c2 = 2, c3 = 3; -static Key poseKey1(x1); -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)); +// First camera pose, looking along X-axis, 1 meter above ground plane (x-y) +Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); +// Second camera 1 meter to the right of first camera +Pose3 pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); +// Third camera 1 meter above the first camera +Pose3 pose_up = level_pose * Pose3(Rot3(), Point3(0, -1, 0)); -typedef PinholeCamera CameraCal3_S2; -typedef SmartProjectionCameraFactor SmartFactor; -typedef SmartProjectionCameraFactor SmartFactorBundler; -typedef GeneralSFMFactor SFMFactor; +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)); template PinholeCamera perturbCameraPose( @@ -95,7 +86,8 @@ PinholeCamera perturbCameraPoseAndCalibration( Pose3 cameraPose = camera.pose(); Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); typename gtsam::traits::TangentVector d; - d.setRandom(); d*=0.1; + d.setRandom(); + d *= 0.1; CALIBRATION perturbedCalibration = camera.calibration().retract(d); return PinholeCamera(perturbedCameraPose, perturbedCalibration); } @@ -114,70 +106,83 @@ void projectToMultipleCameras(const PinholeCamera& cam1, } /* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, perturbCameraPose) { - // 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), Point3(0,0,1)); - CameraCal3_S2 level_camera(level_pose, *K2); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); - Pose3 perturbed_level_pose = level_pose.compose(noise_pose); - CameraCal3_S2 actualCamera(perturbed_level_pose, *K2); +// default Cal3_S2 cameras +namespace vanilla { +typedef PinholeCamera Camera; +static Cal3_S2 K(fov, w, h); +static Cal3_S2 K2(1500, 1200, 0, 640, 480); +Camera level_camera(level_pose, K2); +Camera level_camera_right(pose_right, K2); +Camera cam1(level_pose, K2); +Camera cam2(pose_right, K2); +Camera cam3(pose_up, K2); +typedef GeneralSFMFactor SFMFactor; +typedef SmartProjectionCameraFactor SmartFactor; +} - CameraCal3_S2 expectedCamera = perturbCameraPose(level_camera); +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, perturbCameraPose) { + using namespace vanilla; + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 perturbed_level_pose = level_pose.compose(noise_pose); + Camera actualCamera(perturbed_level_pose, K2); + + Camera expectedCamera = perturbCameraPose(level_camera); CHECK(assert_equal(expectedCamera, actualCamera)); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor) { + using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor()); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor2) { + using namespace vanilla; SmartFactor factor1(rankTol, linThreshold); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor3) { + using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model); + factor1->add(measurement1, x1, model); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor4) { + using namespace vanilla; SmartFactor factor1(rankTol, linThreshold); - factor1.add(measurement1, poseKey1, model); + factor1.add(measurement1, x1, model); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, ConstructorWithTransform) { + using namespace vanilla; bool manageDegeneracy = true; bool isImplicit = false; bool enableEPI = false; - SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, isImplicit, enableEPI, body_P_sensor1); - factor1.add(measurement1, poseKey1, model); + SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, isImplicit, + enableEPI, body_P_sensor1); + factor1.add(measurement1, x1, model); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Equals ) { + using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model); + factor1->add(measurement1, x1, model); SmartFactor::shared_ptr factor2(new SmartFactor()); - factor2->add(measurement1, poseKey1, model); - //CHECK(assert_equal(*factor1, *factor2)); + factor2->add(measurement1, x1, model); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, noiseless ){ +TEST( SmartProjectionCameraFactor, noiseless ) { // cout << " ************************ SmartProjectionCameraFactor: noisy ****************************" << endl; - - // 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), Point3(0,0,1)); - CameraCal3_S2 level_camera(level_pose, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - CameraCal3_S2 level_camera_right(level_pose_right, *K2); + using namespace vanilla; // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); @@ -194,90 +199,41 @@ TEST( SmartProjectionCameraFactor, noiseless ){ factor1->add(level_uv, c1, model); factor1->add(level_uv_right, c2, model); - double actualError = factor1->error(values); - double expectedError = 0.0; - DOUBLES_EQUAL(expectedError, actualError, 1e-7); + DOUBLES_EQUAL(expectedError, factor1->error(values), 1e-7); + CHECK(assert_equal(zero(4), factor1->reprojectionError(values), 1e-7)); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, noiselessBundler ){ +TEST( SmartProjectionCameraFactor, noisy ) { - // 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), Point3(0,0,1)); - Camera level_camera(level_pose, *Kbundler); - - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - Camera level_camera_right(level_pose_right, *Kbundler); + using namespace vanilla; // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); // 1. Project two landmarks into two cameras and triangulate - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); - - Values values; - values.insert(c1, level_camera); - values.insert(c2, level_camera_right); - - SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); - factor1->add(level_uv, c1, model); - factor1->add(level_uv_right, c2, model); - - double actualError = factor1->error(values); - - double expectedError = 0.0; - DOUBLES_EQUAL(expectedError, actualError, 1e-3); - - Point3 oldPoint; // this takes the point stored in the factor (we are not interested in this) - if(factor1->point()) - oldPoint = *(factor1->point()); - - Point3 expectedPoint; - if(factor1->point(values)) - expectedPoint = *(factor1->point(values)); - - EXPECT(assert_equal(expectedPoint,landmark, 1e-3)); -} - -/* *************************************************************************/ -TEST( SmartProjectionCameraFactor, noisy ){ - - // 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), Point3(0,0,1)); - CameraCal3_S2 level_camera(level_pose, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - CameraCal3_S2 level_camera_right(level_pose_right, *K2); - - // 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 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(c1, level_camera); - CameraCal3_S2 perturbed_level_camera_right = perturbCameraPose(level_camera_right); + Camera perturbed_level_camera_right = perturbCameraPose(level_camera_right); values.insert(c2, perturbed_level_camera_right); SmartFactor::shared_ptr factor1(new SmartFactor()); factor1->add(level_uv, c1, model); factor1->add(level_uv_right, c2, model); - double actualError1= factor1->error(values); + double actualError1 = factor1->error(values); SmartFactor::shared_ptr factor2(new SmartFactor()); vector measurements; measurements.push_back(level_uv); measurements.push_back(level_uv_right); - vector< SharedNoiseModel > noises; + vector noises; noises.push_back(model); noises.push_back(model); @@ -287,26 +243,15 @@ TEST( SmartProjectionCameraFactor, noisy ){ factor2->add(measurements, views, noises); - double actualError2= factor2->error(values); + double actualError2 = factor2->error(values); DOUBLES_EQUAL(actualError1, actualError2, 1e-7); } - /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ){ +TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { - // 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), Point3(0,0,1)); - CameraCal3_S2 cam1(pose1, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - CameraCal3_S2 cam2(pose2, *K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - CameraCal3_S2 cam3(pose3, *K2); + using namespace vanilla; // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); @@ -334,24 +279,27 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ){ SmartFactor::shared_ptr smartFactor3(new SmartFactor()); smartFactor3->add(measurements_cam3, views, model); - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6+5, 1e-5); + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(c1, cam1, noisePrior)); - graph.push_back(PriorFactor(c2, cam2, noisePrior)); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); Values values; values.insert(c1, cam1); values.insert(c2, cam2); values.insert(c3, perturbCameraPose(cam3)); - if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); LevenbergMarquardtParams params; - if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + if (isDebugTest) + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + params.verbosity = NonlinearOptimizerParams::ERROR; Values result; gttic_(SmartProjectionCameraFactor); @@ -363,28 +311,21 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ){ // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); // VectorValues delta = GFG->optimize(); - if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(cam1,result.at(c1))); - EXPECT(assert_equal(cam2,result.at(c2))); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); - EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); - if(isDebugTest) tictoc_print_(); + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1))); + EXPECT(assert_equal(cam2, result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ){ +TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { - // 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), Point3(0,0,1)); - CameraCal3_S2 cam1(pose1, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - CameraCal3_S2 cam2(pose2, *K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - CameraCal3_S2 cam3(pose3, *K2); + using namespace vanilla; // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); @@ -403,9 +344,9 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ){ views.push_back(c3); SfM_Track track1; - for(size_t i=0;i<3;++i){ + for (size_t i = 0; i < 3; ++i) { SfM_Measurement measures; - measures.first = i+1;// cameras are from 1 to 3 + measures.first = i + 1; // cameras are from 1 to 3 measures.second = measurements_cam1.at(i); track1.measurements.push_back(measures); } @@ -413,9 +354,9 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ){ smartFactor1->add(track1, model); SfM_Track track2; - for(size_t i=0;i<3;++i){ + for (size_t i = 0; i < 3; ++i) { SfM_Measurement measures; - measures.first = i+1;// cameras are from 1 to 3 + measures.first = i + 1; // cameras are from 1 to 3 measures.second = measurements_cam2.at(i); track2.measurements.push_back(measures); } @@ -425,24 +366,27 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ){ SmartFactor::shared_ptr smartFactor3(new SmartFactor()); smartFactor3->add(measurements_cam3, views, model); - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6+5, 1e-5); + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(c1, cam1, noisePrior)); - graph.push_back(PriorFactor(c2, cam2, noisePrior)); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); Values values; values.insert(c1, cam1); values.insert(c2, cam2); values.insert(c3, perturbCameraPose(cam3)); - if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); LevenbergMarquardtParams params; - if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + if (isDebugTest) + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + params.verbosity = NonlinearOptimizerParams::ERROR; Values result; gttic_(SmartProjectionCameraFactor); @@ -454,28 +398,21 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ){ // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); // VectorValues delta = GFG->optimize(); - if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(cam1,result.at(c1))); - EXPECT(assert_equal(cam2,result.at(c2))); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); - EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); - if(isDebugTest) tictoc_print_(); + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1))); + EXPECT(assert_equal(cam2, result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ){ +TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { - // 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), Point3(0,0,1)); - CameraCal3_S2 cam1(pose1, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - CameraCal3_S2 cam2(pose2, *K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - CameraCal3_S2 cam3(pose3, *K2); + using namespace vanilla; // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); @@ -485,7 +422,7 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ){ Point3 landmark5(10, -0.5, 1.2); vector measurements_cam1, measurements_cam2, measurements_cam3, - measurements_cam4, measurements_cam5; + measurements_cam4, measurements_cam5; // 1. Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -514,7 +451,7 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ){ SmartFactor::shared_ptr smartFactor5(new SmartFactor()); smartFactor5->add(measurements_cam5, views, model); - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6+5, 1e-5); + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); NonlinearFactorGraph graph; graph.push_back(smartFactor1); @@ -522,21 +459,24 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ){ graph.push_back(smartFactor3); graph.push_back(smartFactor4); graph.push_back(smartFactor5); - graph.push_back(PriorFactor(c1, cam1, noisePrior)); - graph.push_back(PriorFactor(c2, cam2, noisePrior)); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); Values values; values.insert(c1, cam1); values.insert(c2, cam2); values.insert(c3, perturbCameraPoseAndCalibration(cam3)); - if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); LevenbergMarquardtParams params; params.relativeErrorTol = 1e-8; params.absoluteErrorTol = 0; params.maxIterations = 20; - if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + if (isDebugTest) + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + params.verbosity = NonlinearOptimizerParams::ERROR; Values result; gttic_(SmartProjectionCameraFactor); @@ -548,28 +488,36 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ){ // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); // VectorValues delta = GFG->optimize(); - if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(cam1,result.at(c1))); - EXPECT(assert_equal(cam2,result.at(c2))); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); - EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 20)); - if(isDebugTest) tictoc_print_(); + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1))); + EXPECT(assert_equal(cam2, result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 20)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, Cal3Bundler ){ +// Cal3Bundler cameras +namespace bundler { +typedef PinholeCamera Camera; +static Cal3Bundler K(500, 1e-3, 1e-3, 0, 0); +Camera level_camera(level_pose, K); +Camera level_camera_right(pose_right, K); +Pose3 pose1 = level_pose; +Camera cam1(level_pose, K); +Camera cam2(pose_right, K); +Camera cam3(pose_up, K); +typedef GeneralSFMFactor SFMFactor; +typedef SmartProjectionCameraFactor SmartFactorBundler; +} - // 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), Point3(0,0,1)); - Camera cam1(pose1, *Kbundler); +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, Cal3Bundler ) { - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - Camera cam2(pose2, *Kbundler); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - Camera cam3(pose3, *Kbundler); + using namespace bundler; // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); @@ -579,7 +527,7 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ){ Point3 landmark5(10, -0.5, 1.2); vector measurements_cam1, measurements_cam2, measurements_cam3, - measurements_cam4, measurements_cam5; + measurements_cam4, measurements_cam5; // 1. Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -622,14 +570,17 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ){ values.insert(c2, cam2); // initialize third pose with some noise, we expect it to move back to original pose3 values.insert(c3, perturbCameraPose(cam3)); - if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); LevenbergMarquardtParams params; params.relativeErrorTol = 1e-8; params.absoluteErrorTol = 0; params.maxIterations = 20; - if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + if (isDebugTest) + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + params.verbosity = NonlinearOptimizerParams::ERROR; Values result; gttic_(SmartProjectionCameraFactor); @@ -638,28 +589,21 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ){ gttoc_(SmartProjectionCameraFactor); tictoc_finishedIteration_(); - if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(cam1,result.at(c1), 1e-4)); - EXPECT(assert_equal(cam2,result.at(c2), 1e-4)); + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); + EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); - EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 1)); - if(isDebugTest) tictoc_print_(); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 1)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, Cal3Bundler2 ){ +TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { - // 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), Point3(0,0,1)); - Camera cam1(pose1, *Kbundler); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - Camera cam2(pose2, *Kbundler); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - Camera cam3(pose3, *Kbundler); + using namespace bundler; // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); @@ -669,7 +613,7 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ){ Point3 landmark5(10, -0.5, 1.2); vector measurements_cam1, measurements_cam2, measurements_cam3, - measurements_cam4, measurements_cam5; + measurements_cam4, measurements_cam5; // 1. Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -712,14 +656,17 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ){ values.insert(c2, cam2); // initialize third pose with some noise, we expect it to move back to original pose3 values.insert(c3, perturbCameraPoseAndCalibration(cam3)); - if(isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); LevenbergMarquardtParams params; params.relativeErrorTol = 1e-8; params.absoluteErrorTol = 0; params.maxIterations = 20; - if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + if (isDebugTest) + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + params.verbosity = NonlinearOptimizerParams::ERROR; Values result; gttic_(SmartProjectionCameraFactor); @@ -728,25 +675,56 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ){ gttoc_(SmartProjectionCameraFactor); tictoc_finishedIteration_(); - if(isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(cam1,result.at(c1), 1e-4)); - EXPECT(assert_equal(cam2,result.at(c2), 1e-4)); + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); + EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); - EXPECT(assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); - if(isDebugTest) tictoc_print_(); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ){ +TEST( SmartProjectionCameraFactor, noiselessBundler ) { - // 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), Point3(0,0,1)); - Camera level_camera(level_pose, *Kbundler); + using namespace bundler; + // landmark ~5 meters infront of camera + Point3 landmark(5, 0.5, 1.2); - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - Camera level_camera_right(level_pose_right, *Kbundler); + // 1. Project two landmarks into two cameras and triangulate + Point2 level_uv = level_camera.project(landmark); + Point2 level_uv_right = level_camera_right.project(landmark); + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + factor1->add(level_uv, c1, model); + factor1->add(level_uv_right, c2, model); + + double actualError = factor1->error(values); + + double expectedError = 0.0; + DOUBLES_EQUAL(expectedError, actualError, 1e-3); + + Point3 oldPoint; // this takes the point stored in the factor (we are not interested in this) + if (factor1->point()) + oldPoint = *(factor1->point()); + + Point3 expectedPoint; + if (factor1->point(values)) + expectedPoint = *(factor1->point(values)); + + EXPECT(assert_equal(expectedPoint, landmark, 1e-3)); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { + + using namespace bundler; // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); @@ -766,7 +744,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ){ double expectedError = factor1->error(values); double expectedErrorGraph = smartGraph.error(values); Point3 expectedPoint; - if(factor1->point()) + if (factor1->point()) expectedPoint = *(factor1->point()); // cout << "expectedPoint " << expectedPoint.vector() << endl; @@ -779,9 +757,10 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ){ generalGraph.push_back(sfm1); generalGraph.push_back(sfm2); values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation - Vector e1 = sfm1.evaluateError(values.at< Camera >(c1), values.at< Point3 >(l1)); - Vector e2 = sfm2.evaluateError(values.at< Camera >(c2), values.at< Point3 >(l1)); - double actualError = 0.5 * (norm_2(e1)*norm_2(e1) + norm_2(e2)*norm_2(e2)); + Vector e1 = sfm1.evaluateError(values.at(c1), values.at(l1)); + Vector e2 = sfm2.evaluateError(values.at(c2), values.at(l1)); + double actualError = 0.5 + * (norm_2(e1) * norm_2(e1) + norm_2(e2) * norm_2(e2)); double actualErrorGraph = generalGraph.error(values); DOUBLES_EQUAL(expectedErrorGraph, actualErrorGraph, 1e-7); @@ -791,14 +770,9 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ){ } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ){ +TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { - // 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), Point3(0,0,1)); - Camera level_camera(level_pose, *Kbundler); - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - Camera level_camera_right(level_pose_right, *Kbundler); + using namespace bundler; // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); // 1. Project two landmarks into two cameras and triangulate @@ -817,7 +791,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ){ Matrix expectedHessian = smartGraph.linearize(values)->hessian().first; Vector expectedInfoVector = smartGraph.linearize(values)->hessian().second; Point3 expectedPoint; - if(factor1->point()) + if (factor1->point()) expectedPoint = *(factor1->point()); // COMMENTS: @@ -831,25 +805,23 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ){ values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation Matrix actualFullHessian = generalGraph.linearize(values)->hessian().first; Matrix actualFullInfoVector = generalGraph.linearize(values)->hessian().second; - Matrix actualHessian = actualFullHessian.block(0,0,18,18) - - actualFullHessian.block(0,18,18,3) * (actualFullHessian.block(18,18,3,3)).inverse() * actualFullHessian.block(18,0,3,18); - Vector actualInfoVector = actualFullInfoVector.block(0,0,18,1) - - actualFullHessian.block(0,18,18,3) * (actualFullHessian.block(18,18,3,3)).inverse() * actualFullInfoVector.block(18,0,3,1); + Matrix actualHessian = actualFullHessian.block(0, 0, 18, 18) + - actualFullHessian.block(0, 18, 18, 3) + * (actualFullHessian.block(18, 18, 3, 3)).inverse() + * actualFullHessian.block(18, 0, 3, 18); + Vector actualInfoVector = actualFullInfoVector.block(0, 0, 18, 1) + - actualFullHessian.block(0, 18, 18, 3) + * (actualFullHessian.block(18, 18, 3, 3)).inverse() + * actualFullInfoVector.block(18, 0, 3, 1); - EXPECT(assert_equal(expectedHessian,actualHessian, 1e-7)); - EXPECT(assert_equal(expectedInfoVector,actualInfoVector, 1e-7)); + EXPECT(assert_equal(expectedHessian, actualHessian, 1e-7)); + EXPECT(assert_equal(expectedInfoVector, actualInfoVector, 1e-7)); } /* *************************************************************************/ // Have to think about how to compare multiplyHessianAdd in generalSfMFactor and smartFactors //TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor2 ){ // -// // 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), Point3(0,0,1)); -// cameraObjectBundler level_camera(level_pose, *Kbundler); -// // create second camera 1 meter to the right of first camera -// Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); -// cameraObjectBundler level_camera_right(level_pose_right, *Kbundler); // // landmark ~5 meters infront of camera // Point3 landmark(5, 0.5, 1.2); // // 1. Project two landmarks into two cameras @@ -901,16 +873,10 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ){ // // EXPECT(assert_equal(yActual,yExpected, 1e-7)); //} - /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, computeImplicitJacobian ){ +TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { - // 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), Point3(0,0,1)); - Camera level_camera(level_pose, *Kbundler); - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - Camera level_camera_right(level_pose_right, *Kbundler); + using namespace bundler; // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); // 1. Project two landmarks into two cameras and triangulate @@ -927,13 +893,13 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ){ Matrix expectedF, expectedE; Vector expectedb; - CameraSet< Camera > cameras; + CameraSet cameras; cameras.push_back(level_camera); cameras.push_back(level_camera_right); factor1->error(values); // this is important to have a triangulation of the point Point3 expectedPoint; - if(factor1->point()) + if (factor1->point()) expectedPoint = *(factor1->point()); factor1->computeJacobians(expectedF, expectedE, expectedb, cameras); @@ -944,21 +910,17 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ){ generalGraph.push_back(sfm2); values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation Matrix actualFullHessian = generalGraph.linearize(values)->hessian().first; - Matrix actualVinv = (actualFullHessian.block(18,18,3,3)).inverse(); + Matrix actualVinv = (actualFullHessian.block(18, 18, 3, 3)).inverse(); Matrix3 expectedVinv = factor1->PointCov(expectedE); - EXPECT(assert_equal(expectedVinv,actualVinv, 1e-7)); + EXPECT(assert_equal(expectedVinv, actualVinv, 1e-7)); } /* *************************************************************************/ -TEST( SmartProjectionCameraFactor, implicitJacobianFactor ){ +TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { + + using namespace bundler; - // 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), Point3(0,0,1)); - Camera level_camera(level_pose, *Kbundler); - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1,0,0)); - Camera level_camera_right(level_pose_right, *Kbundler); // landmark ~5 meters infront of camera Point3 landmark(5, 0.5, 1.2); // 1. Project two landmarks into two cameras and triangulate @@ -975,35 +937,45 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ){ bool isImplicit = false; // Hessian version - SmartFactorBundler::shared_ptr explicitFactor(new SmartFactorBundler(rankTol,linThreshold, manageDegeneracy, useEPI, isImplicit)); + SmartFactorBundler::shared_ptr explicitFactor( + new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy, useEPI, + isImplicit)); explicitFactor->add(level_uv, c1, model); explicitFactor->add(level_uv_right, c2, model); - GaussianFactor::shared_ptr gaussianHessianFactor = explicitFactor->linearize(values); - HessianFactor& hessianFactor = dynamic_cast(*gaussianHessianFactor); + GaussianFactor::shared_ptr gaussianHessianFactor = explicitFactor->linearize( + values); + HessianFactor& hessianFactor = + dynamic_cast(*gaussianHessianFactor); // Implicit Schur version isImplicit = true; - SmartFactorBundler::shared_ptr implicitFactor(new SmartFactorBundler(rankTol,linThreshold, manageDegeneracy, useEPI, isImplicit)); + SmartFactorBundler::shared_ptr implicitFactor( + new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy, useEPI, + isImplicit)); implicitFactor->add(level_uv, c1, model); implicitFactor->add(level_uv_right, c2, model); - GaussianFactor::shared_ptr gaussianImplicitSchurFactor = implicitFactor->linearize(values); + GaussianFactor::shared_ptr gaussianImplicitSchurFactor = + implicitFactor->linearize(values); typedef RegularImplicitSchurFactor<9> Implicit9; - Implicit9& implicitSchurFactor = dynamic_cast(*gaussianImplicitSchurFactor); + Implicit9& implicitSchurFactor = + dynamic_cast(*gaussianImplicitSchurFactor); - VectorValues x = map_list_of - (c1, (Vector(9) << 1,2,3,4,5,6,7,8,9).finished()) - (c2, (Vector(9) << 11,12,13,14,15,16,17,18,19).finished()); + VectorValues x = map_list_of(c1, + (Vector(9) << 1, 2, 3, 4, 5, 6, 7, 8, 9).finished())(c2, + (Vector(9) << 11, 12, 13, 14, 15, 16, 17, 18, 19).finished()); VectorValues yExpected, yActual; double alpha = 1.0; hessianFactor.multiplyHessianAdd(alpha, x, yActual); implicitSchurFactor.multiplyHessianAdd(alpha, x, yExpected); - EXPECT(assert_equal(yActual,yExpected, 1e-7)); + EXPECT(assert_equal(yActual, yExpected, 1e-7)); } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} /* ************************************************************************* */ - From cd10f9aedc57c7d4b984acfeb42d138f8cb4347d Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 21:25:35 +0100 Subject: [PATCH 027/173] Moved scenarios to separate header --- gtsam/slam/tests/smartFactorScenarios.h | 120 ++++++++ .../tests/testSmartProjectionCameraFactor.cpp | 291 ++++-------------- 2 files changed, 180 insertions(+), 231 deletions(-) create mode 100644 gtsam/slam/tests/smartFactorScenarios.h diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h new file mode 100644 index 000000000..c5df4af7e --- /dev/null +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -0,0 +1,120 @@ +/* ---------------------------------------------------------------------------- + + * 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 SmartFactorScenarios.h + * @brief Scenarios for testSmart*.cpp + * @author Frank Dellaert + * @date Feb 2015 + */ + +#pragma once +#include +#include + +using namespace std; +using namespace gtsam; + +// 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); +Point3 landmark4(10, 0.5, 1.2); +Point3 landmark5(10, -0.5, 1.2); + +// First camera pose, looking along X-axis, 1 meter above ground plane (x-y) +Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); +// Second camera 1 meter to the right of first camera +Pose3 pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); +// Third camera 1 meter above the first camera +Pose3 pose_up = level_pose * Pose3(Rot3(), Point3(0, -1, 0)); + +// Create a noise unit2 for the pixel error +static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); + +/* ************************************************************************* */ +// default Cal3_S2 cameras +namespace vanilla { +typedef PinholeCamera Camera; +// make a realistic calibration matrix +static double fov = 60; // degrees +static size_t w = 640, h = 480; +static Cal3_S2 K(fov, w, h); +static Cal3_S2 K2(1500, 1200, 0, w, h); +Camera level_camera(level_pose, K2); +Camera level_camera_right(pose_right, K2); +Point2 level_uv = level_camera.project(landmark1); +Point2 level_uv_right = level_camera_right.project(landmark1); +Camera cam1(level_pose, K2); +Camera cam2(pose_right, K2); +Camera cam3(pose_up, K2); +typedef GeneralSFMFactor SFMFactor; +typedef SmartProjectionCameraFactor SmartFactor; +} + +/* *************************************************************************/ +// Cal3Bundler cameras +namespace bundler { +typedef PinholeCamera Camera; +static Cal3Bundler K(500, 1e-3, 1e-3, 0, 0); +Camera level_camera(level_pose, K); +Camera level_camera_right(pose_right, K); +Point2 level_uv = level_camera.project(landmark1); +Point2 level_uv_right = level_camera_right.project(landmark1); +Pose3 pose1 = level_pose; +Camera cam1(level_pose, K); +Camera cam2(pose_right, K); +Camera cam3(pose_up, K); +typedef GeneralSFMFactor SFMFactor; +typedef SmartProjectionCameraFactor SmartFactorBundler; +} +/* *************************************************************************/ + +template +PinholeCamera perturbCameraPose( + const PinholeCamera& camera) { + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 cameraPose = camera.pose(); + Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); + return PinholeCamera(perturbedCameraPose, camera.calibration()); +} + +template +PinholeCamera perturbCameraPoseAndCalibration( + const PinholeCamera& camera) { + GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 cameraPose = camera.pose(); + Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); + typename gtsam::traits::TangentVector d; + d.setRandom(); + d *= 0.1; + CALIBRATION perturbedCalibration = camera.calibration().retract(d); + return PinholeCamera(perturbedCameraPose, perturbedCalibration); +} + +template +void projectToMultipleCameras(const PinholeCamera& cam1, + const PinholeCamera& cam2, + const PinholeCamera& cam3, Point3 landmark, + vector& measurements_cam) { + Point2 cam1_uv1 = cam1.project(landmark); + Point2 cam2_uv1 = cam2.project(landmark); + Point2 cam3_uv1 = cam3.project(landmark); + measurements_cam.push_back(cam1_uv1); + measurements_cam.push_back(cam2_uv1); + measurements_cam.push_back(cam3_uv1); +} + +/* ************************************************************************* */ + diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 993cefea8..af1ee3ea9 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -18,36 +18,19 @@ * @date Sept 2013 */ -#include - +#include "smartFactorScenarios.h" #include -#include -#include -#include -#include -#include - -//#include "../SmartNonlinearFactorGraph.h" -#undef CHECK +#include #include #include - -using namespace std; +// using namespace boost::assign; -using namespace gtsam; static bool isDebugTest = false; -// make a realistic calibration matrix -static double fov = 60; // degrees -static size_t w = 640, h = 480; - static double rankTol = 1.0; static double linThreshold = -1.0; -// 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; @@ -56,70 +39,10 @@ static Key x1(1); Symbol l1('l', 1), l2('l', 2), l3('l', 3); Key c1 = 1, c2 = 2, c3 = 3; -// First camera pose, looking along X-axis, 1 meter above ground plane (x-y) -Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); -// Second camera 1 meter to the right of first camera -Pose3 pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); -// Third camera 1 meter above the first camera -Pose3 pose_up = level_pose * Pose3(Rot3(), Point3(0, -1, 0)); - 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)); -template -PinholeCamera perturbCameraPose( - const PinholeCamera& camera) { - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), - Point3(0.5, 0.1, 0.3)); - Pose3 cameraPose = camera.pose(); - Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); - return PinholeCamera(perturbedCameraPose, camera.calibration()); -} - -template -PinholeCamera perturbCameraPoseAndCalibration( - const PinholeCamera& camera) { - GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), - Point3(0.5, 0.1, 0.3)); - Pose3 cameraPose = camera.pose(); - Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); - typename gtsam::traits::TangentVector d; - d.setRandom(); - d *= 0.1; - CALIBRATION perturbedCalibration = camera.calibration().retract(d); - return PinholeCamera(perturbedCameraPose, perturbedCalibration); -} - -template -void projectToMultipleCameras(const PinholeCamera& cam1, - const PinholeCamera& cam2, - const PinholeCamera& cam3, Point3 landmark, - vector& measurements_cam) { - Point2 cam1_uv1 = cam1.project(landmark); - Point2 cam2_uv1 = cam2.project(landmark); - Point2 cam3_uv1 = cam3.project(landmark); - measurements_cam.push_back(cam1_uv1); - measurements_cam.push_back(cam2_uv1); - measurements_cam.push_back(cam3_uv1); -} - -/* ************************************************************************* */ -// default Cal3_S2 cameras -namespace vanilla { -typedef PinholeCamera Camera; -static Cal3_S2 K(fov, w, h); -static Cal3_S2 K2(1500, 1200, 0, 640, 480); -Camera level_camera(level_pose, K2); -Camera level_camera_right(pose_right, K2); -Camera cam1(level_pose, K2); -Camera cam2(pose_right, K2); -Camera cam3(pose_up, K2); -typedef GeneralSFMFactor SFMFactor; -typedef SmartProjectionCameraFactor SmartFactor; -} - /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, perturbCameraPose) { using namespace vanilla; @@ -148,14 +71,14 @@ TEST( SmartProjectionCameraFactor, Constructor2) { TEST( SmartProjectionCameraFactor, Constructor3) { using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, x1, model); + factor1->add(measurement1, x1, unit2); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor4) { using namespace vanilla; SmartFactor factor1(rankTol, linThreshold); - factor1.add(measurement1, x1, model); + factor1.add(measurement1, x1, unit2); } /* ************************************************************************* */ @@ -166,17 +89,17 @@ TEST( SmartProjectionCameraFactor, ConstructorWithTransform) { bool enableEPI = false; SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, isImplicit, enableEPI, body_P_sensor1); - factor1.add(measurement1, x1, model); + factor1.add(measurement1, x1, unit2); } /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Equals ) { using namespace vanilla; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, x1, model); + factor1->add(measurement1, x1, unit2); SmartFactor::shared_ptr factor2(new SmartFactor()); - factor2->add(measurement1, x1, model); + factor2->add(measurement1, x1, unit2); } /* *************************************************************************/ @@ -184,20 +107,13 @@ TEST( SmartProjectionCameraFactor, noiseless ) { // cout << " ************************ SmartProjectionCameraFactor: noisy ****************************" << endl; using namespace vanilla; - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - - // 1. Project two landmarks into two cameras and triangulate - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); - Values values; values.insert(c1, level_camera); values.insert(c2, level_camera_right); SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(level_uv, c1, model); - factor1->add(level_uv_right, c2, model); + factor1->add(level_uv, c1, unit2); + factor1->add(level_uv_right, c2, unit2); double expectedError = 0.0; DOUBLES_EQUAL(expectedError, factor1->error(values), 1e-7); @@ -209,13 +125,10 @@ TEST( SmartProjectionCameraFactor, noisy ) { using namespace vanilla; - // 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); + Point2 level_uv = level_camera.project(landmark1) + pixelError; + Point2 level_uv_right = level_camera_right.project(landmark1); Values values; values.insert(c1, level_camera); @@ -223,8 +136,8 @@ TEST( SmartProjectionCameraFactor, noisy ) { values.insert(c2, perturbed_level_camera_right); SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(level_uv, c1, model); - factor1->add(level_uv_right, c2, model); + factor1->add(level_uv, c1, unit2); + factor1->add(level_uv_right, c2, unit2); double actualError1 = factor1->error(values); @@ -234,8 +147,8 @@ TEST( SmartProjectionCameraFactor, noisy ) { measurements.push_back(level_uv_right); vector noises; - noises.push_back(model); - noises.push_back(model); + noises.push_back(unit2); + noises.push_back(unit2); vector views; views.push_back(c1); @@ -253,11 +166,6 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { using namespace vanilla; - // 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 @@ -271,13 +179,13 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { views.push_back(c3); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model); + smartFactor1->add(measurements_cam1, views, unit2); SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model); + smartFactor2->add(measurements_cam2, views, unit2); SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model); + smartFactor3->add(measurements_cam3, views, unit2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); @@ -327,11 +235,6 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { using namespace vanilla; - // 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 projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -351,7 +254,7 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { track1.measurements.push_back(measures); } SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(track1, model); + smartFactor1->add(track1, unit2); SfM_Track track2; for (size_t i = 0; i < 3; ++i) { @@ -361,10 +264,10 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { track2.measurements.push_back(measures); } SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(track2, model); + smartFactor2->add(track2, unit2); SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model); + smartFactor3->add(measurements_cam3, views, unit2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); @@ -414,13 +317,6 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { using namespace vanilla; - // 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); - Point3 landmark4(10, 0.5, 1.2); - Point3 landmark5(10, -0.5, 1.2); - vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4, measurements_cam5; @@ -437,19 +333,19 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { views.push_back(c3); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model); + smartFactor1->add(measurements_cam1, views, unit2); SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model); + smartFactor2->add(measurements_cam2, views, unit2); SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model); + smartFactor3->add(measurements_cam3, views, unit2); SmartFactor::shared_ptr smartFactor4(new SmartFactor()); - smartFactor4->add(measurements_cam4, views, model); + smartFactor4->add(measurements_cam4, views, unit2); SmartFactor::shared_ptr smartFactor5(new SmartFactor()); - smartFactor5->add(measurements_cam5, views, model); + smartFactor5->add(measurements_cam5, views, unit2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); @@ -499,33 +395,11 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { tictoc_print_(); } -/* *************************************************************************/ -// Cal3Bundler cameras -namespace bundler { -typedef PinholeCamera Camera; -static Cal3Bundler K(500, 1e-3, 1e-3, 0, 0); -Camera level_camera(level_pose, K); -Camera level_camera_right(pose_right, K); -Pose3 pose1 = level_pose; -Camera cam1(level_pose, K); -Camera cam2(pose_right, K); -Camera cam3(pose_up, K); -typedef GeneralSFMFactor SFMFactor; -typedef SmartProjectionCameraFactor SmartFactorBundler; -} - /* *************************************************************************/ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { using namespace bundler; - // 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); - Point3 landmark4(10, 0.5, 1.2); - Point3 landmark5(10, -0.5, 1.2); - vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4, measurements_cam5; @@ -542,19 +416,19 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { views.push_back(c3); SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); - smartFactor1->add(measurements_cam1, views, model); + smartFactor1->add(measurements_cam1, views, unit2); SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); - smartFactor2->add(measurements_cam2, views, model); + smartFactor2->add(measurements_cam2, views, unit2); SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); - smartFactor3->add(measurements_cam3, views, model); + smartFactor3->add(measurements_cam3, views, unit2); SmartFactorBundler::shared_ptr smartFactor4(new SmartFactorBundler()); - smartFactor4->add(measurements_cam4, views, model); + smartFactor4->add(measurements_cam4, views, unit2); SmartFactorBundler::shared_ptr smartFactor5(new SmartFactorBundler()); - smartFactor5->add(measurements_cam5, views, model); + smartFactor5->add(measurements_cam5, views, unit2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); @@ -605,13 +479,6 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { using namespace bundler; - // 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); - Point3 landmark4(10, 0.5, 1.2); - Point3 landmark5(10, -0.5, 1.2); - vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4, measurements_cam5; @@ -628,19 +495,19 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { views.push_back(c3); SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); - smartFactor1->add(measurements_cam1, views, model); + smartFactor1->add(measurements_cam1, views, unit2); SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); - smartFactor2->add(measurements_cam2, views, model); + smartFactor2->add(measurements_cam2, views, unit2); SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); - smartFactor3->add(measurements_cam3, views, model); + smartFactor3->add(measurements_cam3, views, unit2); SmartFactorBundler::shared_ptr smartFactor4(new SmartFactorBundler()); - smartFactor4->add(measurements_cam4, views, model); + smartFactor4->add(measurements_cam4, views, unit2); SmartFactorBundler::shared_ptr smartFactor5(new SmartFactorBundler()); - smartFactor5->add(measurements_cam5, views, model); + smartFactor5->add(measurements_cam5, views, unit2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); @@ -690,20 +557,13 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { TEST( SmartProjectionCameraFactor, noiselessBundler ) { using namespace bundler; - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - - // 1. Project two landmarks into two cameras and triangulate - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); - Values values; values.insert(c1, level_camera); values.insert(c2, level_camera_right); SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); - factor1->add(level_uv, c1, model); - factor1->add(level_uv_right, c2, model); + factor1->add(level_uv, c1, unit2); + factor1->add(level_uv_right, c2, unit2); double actualError = factor1->error(values); @@ -718,28 +578,21 @@ TEST( SmartProjectionCameraFactor, noiselessBundler ) { if (factor1->point(values)) expectedPoint = *(factor1->point(values)); - EXPECT(assert_equal(expectedPoint, landmark, 1e-3)); + EXPECT(assert_equal(expectedPoint, landmark1, 1e-3)); } /* *************************************************************************/ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { using namespace bundler; - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - - // 1. Project two landmarks into two cameras and triangulate - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); - Values values; values.insert(c1, level_camera); values.insert(c2, level_camera_right); NonlinearFactorGraph smartGraph; SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); - factor1->add(level_uv, c1, model); - factor1->add(level_uv_right, c2, model); + factor1->add(level_uv, c1, unit2); + factor1->add(level_uv_right, c2, unit2); smartGraph.push_back(factor1); double expectedError = factor1->error(values); double expectedErrorGraph = smartGraph.error(values); @@ -752,8 +605,8 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as // value in the generalGrap NonlinearFactorGraph generalGraph; - SFMFactor sfm1(level_uv, model, c1, l1); - SFMFactor sfm2(level_uv_right, model, c2, l1); + SFMFactor sfm1(level_uv, unit2, c1, l1); + SFMFactor sfm2(level_uv_right, unit2, c2, l1); generalGraph.push_back(sfm1); generalGraph.push_back(sfm2); values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation @@ -773,20 +626,14 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { using namespace bundler; - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - // 1. Project two landmarks into two cameras and triangulate - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); - Values values; values.insert(c1, level_camera); values.insert(c2, level_camera_right); NonlinearFactorGraph smartGraph; SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); - factor1->add(level_uv, c1, model); - factor1->add(level_uv_right, c2, model); + factor1->add(level_uv, c1, unit2); + factor1->add(level_uv_right, c2, unit2); smartGraph.push_back(factor1); Matrix expectedHessian = smartGraph.linearize(values)->hessian().first; Vector expectedInfoVector = smartGraph.linearize(values)->hessian().second; @@ -798,8 +645,8 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as // value in the generalGrap NonlinearFactorGraph generalGraph; - SFMFactor sfm1(level_uv, model, c1, l1); - SFMFactor sfm2(level_uv_right, model, c2, l1); + SFMFactor sfm1(level_uv, unit2, c1, l1); + SFMFactor sfm2(level_uv_right, unit2, c2, l1); generalGraph.push_back(sfm1); generalGraph.push_back(sfm2); values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation @@ -822,20 +669,14 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { // Have to think about how to compare multiplyHessianAdd in generalSfMFactor and smartFactors //TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor2 ){ // -// // landmark ~5 meters infront of camera -// Point3 landmark(5, 0.5, 1.2); -// // 1. Project two landmarks into two cameras -// Point2 level_uv = level_camera.project(landmark); -// Point2 level_uv_right = level_camera_right.project(landmark); -// // Values values; // values.insert(c1, level_camera); // values.insert(c2, level_camera_right); // // NonlinearFactorGraph smartGraph; // SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); -// factor1->add(level_uv, c1, model); -// factor1->add(level_uv_right, c2, model); +// factor1->add(level_uv, c1, unit2); +// factor1->add(level_uv_right, c2, unit2); // smartGraph.push_back(factor1); // GaussianFactorGraph::shared_ptr gfgSmart = smartGraph.linearize(values); // @@ -847,8 +688,8 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { // // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as // // value in the generalGrap // NonlinearFactorGraph generalGraph; -// SFMFactor sfm1(level_uv, model, c1, l1); -// SFMFactor sfm2(level_uv_right, model, c2, l1); +// SFMFactor sfm1(level_uv, unit2, c1, l1); +// SFMFactor sfm2(level_uv_right, unit2, c2, l1); // generalGraph.push_back(sfm1); // generalGraph.push_back(sfm2); // values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation @@ -877,19 +718,13 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { using namespace bundler; - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - // 1. Project two landmarks into two cameras and triangulate - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); - Values values; values.insert(c1, level_camera); values.insert(c2, level_camera_right); SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); - factor1->add(level_uv, c1, model); - factor1->add(level_uv_right, c2, model); + factor1->add(level_uv, c1, unit2); + factor1->add(level_uv_right, c2, unit2); Matrix expectedF, expectedE; Vector expectedb; @@ -904,8 +739,8 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { factor1->computeJacobians(expectedF, expectedE, expectedb, cameras); NonlinearFactorGraph generalGraph; - SFMFactor sfm1(level_uv, model, c1, l1); - SFMFactor sfm2(level_uv_right, model, c2, l1); + SFMFactor sfm1(level_uv, unit2, c1, l1); + SFMFactor sfm2(level_uv_right, unit2, c2, l1); generalGraph.push_back(sfm1); generalGraph.push_back(sfm2); values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation @@ -921,12 +756,6 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { using namespace bundler; - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - // 1. Project two landmarks into two cameras and triangulate - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); - Values values; values.insert(c1, level_camera); values.insert(c2, level_camera_right); @@ -940,8 +769,8 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { SmartFactorBundler::shared_ptr explicitFactor( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy, useEPI, isImplicit)); - explicitFactor->add(level_uv, c1, model); - explicitFactor->add(level_uv_right, c2, model); + explicitFactor->add(level_uv, c1, unit2); + explicitFactor->add(level_uv_right, c2, unit2); GaussianFactor::shared_ptr gaussianHessianFactor = explicitFactor->linearize( values); @@ -953,8 +782,8 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { SmartFactorBundler::shared_ptr implicitFactor( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy, useEPI, isImplicit)); - implicitFactor->add(level_uv, c1, model); - implicitFactor->add(level_uv_right, c2, model); + implicitFactor->add(level_uv, c1, unit2); + implicitFactor->add(level_uv_right, c2, unit2); GaussianFactor::shared_ptr gaussianImplicitSchurFactor = implicitFactor->linearize(values); typedef RegularImplicitSchurFactor<9> Implicit9; From 01dc2c61fa391318056e5cabaf634e71efc167b5 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 22:32:18 +0100 Subject: [PATCH 028/173] MAde it more generic --- gtsam/geometry/triangulation.h | 21 +++++++++++---------- gtsam/slam/TriangulationFactor.h | 5 ++--- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 0a0508efc..ea6c5c041 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include #include @@ -74,8 +75,8 @@ std::pair triangulationGraph( static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); for (size_t i = 0; i < measurements.size(); i++) { const Pose3& pose_i = poses[i]; - PinholePose camera_i(pose_i, sharedCal); - graph.push_back(TriangulationFactor > // + PinholeBaseK camera_i(pose_i, sharedCal); + graph.push_back(TriangulationFactor > // (camera_i, measurements[i], unit2, landmarkKey)); } return std::make_pair(graph, values); @@ -107,13 +108,13 @@ std::pair triangulationGraph( return std::make_pair(graph, values); } -/// PinholeCamera specific version +/// PinholeBaseK specific version template std::pair triangulationGraph( - const std::vector >& cameras, + const std::vector >& cameras, const std::vector& measurements, Key landmarkKey, const Point3& initialEstimate) { - return triangulationGraph > // + return triangulationGraph > // (cameras, measurements, landmarkKey, initialEstimate); } @@ -169,12 +170,12 @@ Point3 triangulateNonlinear(const std::vector& cameras, return optimize(graph, values, Symbol('p', 0)); } -/// PinholeCamera specific version +/// PinholeBaseK specific version template Point3 triangulateNonlinear( - const std::vector >& cameras, + const std::vector >& cameras, const std::vector& measurements, const Point3& initialEstimate) { - return triangulateNonlinear > // + return triangulateNonlinear > // (cameras, measurements, initialEstimate); } @@ -277,10 +278,10 @@ Point3 triangulatePoint3(const std::vector& cameras, /// Pinhole-specific version template Point3 triangulatePoint3( - const std::vector >& cameras, + const std::vector >& cameras, const std::vector& measurements, double rank_tol = 1e-9, bool optimize = false) { - return triangulatePoint3 > // + return triangulatePoint3 > // (cameras, measurements, rank_tol, optimize); } diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 895d00f4c..19615c8cc 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -16,8 +16,7 @@ */ #include -#include -#include +#include #include namespace gtsam { @@ -27,7 +26,7 @@ namespace gtsam { * The calibration and pose are assumed known. * @addtogroup SLAM */ -template > +template class TriangulationFactor: public NoiseModelFactor1 { public: From dff6b22d3287767cad96cd6e1d4d1f5390e559ec Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 22:32:34 +0100 Subject: [PATCH 029/173] redundant header --- gtsam/slam/SmartProjectionFactor.h | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index df78894e9..4a9caf0b0 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -22,7 +22,6 @@ #include #include -#include #include #include From 06ef84f968ba7ea1027e9a53fe08d4c347fc28e7 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 22:33:08 +0100 Subject: [PATCH 030/173] Moved more into common scenario header --- gtsam/slam/tests/smartFactorScenarios.h | 77 +++++++++++-------- .../tests/testSmartProjectionCameraFactor.cpp | 23 +++++- 2 files changed, 68 insertions(+), 32 deletions(-) diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index c5df4af7e..fc68ba7d9 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -17,8 +17,9 @@ */ #pragma once -#include #include +#include +#include using namespace std; using namespace gtsam; @@ -40,13 +41,13 @@ Pose3 pose_up = level_pose * Pose3(Rot3(), Point3(0, -1, 0)); // Create a noise unit2 for the pixel error static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); +static double fov = 60; // degrees +static size_t w = 640, h = 480; + /* ************************************************************************* */ // default Cal3_S2 cameras namespace vanilla { typedef PinholeCamera Camera; -// make a realistic calibration matrix -static double fov = 60; // degrees -static size_t w = 640, h = 480; static Cal3_S2 K(fov, w, h); static Cal3_S2 K2(1500, 1200, 0, w, h); Camera level_camera(level_pose, K2); @@ -57,7 +58,30 @@ Camera cam1(level_pose, K2); Camera cam2(pose_right, K2); Camera cam3(pose_up, K2); typedef GeneralSFMFactor SFMFactor; -typedef SmartProjectionCameraFactor SmartFactor; +} + +/* ************************************************************************* */ +// default Cal3_S2 poses +namespace vanillaPose { +typedef PinholePose Camera; +static Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); +Camera level_camera(level_pose, sharedK); +Camera level_camera_right(pose_right, sharedK); +Camera cam1(level_pose, sharedK); +Camera cam2(pose_right, sharedK); +Camera cam3(pose_up, sharedK); +} + +/* ************************************************************************* */ +// default Cal3_S2 poses +namespace vanillaPose2 { +typedef PinholePose Camera; +static Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); +Camera level_camera(level_pose, sharedK2); +Camera level_camera_right(pose_right, sharedK2); +Camera cam1(level_pose, sharedK2); +Camera cam2(pose_right, sharedK2); +Camera cam3(pose_up, sharedK2); } /* *************************************************************************/ @@ -74,40 +98,33 @@ Camera cam1(level_pose, K); Camera cam2(pose_right, K); Camera cam3(pose_up, K); typedef GeneralSFMFactor SFMFactor; -typedef SmartProjectionCameraFactor SmartFactorBundler; +} +/* *************************************************************************/ +// Cal3Bundler poses +namespace bundlerPose { +typedef PinholePose Camera; +static boost::shared_ptr sharedBundlerK( + new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); +Camera level_camera(level_pose, sharedBundlerK); +Camera level_camera_right(pose_right, sharedBundlerK); +Camera cam1(level_pose, sharedBundlerK); +Camera cam2(pose_right, sharedBundlerK); +Camera cam3(pose_up, sharedBundlerK); } /* *************************************************************************/ -template -PinholeCamera perturbCameraPose( - const PinholeCamera& camera) { +template +CAMERA perturbCameraPose(const CAMERA& camera) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Pose3 cameraPose = camera.pose(); Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); - return PinholeCamera(perturbedCameraPose, camera.calibration()); + return CAMERA(perturbedCameraPose, camera.calibration()); } -template -PinholeCamera perturbCameraPoseAndCalibration( - const PinholeCamera& camera) { - GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), - Point3(0.5, 0.1, 0.3)); - Pose3 cameraPose = camera.pose(); - Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); - typename gtsam::traits::TangentVector d; - d.setRandom(); - d *= 0.1; - CALIBRATION perturbedCalibration = camera.calibration().retract(d); - return PinholeCamera(perturbedCameraPose, perturbedCalibration); -} - -template -void projectToMultipleCameras(const PinholeCamera& cam1, - const PinholeCamera& cam2, - const PinholeCamera& cam3, Point3 landmark, - vector& measurements_cam) { +template +void projectToMultipleCameras(const CAMERA& cam1, const CAMERA& cam2, + const CAMERA& cam3, Point3 landmark, vector& measurements_cam) { Point2 cam1_uv1 = cam1.project(landmark); Point2 cam2_uv1 = cam2.project(landmark); Point2 cam3_uv1 = cam3.project(landmark); diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index af1ee3ea9..3ac95f7e2 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -19,11 +19,12 @@ */ #include "smartFactorScenarios.h" +#include #include -#include #include +#include #include -// + using namespace boost::assign; static bool isDebugTest = false; @@ -43,6 +44,24 @@ 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 SmartProjectionCameraFactor SmartFactor; +typedef SmartProjectionCameraFactor SmartFactorBundler; + +template +PinholeCamera perturbCameraPoseAndCalibration( + const PinholeCamera& camera) { + GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 cameraPose = camera.pose(); + Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); + typename gtsam::traits::TangentVector d; + d.setRandom(); + d *= 0.1; + CALIBRATION perturbedCalibration = camera.calibration().retract(d); + return PinholeCamera(perturbedCameraPose, perturbedCalibration); +} + /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, perturbCameraPose) { using namespace vanilla; From ae1f534e66918747c120e242089f3bbdf437488b Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 23 Feb 2015 23:58:25 +0100 Subject: [PATCH 031/173] Now second test uses common header as well. --- gtsam/slam/tests/smartFactorScenarios.h | 12 +- .../tests/testSmartProjectionPoseFactor.cpp | 504 ++++++------------ 2 files changed, 180 insertions(+), 336 deletions(-) diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index fc68ba7d9..3c64e982c 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -36,7 +36,7 @@ Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); // Second camera 1 meter to the right of first camera Pose3 pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); // Third camera 1 meter above the first camera -Pose3 pose_up = level_pose * Pose3(Rot3(), Point3(0, -1, 0)); +Pose3 pose_above = level_pose * Pose3(Rot3(), Point3(0, -1, 0)); // Create a noise unit2 for the pixel error static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); @@ -56,7 +56,7 @@ Point2 level_uv = level_camera.project(landmark1); Point2 level_uv_right = level_camera_right.project(landmark1); Camera cam1(level_pose, K2); Camera cam2(pose_right, K2); -Camera cam3(pose_up, K2); +Camera cam3(pose_above, K2); typedef GeneralSFMFactor SFMFactor; } @@ -69,7 +69,7 @@ Camera level_camera(level_pose, sharedK); Camera level_camera_right(pose_right, sharedK); Camera cam1(level_pose, sharedK); Camera cam2(pose_right, sharedK); -Camera cam3(pose_up, sharedK); +Camera cam3(pose_above, sharedK); } /* ************************************************************************* */ @@ -81,7 +81,7 @@ Camera level_camera(level_pose, sharedK2); Camera level_camera_right(pose_right, sharedK2); Camera cam1(level_pose, sharedK2); Camera cam2(pose_right, sharedK2); -Camera cam3(pose_up, sharedK2); +Camera cam3(pose_above, sharedK2); } /* *************************************************************************/ @@ -96,7 +96,7 @@ Point2 level_uv_right = level_camera_right.project(landmark1); Pose3 pose1 = level_pose; Camera cam1(level_pose, K); Camera cam2(pose_right, K); -Camera cam3(pose_up, K); +Camera cam3(pose_above, K); typedef GeneralSFMFactor SFMFactor; } /* *************************************************************************/ @@ -109,7 +109,7 @@ Camera level_camera(level_pose, sharedBundlerK); Camera level_camera_right(pose_right, sharedBundlerK); Camera cam1(level_pose, sharedBundlerK); Camera cam2(pose_right, sharedBundlerK); -Camera cam3(pose_up, sharedBundlerK); +Camera cam3(pose_above, sharedBundlerK); } /* *************************************************************************/ diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index e1ef82b82..671fb771f 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -18,34 +18,24 @@ * @date Sept 2013 */ -#include "../SmartProjectionPoseFactor.h" - -#include +#include "smartFactorScenarios.h" #include +#include +#include #include #include #include -#include +#include #include -using namespace std; using namespace boost::assign; -using namespace gtsam; -static bool isDebugTest = true; - -// make a realistic calibration matrix -static double fov = 60; // degrees -static size_t w = 640, h = 480; - -static Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); -static Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); -static boost::shared_ptr sharedBundlerK( - new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); +static bool isDebugTest = false; static const double rankTol = 1.0; static const double linThreshold = -1.0; static const bool manageDegeneracy = true; + // Create a noise model for the pixel error static const double sigma = 0.1; static SharedNoiseModel model(noiseModel::Isotropic::Sigma(2, sigma)); @@ -59,42 +49,13 @@ static Symbol x1('X', 1); static Symbol x2('X', 2); static Symbol x3('X', 3); -static Key poseKey1(x1); 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 PinholePose Camera; typedef SmartProjectionPoseFactor SmartFactor; - -typedef PinholePose CameraBundler; typedef SmartProjectionPoseFactor SmartFactorBundler; -// 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), - Point3(0, 0, 1)); -Camera level_camera(level_pose, sharedK2); - -// create second camera 1 meter to the right of first camera -Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); -Camera level_camera_right(level_pose_right, sharedK2); - -// landmarks ~5 meters in front of camera -Point3 landmark1(5, 0.5, 1.2); -Point3 landmark2(5, -0.5, 1.2); -Point3 landmark3(5, 0, 3.0); - -void projectToMultipleCameras(Camera cam1, Camera cam2, Camera cam3, - Point3 landmark, vector& measurements_cam) { - - Point2 cam1_uv1 = cam1.project(landmark); - Point2 cam2_uv1 = cam2.project(landmark); - Point2 cam3_uv1 = cam3.project(landmark); - measurements_cam.push_back(cam1_uv1); - measurements_cam.push_back(cam2_uv1); - measurements_cam.push_back(cam3_uv1); -} - /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor) { SmartFactor::shared_ptr factor1(new SmartFactor()); @@ -107,32 +68,36 @@ TEST( SmartProjectionPoseFactor, Constructor2) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor3) { + using namespace vanillaPose; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, sharedK); + factor1->add(measurement1, x1, model, sharedK); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { + using namespace vanillaPose; SmartFactor factor1(rankTol, linThreshold); - factor1.add(measurement1, poseKey1, model, sharedK); + factor1.add(measurement1, x1, model, sharedK); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithTransform) { + using namespace vanillaPose; bool manageDegeneracy = true; bool enableEPI = false; SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor1); - factor1.add(measurement1, poseKey1, model, sharedK); + factor1.add(measurement1, x1, model, sharedK); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Equals ) { + using namespace vanillaPose; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, sharedK); + factor1->add(measurement1, x1, model, sharedK); SmartFactor::shared_ptr factor2(new SmartFactor()); - factor2->add(measurement1, poseKey1, model, sharedK); + factor2->add(measurement1, x1, model, sharedK); CHECK(assert_equal(*factor1, *factor2)); } @@ -141,6 +106,8 @@ TEST( SmartProjectionPoseFactor, Equals ) { TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; + using namespace vanillaPose; + // Project two landmarks into two cameras Point2 level_uv = level_camera.project(landmark1); Point2 level_uv_right = level_camera_right.project(landmark1); @@ -151,7 +118,7 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { Values values; values.insert(x1, level_pose); - values.insert(x2, level_pose_right); + values.insert(x2, pose_right); double actualError = factor.error(values); double expectedError = 0.0; @@ -195,7 +162,9 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { TEST( SmartProjectionPoseFactor, noisy ) { // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; - // 1. Project two landmarks into two cameras and triangulate + using namespace vanillaPose; + + // Project two landmarks into two cameras and triangulate Point2 pixelError(0.2, 0.2); Point2 level_uv = level_camera.project(landmark1) + pixelError; Point2 level_uv_right = level_camera_right.project(landmark1); @@ -204,7 +173,7 @@ TEST( SmartProjectionPoseFactor, noisy ) { values.insert(x1, level_pose); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); - values.insert(x2, level_pose_right.compose(noise_pose)); + values.insert(x2, pose_right.compose(noise_pose)); SmartFactor::shared_ptr factor(new SmartFactor()); factor->add(level_uv, x1, model, sharedK); @@ -240,21 +209,10 @@ TEST( SmartProjectionPoseFactor, noisy ) { TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK2); - + using namespace vanillaPose2; vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -279,17 +237,17 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { 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)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), 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.insert(x1, level_pose); + values.insert(x2, pose_right); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -312,7 +270,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { // 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), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); if (isDebugTest) tictoc_print_(); } @@ -320,24 +278,16 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { - // 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), - Point3(0, 0, 1)); // body poses - Pose3 cameraPose2 = cameraPose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Pose3 cameraPose3 = cameraPose1 * Pose3(Rot3(), Point3(0, -1, 0)); - - Camera cam1(cameraPose1, sharedK); // with camera poses - Camera cam2(cameraPose2, sharedK); - Camera cam3(cameraPose3, sharedK); + 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), Point3(1, 1, 1)); // Pose3(); // // 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()); + Pose3 bodyPose1 = level_pose.compose(sensor_to_body.inverse()); + Pose3 bodyPose2 = pose_right.compose(sensor_to_body.inverse()); + Pose3 bodyPose3 = pose_above.compose(sensor_to_body.inverse()); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -396,7 +346,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { 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 + // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, bodyPose3 * noise_pose); LevenbergMarquardtParams params; @@ -564,26 +514,16 @@ TEST( SmartProjectionPoseFactor, Factors ) { TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -603,17 +543,17 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { 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)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), 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.insert(x1, level_pose); + values.insert(x2, pose_right); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -633,7 +573,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { // 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), 1e-7)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); if (isDebugTest) tictoc_print_(); } @@ -641,24 +581,16 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, jacobianSVD ) { + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -681,27 +613,29 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { 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)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3 * noise_pose); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above * noise_pose); LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose3, result.at(x3), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, landmarkDistance ) { + using namespace vanillaPose; + double excludeLandmarksFutherThanDist = 2; vector views; @@ -709,19 +643,9 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -747,16 +671,16 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { 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)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3 * noise_pose); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above * noise_pose); // All factors are disabled and pose should remain where it is LevenbergMarquardtParams params; @@ -769,6 +693,8 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { + using namespace vanillaPose; + double excludeLandmarksFutherThanDist = 1e10; double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error @@ -777,23 +703,13 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK); - // add fourth landmark Point3 landmark4(5, -0.5, 1); vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -827,45 +743,37 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(smartFactor4); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above); // All factors are disabled and pose should remain where it is LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose3, result.at(x3))); + EXPECT(assert_equal(pose_above, result.at(x3))); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, jacobianQ ) { + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -888,49 +796,39 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { 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)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3 * noise_pose); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above * noise_pose); LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose3, result.at(x3), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; + using namespace vanillaPose2; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK2); - typedef GenericProjectionFactor ProjectionFactor; NonlinearFactorGraph graph; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate graph.push_back( ProjectionFactor(cam1.project(landmark1), model, x1, L(1), sharedK2)); graph.push_back( @@ -953,15 +851,15 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { ProjectionFactor(cam3.project(landmark3), model, x3, L(3), sharedK2)); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), 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(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above * noise_pose); values.insert(L(1), landmark1); values.insert(L(2), landmark2); values.insert(L(3), landmark3); @@ -978,7 +876,7 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { if (isDebugTest) result.at(x3).print("Pose3 after optimization: "); - EXPECT(assert_equal(pose3, result.at(x3), 1e-7)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); } /* *************************************************************************/ @@ -989,21 +887,17 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); + using namespace vanillaPose; - // 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)); + // Two slightly different cameras + Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); - - // 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)); Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -1028,10 +922,10 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), 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.insert(x1, level_pose); + values.insert(x2, pose_right); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1068,26 +962,22 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ) { // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; + using namespace vanillaPose2; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK2); - - // 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)); + // Two different cameras + Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK2); - - // 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)); Camera cam3(pose3, sharedK2); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); @@ -1108,7 +998,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( @@ -1117,10 +1007,10 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), 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.insert(x1, level_pose); + values.insert(x2, pose_right * noise_pose); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1143,7 +1033,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; - // EXPECT(assert_equal(pose3,result.at(x3))); + // EXPECT(assert_equal(pose_above,result.at(x3))); if (isDebugTest) tictoc_print_(); } @@ -1152,26 +1042,22 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) { // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks: Rotation Only**********************" << endl; + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); - - // 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)); + // Two different cameras + Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); - - // 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)); Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -1199,7 +1085,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( @@ -1209,10 +1095,10 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), 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.insert(x1, level_pose); + values.insert(x2, pose_right); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1235,7 +1121,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; - // EXPECT(assert_equal(pose3,result.at(x3))); + // EXPECT(assert_equal(pose_above,result.at(x3))); if (isDebugTest) tictoc_print_(); } @@ -1244,19 +1130,13 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) TEST( SmartProjectionPoseFactor, Hessian ) { // cout << " ************************ SmartProjectionPoseFactor: Hessian **********************" << endl; + using namespace vanillaPose2; + vector views; views.push_back(x1); views.push_back(x2); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK2); - - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into 2 cameras and triangulate Point2 cam1_uv1 = cam1.project(landmark1); Point2 cam2_uv1 = cam2.project(landmark1); vector measurements_cam1; @@ -1269,8 +1149,8 @@ TEST( SmartProjectionPoseFactor, Hessian ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); + values.insert(x1, level_pose); + values.insert(x2, pose_right); boost::shared_ptr hessianFactor = smartFactor1->linearize( values); @@ -1287,23 +1167,13 @@ TEST( SmartProjectionPoseFactor, Hessian ) { TEST( SmartProjectionPoseFactor, HessianWithRotation ) { // cout << " ************************ SmartProjectionPoseFactor: rotated Hessian **********************" << endl; + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Camera cam2(pose2, sharedK); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - Camera cam3(pose3, sharedK); - vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -1312,24 +1182,22 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { smartFactorInstance->add(measurements_cam1, views, model, sharedK); Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above); boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); - // hessianFactor->print("Hessian factor \n"); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); + rotValues.insert(x1, poseDrift.compose(level_pose)); + rotValues.insert(x2, poseDrift.compose(pose_right)); + rotValues.insert(x3, poseDrift.compose(pose_above)); boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); - // hessianFactorRot->print("Hessian factor \n"); // Hessian is invariant to rotations in the nondegenerate case EXPECT( @@ -1340,9 +1208,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); + tranValues.insert(x1, poseDrift2.compose(level_pose)); + tranValues.insert(x2, poseDrift2.compose(pose_right)); + tranValues.insert(x3, poseDrift2.compose(pose_above)); boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); @@ -1357,23 +1225,13 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { // cout << " ************************ SmartProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; + using namespace vanillaPose2; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - Camera cam1(pose1, sharedK2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0, 0, 0)); - Camera cam2(pose2, sharedK2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, 0, 0)); - Camera cam3(pose3, sharedK2); - vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -1382,9 +1240,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { smartFactor->add(measurements_cam1, views, model, sharedK2); Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above); boost::shared_ptr hessianFactor = smartFactor->linearize( values); @@ -1394,9 +1252,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); + rotValues.insert(x1, poseDrift.compose(level_pose)); + rotValues.insert(x2, poseDrift.compose(pose_right)); + rotValues.insert(x3, poseDrift.compose(pose_above)); boost::shared_ptr hessianFactorRot = smartFactor->linearize( rotValues); @@ -1412,9 +1270,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); + tranValues.insert(x1, poseDrift2.compose(level_pose)); + tranValues.insert(x2, poseDrift2.compose(pose_right)); + tranValues.insert(x3, poseDrift2.compose(pose_above)); boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); @@ -1430,31 +1288,21 @@ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { SmartFactorBundler factor(rankTol, linThreshold); boost::shared_ptr sharedBundlerK( new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); - factor.add(measurement1, poseKey1, model, sharedBundlerK); + factor.add(measurement1, x1, model, sharedBundlerK); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { // cout << " ************************ SmartProjectionPoseFactor: Cal3Bundler **********************" << endl; - // 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), Point3(0, 0, 1)); - CameraBundler cam1(pose1, sharedBundlerK); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - CameraBundler cam2(pose2, sharedBundlerK); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - CameraBundler cam3(pose3, sharedBundlerK); + using namespace bundlerPose; // three landmarks ~5 meters infront of camera Point3 landmark3(3, 0, 3.0); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // 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); @@ -1496,17 +1344,17 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { 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)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), 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.insert(x1, level_pose); + values.insert(x2, pose_right); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1526,7 +1374,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { // 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), 1e-6)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-6)); if (isDebugTest) tictoc_print_(); } @@ -1534,29 +1382,25 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { + using namespace bundlerPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // 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), Point3(0, 0, 1)); - CameraBundler cam1(pose1, sharedBundlerK); - - // 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)); - CameraBundler cam2(pose2, sharedBundlerK); - - // 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)); - CameraBundler cam3(pose3, sharedBundlerK); + // Two different cameras + Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Camera cam2(pose2, sharedBundlerK); + Camera cam3(pose3, sharedBundlerK); // landmark3 at 3 meters now Point3 landmark3(3, 0, 3.0); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // 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); @@ -1601,7 +1445,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( @@ -1611,10 +1455,10 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), 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.insert(x1, level_pose); + values.insert(x2, pose_right); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1637,7 +1481,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; - // EXPECT(assert_equal(pose3,result.at(x3))); + // EXPECT(assert_equal(pose_above,result.at(x3))); if (isDebugTest) tictoc_print_(); } From eb28d0ffa89c04235b21e47d6bdaf7f0b74b9dc6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 24 Feb 2015 14:09:35 +0100 Subject: [PATCH 032/173] Restored reprojectionErrors -> reprojectionError --- gtsam/geometry/CameraSet.h | 4 ++-- gtsam/geometry/tests/testCameraSet.cpp | 8 ++++---- gtsam/slam/SmartFactorBase.h | 16 ++++++++-------- gtsam/slam/SmartProjectionFactor.h | 2 +- .../slam/tests/testSmartProjectionPoseFactor.cpp | 8 ++++---- .../slam/SmartStereoProjectionFactor.h | 2 +- 6 files changed, 20 insertions(+), 20 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index eb58d1658..2192c38b9 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -140,7 +140,7 @@ public: } /// Calculate vector of re-projection errors - Vector reprojectionErrors(const Point3& point, const std::vector& measured, + Vector reprojectionError(const Point3& point, const std::vector& measured, boost::optional F = boost::none, // boost::optional E = boost::none) const { return ErrorVector(project2(point,F,E), measured); @@ -148,7 +148,7 @@ public: /// Calculate vector of re-projection errors, from point at infinity // TODO: take Unit3 instead - Vector reprojectionErrorsAtInfinity(const Point3& point, + Vector reprojectionErrorAtInfinity(const Point3& point, const std::vector& measured) const { return ErrorVector(projectAtInfinity(point), measured); } diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index a003b6bce..25a6da5b2 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -73,16 +73,16 @@ TEST(CameraSet, Pinhole) { measured.push_back(Point2(3, 4)); Vector4 expectedV; - // reprojectionErrors + // reprojectionError expectedV << -1, -2, -3, -4; - Vector actualV = set.reprojectionErrors(p, measured); + Vector actualV = set.reprojectionError(p, measured); EXPECT(assert_equal(expectedV, actualV)); - // reprojectionErrorsAtInfinity + // reprojectionErrorAtInfinity EXPECT( assert_equal(Point3(0, 0, 1), camera.backprojectPointAtInfinity(Point2()))); - actualV = set.reprojectionErrorsAtInfinity(p, measured); + actualV = set.reprojectionErrorAtInfinity(p, measured); EXPECT(assert_equal(expectedV, actualV)); } diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 6a33eeb6e..9554b7c4a 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -215,7 +215,7 @@ public: /// Calculate vector of re-projection errors, noise model applied Vector whitenedErrors(const Cameras& cameras, const Point3& point) const { - Vector b = cameras.reprojectionErrors(point, measured_); + Vector b = cameras.reprojectionError(point, measured_); if (noiseModel_) noiseModel_->whitenInPlace(b); return b; @@ -225,7 +225,7 @@ public: // TODO: Unit3 Vector whitenedErrorsAtInfinity(const Cameras& cameras, const Point3& point) const { - Vector b = cameras.reprojectionErrorsAtInfinity(point, measured_); + Vector b = cameras.reprojectionErrorAtInfinity(point, measured_); if (noiseModel_) noiseModel_->whitenInPlace(b); return b; @@ -252,8 +252,8 @@ public: } /// Compute reprojection errors - Vector reprojectionErrors(const Cameras& cameras, const Point3& point) const { - return cameras.reprojectionErrors(point, measured_); + Vector reprojectionError(const Cameras& cameras, const Point3& point) const { + return cameras.reprojectionError(point, measured_); } /** @@ -261,10 +261,10 @@ public: * TODO: the treatment of body_P_sensor_ is weird: the transformation * is applied in the caller, but the derivatives are computed here. */ - Vector reprojectionErrors(const Cameras& cameras, const Point3& point, + Vector reprojectionError(const Cameras& cameras, const Point3& point, typename Cameras::FBlocks& F, Matrix& E) const { - Vector b = cameras.reprojectionErrors(point, measured_, F, E); + Vector b = cameras.reprojectionError(point, measured_, F, E); // Apply sensor chain rule if needed TODO: no simpler way ?? if (body_P_sensor_) { @@ -308,7 +308,7 @@ public: /// Assumes non-degenerate ! void computeEP(Matrix& E, Matrix& P, const Cameras& cameras, const Point3& point) const { - cameras.reprojectionErrors(point, measured_, boost::none, E); + cameras.reprojectionError(point, measured_, boost::none, E); P = PointCov(E); } @@ -322,7 +322,7 @@ public: // Project into Camera set and calculate derivatives typename Cameras::FBlocks F; - b = reprojectionErrors(cameras, point, F, E); + b = reprojectionError(cameras, point, F, E); // Now calculate f and divide up the F derivatives into Fblocks double f = 0.0; diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 4a9caf0b0..3a996918f 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -573,7 +573,7 @@ public: /// Calculate vector of re-projection errors, before applying noise model /// Assumes triangulation was done and degeneracy handled Vector reprojectionError(const Cameras& cameras) const { - return cameras.reprojectionErrors(point_,this->measured_); + return cameras.reprojectionError(point_,this->measured_); } /// Calculate vector of re-projection errors, before applying noise model diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 671fb771f..41c0fac0a 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -142,10 +142,10 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { factor.computeEP(actualE, PointCov, values); EXPECT(assert_equal(expectedE, actualE, 1e-7)); - // Calculate using reprojectionErrors, note not yet divided by sigma ! + // Calculate using reprojectionError, note not yet divided by sigma ! SmartFactor::Cameras::FBlocks F; Matrix E; - Vector actualErrors = factor.reprojectionErrors(cameras, *point, F, E); + Vector actualErrors = factor.reprojectionError(cameras, *point, F, E); EXPECT(assert_equal(expectedE, E, 1e-7)); EXPECT(assert_equal(zero(4), actualErrors, 1e-7)); @@ -379,10 +379,10 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { // Calculate using whitenedError Matrix E; SmartFactor::Cameras::FBlocks F; - Vector actualErrors = smartFactor1->reprojectionErrors(cameras, *point, F, E); + Vector actualErrors = smartFactor1->reprojectionError(cameras, *point, F, E); EXPECT(assert_equal(expectedE, E, 1e-7)); - // Success ! The derivatives of reprojectionErrors now agree with f ! + // Success ! The derivatives of reprojectionError now agree with f ! EXPECT(assert_equal(f(*point) * sigma, actualErrors, 1e-7)); } diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 0e70add9f..04383839f 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -629,7 +629,7 @@ public: Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return cameras.reprojectionErrors(point_); + return cameras.reprojectionError(point_); else return zero(cameras.size() * 3); } From 301e827454de9f280b4d269ee1835262e18f184c Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 24 Feb 2015 14:23:44 +0100 Subject: [PATCH 033/173] Switched back to PinholeCamera (though I'm not thrilled) --- gtsam/geometry/triangulation.h | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index ea6c5c041..3b6c2c4b3 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -18,7 +18,7 @@ #pragma once -#include +#include #include #include #include @@ -75,8 +75,8 @@ std::pair triangulationGraph( static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); for (size_t i = 0; i < measurements.size(); i++) { const Pose3& pose_i = poses[i]; - PinholeBaseK camera_i(pose_i, sharedCal); - graph.push_back(TriangulationFactor > // + PinholeCamera camera_i(pose_i, sharedCal); + graph.push_back(TriangulationFactor > // (camera_i, measurements[i], unit2, landmarkKey)); } return std::make_pair(graph, values); @@ -108,13 +108,13 @@ std::pair triangulationGraph( return std::make_pair(graph, values); } -/// PinholeBaseK specific version +/// PinholeCamera specific version template std::pair triangulationGraph( - const std::vector >& cameras, + const std::vector >& cameras, const std::vector& measurements, Key landmarkKey, const Point3& initialEstimate) { - return triangulationGraph > // + return triangulationGraph > // (cameras, measurements, landmarkKey, initialEstimate); } @@ -170,12 +170,12 @@ Point3 triangulateNonlinear(const std::vector& cameras, return optimize(graph, values, Symbol('p', 0)); } -/// PinholeBaseK specific version +/// PinholeCamera specific version template Point3 triangulateNonlinear( - const std::vector >& cameras, + const std::vector >& cameras, const std::vector& measurements, const Point3& initialEstimate) { - return triangulateNonlinear > // + return triangulateNonlinear > // (cameras, measurements, initialEstimate); } @@ -278,10 +278,10 @@ Point3 triangulatePoint3(const std::vector& cameras, /// Pinhole-specific version template Point3 triangulatePoint3( - const std::vector >& cameras, + const std::vector >& cameras, const std::vector& measurements, double rank_tol = 1e-9, bool optimize = false) { - return triangulatePoint3 > // + return triangulatePoint3 > // (cameras, measurements, rank_tol, optimize); } From c4095d2ed92ed34e198778e1a9d2a0203eee8ff2 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 24 Feb 2015 14:44:01 +0100 Subject: [PATCH 034/173] Fixed linking --- gtsam/slam/SmartFactorBase.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 9554b7c4a..edb3d399f 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -66,8 +66,8 @@ protected: */ std::vector measured_; - static const int ZDim = traits::dimension; ///< Measurement dimension static const int Dim = traits::dimension; ///< Camera dimension + static const int ZDim = traits::dimension; ///< Measurement dimension // Definitions for block matrices used internally typedef Eigen::Matrix MatrixD2; // F' @@ -706,8 +706,8 @@ private: }; // end class SmartFactorBase -// TODO: Why is this here? -template -const int SmartFactorBase::ZDim; +// Definitions need to avoid link errors (above are only declarations) +template const int SmartFactorBase::Dim; +template const int SmartFactorBase::ZDim; } // \ namespace gtsam From b3d0b1809cc3e3f252a2f4b24e2b7f3c8fcc84e7 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 24 Feb 2015 21:55:37 +0100 Subject: [PATCH 035/173] Fixed some compilation issues --- gtsam/geometry/tests/testTriangulation.cpp | 1 + gtsam/geometry/triangulation.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index f986cca1d..3045668d5 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -17,6 +17,7 @@ */ #include +#include #include #include diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 3b6c2c4b3..ded893fbe 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -75,7 +75,7 @@ std::pair triangulationGraph( static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); for (size_t i = 0; i < measurements.size(); i++) { const Pose3& pose_i = poses[i]; - PinholeCamera camera_i(pose_i, sharedCal); + PinholePose camera_i(pose_i, sharedCal); graph.push_back(TriangulationFactor > // (camera_i, measurements[i], unit2, landmarkKey)); } From 694e6e903cb7ace6691949315520226bac053253 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 25 Feb 2015 00:57:51 +0100 Subject: [PATCH 036/173] Fixed template issue --- gtsam/geometry/triangulation.h | 5 +++-- gtsam/slam/tests/testTriangulationFactor.cpp | 5 +++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index ded893fbe..5b8be0168 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -75,8 +75,9 @@ std::pair triangulationGraph( static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); for (size_t i = 0; i < measurements.size(); i++) { const Pose3& pose_i = poses[i]; - PinholePose camera_i(pose_i, sharedCal); - graph.push_back(TriangulationFactor > // + typedef PinholePose Camera; + Camera camera_i(pose_i, sharedCal); + graph.push_back(TriangulationFactor // (camera_i, measurements[i], unit2, landmarkKey)); } return std::make_pair(graph, values); diff --git a/gtsam/slam/tests/testTriangulationFactor.cpp b/gtsam/slam/tests/testTriangulationFactor.cpp index 6b79171df..2c3a64495 100644 --- a/gtsam/slam/tests/testTriangulationFactor.cpp +++ b/gtsam/slam/tests/testTriangulationFactor.cpp @@ -17,6 +17,7 @@ */ #include +#include #include #include #include @@ -35,7 +36,7 @@ static const boost::shared_ptr sharedCal = // // Looking along X-axis, 1 meter above ground plane (x-y) static const Rot3 upright = Rot3::ypr(-M_PI / 2, 0., -M_PI / 2); static const Pose3 pose1 = Pose3(upright, gtsam::Point3(0, 0, 1)); -PinholeCamera camera1(pose1, *sharedCal); +SimpleCamera camera1(pose1, *sharedCal); // landmark ~5 meters infront of camera static const Point3 landmark(5, 0.5, 1.2); @@ -48,7 +49,7 @@ TEST( triangulation, TriangulationFactor ) { // Create the factor with a measurement that is 3 pixels off in x Key pointKey(1); SharedNoiseModel model; - typedef TriangulationFactor<> Factor; + typedef TriangulationFactor Factor; Factor factor(camera1, z1, model, pointKey); // Use the factor to calculate the Jacobians From d7b5156dcc12dcdf31b32e68f7611bc75c44d1e6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 25 Feb 2015 01:14:36 +0100 Subject: [PATCH 037/173] rename to reprojectionErrorAfterTriangulation --- gtsam/slam/SmartProjectionFactor.h | 10 ++-------- gtsam/slam/tests/testSmartProjectionCameraFactor.cpp | 4 +++- gtsam_unstable/slam/SmartStereoProjectionFactor.h | 4 ++-- 3 files changed, 7 insertions(+), 11 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 3a996918f..2f4da3ce6 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -571,17 +571,11 @@ public: } /// Calculate vector of re-projection errors, before applying noise model - /// Assumes triangulation was done and degeneracy handled - Vector reprojectionError(const Cameras& cameras) const { - return cameras.reprojectionError(point_,this->measured_); - } - - /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionError(const Values& values) const { + Vector reprojectionErrorAfterTriangulation(const Values& values) const { Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return reprojectionError(cameras); + return Base::reprojectionError(cameras, point_); else return zero(cameras.size() * 2); } diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 3ac95f7e2..f82073e81 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -136,7 +136,9 @@ TEST( SmartProjectionCameraFactor, noiseless ) { double expectedError = 0.0; DOUBLES_EQUAL(expectedError, factor1->error(values), 1e-7); - CHECK(assert_equal(zero(4), factor1->reprojectionError(values), 1e-7)); + CHECK( + assert_equal(zero(4), + factor1->reprojectionErrorAfterTriangulation(values), 1e-7)); } /* *************************************************************************/ diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 04383839f..337bf2f68 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -625,11 +625,11 @@ public: } /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionError(const Values& values) const { + Vector reprojectionErrorAfterTriangulation(const Values& values) const { Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return cameras.reprojectionError(point_); + return Base::reprojectionError(cameras, point_); else return zero(cameras.size() * 3); } From f7292488c439bd154c218a1e05f4266a7f3ad6af Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 25 Feb 2015 14:00:21 +0100 Subject: [PATCH 038/173] Made RegularImplicitSchurFactor fully functional, and whitened again. --- gtsam/slam/RegularImplicitSchurFactor.h | 114 ++++++++++++------------ gtsam/slam/SmartFactorBase.h | 24 +++-- 2 files changed, 73 insertions(+), 65 deletions(-) diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index b1490d465..731db479f 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -30,23 +30,10 @@ protected: typedef Eigen::Matrix MatrixDD; ///< camera hessian typedef std::pair KeyMatrix2D; ///< named F block - std::vector Fblocks_; ///< All 2*D F blocks (one for each camera) - Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (2*2 if degenerate) - Matrix E_; ///< The 2m*3 E Jacobian with respect to the point - Vector b_; ///< 2m-dimensional RHS vector - -public: - - /// Constructor - RegularImplicitSchurFactor() { - } - - /// Construct from blcoks of F, E, inv(E'*E), and RHS vector b - RegularImplicitSchurFactor(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b) : - Fblocks_(Fblocks), PointCovariance_(P), E_(E), b_(b) { - initKeys(); - } + const std::vector Fblocks_; ///< All 2*D F blocks (one for each camera) + const Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (2*2 if degenerate) + const Matrix E_; ///< The 2m*3 E Jacobian with respect to the point + const Vector b_; ///< 2m-dimensional RHS vector /// initialize keys from Fblocks void initKeys() { @@ -55,36 +42,42 @@ public: keys_.push_back(it.first); } +public: + + /// Constructor + RegularImplicitSchurFactor() { + } + + /// Construct from blocks of F, E, inv(E'*E), and RHS vector b + RegularImplicitSchurFactor(const std::vector& Fblocks, + const Matrix& E, const Matrix3& P, const Vector& b) : + Fblocks_(Fblocks), PointCovariance_(P), E_(E), b_(b) { + initKeys(); + } + /// Destructor virtual ~RegularImplicitSchurFactor() { } - // Write access, only use for construction! - - inline std::vector& Fblocks() { + inline std::vector& Fblocks() const { return Fblocks_; } - inline Matrix3& PointCovariance() { - return PointCovariance_; - } - - inline Matrix& E() { + inline const Matrix& E() const { return E_; } - inline Vector& b() { + inline const Vector& b() const { return b_; } - /// Get matrix P inline const Matrix3& getPointCovariance() const { return PointCovariance_; } /// print - void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const { std::cout << " RegularImplicitSchurFactor " << std::endl; Factor::print(s); for (size_t pos = 0; pos < size(); ++pos) { @@ -101,9 +94,13 @@ public: if (!f) return false; for (size_t pos = 0; pos < size(); ++pos) { - if (keys_[pos] != f->keys_[pos]) return false; - if (Fblocks_[pos].first != f->Fblocks_[pos].first) return false; - if (!equal_with_abs_tol(Fblocks_[pos].second,f->Fblocks_[pos].second,tol)) return false; + if (keys_[pos] != f->keys_[pos]) + return false; + if (Fblocks_[pos].first != f->Fblocks_[pos].first) + return false; + if (!equal_with_abs_tol(Fblocks_[pos].second, f->Fblocks_[pos].second, + tol)) + return false; } return equal_with_abs_tol(PointCovariance_, f->PointCovariance_, tol) && equal_with_abs_tol(E_, f->E_, tol) @@ -121,7 +118,8 @@ public: return Matrix(); } virtual std::pair jacobian() const { - throw std::runtime_error("RegularImplicitSchurFactor::jacobian non implemented"); + throw std::runtime_error( + "RegularImplicitSchurFactor::jacobian non implemented"); return std::make_pair(Matrix(), Vector()); } virtual Matrix augmentedInformation() const { @@ -146,7 +144,7 @@ public: // Calculate Fj'*Ej for the current camera (observing a single point) // D x 3 = (D x 2) * (2 x 3) const Matrix2D& Fj = Fblocks_[pos].second; - Eigen::Matrix FtE = Fj.transpose() + Eigen::Matrix FtE = Fj.transpose() * E_.block<2, 3>(2 * pos, 0); Eigen::Matrix dj; @@ -205,7 +203,8 @@ public: // - FtE * PointCovariance_ * FtE.transpose(); const Matrix23& Ej = E_.block<2, 3>(2 * pos, 0); - blocks[j] = Fj.transpose() * (Fj - Ej * PointCovariance_ * Ej.transpose() * Fj); + blocks[j] = Fj.transpose() + * (Fj - Ej * PointCovariance_ * Ej.transpose() * Fj); // F'*(I - E*P*E')*F, TODO: this should work, but it does not :-( // static const Eigen::Matrix I2 = eye(2); @@ -219,7 +218,8 @@ public: virtual GaussianFactor::shared_ptr clone() const { return boost::make_shared >(Fblocks_, PointCovariance_, E_, b_); - throw std::runtime_error("RegularImplicitSchurFactor::clone non implemented"); + throw std::runtime_error( + "RegularImplicitSchurFactor::clone non implemented"); } virtual bool empty() const { return false; @@ -228,7 +228,8 @@ public: virtual GaussianFactor::shared_ptr negate() const { return boost::make_shared >(Fblocks_, PointCovariance_, E_, b_); - throw std::runtime_error("RegularImplicitSchurFactor::negate non implemented"); + throw std::runtime_error( + "RegularImplicitSchurFactor::negate non implemented"); } // Raw Vector version of y += F'*alpha*(I - E*P*E')*F*x, for testing @@ -254,14 +255,15 @@ public: Vector3 d1; d1.setZero(); for (size_t k = 0; k < size(); k++) - d1 += E_.block < 2, 3 > (2 * k, 0).transpose() * (e1[k] - 2 * b_.segment < 2 > (k * 2)); + d1 += E_.block<2, 3>(2 * k, 0).transpose() + * (e1[k] - 2 * b_.segment<2>(k * 2)); // d2 = E.transpose() * e1 = (3*2m)*2m Vector3 d2 = PointCovariance_ * d1; // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - 2 * b_.segment < 2 > (k * 2) - E_.block < 2, 3 > (2 * k, 0) * d2; + e2[k] = e1[k] - 2 * b_.segment<2>(k * 2) - E_.block<2, 3>(2 * k, 0) * d2; } /* @@ -303,7 +305,7 @@ public: // e1 = F * x - b = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment < 2 > (k * 2); + e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment<2>(k * 2); projectError(e1, e2); double result = 0; @@ -316,21 +318,21 @@ public: /** * @brief Calculate corrected error Q*e = (I - E*P*E')*e */ - void projectError(const Error2s& e1, Error2s& e2) const { + void projectError(const Error2s& e1, Error2s& e2) const { - // d1 = E.transpose() * e1 = (3*2m)*2m - Vector3 d1; - d1.setZero(); - for (size_t k = 0; k < size(); k++) - d1 += E_.block < 2, 3 > (2 * k, 0).transpose() * e1[k]; + // d1 = E.transpose() * e1 = (3*2m)*2m + Vector3 d1; + d1.setZero(); + for (size_t k = 0; k < size(); k++) + d1 += E_.block<2, 3>(2 * k, 0).transpose() * e1[k]; - // d2 = E.transpose() * e1 = (3*2m)*2m - Vector3 d2 = PointCovariance_ * d1; + // d2 = E.transpose() * e1 = (3*2m)*2m + Vector3 d2 = PointCovariance_ * d1; - // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] - for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - E_.block < 2, 3 > (2 * k, 0) * d2; - } + // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] + for (size_t k = 0; k < size(); k++) + e2[k] = e1[k] - E_.block<2, 3>(2 * k, 0) * d2; + } /// Scratch space for multiplyHessianAdd mutable Error2s e1, e2; @@ -424,7 +426,7 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment < 2 > (2 * k); + e1[k] = b_.segment<2>(2 * k); projectError(e1, e2); // g = F.transpose()*e2 @@ -451,7 +453,7 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment < 2 > (2 * k); + e1[k] = b_.segment<2>(2 * k); projectError(e1, e2); for (size_t k = 0; k < size(); ++k) { // for each camera in the factor @@ -462,10 +464,10 @@ public: /// Gradient wrt a key at any values Vector gradient(Key key, const VectorValues& x) const { - throw std::runtime_error("gradient for RegularImplicitSchurFactor is not implemented yet"); + throw std::runtime_error( + "gradient for RegularImplicitSchurFactor is not implemented yet"); } - }; // end class RegularImplicitSchurFactor diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index edb3d399f..3d29b34e8 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -657,12 +657,16 @@ public: boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - typename boost::shared_ptr > f( - new RegularImplicitSchurFactor()); - computeJacobians(f->Fblocks(), f->E(), f->b(), cameras, point); - f->PointCovariance() = PointCov(f->E(), lambda, diagonalDamping); - f->initKeys(); - return f; + std::vector F; + Matrix E; + Vector b; + computeJacobians(F, E, b, cameras, point); + noiseModel_->WhitenSystem(E,b); + Matrix3 P = PointCov(E, lambda, diagonalDamping); + // TODO make WhitenInPlace work with any dense matrix type + BOOST_FOREACH(KeyMatrix2D& Fblock,F) + Fblock.second = noiseModel_->Whiten(Fblock.second); + return boost::make_shared >(F, E, P, b); } /** @@ -676,7 +680,8 @@ public: Vector b; computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - return boost::make_shared >(Fblocks, E, P, b); + return boost::make_shared > // + (Fblocks, E, P, b, noiseModel_); } /** @@ -690,12 +695,13 @@ public: Vector b; Matrix Enull(ZDim * numKeys, ZDim * numKeys - 3); computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - return boost::make_shared >(Fblocks, Enull, b); + return boost::make_shared > // + (Fblocks, Enull, b, noiseModel_); } private: - /// Serialization function +/// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { From 3d85bf8e1fb0a967389467156bf073c5d3932961 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 25 Feb 2015 19:28:59 +0100 Subject: [PATCH 039/173] Removed testSmartProjectionFactor.run target --- .cproject | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/.cproject b/.cproject index 79cb93f93..5d3733e28 100644 --- a/.cproject +++ b/.cproject @@ -1131,14 +1131,6 @@ true true - - make - -j5 - testSmartProjectionFactor.run - true - true - true - make -j5 @@ -1309,7 +1301,6 @@ make - testSimulated2DOriented.run true false @@ -1349,7 +1340,6 @@ make - testSimulated2D.run true false @@ -1357,7 +1347,6 @@ make - testSimulated3D.run true false @@ -1461,6 +1450,7 @@ make + testErrors.run true false @@ -1795,6 +1785,7 @@ cpack + -G DEB true false @@ -1802,6 +1793,7 @@ cpack + -G RPM true false @@ -1809,6 +1801,7 @@ cpack + -G TGZ true false @@ -1816,6 +1809,7 @@ cpack + --config CPackSourceConfig.cmake true false @@ -2007,7 +2001,6 @@ make - tests/testGaussianISAM2 true false @@ -2159,6 +2152,7 @@ make + tests/testBayesTree.run true false @@ -2166,6 +2160,7 @@ make + testBinaryBayesNet.run true false @@ -2213,6 +2208,7 @@ make + testSymbolicBayesNet.run true false @@ -2220,6 +2216,7 @@ make + tests/testSymbolicFactor.run true false @@ -2227,6 +2224,7 @@ make + testSymbolicFactorGraph.run true false @@ -2242,6 +2240,7 @@ make + tests/testBayesTree true false @@ -3385,6 +3384,7 @@ make + testGraph.run true false @@ -3392,6 +3392,7 @@ make + testJunctionTree.run true false @@ -3399,6 +3400,7 @@ make + testSymbolicBayesNetB.run true false From c5394da29ecdeb24c61e55e286a9cdcf90883046 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 25 Feb 2015 19:29:12 +0100 Subject: [PATCH 040/173] Better print of isotropic --- gtsam/linear/NoiseModel.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 6ab26474a..f9a9ca804 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include #include @@ -486,7 +487,7 @@ Isotropic::shared_ptr Isotropic::Variance(size_t dim, double variance, bool smar /* ************************************************************************* */ void Isotropic::print(const string& name) const { - cout << name << "isotropic sigma " << " " << sigma_ << endl; + cout << boost::format("isotropic dim=%1% sigma=%2%") % dim() % sigma_ << endl; } /* ************************************************************************* */ From 850470ef06f3a17071e8d9f5d085f7204c514dc0 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 25 Feb 2015 19:30:17 +0100 Subject: [PATCH 041/173] rename of computeJacobians overloads to better reflect functionality --- gtsam/slam/JacobianFactorSVD.h | 11 ++- gtsam/slam/SmartFactorBase.h | 88 ++++++++++--------- gtsam/slam/SmartProjectionFactor.h | 65 ++++++-------- .../tests/testSmartProjectionCameraFactor.cpp | 8 +- .../tests/testSmartProjectionPoseFactor.cpp | 41 +++++---- .../slam/SmartStereoProjectionFactor.h | 45 +++------- 6 files changed, 121 insertions(+), 137 deletions(-) diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index 255c799a6..e5e39d1a1 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -9,7 +9,7 @@ namespace gtsam { /** - * JacobianFactor for Schur complement that uses Q noise model + * JacobianFactor for Schur complement */ template class JacobianFactorSVD: public RegularJacobianFactor { @@ -38,7 +38,14 @@ public: JacobianFactor::fillTerms(QF, zeroVector, model); } - /// Constructor + /** + * @brief Constructor + * Takes the CameraSet derivatives (as ZDim*D blocks of block-diagonal F) + * and a reduced point derivative, Enull + * and creates a reduced-rank Jacobian factor on the CameraSet + * + * @Fblocks: + */ JacobianFactorSVD(const std::vector& Fblocks, const Matrix& Enull, const Vector& b, // const SharedDiagonal& model = SharedDiagonal()) : diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 3d29b34e8..d33b5957f 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -81,6 +81,7 @@ protected: boost::optional body_P_sensor_; // check that noise model is isotropic and the same + // TODO, this is hacky, we should just do this via constructor, not add void maybeSetNoiseModel(const SharedNoiseModel& sharedNoiseModel) { if (!sharedNoiseModel) return; @@ -213,6 +214,36 @@ public: && body_P_sensor_->equals(*e->body_P_sensor_))); } + /// Compute reprojection errors + Vector reprojectionError(const Cameras& cameras, const Point3& point) const { + return cameras.reprojectionError(point, measured_); + } + + /** + * Compute reprojection errors and derivatives + * TODO: the treatment of body_P_sensor_ is weird: the transformation + * is applied in the caller, but the derivatives are computed here. + */ + Vector reprojectionError(const Cameras& cameras, const Point3& point, + typename Cameras::FBlocks& F, Matrix& E) const { + + Vector b = cameras.reprojectionError(point, measured_, F, E); + + // Apply sensor chain rule if needed TODO: no simpler way ?? + if (body_P_sensor_) { + size_t m = keys_.size(); + for (size_t i = 0; i < m; i++) { + const Pose3& pose_i = cameras[i].pose(); + Pose3 w_Pose_body = pose_i.compose(body_P_sensor_->inverse()); + Matrix66 J; + Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); + F[i].leftCols(6) *= J; + } + } + + return b; + } + /// Calculate vector of re-projection errors, noise model applied Vector whitenedErrors(const Cameras& cameras, const Point3& point) const { Vector b = cameras.reprojectionError(point, measured_); @@ -251,36 +282,6 @@ public: return 0.5 * b.dot(b); } - /// Compute reprojection errors - Vector reprojectionError(const Cameras& cameras, const Point3& point) const { - return cameras.reprojectionError(point, measured_); - } - - /** - * Compute reprojection errors and derivatives - * TODO: the treatment of body_P_sensor_ is weird: the transformation - * is applied in the caller, but the derivatives are computed here. - */ - Vector reprojectionError(const Cameras& cameras, const Point3& point, - typename Cameras::FBlocks& F, Matrix& E) const { - - Vector b = cameras.reprojectionError(point, measured_, F, E); - - // Apply sensor chain rule if needed TODO: no simpler way ?? - if (body_P_sensor_) { - size_t m = keys_.size(); - for (size_t i = 0; i < m; i++) { - const Pose3& pose_i = cameras[i].pose(); - Pose3 w_Pose_body = pose_i.compose(body_P_sensor_->inverse()); - Matrix66 J; - Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); - F[i].leftCols(6) *= J; - } - } - - return b; - } - /// Computes Point Covariance P from E static Matrix3 PointCov(Matrix& E) { return (E.transpose() * E).inverse(); @@ -371,7 +372,6 @@ public: Eigen::JacobiSVD svd(E, Eigen::ComputeFullU); Vector s = svd.singularValues(); size_t m = this->keys_.size(); - // Enull = zeros(ZDim * m, ZDim * m - 3); Enull = svd.matrixU().block(0, 3, ZDim * m, ZDim * m - 3); // last ZDim*m-3 columns return f; @@ -661,7 +661,7 @@ public: Matrix E; Vector b; computeJacobians(F, E, b, cameras, point); - noiseModel_->WhitenSystem(E,b); + noiseModel_->WhitenSystem(E, b); Matrix3 P = PointCov(E, lambda, diagonalDamping); // TODO make WhitenInPlace work with any dense matrix type BOOST_FOREACH(KeyMatrix2D& Fblock,F) @@ -675,13 +675,15 @@ public: boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - std::vector Fblocks; + std::vector F; Matrix E; Vector b; - computeJacobians(Fblocks, E, b, cameras, point); + computeJacobians(F, E, b, cameras, point); + const size_t M = b.size(); + std::cout << M << std::endl; Matrix3 P = PointCov(E, lambda, diagonalDamping); - return boost::make_shared > // - (Fblocks, E, P, b, noiseModel_); + SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); + return boost::make_shared >(F, E, P, b, n); } /** @@ -690,13 +692,15 @@ public: */ boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0) const { - size_t numKeys = this->keys_.size(); - std::vector Fblocks; + size_t m = this->keys_.size(); + std::vector F; Vector b; - Matrix Enull(ZDim * numKeys, ZDim * numKeys - 3); - computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - return boost::make_shared > // - (Fblocks, Enull, b, noiseModel_); + const size_t M = ZDim * m; + Matrix E0(M, M - 3); + computeJacobiansSVD(F, E0, b, cameras, point); + std::cout << M << std::endl; + SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); + return boost::make_shared >(F, E0, b, n); } private: diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 2f4da3ce6..d932a1672 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -368,7 +368,12 @@ public: // ================================================================== Matrix F, E; Vector b; - double f = computeJacobians(F, E, b, cameras); + double f; + { + std::vector Fblocks; + f = computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + Base::FillDiagonalF(Fblocks,F); // expensive ! + } // Schur complement trick // Frank says: should be possible to do this more efficiently? @@ -486,21 +491,12 @@ public: return nonDegenerate; } - /// Version that takes values, and creates the point - bool computeJacobians(std::vector& Fblocks, - Matrix& E, Vector& b, const Values& values) const { - Cameras cameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); - if (nonDegenerate) - computeJacobians(Fblocks, E, b, cameras); - return nonDegenerate; - } - /// Compute F, E only (called below in both vanilla and SVD versions) /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate - double computeJacobians(std::vector& Fblocks, - Matrix& E, Vector& b, const Cameras& cameras) const { + double computeJacobiansWithTriangulatedPoint( + std::vector& Fblocks, Matrix& E, Vector& b, + const Cameras& cameras) const { if (this->degenerate_) { std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl; @@ -515,9 +511,9 @@ public: } // TODO replace all this by Call to CameraSet - int numKeys = this->keys_.size(); - E = zeros(2 * numKeys, 2); - b = zero(2 * numKeys); + int m = this->keys_.size(); + E = zeros(2 * m, 2); + b = zero(2 * m); double f = 0; for (size_t i = 0; i < this->measured_.size(); i++) { if (i == 0) { // first pose @@ -541,35 +537,27 @@ public: } // end else } + /// Version that takes values, and creates the point + bool triangulateAndComputeJacobians(std::vector& Fblocks, + Matrix& E, Vector& b, const Values& values) const { + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); + if (nonDegenerate) + computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + return nonDegenerate; + } + /// takes values - bool computeJacobiansSVD(std::vector& Fblocks, - Matrix& Enull, Vector& b, const Values& values) const { + bool triangulateAndComputeJacobiansSVD( + std::vector& Fblocks, Matrix& Enull, + Vector& b, const Values& values) const { typename Base::Cameras cameras; double good = computeCamerasAndTriangulate(values, cameras); if (good) - computeJacobiansSVD(Fblocks, Enull, b, cameras); + Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_); return true; } - /// SVD version - double computeJacobiansSVD(std::vector& Fblocks, - Matrix& Enull, Vector& b, const Cameras& cameras) const { - return Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_); - } - - /// Returns Matrix, TODO: maybe should not exist -> not sparse ! - // TODO should there be a lambda? - double computeJacobiansSVD(Matrix& F, Matrix& Enull, Vector& b, - const Cameras& cameras) const { - return Base::computeJacobiansSVD(F, Enull, b, cameras, point_); - } - - /// Returns Matrix, TODO: maybe should not exist -> not sparse ! - double computeJacobians(Matrix& F, Matrix& E, Vector& b, - const Cameras& cameras) const { - return Base::computeJacobians(F, E, b, cameras, point_); - } - /// Calculate vector of re-projection errors, before applying noise model Vector reprojectionErrorAfterTriangulation(const Values& values) const { Cameras cameras; @@ -652,6 +640,7 @@ public: inline bool isPointBehindCamera() const { return cheiralityException_; } + /** return cheirality verbosity */ inline bool verboseCheirality() const { return verboseCheirality_; diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index f82073e81..4ff53664d 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -754,17 +754,17 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { cameras.push_back(level_camera_right); factor1->error(values); // this is important to have a triangulation of the point - Point3 expectedPoint; + Point3 point; if (factor1->point()) - expectedPoint = *(factor1->point()); - factor1->computeJacobians(expectedF, expectedE, expectedb, cameras); + point = *(factor1->point()); + factor1->computeJacobians(expectedF, expectedE, expectedb, cameras, point); NonlinearFactorGraph generalGraph; SFMFactor sfm1(level_uv, unit2, c1, l1); SFMFactor sfm2(level_uv_right, unit2, c2, l1); generalGraph.push_back(sfm1); generalGraph.push_back(sfm2); - values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation + values.insert(l1, point); // note: we get rid of possible errors in the triangulation Matrix actualFullHessian = generalGraph.linearize(values)->hessian().first; Matrix actualVinv = (actualFullHessian.block(18, 18, 3, 3)).inverse(); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 41c0fac0a..78b8b5240 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -153,7 +153,7 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // Calculate using computeJacobians Vector b; vector Fblocks; - double actualError3 = factor.computeJacobians(Fblocks, E, b, cameras); + double actualError3 = factor.computeJacobians(Fblocks, E, b, cameras, *point); EXPECT(assert_equal(expectedE, E, 1e-7)); EXPECT_DOUBLES_EQUAL(expectedError, actualError3, 1e-8); } @@ -364,19 +364,19 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { // Calculate expected derivative for point (easiest to check) SmartFactor::Cameras cameras = smartFactor1->cameras(values); boost::function f = // - boost::bind(&SmartFactor::whitenedErrors, *smartFactor1, cameras, _1); + boost::bind(&SmartFactor::reprojectionError, *smartFactor1, cameras, _1); boost::optional point = smartFactor1->point(); CHECK(point); - // Note ! After refactor the noiseModel is only in the factors, not these matrices - Matrix expectedE = sigma * numericalDerivative11(f, *point); + // TODO, this is really a test of CameraSet + Matrix expectedE = numericalDerivative11(f, *point); // Calculate using computeEP Matrix actualE, PointCov; smartFactor1->computeEP(actualE, PointCov, values); EXPECT(assert_equal(expectedE, actualE, 1e-7)); - // Calculate using whitenedError + // Calculate using reprojectionError Matrix E; SmartFactor::Cameras::FBlocks F; Vector actualErrors = smartFactor1->reprojectionError(cameras, *point, F, E); @@ -472,7 +472,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { E(2, 2) = 10; E(3, 1) = 100; const vector > Fblocks = list_of > // - (make_pair(x1, 10 * F1))(make_pair(x2, 10 * F2)); + (make_pair(x1, F1))(make_pair(x2, F2)); Matrix3 P = (E.transpose() * E).inverse(); Vector4 b; b.setZero(); @@ -483,10 +483,11 @@ TEST( SmartProjectionPoseFactor, Factors ) { boost::shared_ptr > actual = smartFactor1->createRegularImplicitSchurFactor(cameras, 0.0); CHECK(actual); - CHECK(assert_equal(expected, *actual)); + EXPECT(assert_equal(expected, *actual)); // createJacobianQFactor - JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b); + SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); + JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b, n); boost::shared_ptr > actualQ = smartFactor1->createJacobianQFactor(cameras, 0.0); @@ -890,8 +891,10 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { using namespace vanillaPose; // Two slightly different cameras - Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose2 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); @@ -970,8 +973,10 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac views.push_back(x3); // Two different cameras - Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose2 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK2); Camera cam3(pose3, sharedK2); @@ -1050,8 +1055,10 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) views.push_back(x3); // Two different cameras - Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose2 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); @@ -1390,8 +1397,10 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { views.push_back(x3); // Two different cameras - Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose2 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedBundlerK); Camera cam3(pose3, sharedBundlerK); diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 337bf2f68..5c38ccca8 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -582,41 +582,16 @@ public: } // end else } -// /// Version that computes PointCov, with optional lambda parameter -// double computeJacobians(std::vector& Fblocks, -// Matrix& E, Matrix& PointCov, Vector& b, const Cameras& cameras, -// const double lambda = 0.0) const { -// -// double f = computeJacobians(Fblocks, E, b, cameras); -// -// // Point covariance inv(E'*E) -// PointCov.noalias() = (E.transpose() * E + lambda * eye(E.cols())).inverse(); -// -// return f; -// } -// -// /// takes values -// bool computeJacobiansSVD(std::vector& Fblocks, -// Matrix& Enull, Vector& b, const Values& values) const { -// typename Base::Cameras cameras; -// double good = computeCamerasAndTriangulate(values, cameras); -// if (good) -// computeJacobiansSVD(Fblocks, Enull, b, cameras); -// return true; -// } -// -// /// SVD version -// double computeJacobiansSVD(std::vector& Fblocks, -// Matrix& Enull, Vector& b, const Cameras& cameras) const { -// return Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_); -// } -// -// /// Returns Matrix, TODO: maybe should not exist -> not sparse ! -// // TODO should there be a lambda? -// double computeJacobiansSVD(Matrix& F, Matrix& Enull, Vector& b, -// const Cameras& cameras) const { -// return Base::computeJacobiansSVD(F, Enull, b, cameras, point_); -// } + /// takes values + bool triangulateAndComputeJacobiansSVD( + std::vector& Fblocks, Matrix& Enull, + Vector& b, const Values& values) const { + typename Base::Cameras cameras; + double good = computeCamerasAndTriangulate(values, cameras); + if (good) + return Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_); + return true; + } /// Returns Matrix, TODO: maybe should not exist -> not sparse ! double computeJacobians(Matrix& F, Matrix& E, Vector& b, From fd71974ff3250b12913ef805b4f0c8c4ac48f152 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 25 Feb 2015 20:52:16 +0100 Subject: [PATCH 042/173] Got mostly rid of computeEP: just a call to cameras.project2 --- gtsam/slam/SmartFactorBase.h | 22 ++++++----------- gtsam/slam/SmartProjectionFactor.h | 9 ++++--- .../tests/testSmartProjectionPoseFactor.cpp | 24 ++++++++++--------- .../slam/SmartStereoProjectionFactor.h | 14 +++++------ 4 files changed, 32 insertions(+), 37 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index d33b5957f..a5d2cfabe 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -306,13 +306,6 @@ public: return (EtE).inverse(); } - /// Assumes non-degenerate ! - void computeEP(Matrix& E, Matrix& P, const Cameras& cameras, - const Point3& point) const { - cameras.reprojectionError(point, measured_, boost::none, E); - P = PointCov(E); - } - /** * Compute F, E, and b (called below in both vanilla and SVD versions), where * F is a vector of derivatives wrpt the cameras, and E the stacked derivatives @@ -394,8 +387,7 @@ public: const Cameras& cameras, const Point3& point, const double lambda = 0.0, bool diagonalDamping = false) const { - int numKeys = this->keys_.size(); - + int m = this->keys_.size(); std::vector Fblocks; Matrix E; Vector b; @@ -405,8 +397,8 @@ public: //#define HESSIAN_BLOCKS // slower, as internally the Hessian factor will transform the blocks into SymmetricBlockMatrix #ifdef HESSIAN_BLOCKS // Create structures for Hessian Factors - std::vector < Matrix > Gs(numKeys * (numKeys + 1) / 2); - std::vector < Vector > gs(numKeys); + std::vector < Matrix > Gs(m * (m + 1) / 2); + std::vector < Vector > gs(m); sparseSchurComplement(Fblocks, E, P, b, Gs, gs); // schurComplement(Fblocks, E, P, b, Gs, gs); @@ -416,15 +408,15 @@ public: return boost::make_shared < RegularHessianFactor > (this->keys_, Gs, gs, f); #else // we create directly a SymmetricBlockMatrix - size_t n1 = Dim * numKeys + 1; - std::vector dims(numKeys + 1); // this also includes the b term + size_t n1 = Dim * m + 1; + std::vector dims(m + 1); // this also includes the b term std::fill(dims.begin(), dims.end() - 1, Dim); dims.back() = 1; SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(n1, n1)); // for 10 cameras, size should be (10*Dim+1 x 10*Dim+1) sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... - augmentedHessian(numKeys, numKeys)(0, 0) = f; - return boost::make_shared >(this->keys_, + augmentedHessian(m, m)(0, 0) = f; + return boost::make_shared >(keys_, augmentedHessian); #endif } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index d932a1672..b4fad72fb 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -482,12 +482,15 @@ public: return true; } - /// Takes values - bool computeEP(Matrix& E, Matrix& P, const Values& values) const { + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Values& values) const { Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - Base::computeEP(E, P, cameras, point_); + cameras.project2(point_, boost::none, E); return nonDegenerate; } diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 78b8b5240..caa0e5162 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -131,18 +131,20 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // Calculate expected derivative for point (easiest to check) boost::function f = // boost::bind(&SmartFactor::whitenedErrors, factor, cameras, _1); + + // Calculate using computeEP + Matrix actualE; + factor.triangulateAndComputeE(actualE, values); + + // get point boost::optional point = factor.point(); CHECK(point); - // Note ! After refactor the noiseModel is only in the factors, not these matrices + // calculate numerical derivative with triangulated point Matrix expectedE = sigma * numericalDerivative11(f, *point); - - // Calculate using computeEP - Matrix actualE, PointCov; - factor.computeEP(actualE, PointCov, values); EXPECT(assert_equal(expectedE, actualE, 1e-7)); - // Calculate using reprojectionError, note not yet divided by sigma ! + // Calculate using reprojectionError SmartFactor::Cameras::FBlocks F; Matrix E; Vector actualErrors = factor.reprojectionError(cameras, *point, F, E); @@ -361,6 +363,10 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { // Check derivatives + // Calculate E and P using computeEP, triangulates + Matrix actualE; + smartFactor1->triangulateAndComputeE(actualE, values); + // Calculate expected derivative for point (easiest to check) SmartFactor::Cameras cameras = smartFactor1->cameras(values); boost::function f = // @@ -370,10 +376,6 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { // TODO, this is really a test of CameraSet Matrix expectedE = numericalDerivative11(f, *point); - - // Calculate using computeEP - Matrix actualE, PointCov; - smartFactor1->computeEP(actualE, PointCov, values); EXPECT(assert_equal(expectedE, actualE, 1e-7)); // Calculate using reprojectionError @@ -383,7 +385,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { EXPECT(assert_equal(expectedE, E, 1e-7)); // Success ! The derivatives of reprojectionError now agree with f ! - EXPECT(assert_equal(f(*point) * sigma, actualErrors, 1e-7)); + EXPECT(assert_equal(f(*point), actualErrors, 1e-7)); } /* *************************************************************************/ diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 5c38ccca8..551ad078c 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -513,17 +513,15 @@ public: return true; } - /// Assumes non-degenerate ! - void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras) const { - Base::computeEP(E, PointCov, cameras, point_); - } - - /// Takes values - bool computeEP(Matrix& E, Matrix& PointCov, const Values& values) const { + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Values& values) const { Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - computeEP(E, PointCov, cameras); + cameras.project2(point_, boost::none, E); return nonDegenerate; } From 0bf95ae7f63e1bf26845a843bb0d59c0df917513 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 11:44:51 +0100 Subject: [PATCH 043/173] Removed obsolete code, including slow Schur-complement versions --- gtsam/slam/SmartFactorBase.h | 133 +----------------- .../tests/testSmartProjectionCameraFactor.cpp | 5 +- .../slam/SmartStereoProjectionFactor.h | 10 +- 3 files changed, 12 insertions(+), 136 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a5d2cfabe..10de39049 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -342,18 +342,6 @@ public: F.block(This::ZDim * i, Dim * i) = Fblocks.at(i).second; } - /** - * Compute F, E, and b, where F and E are the stacked derivatives - * with respect to the point. The value of cameras/point are passed as parameters. - */ - double computeJacobians(Matrix& F, Matrix& E, Vector& b, - const Cameras& cameras, const Point3& point) const { - std::vector Fblocks; - double f = computeJacobians(Fblocks, E, b, cameras, point); - FillDiagonalF(Fblocks, F); - return f; - } - /// SVD version double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, Vector& b, const Cameras& cameras, const Point3& point) const { @@ -370,16 +358,6 @@ public: return f; } - /// Matrix version of SVD - // TODO, there should not be a Matrix version, really - double computeJacobiansSVD(Matrix& F, Matrix& Enull, Vector& b, - const Cameras& cameras, const Point3& point) const { - std::vector Fblocks; - double f = computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - FillDiagonalF(Fblocks, F); - return f; - } - /** * Linearize returns a Hessianfactor that is an approximation of error(p) */ @@ -394,69 +372,19 @@ public: double f = computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); -//#define HESSIAN_BLOCKS // slower, as internally the Hessian factor will transform the blocks into SymmetricBlockMatrix -#ifdef HESSIAN_BLOCKS - // Create structures for Hessian Factors - std::vector < Matrix > Gs(m * (m + 1) / 2); - std::vector < Vector > gs(m); - - sparseSchurComplement(Fblocks, E, P, b, Gs, gs); - // schurComplement(Fblocks, E, P, b, Gs, gs); - - //std::vector < Matrix > Gs2(Gs.begin(), Gs.end()); - //std::vector < Vector > gs2(gs.begin(), gs.end()); - - return boost::make_shared < RegularHessianFactor > (this->keys_, Gs, gs, f); -#else // we create directly a SymmetricBlockMatrix - size_t n1 = Dim * m + 1; + // we create directly a SymmetricBlockMatrix + size_t M1 = Dim * m + 1; std::vector dims(m + 1); // this also includes the b term std::fill(dims.begin(), dims.end() - 1, Dim); dims.back() = 1; - SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(n1, n1)); // for 10 cameras, size should be (10*Dim+1 x 10*Dim+1) - sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... + // build augmented hessian + SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); + sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); augmentedHessian(m, m)(0, 0) = f; + return boost::make_shared >(keys_, augmentedHessian); -#endif - } - - /** - * Do Schur complement, given Jacobian as F,E,P. - * Slow version - works on full matrices - */ - void schurComplement(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b, - /*output ->*/std::vector& Gs, std::vector& gs) const { - // Schur complement trick - // Gs = F' * F - F' * E * inv(E'*E) * E' * F - // gs = F' * (b - E * inv(E'*E) * E' * b) - // This version uses full matrices - - int numKeys = this->keys_.size(); - - /// Compute Full F ???? - Matrix F; - FillDiagonalF(Fblocks, F); - - Matrix H(Dim * numKeys, Dim * numKeys); - Vector gs_vector; - - H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); - - // Populate Gs and gs - int GsCount2 = 0; - for (DenseIndex i1 = 0; i1 < numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * Dim; - gs.at(i1) = gs_vector.segment(i1D); - for (DenseIndex i2 = 0; i2 < numKeys; i2++) { - if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * Dim); - GsCount2++; - } - } - } } /** @@ -500,55 +428,6 @@ public: } // end of for over cameras } - /** - * Do Schur complement, given Jacobian as F,E,P, return Gs/gs - * Fast version - works on with sparsity - */ - void sparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - /*output ->*/std::vector& Gs, std::vector& gs) const { - // Schur complement trick - // Gs = F' * F - F' * E * P * E' * F - // gs = F' * (b - E * P * E' * b) - - // a single point is observed in numKeys cameras - size_t numKeys = this->keys_.size(); - - int GsIndex = 0; - // Blockwise Schur complement - for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera - // GsIndex points to the upper triangular blocks - // 0 1 2 3 4 - // X 5 6 7 8 - // X X 9 10 11 - // X X X 12 13 - // X X X X 14 - const Matrix2D& Fi1 = Fblocks.at(i1).second; - - const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; - - { // for i1 = i2 - // Dim = (Dx2) * (2) - gs.at(i1) = Fi1.transpose() * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - Gs.at(GsIndex) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1); - GsIndex++; - } - // upper triangular part of the hessian - for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera - const Matrix2D& Fi2 = Fblocks.at(i2).second; - - // (DxD) = (Dx2) * ( (2x2) * (2xD) ) - Gs.at(GsIndex) = -Fi1.transpose() - * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); - GsIndex++; - } - } // end of for over cameras - } - /** * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 4ff53664d..a106bf382 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -746,7 +746,7 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); factor1->add(level_uv, c1, unit2); factor1->add(level_uv_right, c2, unit2); - Matrix expectedF, expectedE; + Matrix expectedE; Vector expectedb; CameraSet cameras; @@ -757,7 +757,8 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { Point3 point; if (factor1->point()) point = *(factor1->point()); - factor1->computeJacobians(expectedF, expectedE, expectedb, cameras, point); + vector Fblocks; + factor1->computeJacobians(Fblocks, expectedE, expectedb, cameras, point); NonlinearFactorGraph generalGraph; SFMFactor sfm1(level_uv, unit2, c1, l1); diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 551ad078c..1cb026040 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -406,9 +406,11 @@ public: } // ================================================================== + std::vector Fblocks; Matrix F, E; Vector b; - double f = computeJacobians(F, E, b, cameras); + double f = computeJacobians(Fblocks, E, b, cameras); + Base::FillDiagonalF(Fblocks,F); // expensive !!! // Schur complement trick // Frank says: should be possible to do this more efficiently? @@ -591,12 +593,6 @@ public: return true; } - /// Returns Matrix, TODO: maybe should not exist -> not sparse ! - double computeJacobians(Matrix& F, Matrix& E, Vector& b, - const Cameras& cameras) const { - return Base::computeJacobians(F, E, b, cameras, point_); - } - /// Calculate vector of re-projection errors, before applying noise model Vector reprojectionErrorAfterTriangulation(const Values& values) const { Cameras cameras; From a132d959f5c8af1172b9d7edc4303dbed2166108 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 12:06:43 +0100 Subject: [PATCH 044/173] RADICAL: Got rid of sensor_pose. In the new PinholePose philosophy, this is entirely the responsibility of the CAMERA. Just like PinholePose, we can have a camera class that has a shared extra transform: it is part of the calibration. PinholePose itself is not able to do this, as the calibration is assumed 2D only, but it's easy to create a class and have the correct derivatives in place. --- gtsam/slam/SmartFactorBase.h | 42 +---- gtsam/slam/SmartProjectionCameraFactor.h | 10 +- gtsam/slam/SmartProjectionFactor.h | 27 ++-- gtsam/slam/SmartProjectionPoseFactor.h | 16 +- .../tests/testSmartProjectionCameraFactor.cpp | 13 -- .../tests/testSmartProjectionPoseFactor.cpp | 150 ++---------------- .../slam/SmartStereoProjectionFactor.h | 15 +- .../slam/SmartStereoProjectionPoseFactor.h | 11 +- .../testSmartStereoProjectionPoseFactor.cpp | 35 ++-- 9 files changed, 68 insertions(+), 251 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 10de39049..56c214264 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -76,10 +76,6 @@ protected: typedef Eigen::Matrix VectorD; typedef Eigen::Matrix Matrix2; - /// An optional sensor pose, in the body frame (one for all cameras) - /// This seems to make sense for a CameraTrack, not for a CameraSet - boost::optional body_P_sensor_; - // check that noise model is isotropic and the same // TODO, this is hacky, we should just do this via constructor, not add void maybeSetNoiseModel(const SharedNoiseModel& sharedNoiseModel) { @@ -107,17 +103,10 @@ public: /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; + /// We use the new CameraSte data structure to refer to a set of cameras typedef CameraSet Cameras; - /** - * Constructor - * @param body_P_sensor is the transform from sensor to body frame (default identity) - */ - SmartFactorBase(boost::optional body_P_sensor = boost::none) : - body_P_sensor_(body_P_sensor) { - } - - /** Virtual destructor */ + /// Virtual destructor, subclasses from NonlinearFactor virtual ~SmartFactorBase() { } @@ -193,8 +182,6 @@ public: std::cout << "measurement, p = " << measured_[k] << "\t"; noiseModel_->print("noise model = "); } - if (this->body_P_sensor_) - this->body_P_sensor_->print(" sensor pose in body frame: "); Base::print("", keyFormatter); } @@ -208,10 +195,7 @@ public: areMeasurementsEqual = false; break; } - return e && Base::equals(p, tol) && areMeasurementsEqual - && ((!body_P_sensor_ && !e->body_P_sensor_) - || (body_P_sensor_ && e->body_P_sensor_ - && body_P_sensor_->equals(*e->body_P_sensor_))); + return e && Base::equals(p, tol) && areMeasurementsEqual; } /// Compute reprojection errors @@ -221,27 +205,10 @@ public: /** * Compute reprojection errors and derivatives - * TODO: the treatment of body_P_sensor_ is weird: the transformation - * is applied in the caller, but the derivatives are computed here. */ Vector reprojectionError(const Cameras& cameras, const Point3& point, typename Cameras::FBlocks& F, Matrix& E) const { - - Vector b = cameras.reprojectionError(point, measured_, F, E); - - // Apply sensor chain rule if needed TODO: no simpler way ?? - if (body_P_sensor_) { - size_t m = keys_.size(); - for (size_t i = 0; i < m; i++) { - const Pose3& pose_i = cameras[i].pose(); - Pose3 w_Pose_body = pose_i.compose(body_P_sensor_->inverse()); - Matrix66 J; - Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); - F[i].leftCols(6) *= J; - } - } - - return b; + return cameras.reprojectionError(point, measured_, F, E); } /// Calculate vector of re-projection errors, noise model applied @@ -582,7 +549,6 @@ private: void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); - ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } }; // end class SmartFactorBase diff --git a/gtsam/slam/SmartProjectionCameraFactor.h b/gtsam/slam/SmartProjectionCameraFactor.h index 8381c847e..7ca8a4e1d 100644 --- a/gtsam/slam/SmartProjectionCameraFactor.h +++ b/gtsam/slam/SmartProjectionCameraFactor.h @@ -56,17 +56,15 @@ public: * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations * @param isImplicit if set to true linearize the factor to an implicit Schur factor - * @param body_P_sensor is the transform from body to sensor frame (default identity) */ SmartProjectionCameraFactor(const double rankTol = 1, const double linThreshold = -1, const bool manageDegeneracy = false, - const bool enableEPI = false, const bool isImplicit = false, - boost::optional body_P_sensor = boost::none) : - Base(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor), isImplicit_( + const bool enableEPI = false, const bool isImplicit = false) : + Base(rankTol, linThreshold, manageDegeneracy, enableEPI), isImplicit_( isImplicit) { if (linThreshold != -1) { - std::cout << "SmartProjectionCameraFactor: linThreshold " - << linThreshold << std::endl; + std::cout << "SmartProjectionCameraFactor: linThreshold " << linThreshold + << std::endl; } } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index b4fad72fb..f99ce7085 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -116,16 +116,14 @@ public: * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from sensor to body frame (default identity) */ SmartProjectionFactor(const double rankTol, const double linThreshold, const bool manageDegeneracy, const bool enableEPI, - boost::optional body_P_sensor = boost::none, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1, SmartFactorStatePtr state = SmartFactorStatePtr(new SmartProjectionFactorState())) : - Base(body_P_sensor), rankTolerance_(rankTol), retriangulationThreshold_( - 1e-5), manageDegeneracy_(manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( + rankTolerance_(rankTol), retriangulationThreshold_(1e-5), manageDegeneracy_( + manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( false), verboseCheirality_(false), state_(state), landmarkDistanceThreshold_( landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( @@ -336,8 +334,8 @@ public: m = zeros(Base::Dim, Base::Dim); BOOST_FOREACH(Vector& v, gs) v = zero(Base::Dim); - return boost::make_shared >(this->keys_, Gs, gs, - 0.0); + return boost::make_shared >(this->keys_, + Gs, gs, 0.0); } // instead, if we want to manage the exception.. @@ -372,7 +370,7 @@ public: { std::vector Fblocks; f = computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); - Base::FillDiagonalF(Fblocks,F); // expensive ! + Base::FillDiagonalF(Fblocks, F); // expensive ! } // Schur complement trick @@ -390,7 +388,8 @@ public: // Note the minus sign above! g has negative b. // Informal reasoning: when we write the error as 0.5*|Ax-b|^2 // the derivative is A'*(Ax-b), and at x=0, this becomes -A'*b - gs_vector.noalias() = - F.transpose() * (b - (E * (P * (E.transpose() * b)))); + gs_vector.noalias() = -F.transpose() + * (b - (E * (P * (E.transpose() * b)))); // Populate Gs and gs int GsCount2 = 0; @@ -410,7 +409,8 @@ public: this->state_->gs = gs; this->state_->f = f; } - return boost::make_shared >(this->keys_, Gs, gs, f); + return boost::make_shared >(this->keys_, Gs, + gs, f); } // create factor @@ -541,8 +541,9 @@ public: } /// Version that takes values, and creates the point - bool triangulateAndComputeJacobians(std::vector& Fblocks, - Matrix& E, Vector& b, const Values& values) const { + bool triangulateAndComputeJacobians( + std::vector& Fblocks, Matrix& E, Vector& b, + const Values& values) const { Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) @@ -566,7 +567,7 @@ public: Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return Base::reprojectionError(cameras, point_); + return Base::reprojectionError(cameras, point_); else return zero(cameras.size() * 2); } @@ -613,7 +614,7 @@ public: // 3D parameterization of point at infinity const Point2& zi = this->measured_.at(0); this->point_ = cameras.front().backprojectPointAtInfinity(zi); - return Base::totalReprojectionErrorAtInfinity(cameras,this->point_); + return Base::totalReprojectionErrorAtInfinity(cameras, this->point_); } else { // Just use version in base class return Base::totalReprojectionError(cameras, point_); diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 5cfd74913..2ee807d9d 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -64,15 +64,16 @@ public: * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from sensor to body frame (default identity) */ SmartProjectionPoseFactor(const double rankTol = 1, const double linThreshold = -1, const bool manageDegeneracy = false, - const bool enableEPI = false, boost::optional body_P_sensor = boost::none, - LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, + const bool enableEPI = false, LinearizationMode linearizeTo = HESSIAN, + double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : - Base(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_(linearizeTo) {} + Base(rankTol, linThreshold, manageDegeneracy, enableEPI, + landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_( + linearizeTo) { + } /** Virtual destructor */ virtual ~SmartProjectionPoseFactor() {} @@ -150,12 +151,9 @@ public: */ typename Base::Cameras cameras(const Values& values) const { typename Base::Cameras cameras; - size_t i=0; + size_t i = 0; BOOST_FOREACH(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, sharedKs_[i++]); cameras.push_back(camera); } diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index a106bf382..ba7b7bf51 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -41,8 +41,6 @@ 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 Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), - Point3(0.25, -0.10, 1.0)); typedef SmartProjectionCameraFactor SmartFactor; typedef SmartProjectionCameraFactor SmartFactorBundler; @@ -100,17 +98,6 @@ TEST( SmartProjectionCameraFactor, Constructor4) { factor1.add(measurement1, x1, unit2); } -/* ************************************************************************* */ -TEST( SmartProjectionCameraFactor, ConstructorWithTransform) { - using namespace vanilla; - bool manageDegeneracy = true; - bool isImplicit = false; - bool enableEPI = false; - SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, isImplicit, - enableEPI, body_P_sensor1); - factor1.add(measurement1, x1, unit2); -} - /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Equals ) { using namespace vanilla; diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index caa0e5162..9345b5f45 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -50,9 +50,6 @@ static Symbol x2('X', 2); static Symbol x3('X', 3); 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 SmartProjectionPoseFactor SmartFactor; typedef SmartProjectionPoseFactor SmartFactorBundler; @@ -80,16 +77,6 @@ TEST( SmartProjectionPoseFactor, Constructor4) { factor1.add(measurement1, x1, model, sharedK); } -/* ************************************************************************* */ -TEST( SmartProjectionPoseFactor, ConstructorWithTransform) { - using namespace vanillaPose; - bool manageDegeneracy = true; - bool enableEPI = false; - SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, enableEPI, - body_P_sensor1); - factor1.add(measurement1, x1, model, sharedK); -} - /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Equals ) { using namespace vanillaPose; @@ -277,117 +264,6 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { tictoc_print_(); } -/* *************************************************************************/ -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), - Point3(1, 1, 1)); // Pose3(); // - - // These are the poses we want to estimate, from camera measurements - Pose3 bodyPose1 = level_pose.compose(sensor_to_body.inverse()); - Pose3 bodyPose2 = pose_right.compose(sensor_to_body.inverse()); - Pose3 bodyPose3 = pose_above.compose(sensor_to_body.inverse()); - - vector 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 - vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - - double rankTol = 1; - double linThreshold = -1; - bool manageDegeneracy = false; - bool enableEPI = false; - - SmartFactor::shared_ptr smartFactor1( - new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, - sensor_to_body)); - smartFactor1->add(measurements_cam1, views, model, sharedK); - - SmartFactor::shared_ptr smartFactor2( - new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, - sensor_to_body)); - smartFactor2->add(measurements_cam2, views, model, sharedK); - - SmartFactor::shared_ptr smartFactor3( - new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, - sensor_to_body)); - smartFactor3->add(measurements_cam3, views, model, sharedK); - - 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); - graph.push_back(PriorFactor(x1, bodyPose1, noisePrior)); - graph.push_back(PriorFactor(x2, bodyPose2, noisePrior)); - - // Check errors at ground truth poses - Values gtValues; - gtValues.insert(x1, bodyPose1); - gtValues.insert(x2, bodyPose2); - gtValues.insert(x3, bodyPose3); - 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), - 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 pose_above - values.insert(x3, bodyPose3 * noise_pose); - - LevenbergMarquardtParams params; - Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(bodyPose3, result.at(x3))); - - // Check derivatives - - // Calculate E and P using computeEP, triangulates - Matrix actualE; - smartFactor1->triangulateAndComputeE(actualE, values); - - // Calculate expected derivative for point (easiest to check) - SmartFactor::Cameras cameras = smartFactor1->cameras(values); - boost::function f = // - boost::bind(&SmartFactor::reprojectionError, *smartFactor1, cameras, _1); - boost::optional point = smartFactor1->point(); - CHECK(point); - - // TODO, this is really a test of CameraSet - Matrix expectedE = numericalDerivative11(f, *point); - EXPECT(assert_equal(expectedE, actualE, 1e-7)); - - // Calculate using reprojectionError - Matrix E; - SmartFactor::Cameras::FBlocks F; - Vector actualErrors = smartFactor1->reprojectionError(cameras, *point, F, E); - EXPECT(assert_equal(expectedE, E, 1e-7)); - - // Success ! The derivatives of reprojectionError now agree with f ! - EXPECT(assert_equal(f(*point), actualErrors, 1e-7)); -} - /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Factors ) { @@ -599,15 +475,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -654,17 +530,17 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor3->add(measurements_cam3, views, model, sharedK); @@ -720,22 +596,22 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model, sharedK); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model, sharedK); @@ -782,15 +658,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); + new SmartFactor(1, -1, false, false, JACOBIAN_Q)); smartFactor1->add(measurements_cam1, views, model, sharedK); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); + new SmartFactor(1, -1, false, false, JACOBIAN_Q)); smartFactor2->add(measurements_cam2, views, model, sharedK); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); + new SmartFactor(1, -1, false, false, JACOBIAN_Q)); smartFactor3->add(measurements_cam3, views, model, sharedK); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 1cb026040..68b396cd6 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -130,16 +130,15 @@ public: */ SmartStereoProjectionFactor(const double rankTol, const double linThreshold, const bool manageDegeneracy, const bool enableEPI, - boost::optional body_P_sensor = boost::none, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1, - SmartFactorStatePtr state = SmartFactorStatePtr(new SmartStereoProjectionFactorState())) : - Base(body_P_sensor), rankTolerance_(rankTol), retriangulationThreshold_( - 1e-5), manageDegeneracy_(manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( + double dynamicOutlierRejectionThreshold = -1, SmartFactorStatePtr state = + SmartFactorStatePtr(new SmartStereoProjectionFactorState())) : + rankTolerance_(rankTol), retriangulationThreshold_(1e-5), manageDegeneracy_( + manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( - false), verboseCheirality_(false), state_(state), - landmarkDistanceThreshold_(landmarkDistanceThreshold), - dynamicOutlierRejectionThreshold_(dynamicOutlierRejectionThreshold) { + false), verboseCheirality_(false), state_(state), landmarkDistanceThreshold_( + landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( + dynamicOutlierRejectionThreshold) { } /** Virtual destructor */ diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 3e0c6476f..2f4677835 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -65,15 +65,16 @@ public: * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from body to sensor frame (default identity) */ SmartStereoProjectionPoseFactor(const double rankTol = 1, const double linThreshold = -1, const bool manageDegeneracy = false, - const bool enableEPI = false, boost::optional body_P_sensor = boost::none, - LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, + const bool enableEPI = false, LinearizationMode linearizeTo = HESSIAN, + double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : - Base(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_(linearizeTo) {} + Base(rankTol, linThreshold, manageDegeneracy, enableEPI, + landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_( + linearizeTo) { + } /** Virtual destructor */ virtual ~SmartStereoProjectionPoseFactor() {} diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 4cc8e66ff..48dfa1ff0 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -106,15 +106,6 @@ TEST( SmartStereoProjectionPoseFactor, Constructor4) { factor1.add(measurement1, poseKey1, model, K); } -/* ************************************************************************* */ -TEST( SmartStereoProjectionPoseFactor, ConstructorWithTransform) { - bool manageDegeneracy = true; - bool enableEPI = false; - SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, enableEPI, - body_P_sensor1); - factor1.add(measurement1, poseKey1, model, K); -} - /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Equals ) { SmartFactor::shared_ptr factor1(new SmartFactor()); @@ -345,15 +336,15 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { cam2, cam3, landmark3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); smartFactor1->add(measurements_cam1, views, model, K); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); smartFactor2->add(measurements_cam2, views, model, K); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); smartFactor3->add(measurements_cam3, views, model, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -414,17 +405,17 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { cam2, cam3, landmark3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor1->add(measurements_cam1, views, model, K); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor2->add(measurements_cam2, views, model, K); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor3->add(measurements_cam3, views, model, K); @@ -493,22 +484,22 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + StereoPoint2(10, 10, 1); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model, K); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model, K); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model, K); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model, K); @@ -567,13 +558,13 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); // -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor1->add(measurements_cam1, views, model, K); // -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor2->add(measurements_cam2, views, model, K); // -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor3->add(measurements_cam3, views, model, K); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); From a375e7b5be1b43d254a7d295e413ef16f22aaa4d Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 13:55:16 +0100 Subject: [PATCH 045/173] RADICAL2: The SmartProjectionPoseFactor (soon to be renamed SmartPinholePoseFactor, if it survives at all) now no longer stores shared calibrations. Values expect to contain PinholePoses not Pose3s now. The current state of affairs was simply a bug: one pose could be optimized for several different calibrations. It relied on the user to make sure all measurements for a specific pose to optimize were all given the same shared calibration, which was then stored *millions of times* in the pose factors. Instead, there is now *one* shared calibration per PinholePose unknown. --- .cproject | 22 +- examples/SFMExample_SmartFactor.cpp | 15 +- examples/SFMExample_SmartFactorPCG.cpp | 15 +- gtsam/slam/SmartFactorBase.h | 20 +- gtsam/slam/SmartProjectionCameraFactor.h | 20 +- gtsam/slam/SmartProjectionFactor.h | 3 - gtsam/slam/SmartProjectionPoseFactor.h | 70 +---- .../tests/testSmartProjectionPoseFactor.cpp | 263 +++++++++--------- .../examples/SmartProjectionFactorExample.cpp | 30 +- .../slam/SmartStereoProjectionPoseFactor.h | 1 + 10 files changed, 195 insertions(+), 264 deletions(-) diff --git a/.cproject b/.cproject index 5d3733e28..e190d8f65 100644 --- a/.cproject +++ b/.cproject @@ -811,18 +811,10 @@ false true - + make - -j5 - SmartProjectionFactorExample_kitti_nonbatch.run - true - true - true - - - make - -j5 - SmartProjectionFactorExample_kitti.run + -j4 + SmartStereoProjectionFactorExample.run true true true @@ -835,6 +827,14 @@ true true + + make + -j4 + SmartProjectionFactorExample.run + true + true + true + make -j2 diff --git a/examples/SFMExample_SmartFactor.cpp b/examples/SFMExample_SmartFactor.cpp index fce046a59..cd6024e6c 100644 --- a/examples/SFMExample_SmartFactor.cpp +++ b/examples/SFMExample_SmartFactor.cpp @@ -34,6 +34,9 @@ using namespace gtsam; // Make the typename short so it looks much cleaner typedef SmartProjectionPoseFactor SmartFactor; +// create a typedef to the camera type +typedef PinholePose Camera; + /* ************************************************************************* */ int main(int argc, char* argv[]) { @@ -60,7 +63,7 @@ int main(int argc, char* argv[]) { for (size_t i = 0; i < poses.size(); ++i) { // generate the 2D measurement - SimpleCamera camera(poses[i], *K); + Camera camera(poses[i], K); Point2 measurement = camera.project(points[j]); // call add() function to add measurement into a single factor, here we need to add: @@ -68,7 +71,7 @@ int main(int argc, char* argv[]) { // 2. the corresponding camera's key // 3. camera noise model // 4. camera calibration - smartfactor->add(measurement, i, measurementNoise, K); + smartfactor->add(measurement, i, measurementNoise); } // insert the smart factor in the graph @@ -77,15 +80,15 @@ int main(int argc, char* argv[]) { // Add a prior on pose x0. This indirectly specifies where the origin is. // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw - noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas( + noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas( (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished()); - graph.push_back(PriorFactor(0, poses[0], poseNoise)); + graph.push_back(PriorFactor(0, Camera(poses[0],K), noise)); // Because the structure-from-motion problem has a scale ambiguity, the problem is // still under-constrained. Here we add a prior on the second pose x1, so this will // fix the scale by indicating the distance between x0 and x1. // Because these two are fixed, the rest of the poses will be also be fixed. - graph.push_back(PriorFactor(1, poses[1], poseNoise)); // add directly to graph + graph.push_back(PriorFactor(1, Camera(poses[1],K), noise)); // add directly to graph graph.print("Factor Graph:\n"); @@ -94,7 +97,7 @@ int main(int argc, char* argv[]) { Values initialEstimate; Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); for (size_t i = 0; i < poses.size(); ++i) - initialEstimate.insert(i, poses[i].compose(delta)); + initialEstimate.insert(i, Camera(poses[i].compose(delta), K)); initialEstimate.print("Initial Estimates:\n"); // Optimize the graph and print results diff --git a/examples/SFMExample_SmartFactorPCG.cpp b/examples/SFMExample_SmartFactorPCG.cpp index 49482292f..27ef7b9cc 100644 --- a/examples/SFMExample_SmartFactorPCG.cpp +++ b/examples/SFMExample_SmartFactorPCG.cpp @@ -30,6 +30,9 @@ using namespace gtsam; // Make the typename short so it looks much cleaner typedef SmartProjectionPoseFactor SmartFactor; +// create a typedef to the camera type +typedef PinholePose Camera; + /* ************************************************************************* */ int main(int argc, char* argv[]) { @@ -56,11 +59,11 @@ int main(int argc, char* argv[]) { for (size_t i = 0; i < poses.size(); ++i) { // generate the 2D measurement - SimpleCamera camera(poses[i], *K); + Camera camera(poses[i], K); Point2 measurement = camera.project(points[j]); // call add() function to add measurement into a single factor, here we need to add: - smartfactor->add(measurement, i, measurementNoise, K); + smartfactor->add(measurement, i, measurementNoise); } // insert the smart factor in the graph @@ -69,18 +72,18 @@ int main(int argc, char* argv[]) { // Add a prior on pose x0. This indirectly specifies where the origin is. // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw - noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas( + noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas( (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished()); - graph.push_back(PriorFactor(0, poses[0], poseNoise)); + graph.push_back(PriorFactor(0, Camera(poses[0],K), noise)); // Fix the scale ambiguity by adding a prior - graph.push_back(PriorFactor(1, poses[1], poseNoise)); + graph.push_back(PriorFactor(1, Camera(poses[0],K), noise)); // Create the initial estimate to the solution Values initialEstimate; Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); for (size_t i = 0; i < poses.size(); ++i) - initialEstimate.insert(i, poses[i].compose(delta)); + initialEstimate.insert(i, Camera(poses[i].compose(delta),K)); // We will use LM in the outer optimization loop, but by specifying "Iterative" below // We indicate that an iterative linear solver should be used. diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 56c214264..ba0d27530 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -116,21 +116,21 @@ public: * @param poseKey is the index corresponding to the camera observing the landmark * @param sharedNoiseModel is the measurement noise */ - void add(const Z& measured_i, const Key& poseKey_i, + void add(const Z& measured_i, const Key& cameraKey_i, const SharedNoiseModel& sharedNoiseModel) { this->measured_.push_back(measured_i); - this->keys_.push_back(poseKey_i); + this->keys_.push_back(cameraKey_i); maybeSetNoiseModel(sharedNoiseModel); } /** * Add a bunch of measurements, together with the camera keys and noises */ - void add(std::vector& measurements, std::vector& poseKeys, + void add(std::vector& measurements, std::vector& cameraKeys, std::vector& noises) { for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); - this->keys_.push_back(poseKeys.at(i)); + this->keys_.push_back(cameraKeys.at(i)); maybeSetNoiseModel(noises.at(i)); } } @@ -138,11 +138,11 @@ public: /** * Add a bunch of measurements and uses the same noise model for all of them */ - void add(std::vector& measurements, std::vector& poseKeys, + void add(std::vector& measurements, std::vector& cameraKeys, const SharedNoiseModel& noise) { for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); - this->keys_.push_back(poseKeys.at(i)); + this->keys_.push_back(cameraKeys.at(i)); maybeSetNoiseModel(noise); } } @@ -170,6 +170,14 @@ public: return measured_; } + /// Collect all cameras: important that in key order + Cameras cameras(const Values& values) const { + Cameras cameras; + BOOST_FOREACH(const Key& k, this->keys_) + cameras.push_back(values.at(k)); + return cameras; + } + /** * print * @param s optional string naming the factor diff --git a/gtsam/slam/SmartProjectionCameraFactor.h b/gtsam/slam/SmartProjectionCameraFactor.h index 7ca8a4e1d..f10681ab8 100644 --- a/gtsam/slam/SmartProjectionCameraFactor.h +++ b/gtsam/slam/SmartProjectionCameraFactor.h @@ -95,39 +95,31 @@ public: return Dim * this->keys_.size(); // 6 for the pose and 3 for the calibration } - /// Collect all cameras: important that in key order - Cameras cameras(const Values& values) const { - Cameras cameras; - BOOST_FOREACH(const Key& k, this->keys_) - cameras.push_back(values.at(k)); - return cameras; - } - /// linearize and adds damping on the points boost::shared_ptr linearizeDamped(const Values& values, const double lambda=0.0) const { if (!isImplicit_) - return Base::createHessianFactor(cameras(values), lambda); + return Base::createHessianFactor(Base::cameras(values), lambda); else - return Base::createRegularImplicitSchurFactor(cameras(values)); + return Base::createRegularImplicitSchurFactor(Base::cameras(values)); } /// linearize returns a Hessianfactor that is an approximation of error(p) virtual boost::shared_ptr > linearizeToHessian( const Values& values, double lambda=0.0) const { - return Base::createHessianFactor(cameras(values),lambda); + return Base::createHessianFactor(Base::cameras(values),lambda); } /// linearize returns a Hessianfactor that is an approximation of error(p) virtual boost::shared_ptr > linearizeToImplicit( const Values& values, double lambda=0.0) const { - return Base::createRegularImplicitSchurFactor(cameras(values),lambda); + return Base::createRegularImplicitSchurFactor(Base::cameras(values),lambda); } /// linearize returns a Jacobianfactor that is an approximation of error(p) virtual boost::shared_ptr > linearizeToJacobian( const Values& values, double lambda=0.0) const { - return Base::createJacobianQFactor(cameras(values),lambda); + return Base::createJacobianQFactor(Base::cameras(values),lambda); } /// linearize returns a Hessianfactor that is an approximation of error(p) @@ -148,7 +140,7 @@ public: /// Calculare total reprojection error virtual double error(const Values& values) const { if (this->active(values)) { - return Base::totalReprojectionError(cameras(values)); + return Base::totalReprojectionError(Base::cameras(values)); } else { // else of active flag return 0.0; } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index f99ce7085..5b061f612 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -621,9 +621,6 @@ public: } } - /// Cameras are computed in derived class - virtual Cameras cameras(const Values& values) const = 0; - /** return the landmark */ boost::optional point() const { return point_; diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 2ee807d9d..48fbd937f 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -78,51 +78,6 @@ public: /** Virtual destructor */ virtual ~SmartProjectionPoseFactor() {} - /** - * add a new measurement and pose key - * @param measured is the 2m dimensional location of the projection of a single landmark in the m view (the measurement) - * @param poseKey is key corresponding to the camera observing the same landmark - * @param noise_i is the measurement noise - * @param K_i is the (known) camera calibration - */ - void add(const Point2 measured_i, const Key poseKey_i, - const SharedNoiseModel noise_i, - const boost::shared_ptr K_i) { - Base::add(measured_i, poseKey_i, noise_i); - sharedKs_.push_back(K_i); - } - - /** - * Variant of the previous one in which we include a set of measurements - * @param measurements vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) - * @param poseKeys vector of keys corresponding to the camera observing the same landmark - * @param noises vector of measurement noises - * @param Ks vector of calibration objects - */ - void add(std::vector measurements, std::vector poseKeys, - std::vector noises, - std::vector > Ks) { - Base::add(measurements, poseKeys, noises); - for (size_t i = 0; i < measurements.size(); i++) { - sharedKs_.push_back(Ks.at(i)); - } - } - - /** - * Variant of the previous one in which we include a set of measurements with the same noise and calibration - * @param mmeasurements vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) - * @param poseKeys vector of keys corresponding to the camera observing the same landmark - * @param noise measurement noise (same for all measurements) - * @param K the (known) camera calibration (same for all measurements) - */ - void add(std::vector measurements, std::vector poseKeys, - const SharedNoiseModel noise, const boost::shared_ptr K) { - for (size_t i = 0; i < measurements.size(); i++) { - Base::add(measurements.at(i), poseKeys.at(i), noise); - sharedKs_.push_back(K); - } - } - /** * print * @param s optional string naming the factor @@ -143,23 +98,6 @@ public: return e && Base::equals(p, tol); } - /** - * Collect all cameras involved in this factor - * @param values Values structure which must contain camera poses corresponding - * to keys involved in this factor - * @return vector of Values - */ - typename Base::Cameras cameras(const Values& values) const { - typename Base::Cameras cameras; - size_t i = 0; - BOOST_FOREACH(const Key& k, this->keys_) { - Pose3 pose = values.at(k); - Camera camera(pose, sharedKs_[i++]); - cameras.push_back(camera); - } - return cameras; - } - /** * Linearize to Gaussian Factor * @param values Values structure which must contain camera poses for this factor @@ -170,13 +108,13 @@ public: // depending on flag set on construction we may linearize to different linear factors switch(linearizeTo_){ case JACOBIAN_SVD : - return this->createJacobianSVDFactor(cameras(values), 0.0); + return this->createJacobianSVDFactor(Base::cameras(values), 0.0); break; case JACOBIAN_Q : - return this->createJacobianQFactor(cameras(values), 0.0); + return this->createJacobianQFactor(Base::cameras(values), 0.0); break; default: - return this->createHessianFactor(cameras(values)); + return this->createHessianFactor(Base::cameras(values)); break; } } @@ -186,7 +124,7 @@ public: */ virtual double error(const Values& values) const { if (this->active(values)) { - return this->totalReprojectionError(cameras(values)); + return this->totalReprojectionError(Base::cameras(values)); } else { // else of active flag return 0.0; } diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 9345b5f45..b235d8e2b 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -19,8 +19,8 @@ */ #include "smartFactorScenarios.h" -#include #include +#include #include #include #include @@ -67,24 +67,24 @@ TEST( SmartProjectionPoseFactor, Constructor2) { TEST( SmartProjectionPoseFactor, Constructor3) { using namespace vanillaPose; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, x1, model, sharedK); + factor1->add(measurement1, x1, model); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { using namespace vanillaPose; SmartFactor factor1(rankTol, linThreshold); - factor1.add(measurement1, x1, model, sharedK); + factor1.add(measurement1, x1, model); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Equals ) { using namespace vanillaPose; SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, x1, model, sharedK); + factor1->add(measurement1, x1, model); SmartFactor::shared_ptr factor2(new SmartFactor()); - factor2->add(measurement1, x1, model, sharedK); + factor2->add(measurement1, x1, model); CHECK(assert_equal(*factor1, *factor2)); } @@ -100,12 +100,12 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { Point2 level_uv_right = level_camera_right.project(landmark1); SmartFactor factor; - factor.add(level_uv, x1, model, sharedK); - factor.add(level_uv_right, x2, model, sharedK); + factor.add(level_uv, x1, model); + factor.add(level_uv_right, x2, model); Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam1); + values.insert(x2, cam2); double actualError = factor.error(values); double expectedError = 0.0; @@ -159,14 +159,14 @@ TEST( SmartProjectionPoseFactor, noisy ) { Point2 level_uv_right = level_camera_right.project(landmark1); Values values; - values.insert(x1, level_pose); + values.insert(x1, cam2); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); - values.insert(x2, pose_right.compose(noise_pose)); + values.insert(x2, Camera(pose_right.compose(noise_pose), sharedK)); SmartFactor::shared_ptr factor(new SmartFactor()); - factor->add(level_uv, x1, model, sharedK); - factor->add(level_uv_right, x2, model, sharedK); + factor->add(level_uv, x1, model); + factor->add(level_uv_right, x2, model); double actualError1 = factor->error(values); @@ -179,18 +179,12 @@ TEST( SmartProjectionPoseFactor, noisy ) { noises.push_back(model); noises.push_back(model); - vector > Ks; ///< shared pointer to calibration object (one for each camera) - Ks.push_back(sharedK); - Ks.push_back(sharedK); - vector views; views.push_back(x1); views.push_back(x2); - factor2->add(measurements, views, noises, Ks); - + factor2->add(measurements, views, noises); double actualError2 = factor2->error(values); - DOUBLES_EQUAL(actualError1, actualError2, 1e-7); } @@ -212,13 +206,13 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { views.push_back(x3); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, sharedK2); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, sharedK2); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, sharedK2); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -226,17 +220,17 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam2); + values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose_above * noise_pose); + values.insert(x3, Camera(pose_above * noise_pose, sharedK2)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -288,7 +282,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { views.push_back(x2); SmartFactor::shared_ptr smartFactor1 = boost::make_shared(); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::Cameras cameras; cameras.push_back(cam1); @@ -408,13 +402,13 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, sharedK); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, sharedK); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -422,17 +416,17 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam2); + values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose_above * noise_pose); + values.insert(x3, Camera(pose_above * noise_pose, sharedK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -476,15 +470,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); - smartFactor2->add(measurements_cam2, views, model, sharedK); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); - smartFactor3->add(measurements_cam3, views, model, sharedK); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -492,16 +486,16 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); - values.insert(x3, pose_above * noise_pose); + values.insert(x1, cam2); + values.insert(x2, cam2); + values.insert(x3, Camera(pose_above * noise_pose, sharedK)); LevenbergMarquardtParams params; Values result; @@ -532,17 +526,17 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor2->add(measurements_cam2, views, model, sharedK); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor3->add(measurements_cam3, views, model, sharedK); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -550,16 +544,16 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); - values.insert(x3, pose_above * noise_pose); + values.insert(x1, cam2); + values.insert(x2, cam2); + values.insert(x3, Camera(pose_above * noise_pose, sharedK)); // All factors are disabled and pose should remain where it is LevenbergMarquardtParams params; @@ -598,22 +592,22 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor2->add(measurements_cam2, views, model, sharedK); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor3->add(measurements_cam3, views, model, sharedK); + smartFactor3->add(measurements_cam3, views, model); SmartFactor::shared_ptr smartFactor4( new SmartFactor(1, -1, false, false, JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor4->add(measurements_cam4, views, model, sharedK); + smartFactor4->add(measurements_cam4, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -622,15 +616,15 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(smartFactor4); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); - values.insert(x3, pose_above); + values.insert(x1, cam2); + values.insert(x2, cam2); + values.insert(x3, Camera(pose_above * noise_pose, sharedK)); // All factors are disabled and pose should remain where it is LevenbergMarquardtParams params; @@ -659,15 +653,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(1, -1, false, false, JACOBIAN_Q)); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( new SmartFactor(1, -1, false, false, JACOBIAN_Q)); - smartFactor2->add(measurements_cam2, views, model, sharedK); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( new SmartFactor(1, -1, false, false, JACOBIAN_Q)); - smartFactor3->add(measurements_cam3, views, model, sharedK); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -675,16 +669,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); - values.insert(x3, pose_above * noise_pose); + values.insert(x1, cam2); + values.insert(x2, cam2); + values.insert(x3, Camera(pose_above * noise_pose, sharedK)); LevenbergMarquardtParams params; Values result; @@ -730,15 +723,15 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { ProjectionFactor(cam3.project(landmark3), model, x3, L(3), sharedK2)); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); - values.insert(x3, pose_above * noise_pose); + values.insert(x1, cam2); + values.insert(x2, cam2); + values.insert(x3, Camera(pose_above * noise_pose, sharedK2)); values.insert(L(1), landmark1); values.insert(L(2), landmark2); values.insert(L(3), landmark3); @@ -786,13 +779,13 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); - smartFactor2->add(measurements_cam2, views, model, sharedK); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); - smartFactor3->add(measurements_cam3, views, model, sharedK); + smartFactor3->add(measurements_cam3, views, model); NonlinearFactorGraph graph; graph.push_back(smartFactor1); @@ -803,10 +796,10 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam2); + values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose_above * noise_pose); + values.insert(x3, Camera(pose_above * noise_pose, sharedK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -867,11 +860,11 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, sharedK2); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, sharedK2); + smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, @@ -881,7 +874,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( @@ -890,10 +883,10 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right * noise_pose); + values.insert(x1, cam2); + values.insert(x2, Camera(pose_right * noise_pose, sharedK2)); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose_above * noise_pose * noise_pose); + values.insert(x3, Camera(pose_above * noise_pose * noise_pose, sharedK2)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -951,15 +944,15 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) SmartFactor::shared_ptr smartFactor1( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, sharedK); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, sharedK); + smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor3->add(measurements_cam3, views, model, sharedK); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, @@ -970,7 +963,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( @@ -980,10 +973,10 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam2); + values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose_above * noise_pose); + values.insert(x3, Camera(pose_above * noise_pose,sharedK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1029,13 +1022,13 @@ TEST( SmartProjectionPoseFactor, Hessian ) { measurements_cam1.push_back(cam2_uv1); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, sharedK2); + smartFactor1->add(measurements_cam1, views, model); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam2); + values.insert(x2, cam2); boost::shared_ptr hessianFactor = smartFactor1->linearize( values); @@ -1064,12 +1057,12 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); - smartFactorInstance->add(measurements_cam1, views, model, sharedK); + smartFactorInstance->add(measurements_cam1, views, model); Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); - values.insert(x3, pose_above); + values.insert(x1, cam2); + values.insert(x2, cam2); + values.insert(x3, cam3); boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); @@ -1077,9 +1070,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, poseDrift.compose(level_pose)); - rotValues.insert(x2, poseDrift.compose(pose_right)); - rotValues.insert(x3, poseDrift.compose(pose_above)); + rotValues.insert(x1, Camera(poseDrift.compose(level_pose),sharedK)); + rotValues.insert(x2, Camera(poseDrift.compose(pose_right),sharedK)); + rotValues.insert(x3, Camera(poseDrift.compose(pose_above),sharedK)); boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); @@ -1093,9 +1086,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, poseDrift2.compose(level_pose)); - tranValues.insert(x2, poseDrift2.compose(pose_right)); - tranValues.insert(x3, poseDrift2.compose(pose_above)); + tranValues.insert(x1, Camera(poseDrift2.compose(level_pose),sharedK)); + tranValues.insert(x2, Camera(poseDrift2.compose(pose_right),sharedK)); + tranValues.insert(x3, Camera(poseDrift2.compose(pose_above),sharedK)); boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); @@ -1122,12 +1115,12 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); SmartFactor::shared_ptr smartFactor(new SmartFactor()); - smartFactor->add(measurements_cam1, views, model, sharedK2); + smartFactor->add(measurements_cam1, views, model); Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); - values.insert(x3, pose_above); + values.insert(x1, cam2); + values.insert(x2, cam2); + values.insert(x3, cam3); boost::shared_ptr hessianFactor = smartFactor->linearize( values); @@ -1137,9 +1130,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, poseDrift.compose(level_pose)); - rotValues.insert(x2, poseDrift.compose(pose_right)); - rotValues.insert(x3, poseDrift.compose(pose_above)); + rotValues.insert(x1, Camera(poseDrift.compose(level_pose),sharedK2)); + rotValues.insert(x2, Camera(poseDrift.compose(pose_right),sharedK2)); + rotValues.insert(x3, Camera(poseDrift.compose(pose_above),sharedK2)); boost::shared_ptr hessianFactorRot = smartFactor->linearize( rotValues); @@ -1155,9 +1148,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, poseDrift2.compose(level_pose)); - tranValues.insert(x2, poseDrift2.compose(pose_right)); - tranValues.insert(x3, poseDrift2.compose(pose_above)); + tranValues.insert(x1, Camera(poseDrift2.compose(level_pose),sharedK2)); + tranValues.insert(x2, Camera(poseDrift2.compose(pose_right),sharedK2)); + tranValues.insert(x3, Camera(poseDrift2.compose(pose_above),sharedK2)); boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); @@ -1171,9 +1164,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { SmartFactorBundler factor(rankTol, linThreshold); - boost::shared_ptr sharedBundlerK( - new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); - factor.add(measurement1, x1, model, sharedBundlerK); + factor.add(measurement1, x1, model); } /* *************************************************************************/ @@ -1215,13 +1206,13 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { views.push_back(x3); SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); - smartFactor1->add(measurements_cam1, views, model, sharedBundlerK); + smartFactor1->add(measurements_cam1, views, model); SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); - smartFactor2->add(measurements_cam2, views, model, sharedBundlerK); + smartFactor2->add(measurements_cam2, views, model); SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); - smartFactor3->add(measurements_cam3, views, model, sharedBundlerK); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1229,17 +1220,17 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); - graph.push_back(PriorFactor(x2, pose_right, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x2, cam2, noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam2); + values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose_above * noise_pose); + values.insert(x3, Camera(pose_above * noise_pose,sharedBundlerK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1313,15 +1304,15 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { SmartFactorBundler::shared_ptr smartFactor1( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, sharedBundlerK); + smartFactor1->add(measurements_cam1, views, model); SmartFactorBundler::shared_ptr smartFactor2( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, sharedBundlerK); + smartFactor2->add(measurements_cam2, views, model); SmartFactorBundler::shared_ptr smartFactor3( new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor3->add(measurements_cam3, views, model, sharedBundlerK); + smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, @@ -1332,7 +1323,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( @@ -1342,10 +1333,10 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, level_pose); - values.insert(x2, pose_right); + values.insert(x1, cam2); + values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose_above * noise_pose); + values.insert(x3, Camera(pose_above * noise_pose,sharedBundlerK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); diff --git a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp index dc921a7da..9e8523ebb 100644 --- a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp @@ -26,16 +26,14 @@ * -makes monocular observations of many landmarks */ -#include +#include +#include #include #include #include #include #include #include -#include - -#include #include #include @@ -46,6 +44,7 @@ using namespace gtsam; int main(int argc, char** argv){ + typedef PinholePose Camera; typedef SmartProjectionPoseFactor SmartFactor; Values initial_estimate; @@ -68,18 +67,17 @@ int main(int argc, char** argv){ cout << "Reading camera poses" << endl; ifstream pose_file(pose_loc.c_str()); - int pose_id; + int i; MatrixRowMajor m(4,4); //read camera pose parameters and use to make initial estimates of camera poses - while (pose_file >> pose_id) { - for (int i = 0; i < 16; i++) { + while (pose_file >> i) { + for (int i = 0; i < 16; i++) pose_file >> m.data()[i]; - } - initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); + initial_estimate.insert(i, Camera(Pose3(m),K)); } - // camera and landmark keys - size_t x, l; + // landmark keys + size_t l; // pixel coordinates uL, uR, v (same for left/right images due to rectification) // landmark coordinates X, Y, Z in camera frame, resulting from triangulation @@ -92,21 +90,21 @@ int main(int argc, char** argv){ SmartFactor::shared_ptr factor(new SmartFactor()); size_t current_l = 3; // hardcoded landmark ID from first measurement - while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) { + while (factor_file >> i >> l >> uL >> uR >> v >> X >> Y >> Z) { if(current_l != l) { graph.push_back(factor); factor = SmartFactor::shared_ptr(new SmartFactor()); current_l = l; } - factor->add(Point2(uL,v), Symbol('x',x), model, K); + factor->add(Point2(uL,v), i, model); } - Pose3 first_pose = initial_estimate.at(Symbol('x',1)); + Camera firstCamera = initial_estimate.at(1); //constrain the first pose such that it cannot change from its original value during optimization // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky // QR is much slower than Cholesky, but numerically more stable - graph.push_back(NonlinearEquality(Symbol('x',1),first_pose)); + graph.push_back(NonlinearEquality(1,firstCamera)); LevenbergMarquardtParams params; params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; @@ -118,7 +116,7 @@ int main(int argc, char** argv){ Values result = optimizer.optimize(); cout << "Final result sample:" << endl; - Values pose_values = result.filter(); + Values pose_values = result.filter(); pose_values.print("Final camera poses:\n"); return 0; diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 2f4677835..8fe8bea69 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -15,6 +15,7 @@ * @author Luca Carlone * @author Chris Beall * @author Zsolt Kira + * @author Frank Dellaert */ #pragma once From f639ae0d7c70eca3e00b9b3713075990100c7295 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 13:55:32 +0100 Subject: [PATCH 046/173] Ignore generated files --- examples/Data/.gitignore | 1 + 1 file changed, 1 insertion(+) create mode 100644 examples/Data/.gitignore diff --git a/examples/Data/.gitignore b/examples/Data/.gitignore new file mode 100644 index 000000000..2211df63d --- /dev/null +++ b/examples/Data/.gitignore @@ -0,0 +1 @@ +*.txt From be26d99f1e73bac4d7a56640e2d95fc347272386 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 14:19:22 +0100 Subject: [PATCH 047/173] Moved to less intrusive spot --- gtsam/slam/SmartFactorBase.h | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index ba0d27530..417ba1354 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -307,16 +307,6 @@ public: return f; } - /// Create BIG block-diagonal matrix F from Fblocks - static void FillDiagonalF(const std::vector& Fblocks, - Matrix& F) { - size_t m = Fblocks.size(); - F.resize(ZDim * m, Dim * m); - F.setZero(); - for (size_t i = 0; i < m; ++i) - F.block(This::ZDim * i, Dim * i) = Fblocks.at(i).second; - } - /// SVD version double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, Vector& b, const Cameras& cameras, const Point3& point) const { @@ -549,6 +539,16 @@ public: return boost::make_shared >(F, E0, b, n); } + /// Create BIG block-diagonal matrix F from Fblocks + static void FillDiagonalF(const std::vector& Fblocks, + Matrix& F) { + size_t m = Fblocks.size(); + F.resize(ZDim * m, Dim * m); + F.setZero(); + for (size_t i = 0; i < m; ++i) + F.block(This::ZDim * i, Dim * i) = Fblocks.at(i).second; + } + private: /// Serialization function From b8d39e8aea78ff2eae80221d8f867e72cb31276a Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 14:19:36 +0100 Subject: [PATCH 048/173] Removed obsolete sharedKs --- gtsam/slam/SmartProjectionPoseFactor.h | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 48fbd937f..851cfe030 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -50,8 +50,6 @@ protected: LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) - std::vector > sharedKs_; ///< shared pointer to calibration object (one for each camera) - public: /// shorthand for a smart pointer to a factor @@ -86,8 +84,6 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionPoseFactor, z = \n "; - BOOST_FOREACH(const boost::shared_ptr& K, sharedKs_) - K->print("calibration = "); Base::print("", keyFormatter); } @@ -130,11 +126,6 @@ public: } } - /** return calibration shared pointers */ - inline const std::vector > calibration() const { - return sharedKs_; - } - private: /// Serialization function @@ -142,7 +133,6 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(sharedKs_); } }; // end of class declaration From 0a75da98584bf07c07ebe50c41097212649cc577 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 14:50:52 +0100 Subject: [PATCH 049/173] PinholeSet first draft: a CameraSet that assumes PinholeBase-derived CAMERA: knows how to triangulate. First draft is still imperative, with mutable point_, and that might change. --- .cproject | 8 + gtsam/geometry/CameraSet.h | 4 +- gtsam/geometry/PinholeSet.h | 381 ++++++++++++++++++++++++ gtsam/geometry/tests/testPinholeSet.cpp | 131 ++++++++ 4 files changed, 522 insertions(+), 2 deletions(-) create mode 100644 gtsam/geometry/PinholeSet.h create mode 100644 gtsam/geometry/tests/testPinholeSet.cpp diff --git a/.cproject b/.cproject index e190d8f65..94e8c3a50 100644 --- a/.cproject +++ b/.cproject @@ -1043,6 +1043,14 @@ true true + + make + -j4 + testPinholeSet.run + true + true + true + make -j2 diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 2192c38b9..179ec9c50 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -78,7 +78,7 @@ public: } /// equals - virtual bool equals(const CameraSet& p, double tol = 1e-9) const { + bool equals(const CameraSet& p, double tol = 1e-9) const { if (this->size() != p.size()) return false; bool camerasAreEqual = true; @@ -143,7 +143,7 @@ public: Vector reprojectionError(const Point3& point, const std::vector& measured, boost::optional F = boost::none, // boost::optional E = boost::none) const { - return ErrorVector(project2(point,F,E), measured); + return ErrorVector(project2(point, F, E), measured); } /// Calculate vector of re-projection errors, from point at infinity diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h new file mode 100644 index 000000000..c950a9150 --- /dev/null +++ b/gtsam/geometry/PinholeSet.h @@ -0,0 +1,381 @@ +/* ---------------------------------------------------------------------------- + + * 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 PinholeSet.h + * @brief A CameraSet of either CalibratedCamera, PinholePose, or PinholeCamera + * @author Frank Dellaert + * @author Luca Carlone + * @author Zsolt Kira + */ + +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +/** + * PinholeSet: triangulates point and keeps an estimate of it around. + */ +template +class PinholeSet: public CameraSet { + +private: + typedef CameraSet Base; + typedef PinholeSet This; + +protected: + + // Some triangulation parameters + const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ + const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate + mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses + + const bool enableEPI_; ///< if set to true, will refine triangulation using LM + + mutable Point3 point_; ///< Current estimate of the 3D point + + mutable bool degenerate_; + mutable bool cheiralityException_; + + // verbosity handling for Cheirality Exceptions + const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) + const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) + + double landmarkDistanceThreshold_; // if the landmark is triangulated at a + // distance larger than that the factor is considered degenerate + + double dynamicOutlierRejectionThreshold_; // if this is nonnegative the factor will check if the + // average reprojection error is smaller than this threshold after triangulation, + // and the factor is disregarded if the error is large + +public: + + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /// shorthand for a set of cameras + typedef CameraSet Cameras; + + /** + * Constructor + * @param rankTol tolerance used to check if point triangulation is degenerate + * otherwise the factor is simply neglected + * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations + */ + PinholeSet(const double rankTol = 1.0, const bool enableEPI = false, + double landmarkDistanceThreshold = 1e10, + double dynamicOutlierRejectionThreshold = -1) : + rankTolerance_(rankTol), retriangulationThreshold_(1e-5), enableEPI_( + enableEPI), degenerate_(false), cheiralityException_(false), throwCheirality_( + false), verboseCheirality_(false), landmarkDistanceThreshold_( + landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( + dynamicOutlierRejectionThreshold) { + } + + /** Virtual destructor */ + virtual ~PinholeSet() { + } + + /** + * print + * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols + */ + void print(const std::string& s = "") const { + std::cout << s << "PinholeSet, z = \n"; + std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; + std::cout << "degenerate_ = " << degenerate_ << std::endl; + std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; + Base::print(""); + } + + /// equals + bool equals(const PinholeSet& p, double tol = 1e-9) const { + return Base::equals(p, tol); // TODO all flags + } + + /// Check if the new linearization point_ is the same as the one used for previous triangulation + bool decideIfTriangulate(const Cameras& cameras) const { + // several calls to linearize will be done from the same linearization point_, hence it is not needed to re-triangulate + // Note that this is not yet "selecting linearization", that will come later, and we only check if the + // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point_ + + size_t m = cameras.size(); + + bool retriangulate = false; + + // if we do not have a previous linearization point_ or the new linearization point_ includes more poses + if (cameraPosesTriangulation_.empty() + || cameras.size() != cameraPosesTriangulation_.size()) + retriangulate = true; + + if (!retriangulate) { + for (size_t i = 0; i < cameras.size(); i++) { + if (!cameras[i].pose().equals(cameraPosesTriangulation_[i], + retriangulationThreshold_)) { + retriangulate = true; // at least two poses are different, hence we retriangulate + break; + } + } + } + + if (retriangulate) { // we store the current poses used for triangulation + cameraPosesTriangulation_.clear(); + cameraPosesTriangulation_.reserve(m); + for (size_t i = 0; i < m; i++) + // cameraPosesTriangulation_[i] = cameras[i].pose(); + cameraPosesTriangulation_.push_back(cameras[i].pose()); + } + + return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation + } + + /// triangulateSafe + size_t triangulateSafe(const Values& values) const { + return triangulateSafe(this->cameras(values)); + } + + /// triangulateSafe + size_t triangulateSafe(const Cameras& cameras) const { + + size_t m = cameras.size(); + if (m < 2) { // if we have a single pose the corresponding factor is uninformative + degenerate_ = true; + return m; + } + bool retriangulate = decideIfTriangulate(cameras); + + if (retriangulate) { + // We triangulate the 3D position of the landmark + try { + // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; + point_ = triangulatePoint3(cameras, this->measured_, + rankTolerance_, enableEPI_); + degenerate_ = false; + cheiralityException_ = false; + + // Check landmark distance and reprojection errors to avoid outliers + double totalReprojError = 0.0; + size_t i = 0; + BOOST_FOREACH(const CAMERA& camera, cameras) { + Point3 cameraTranslation = camera.pose().translation(); + // we discard smart factors corresponding to points that are far away + if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { + degenerate_ = true; + break; + } + const Point2& zi = this->measured_.at(i); + try { + Point2 reprojectionError(camera.project(point_) - zi); + totalReprojError += reprojectionError.vector().norm(); + } catch (CheiralityException) { + cheiralityException_ = true; + } + i += 1; + } + // we discard smart factors that have large reprojection error + if (dynamicOutlierRejectionThreshold_ > 0 + && totalReprojError / m > dynamicOutlierRejectionThreshold_) + degenerate_ = true; + + } catch (TriangulationUnderconstrainedException&) { + // if TriangulationUnderconstrainedException can be + // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before + // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) + // in the second case we want to use a rotation-only smart factor + degenerate_ = true; + cheiralityException_ = false; + } catch (TriangulationCheiralityException&) { + // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers + // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint + cheiralityException_ = true; + } + } + return m; + } + + /// triangulate + bool triangulateForLinearize(const Cameras& cameras) const { + + bool isDebug = false; + size_t nrCameras = this->triangulateSafe(cameras); + + if (nrCameras < 2 || (this->cheiralityException_ || this->degenerate_)) { + if (isDebug) { + std::cout + << "createRegularImplicitSchurFactor: degenerate configuration" + << std::endl; + } + return false; + } else { + + // instead, if we want to manage the exception.. + if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors + this->degenerate_ = true; + } + return true; + } + } + + /// Returns true if nonDegenerate + bool computeCamerasAndTriangulate(const Values& values, + Cameras& cameras) const { + Values valuesFactor; + + // Select only the cameras + BOOST_FOREACH(const Key key, this->keys_) + valuesFactor.insert(key, values.at(key)); + + cameras = this->cameras(valuesFactor); + size_t nrCameras = this->triangulateSafe(cameras); + + if (nrCameras < 2 || (this->cheiralityException_ || this->degenerate_)) + return false; + + // instead, if we want to manage the exception.. + if (this->cheiralityException_ || this->degenerate_) // if we want to manage the exceptions with rotation-only factors + this->degenerate_ = true; + + if (this->degenerate_) { + std::cout << "PinholeSet: this is not ready" << std::endl; + std::cout << "this->cheiralityException_ " << this->cheiralityException_ + << std::endl; + std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; + } + return true; + } + + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Values& values) const { + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); + if (nonDegenerate) + cameras.project2(point_, boost::none, E); + return nonDegenerate; + } + + /// Calculate vector of re-projection errors, before applying noise model + Vector reprojectionErrorAfterTriangulation(const Values& values) const { + Cameras cameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); + if (nonDegenerate) + return Base::reprojectionError(cameras, point_); + else + return zero(cameras.size() * 2); + } + + /** + * Calculate the error of the factor. + * This is the log-likelihood, e.g. \f$ 0.5(h(x)-z)^2/\sigma^2 \f$ in case of Gaussian. + * In this class, we take the raw prediction error \f$ h(x)-z \f$, ask the noise model + * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. + */ + double totalReprojectionError(const Cameras& cameras, + boost::optional externalPoint = boost::none) const { + + size_t nrCameras; + if (externalPoint) { + nrCameras = this->keys_.size(); + point_ = *externalPoint; + degenerate_ = false; + cheiralityException_ = false; + } else { + nrCameras = this->triangulateSafe(cameras); + } + + if (nrCameras < 2 || (this->cheiralityException_ || this->degenerate_)) { + // if we don't want to manage the exceptions we discard the factor + // std::cout << "In error evaluation: exception" << std::endl; + return 0.0; + } + + if (this->cheiralityException_) { // if we want to manage the exceptions with rotation-only factors + std::cout + << "SmartProjectionHessianFactor: cheirality exception (this should not happen if CheiralityException is disabled)!" + << std::endl; + this->degenerate_ = true; + } + + if (this->degenerate_) { + // return 0.0; // TODO: this maybe should be zero? + std::cout + << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" + << std::endl; + // 3D parameterization of point at infinity + const Point2& zi = this->measured_.at(0); + this->point_ = cameras.front().backprojectPointAtInfinity(zi); + return Base::totalReprojectionErrorAtInfinity(cameras, this->point_); + } else { + // Just use version in base class + return Base::totalReprojectionError(cameras, point_); + } + } + + /** return the landmark */ + boost::optional point() const { + return point_; + } + + /** COMPUTE the landmark */ + boost::optional point(const Values& values) const { + triangulateSafe(values); + return point_; + } + + /** return the degenerate state */ + inline bool isDegenerate() const { + return (cheiralityException_ || degenerate_); + } + + /** return the cheirality status flag */ + inline bool isPointBehindCamera() const { + return cheiralityException_; + } + + /** return cheirality verbosity */ + inline bool verboseCheirality() const { + return verboseCheirality_; + } + + /** return flag for throwing cheirality exceptions */ + inline bool throwCheirality() const { + return throwCheirality_; + } + +private: + + /// Serialization function + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar & BOOST_SERIALIZATION_NVP(throwCheirality_); + ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); + } +}; + +template +struct traits > : public Testable > { +}; + +template +struct traits > : public Testable > { +}; + +} // \ namespace gtsam diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp new file mode 100644 index 000000000..079833ec4 --- /dev/null +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -0,0 +1,131 @@ +/* ---------------------------------------------------------------------------- + + * 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 testCameraSet.cpp + * @brief Unit tests for testCameraSet Class + * @author Frank Dellaert + * @date Feb 19, 2015 + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +#include +TEST(PinholeSet, Stereo) { + typedef vector ZZ; + PinholeSet set; + CalibratedCamera camera; + set.push_back(camera); + set.push_back(camera); + Point3 p(0, 0, 1); + EXPECT_LONGS_EQUAL(6, traits::dimension); + + // Check measurements + Point2 expected(0, 0); + ZZ z = set.project2(p); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); + + // Calculate expected derivatives using Pinhole + Matrix43 actualE; + Matrix F1; + { + Matrix23 E1; + camera.project2(p, F1, E1); + actualE << E1, E1; + } + + // Check computed derivatives + PinholeSet::FBlocks F; + Matrix E; + set.project2(p, F, E); + LONGS_EQUAL(2, F.size()); + EXPECT(assert_equal(F1, F[0])); + EXPECT(assert_equal(F1, F[1])); + EXPECT(assert_equal(actualE, E)); +} + +/* ************************************************************************* */ +// Cal3Bundler test +#include +#include +TEST(PinholeSet, Pinhole) { + typedef PinholeCamera Camera; + typedef vector ZZ; + PinholeSet set; + Camera camera; + set.push_back(camera); + set.push_back(camera); + Point3 p(0, 0, 1); + EXPECT(assert_equal(set, set)); + PinholeSet set2 = set; + set2.push_back(camera); + EXPECT(!set.equals(set2)); + + // Check measurements + Point2 expected; + ZZ z = set.project2(p); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); + + // Calculate expected derivatives using Pinhole + Matrix43 actualE; + Matrix F1; + { + Matrix23 E1; + Matrix23 H1; + camera.project2(p, F1, E1); + actualE << E1, E1; + } + + // Check computed derivatives + PinholeSet::FBlocks F; + Matrix E, H; + set.project2(p, F, E); + LONGS_EQUAL(2, F.size()); + EXPECT(assert_equal(F1, F[0])); + EXPECT(assert_equal(F1, F[1])); + EXPECT(assert_equal(actualE, E)); + + // Check errors + ZZ measured; + measured.push_back(Point2(1, 2)); + measured.push_back(Point2(3, 4)); + Vector4 expectedV; + + // reprojectionError + expectedV << -1, -2, -3, -4; + Vector actualV = set.reprojectionError(p, measured); + EXPECT(assert_equal(expectedV, actualV)); + + // reprojectionErrorAtInfinity + EXPECT( + assert_equal(Point3(0, 0, 1), + camera.backprojectPointAtInfinity(Point2()))); + actualV = set.reprojectionErrorAtInfinity(p, measured); + EXPECT(assert_equal(expectedV, actualV)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + From 3b808e644b96b1031de1ec65a26c409a734a826e Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 15:01:25 +0100 Subject: [PATCH 050/173] Removed a lot of obsolete code --- gtsam/geometry/PinholeSet.h | 263 +++++++----------------------------- 1 file changed, 51 insertions(+), 212 deletions(-) diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h index c950a9150..5a1378782 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -38,22 +38,19 @@ private: protected: - // Some triangulation parameters - const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ - const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate - mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses + /// @name Triangulation parameters + /// @{ + const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ const bool enableEPI_; ///< if set to true, will refine triangulation using LM + /// @} + mutable Point3 point_; ///< Current estimate of the 3D point mutable bool degenerate_; mutable bool cheiralityException_; - // verbosity handling for Cheirality Exceptions - const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) - const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) - double landmarkDistanceThreshold_; // if the landmark is triangulated at a // distance larger than that the factor is considered degenerate @@ -66,9 +63,6 @@ public: /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; - /// shorthand for a set of cameras - typedef CameraSet Cameras; - /** * Constructor * @param rankTol tolerance used to check if point triangulation is degenerate @@ -78,10 +72,8 @@ public: PinholeSet(const double rankTol = 1.0, const bool enableEPI = false, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : - rankTolerance_(rankTol), retriangulationThreshold_(1e-5), enableEPI_( - enableEPI), degenerate_(false), cheiralityException_(false), throwCheirality_( - false), verboseCheirality_(false), landmarkDistanceThreshold_( - landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( + rankTolerance_(rankTol), enableEPI_(enableEPI), degenerate_(false), cheiralityException_( + false), landmarkDistanceThreshold_(landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( dynamicOutlierRejectionThreshold) { } @@ -107,111 +99,67 @@ public: return Base::equals(p, tol); // TODO all flags } - /// Check if the new linearization point_ is the same as the one used for previous triangulation - bool decideIfTriangulate(const Cameras& cameras) const { - // several calls to linearize will be done from the same linearization point_, hence it is not needed to re-triangulate - // Note that this is not yet "selecting linearization", that will come later, and we only check if the - // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point_ - - size_t m = cameras.size(); - - bool retriangulate = false; - - // if we do not have a previous linearization point_ or the new linearization point_ includes more poses - if (cameraPosesTriangulation_.empty() - || cameras.size() != cameraPosesTriangulation_.size()) - retriangulate = true; - - if (!retriangulate) { - for (size_t i = 0; i < cameras.size(); i++) { - if (!cameras[i].pose().equals(cameraPosesTriangulation_[i], - retriangulationThreshold_)) { - retriangulate = true; // at least two poses are different, hence we retriangulate - break; - } - } - } - - if (retriangulate) { // we store the current poses used for triangulation - cameraPosesTriangulation_.clear(); - cameraPosesTriangulation_.reserve(m); - for (size_t i = 0; i < m; i++) - // cameraPosesTriangulation_[i] = cameras[i].pose(); - cameraPosesTriangulation_.push_back(cameras[i].pose()); - } - - return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation - } - /// triangulateSafe - size_t triangulateSafe(const Values& values) const { - return triangulateSafe(this->cameras(values)); - } + size_t triangulateSafe() const { - /// triangulateSafe - size_t triangulateSafe(const Cameras& cameras) const { - - size_t m = cameras.size(); + size_t m = this->size(); if (m < 2) { // if we have a single pose the corresponding factor is uninformative degenerate_ = true; return m; } - bool retriangulate = decideIfTriangulate(cameras); - if (retriangulate) { - // We triangulate the 3D position of the landmark - try { - // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - point_ = triangulatePoint3(cameras, this->measured_, - rankTolerance_, enableEPI_); - degenerate_ = false; - cheiralityException_ = false; + // We triangulate the 3D position of the landmark + try { + // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; + point_ = triangulatePoint3(*this, this->measured_, rankTolerance_, + enableEPI_); + degenerate_ = false; + cheiralityException_ = false; - // Check landmark distance and reprojection errors to avoid outliers - double totalReprojError = 0.0; - size_t i = 0; - BOOST_FOREACH(const CAMERA& camera, cameras) { - Point3 cameraTranslation = camera.pose().translation(); - // we discard smart factors corresponding to points that are far away - if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { - degenerate_ = true; - break; - } - const Point2& zi = this->measured_.at(i); - try { - Point2 reprojectionError(camera.project(point_) - zi); - totalReprojError += reprojectionError.vector().norm(); - } catch (CheiralityException) { - cheiralityException_ = true; - } - i += 1; - } - // we discard smart factors that have large reprojection error - if (dynamicOutlierRejectionThreshold_ > 0 - && totalReprojError / m > dynamicOutlierRejectionThreshold_) + // Check landmark distance and reprojection errors to avoid outliers + double totalReprojError = 0.0; + size_t i = 0; + BOOST_FOREACH(const CAMERA& camera, *this) { + Point3 cameraTranslation = camera.pose().translation(); + // we discard smart factors corresponding to points that are far away + if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { degenerate_ = true; - - } catch (TriangulationUnderconstrainedException&) { - // if TriangulationUnderconstrainedException can be - // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before - // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) - // in the second case we want to use a rotation-only smart factor - degenerate_ = true; - cheiralityException_ = false; - } catch (TriangulationCheiralityException&) { - // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers - // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint - cheiralityException_ = true; + break; + } + const Point2& zi = this->measured_.at(i); + try { + Point2 reprojectionError(camera.project(point_) - zi); + totalReprojError += reprojectionError.vector().norm(); + } catch (CheiralityException) { + cheiralityException_ = true; + } + i += 1; } + // we discard smart factors that have large reprojection error + if (dynamicOutlierRejectionThreshold_ > 0 + && totalReprojError / m > dynamicOutlierRejectionThreshold_) + degenerate_ = true; + + } catch (TriangulationUnderconstrainedException&) { + // if TriangulationUnderconstrainedException can be + // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before + // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel *this (or motion towards the landmark) + // in the second case we want to use a rotation-only smart factor + degenerate_ = true; + cheiralityException_ = false; + } catch (TriangulationCheiralityException&) { + // point is behind one of the *this: can be the case of close-to-parallel *this or may depend on outliers + // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint + cheiralityException_ = true; } return m; } /// triangulate - bool triangulateForLinearize(const Cameras& cameras) const { + bool triangulateForLinearize() const { bool isDebug = false; - size_t nrCameras = this->triangulateSafe(cameras); + size_t nrCameras = this->triangulateSafe(*this); if (nrCameras < 2 || (this->cheiralityException_ || this->degenerate_)) { if (isDebug) { @@ -230,103 +178,6 @@ public: } } - /// Returns true if nonDegenerate - bool computeCamerasAndTriangulate(const Values& values, - Cameras& cameras) const { - Values valuesFactor; - - // Select only the cameras - BOOST_FOREACH(const Key key, this->keys_) - valuesFactor.insert(key, values.at(key)); - - cameras = this->cameras(valuesFactor); - size_t nrCameras = this->triangulateSafe(cameras); - - if (nrCameras < 2 || (this->cheiralityException_ || this->degenerate_)) - return false; - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - - if (this->degenerate_) { - std::cout << "PinholeSet: this is not ready" << std::endl; - std::cout << "this->cheiralityException_ " << this->cheiralityException_ - << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; - } - return true; - } - - /** - * Triangulate and compute derivative of error with respect to point - * @return whether triangulation worked - */ - bool triangulateAndComputeE(Matrix& E, const Values& values) const { - Cameras cameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); - if (nonDegenerate) - cameras.project2(point_, boost::none, E); - return nonDegenerate; - } - - /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionErrorAfterTriangulation(const Values& values) const { - Cameras cameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); - if (nonDegenerate) - return Base::reprojectionError(cameras, point_); - else - return zero(cameras.size() * 2); - } - - /** - * Calculate the error of the factor. - * This is the log-likelihood, e.g. \f$ 0.5(h(x)-z)^2/\sigma^2 \f$ in case of Gaussian. - * In this class, we take the raw prediction error \f$ h(x)-z \f$, ask the noise model - * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. - */ - double totalReprojectionError(const Cameras& cameras, - boost::optional externalPoint = boost::none) const { - - size_t nrCameras; - if (externalPoint) { - nrCameras = this->keys_.size(); - point_ = *externalPoint; - degenerate_ = false; - cheiralityException_ = false; - } else { - nrCameras = this->triangulateSafe(cameras); - } - - if (nrCameras < 2 || (this->cheiralityException_ || this->degenerate_)) { - // if we don't want to manage the exceptions we discard the factor - // std::cout << "In error evaluation: exception" << std::endl; - return 0.0; - } - - if (this->cheiralityException_) { // if we want to manage the exceptions with rotation-only factors - std::cout - << "SmartProjectionHessianFactor: cheirality exception (this should not happen if CheiralityException is disabled)!" - << std::endl; - this->degenerate_ = true; - } - - if (this->degenerate_) { - // return 0.0; // TODO: this maybe should be zero? - std::cout - << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" - << std::endl; - // 3D parameterization of point at infinity - const Point2& zi = this->measured_.at(0); - this->point_ = cameras.front().backprojectPointAtInfinity(zi); - return Base::totalReprojectionErrorAtInfinity(cameras, this->point_); - } else { - // Just use version in base class - return Base::totalReprojectionError(cameras, point_); - } - } - /** return the landmark */ boost::optional point() const { return point_; @@ -348,16 +199,6 @@ public: return cheiralityException_; } - /** return cheirality verbosity */ - inline bool verboseCheirality() const { - return verboseCheirality_; - } - - /** return flag for throwing cheirality exceptions */ - inline bool throwCheirality() const { - return throwCheirality_; - } - private: /// Serialization function @@ -365,8 +206,6 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(throwCheirality_); - ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } }; From 61ba2f080cfc0af42d09bf9d1a07de07bc09f8fb Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 15:33:27 +0100 Subject: [PATCH 051/173] made print virtual --- gtsam/geometry/CameraSet.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 179ec9c50..7e9062a8d 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -71,10 +71,10 @@ public: * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "") const { + virtual void print(const std::string& s = "") const { std::cout << s << "CameraSet, cameras = \n"; for (size_t k = 0; k < this->size(); ++k) - this->at(k).print(); + this->at(k).print(s); } /// equals From 262b42e82973c9add110ef286c0205359943fdfa Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 15:33:43 +0100 Subject: [PATCH 052/173] Now complete functional triangulateSafe --- gtsam/geometry/PinholeSet.h | 145 +++++++++--------------- gtsam/geometry/tests/testPinholeSet.cpp | 9 ++ 2 files changed, 64 insertions(+), 90 deletions(-) diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h index 5a1378782..37489355d 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -41,39 +41,44 @@ protected: /// @name Triangulation parameters /// @{ - const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ + const double rankTolerance_; ///< threshold to decide whether triangulation is result.degenerate const bool enableEPI_; ///< if set to true, will refine triangulation using LM + /** + * if the landmark is triangulated at distance larger than this, + * result is flagged as degenerate. + */ + const double landmarkDistanceThreshold_; // + + /** + * If this is nonnegative the we will check if the average reprojection error + * is smaller than this threshold after triangulation, otherwise result is + * flagged as degenerate. + */ + const double dynamicOutlierRejectionThreshold_; /// @} - mutable Point3 point_; ///< Current estimate of the 3D point - - mutable bool degenerate_; - mutable bool cheiralityException_; - - double landmarkDistanceThreshold_; // if the landmark is triangulated at a - // distance larger than that the factor is considered degenerate - - double dynamicOutlierRejectionThreshold_; // if this is nonnegative the factor will check if the - // average reprojection error is smaller than this threshold after triangulation, - // and the factor is disregarded if the error is large - public: - /// shorthand for a smart pointer to a factor - typedef boost::shared_ptr shared_ptr; + /// @name Triangulation result + /// @{ + struct Result { + Point3 point; + bool degenerate; + bool cheiralityException; + }; + /// @} /** * Constructor * @param rankTol tolerance used to check if point triangulation is degenerate - * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations */ PinholeSet(const double rankTol = 1.0, const bool enableEPI = false, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : - rankTolerance_(rankTol), enableEPI_(enableEPI), degenerate_(false), cheiralityException_( - false), landmarkDistanceThreshold_(landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( + rankTolerance_(rankTol), enableEPI_(enableEPI), landmarkDistanceThreshold_( + landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( dynamicOutlierRejectionThreshold) { } @@ -81,17 +86,14 @@ public: virtual ~PinholeSet() { } - /** - * print - * @param s optional string naming the factor - * @param keyFormatter optional formatter useful for printing Symbols - */ - void print(const std::string& s = "") const { - std::cout << s << "PinholeSet, z = \n"; - std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; - std::cout << "degenerate_ = " << degenerate_ << std::endl; - std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; - Base::print(""); + /// @name Testable + /// @{ + + /// print + virtual void print(const std::string& s = "") const { + Base::print(s); + std::cout << s << "PinholeSet\n"; + std::cout << "rankTolerance = " << rankTolerance_ << std::endl; } /// equals @@ -99,22 +101,28 @@ public: return Base::equals(p, tol); // TODO all flags } + /// @} + /// triangulateSafe - size_t triangulateSafe() const { + Result triangulateSafe(const std::vector& measured) const { + + Result result; size_t m = this->size(); - if (m < 2) { // if we have a single pose the corresponding factor is uninformative - degenerate_ = true; - return m; + + // if we have a single pose the corresponding factor is uninformative + if (m < 2) { + result.degenerate = true; + return result; } // We triangulate the 3D position of the landmark try { // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - point_ = triangulatePoint3(*this, this->measured_, rankTolerance_, + result.point = triangulatePoint3(*this, measured, rankTolerance_, enableEPI_); - degenerate_ = false; - cheiralityException_ = false; + result.degenerate = false; + result.cheiralityException = false; // Check landmark distance and reprojection errors to avoid outliers double totalReprojError = 0.0; @@ -122,81 +130,38 @@ public: BOOST_FOREACH(const CAMERA& camera, *this) { Point3 cameraTranslation = camera.pose().translation(); // we discard smart factors corresponding to points that are far away - if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { - degenerate_ = true; + if (cameraTranslation.distance(result.point) + > landmarkDistanceThreshold_) { + result.degenerate = true; break; } - const Point2& zi = this->measured_.at(i); + const Point2& zi = measured.at(i); try { - Point2 reprojectionError(camera.project(point_) - zi); + Point2 reprojectionError(camera.project(result.point) - zi); totalReprojError += reprojectionError.vector().norm(); } catch (CheiralityException) { - cheiralityException_ = true; + result.cheiralityException = true; } i += 1; } // we discard smart factors that have large reprojection error if (dynamicOutlierRejectionThreshold_ > 0 && totalReprojError / m > dynamicOutlierRejectionThreshold_) - degenerate_ = true; + result.degenerate = true; } catch (TriangulationUnderconstrainedException&) { // if TriangulationUnderconstrainedException can be // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel *this (or motion towards the landmark) // in the second case we want to use a rotation-only smart factor - degenerate_ = true; - cheiralityException_ = false; + result.degenerate = true; + result.cheiralityException = false; } catch (TriangulationCheiralityException&) { // point is behind one of the *this: can be the case of close-to-parallel *this or may depend on outliers // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint - cheiralityException_ = true; + result.cheiralityException = true; } - return m; - } - - /// triangulate - bool triangulateForLinearize() const { - - bool isDebug = false; - size_t nrCameras = this->triangulateSafe(*this); - - if (nrCameras < 2 || (this->cheiralityException_ || this->degenerate_)) { - if (isDebug) { - std::cout - << "createRegularImplicitSchurFactor: degenerate configuration" - << std::endl; - } - return false; - } else { - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - } - return true; - } - } - - /** return the landmark */ - boost::optional point() const { - return point_; - } - - /** COMPUTE the landmark */ - boost::optional point(const Values& values) const { - triangulateSafe(values); - return point_; - } - - /** return the degenerate state */ - inline bool isDegenerate() const { - return (cheiralityException_ || degenerate_); - } - - /** return the cheirality status flag */ - inline bool isPointBehindCamera() const { - return cheiralityException_; + return result; } private: diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp index 079833ec4..b4b065802 100644 --- a/gtsam/geometry/tests/testPinholeSet.cpp +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -33,6 +33,7 @@ TEST(PinholeSet, Stereo) { CalibratedCamera camera; set.push_back(camera); set.push_back(camera); + // set.print("set: "); Point3 p(0, 0, 1); EXPECT_LONGS_EQUAL(6, traits::dimension); @@ -59,6 +60,10 @@ TEST(PinholeSet, Stereo) { EXPECT(assert_equal(F1, F[0])); EXPECT(assert_equal(F1, F[1])); EXPECT(assert_equal(actualE, E)); + + // Instantiate triangulateSafe + // TODO triangulation does not work yet for CalibratedCamera + // PinholeSet::Result actual = set.triangulateSafe(z); } /* ************************************************************************* */ @@ -120,6 +125,10 @@ TEST(PinholeSet, Pinhole) { camera.backprojectPointAtInfinity(Point2()))); actualV = set.reprojectionErrorAtInfinity(p, measured); EXPECT(assert_equal(expectedV, actualV)); + + // Instantiate triangulateSafe + PinholeSet::Result actual = set.triangulateSafe(z); + CHECK(actual.degenerate); } /* ************************************************************************* */ From 69e56cee1c46814a81504de226fe1aebd53a3a92 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 26 Feb 2015 15:54:50 +0100 Subject: [PATCH 053/173] Everything moved to triangulation, PinholeSet eviscerated. --- gtsam/geometry/PinholeSet.h | 108 +----------------------- gtsam/geometry/tests/testPinholeSet.cpp | 3 +- gtsam/geometry/triangulation.h | 106 ++++++++++++++++++++++- 3 files changed, 110 insertions(+), 107 deletions(-) diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h index 37489355d..5101e9fc8 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -13,8 +13,6 @@ * @file PinholeSet.h * @brief A CameraSet of either CalibratedCamera, PinholePose, or PinholeCamera * @author Frank Dellaert - * @author Luca Carlone - * @author Zsolt Kira */ #pragma once @@ -38,50 +36,8 @@ private: protected: - /// @name Triangulation parameters - /// @{ - - const double rankTolerance_; ///< threshold to decide whether triangulation is result.degenerate - const bool enableEPI_; ///< if set to true, will refine triangulation using LM - - /** - * if the landmark is triangulated at distance larger than this, - * result is flagged as degenerate. - */ - const double landmarkDistanceThreshold_; // - - /** - * If this is nonnegative the we will check if the average reprojection error - * is smaller than this threshold after triangulation, otherwise result is - * flagged as degenerate. - */ - const double dynamicOutlierRejectionThreshold_; - /// @} - public: - /// @name Triangulation result - /// @{ - struct Result { - Point3 point; - bool degenerate; - bool cheiralityException; - }; - /// @} - - /** - * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - */ - PinholeSet(const double rankTol = 1.0, const bool enableEPI = false, - double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1) : - rankTolerance_(rankTol), enableEPI_(enableEPI), landmarkDistanceThreshold_( - landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( - dynamicOutlierRejectionThreshold) { - } - /** Virtual destructor */ virtual ~PinholeSet() { } @@ -92,8 +48,6 @@ public: /// print virtual void print(const std::string& s = "") const { Base::print(s); - std::cout << s << "PinholeSet\n"; - std::cout << "rankTolerance = " << rankTolerance_ << std::endl; } /// equals @@ -104,64 +58,10 @@ public: /// @} /// triangulateSafe - Result triangulateSafe(const std::vector& measured) const { - - Result result; - - size_t m = this->size(); - - // if we have a single pose the corresponding factor is uninformative - if (m < 2) { - result.degenerate = true; - return result; - } - - // We triangulate the 3D position of the landmark - try { - // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - result.point = triangulatePoint3(*this, measured, rankTolerance_, - enableEPI_); - result.degenerate = false; - result.cheiralityException = false; - - // Check landmark distance and reprojection errors to avoid outliers - double totalReprojError = 0.0; - size_t i = 0; - BOOST_FOREACH(const CAMERA& camera, *this) { - Point3 cameraTranslation = camera.pose().translation(); - // we discard smart factors corresponding to points that are far away - if (cameraTranslation.distance(result.point) - > landmarkDistanceThreshold_) { - result.degenerate = true; - break; - } - const Point2& zi = measured.at(i); - try { - Point2 reprojectionError(camera.project(result.point) - zi); - totalReprojError += reprojectionError.vector().norm(); - } catch (CheiralityException) { - result.cheiralityException = true; - } - i += 1; - } - // we discard smart factors that have large reprojection error - if (dynamicOutlierRejectionThreshold_ > 0 - && totalReprojError / m > dynamicOutlierRejectionThreshold_) - result.degenerate = true; - - } catch (TriangulationUnderconstrainedException&) { - // if TriangulationUnderconstrainedException can be - // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before - // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel *this (or motion towards the landmark) - // in the second case we want to use a rotation-only smart factor - result.degenerate = true; - result.cheiralityException = false; - } catch (TriangulationCheiralityException&) { - // point is behind one of the *this: can be the case of close-to-parallel *this or may depend on outliers - // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint - result.cheiralityException = true; - } - return result; + TriangulationResult triangulateSafe( + const std::vector& measured, + const TriangulationParameters& params) const { + return gtsam::triangulateSafe(*this, measured, params); } private: diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp index b4b065802..5de2b5f4d 100644 --- a/gtsam/geometry/tests/testPinholeSet.cpp +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -127,7 +127,8 @@ TEST(PinholeSet, Pinhole) { EXPECT(assert_equal(expectedV, actualV)); // Instantiate triangulateSafe - PinholeSet::Result actual = set.triangulateSafe(z); + TriangulationParameters params; + TriangulationResult actual = set.triangulateSafe(z,params); CHECK(actual.degenerate); } diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 5b8be0168..15721e81c 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -221,7 +221,7 @@ Point3 triangulatePoint3(const std::vector& poses, BOOST_FOREACH(const Pose3& pose, poses) { const Point3& p_local = pose.transform_to(point); if (p_local.z() <= 0) - throw(TriangulationCheiralityException()); + throw(TriangulationCheiralityException()); } #endif @@ -269,7 +269,7 @@ Point3 triangulatePoint3(const std::vector& cameras, BOOST_FOREACH(const CAMERA& camera, cameras) { const Point3& p_local = camera.pose().transform_to(point); if (p_local.z() <= 0) - throw(TriangulationCheiralityException()); + throw(TriangulationCheiralityException()); } #endif @@ -286,5 +286,107 @@ Point3 triangulatePoint3( (cameras, measurements, rank_tol, optimize); } +struct TriangulationParameters { + + const double rankTolerance; ///< threshold to decide whether triangulation is result.degenerate + const bool enableEPI; ///< if set to true, will refine triangulation using LM + + /** + * if the landmark is triangulated at distance larger than this, + * result is flagged as degenerate. + */ + const double landmarkDistanceThreshold; // + + /** + * If this is nonnegative the we will check if the average reprojection error + * is smaller than this threshold after triangulation, otherwise result is + * flagged as degenerate. + */ + const double dynamicOutlierRejectionThreshold; + + /** + * Constructor + * @param rankTol tolerance used to check if point triangulation is degenerate + * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations + */ + TriangulationParameters(const double _rankTolerance = 1.0, + const bool _enableEPI = false, double _landmarkDistanceThreshold = 1e10, + double _dynamicOutlierRejectionThreshold = -1) : + rankTolerance(_rankTolerance), enableEPI(_enableEPI), landmarkDistanceThreshold( + _landmarkDistanceThreshold), dynamicOutlierRejectionThreshold( + _dynamicOutlierRejectionThreshold) { + } +}; + +struct TriangulationResult { + Point3 point; + bool degenerate; + bool cheiralityException; +}; + +/// triangulateSafe: extensive checking of the outcome +template +TriangulationResult triangulateSafe(const std::vector& cameras, + const std::vector& measured, + const TriangulationParameters& params) { + + TriangulationResult result; + + size_t m = cameras.size(); + + // if we have a single pose the corresponding factor is uninformative + if (m < 2) { + result.degenerate = true; + return result; + } + + // We triangulate the 3D position of the landmark + try { + // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; + result.point = triangulatePoint3(cameras, measured, + params.rankTolerance, params.enableEPI); + result.degenerate = false; + result.cheiralityException = false; + + // Check landmark distance and reprojection errors to avoid outliers + double totalReprojError = 0.0; + size_t i = 0; + BOOST_FOREACH(const CAMERA& camera, cameras) { + Point3 cameraTranslation = camera.pose().translation(); + // we discard smart factors corresponding to points that are far away + if (cameraTranslation.distance(result.point) + > params.landmarkDistanceThreshold) { + result.degenerate = true; + break; + } + const Point2& zi = measured.at(i); + try { + Point2 reprojectionError(camera.project(result.point) - zi); + totalReprojError += reprojectionError.vector().norm(); + } catch (CheiralityException) { + result.cheiralityException = true; + } + i += 1; + } + // we discard smart factors that have large reprojection error + if (params.dynamicOutlierRejectionThreshold > 0 + && totalReprojError / m > params.dynamicOutlierRejectionThreshold) + result.degenerate = true; + + } catch (TriangulationUnderconstrainedException&) { + // if TriangulationUnderconstrainedException can be + // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before + // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) + // in the second case we want to use a rotation-only smart factor + result.degenerate = true; + result.cheiralityException = false; + } catch (TriangulationCheiralityException&) { + // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers + // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint + result.cheiralityException = true; + } + return result; +} + } // \namespace gtsam From 83d0bd414db0bce122271f793473f6564caa2094 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 12:06:16 +0100 Subject: [PATCH 054/173] Introduced TriangulationResult --- gtsam/geometry/triangulation.h | 144 ++++++++++++++++++++------------- 1 file changed, 90 insertions(+), 54 deletions(-) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 15721e81c..a67f26bf2 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -316,12 +316,57 @@ struct TriangulationParameters { _landmarkDistanceThreshold), dynamicOutlierRejectionThreshold( _dynamicOutlierRejectionThreshold) { } + + // stream to output + friend std::ostream &operator<<(std::ostream &os, + const TriangulationParameters& p) { + os << "rankTolerance = " << p.rankTolerance << std::endl; + os << "enableEPI = " << p.enableEPI << std::endl; + os << "landmarkDistanceThreshold = " << p.landmarkDistanceThreshold + << std::endl; + os << "dynamicOutlierRejectionThreshold = " + << p.dynamicOutlierRejectionThreshold << std::endl; + return os; + } }; -struct TriangulationResult { - Point3 point; - bool degenerate; - bool cheiralityException; +/** + * TriangulationResult is an optional point, along with the reasons why it is invalid. + */ +class TriangulationResult: public boost::optional { + enum Status { + VALID, DEGENERATE, BEHIND_CAMERA + }; + Status status_; + TriangulationResult(Status s) : + status_(s) { + } +public: + TriangulationResult(const Point3& p) : + status_(VALID) { + reset(p); + } + static TriangulationResult Degenerate() { + return TriangulationResult(DEGENERATE); + } + static TriangulationResult BehindCamera() { + return TriangulationResult(BEHIND_CAMERA); + } + bool degenerate() const { + return status_ == DEGENERATE; + } + bool behindCamera() const { + return status_ == BEHIND_CAMERA; + } + // stream to output + friend std::ostream &operator<<(std::ostream &os, + const TriangulationResult& result) { + if (result) + os << "point = " << *result << std::endl; + else + os << "no point, status = " << result.status_ << std::endl; + return os; + } }; /// triangulateSafe: extensive checking of the outcome @@ -330,62 +375,53 @@ TriangulationResult triangulateSafe(const std::vector& cameras, const std::vector& measured, const TriangulationParameters& params) { - TriangulationResult result; - size_t m = cameras.size(); // if we have a single pose the corresponding factor is uninformative - if (m < 2) { - result.degenerate = true; - return result; - } + if (m < 2) + return TriangulationResult::Degenerate(); + else + // We triangulate the 3D position of the landmark + try { + Point3 point = triangulatePoint3(cameras, measured, + params.rankTolerance, params.enableEPI); - // We triangulate the 3D position of the landmark - try { - // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - result.point = triangulatePoint3(cameras, measured, - params.rankTolerance, params.enableEPI); - result.degenerate = false; - result.cheiralityException = false; + // Check landmark distance and reprojection errors to avoid outliers + size_t i = 0; + double totalReprojError = 0.0; + BOOST_FOREACH(const CAMERA& camera, cameras) { + // we discard smart factors corresponding to points that are far away + Point3 cameraTranslation = camera.pose().translation(); + if (cameraTranslation.distance(point) > params.landmarkDistanceThreshold) + return TriangulationResult::Degenerate(); + // Also flag if point is behind any of the cameras + try { + const Point2& zi = measured.at(i); + Point2 reprojectionError(camera.project(point) - zi); + totalReprojError += reprojectionError.vector().norm(); + } catch (CheiralityException) { + return TriangulationResult::BehindCamera(); + } + i += 1; + } + // we discard smart factors that have large reprojection error + if (params.dynamicOutlierRejectionThreshold > 0 + && totalReprojError / m > params.dynamicOutlierRejectionThreshold) + return TriangulationResult::Degenerate(); - // Check landmark distance and reprojection errors to avoid outliers - double totalReprojError = 0.0; - size_t i = 0; - BOOST_FOREACH(const CAMERA& camera, cameras) { - Point3 cameraTranslation = camera.pose().translation(); - // we discard smart factors corresponding to points that are far away - if (cameraTranslation.distance(result.point) - > params.landmarkDistanceThreshold) { - result.degenerate = true; - break; - } - const Point2& zi = measured.at(i); - try { - Point2 reprojectionError(camera.project(result.point) - zi); - totalReprojError += reprojectionError.vector().norm(); - } catch (CheiralityException) { - result.cheiralityException = true; - } - i += 1; + // all good! + return TriangulationResult(point); + } catch (TriangulationUnderconstrainedException&) { + // if TriangulationUnderconstrainedException can be + // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before + // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) + // in the second case we want to use a rotation-only smart factor + return TriangulationResult::Degenerate(); + } catch (TriangulationCheiralityException&) { + // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers + // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint + return TriangulationResult::BehindCamera(); } - // we discard smart factors that have large reprojection error - if (params.dynamicOutlierRejectionThreshold > 0 - && totalReprojError / m > params.dynamicOutlierRejectionThreshold) - result.degenerate = true; - - } catch (TriangulationUnderconstrainedException&) { - // if TriangulationUnderconstrainedException can be - // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before - // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) - // in the second case we want to use a rotation-only smart factor - result.degenerate = true; - result.cheiralityException = false; - } catch (TriangulationCheiralityException&) { - // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers - // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint - result.cheiralityException = true; - } - return result; } } // \namespace gtsam From bc6069a94bc8eeb3f6ced3eca7f42349c0b8ef14 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 12:06:26 +0100 Subject: [PATCH 055/173] Now using TriangulationResult --- gtsam/slam/SmartProjectionFactor.h | 355 +++++++++-------------------- 1 file changed, 105 insertions(+), 250 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 5b061f612..13d17f683 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -35,14 +35,8 @@ namespace gtsam { * Structure for storing some state memory, used to speed up optimization * @addtogroup SLAM */ -class SmartProjectionFactorState { +struct SmartProjectionFactorState { -protected: - -public: - - SmartProjectionFactorState() { - } // Hessian representation (after Schur complement) bool calculatedHessian; Matrix H; @@ -68,38 +62,31 @@ private: protected: - // Some triangulation parameters - const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ + /// @name Caching triangulation + /// @{ + const TriangulationParameters parameters_; + mutable TriangulationResult result_; ///< result from triangulateSafe + const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses + /// @} + /// @name Parameters governing how triangulation result is treated + /// @{ const bool manageDegeneracy_; ///< if set to true will use the rotation-only version for degenerate cases + const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) + const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) + /// @} - const bool enableEPI_; ///< if set to true, will refine triangulation using LM + /// @name Caching linearization + /// @{ + /// shorthand for smart projection factor state variable + typedef boost::shared_ptr SmartFactorStatePtr; + SmartFactorStatePtr state_; ///< cached linearization const double linearizationThreshold_; ///< threshold to decide whether to re-linearize mutable std::vector cameraPosesLinearization_; ///< current linearization poses - - mutable Point3 point_; ///< Current estimate of the 3D point - - mutable bool degenerate_; - mutable bool cheiralityException_; - - // verbosity handling for Cheirality Exceptions - const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) - const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) - - boost::shared_ptr state_; - - /// shorthand for smart projection factor state variable - typedef boost::shared_ptr SmartFactorStatePtr; - - double landmarkDistanceThreshold_; // if the landmark is triangulated at a - // distance larger than that the factor is considered degenerate - - double dynamicOutlierRejectionThreshold_; // if this is nonnegative the factor will check if the - // average reprojection error is smaller than this threshold after triangulation, - // and the factor is disregarded if the error is large + /// @} public: @@ -117,17 +104,18 @@ public: * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations */ - SmartProjectionFactor(const double rankTol, const double linThreshold, + SmartProjectionFactor(const double rankTolerance, const double linThreshold, const bool manageDegeneracy, const bool enableEPI, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1, SmartFactorStatePtr state = SmartFactorStatePtr(new SmartProjectionFactorState())) : - rankTolerance_(rankTol), retriangulationThreshold_(1e-5), manageDegeneracy_( - manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( - linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( - false), verboseCheirality_(false), state_(state), landmarkDistanceThreshold_( - landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( - dynamicOutlierRejectionThreshold) { + parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, + dynamicOutlierRejectionThreshold), // + result_(TriangulationResult::Degenerate()), // + retriangulationThreshold_(1e-5), // + manageDegeneracy_(manageDegeneracy), // + throwCheirality_(false), verboseCheirality_(false), // + state_(state), linearizationThreshold_(linThreshold) { } /** Virtual destructor */ @@ -141,24 +129,23 @@ public: */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "SmartProjectionFactor, z = \n"; - std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; - std::cout << "degenerate_ = " << degenerate_ << std::endl; - std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; + std::cout << s << "SmartProjectionFactor\n"; + std::cout << "triangulationParameters:\n" << parameters_ << std::endl; + std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); } - /// Check if the new linearization point_ is the same as the one used for previous triangulation + /// Check if the new linearization point is the same as the one used for previous triangulation bool decideIfTriangulate(const Cameras& cameras) const { - // several calls to linearize will be done from the same linearization point_, hence it is not needed to re-triangulate + // several calls to linearize will be done from the same linearization point, hence it is not needed to re-triangulate // Note that this is not yet "selecting linearization", that will come later, and we only check if the - // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point_ + // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point size_t m = cameras.size(); bool retriangulate = false; - // if we do not have a previous linearization point_ or the new linearization point_ includes more poses + // if we do not have a previous linearization point or the new linearization point includes more poses if (cameraPosesTriangulation_.empty() || cameras.size() != cameraPosesTriangulation_.size()) retriangulate = true; @@ -181,19 +168,19 @@ public: cameraPosesTriangulation_.push_back(cameras[i].pose()); } - return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation + return retriangulate; // if we arrive to this point all poses are the same and we don't need re-triangulation } - /// This function checks if the new linearization point_ is 'close' to the previous one used for linearization + /// This function checks if the new linearization point is 'close' to the previous one used for linearization bool decideIfLinearize(const Cameras& cameras) const { // "selective linearization" // The function evaluates how close are the old and the new poses, transformed in the ref frame of the first pose // (we only care about the "rigidity" of the poses, not about their absolute pose) - if (this->linearizationThreshold_ < 0) //by convention if linearizationThreshold is negative we always relinearize + if (linearizationThreshold_ < 0) //by convention if linearizationThreshold is negative we always relinearize return true; - // if we do not have a previous linearization point_ or the new linearization point_ includes more poses + // if we do not have a previous linearization point or the new linearization point includes more poses if (cameraPosesLinearization_.empty() || (cameras.size() != cameraPosesLinearization_.size())) return true; @@ -211,100 +198,29 @@ public: Pose3 localCameraPose = firstCameraPose.between(cameras[i].pose()); Pose3 localCameraPoseOld = firstCameraPoseOld.between( cameraPosesLinearization_[i]); - if (!localCameraPose.equals(localCameraPoseOld, - this->linearizationThreshold_)) + if (!localCameraPose.equals(localCameraPoseOld, linearizationThreshold_)) return true; // at least two "relative" poses are different, hence we re-linearize } - return false; // if we arrive to this point_ all poses are the same and we don't need re-linearize + return false; // if we arrive to this point all poses are the same and we don't need re-linearize } /// triangulateSafe - size_t triangulateSafe(const Values& values) const { - return triangulateSafe(this->cameras(values)); - } - - /// triangulateSafe - size_t triangulateSafe(const Cameras& cameras) const { + TriangulationResult triangulateSafe(const Cameras& cameras) const { size_t m = cameras.size(); - if (m < 2) { // if we have a single pose the corresponding factor is uninformative - degenerate_ = true; - return m; - } + if (m < 2) // if we have a single pose the corresponding factor is uninformative + return TriangulationResult::Degenerate(); + bool retriangulate = decideIfTriangulate(cameras); - - if (retriangulate) { - // We triangulate the 3D position of the landmark - try { - // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - point_ = triangulatePoint3(cameras, this->measured_, - rankTolerance_, enableEPI_); - degenerate_ = false; - cheiralityException_ = false; - - // Check landmark distance and reprojection errors to avoid outliers - double totalReprojError = 0.0; - size_t i = 0; - BOOST_FOREACH(const CAMERA& camera, cameras) { - Point3 cameraTranslation = camera.pose().translation(); - // we discard smart factors corresponding to points that are far away - if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { - degenerate_ = true; - break; - } - const Point2& zi = this->measured_.at(i); - try { - Point2 reprojectionError(camera.project(point_) - zi); - totalReprojError += reprojectionError.vector().norm(); - } catch (CheiralityException) { - cheiralityException_ = true; - } - i += 1; - } - // we discard smart factors that have large reprojection error - if (dynamicOutlierRejectionThreshold_ > 0 - && totalReprojError / m > dynamicOutlierRejectionThreshold_) - degenerate_ = true; - - } catch (TriangulationUnderconstrainedException&) { - // if TriangulationUnderconstrainedException can be - // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before - // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) - // in the second case we want to use a rotation-only smart factor - degenerate_ = true; - cheiralityException_ = false; - } catch (TriangulationCheiralityException&) { - // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers - // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint - cheiralityException_ = true; - } - } - return m; + if (retriangulate) + result_ = gtsam::triangulateSafe(cameras, this->measured_, parameters_); + return result_; } /// triangulate bool triangulateForLinearize(const Cameras& cameras) const { - - bool isDebug = false; - size_t nrCameras = this->triangulateSafe(cameras); - - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { - if (isDebug) { - std::cout - << "createRegularImplicitSchurFactor: degenerate configuration" - << std::endl; - } - return false; - } else { - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - } - return true; - } + triangulateSafe(cameras); // imperative, might reset result_ + return (manageDegeneracy_ || result_); } /// linearize returns a Hessianfactor that is an approximation of error(p) @@ -324,12 +240,10 @@ public: exit(1); } - this->triangulateSafe(cameras); + triangulateSafe(cameras); - if (numKeys < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { - // std::cout << "In linearize: exception" << std::endl; + if (!manageDegeneracy_ && !result_) { + // put in "empty" Hessian BOOST_FOREACH(Matrix& m, Gs) m = zeros(Base::Dim, Base::Dim); BOOST_FOREACH(Vector& v, gs) @@ -338,23 +252,19 @@ public: Gs, gs, 0.0); } - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - } - + // decide whether to re-linearize bool doLinearize = this->decideIfLinearize(cameras); - if (this->linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize + if (linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize for (size_t i = 0; i < cameras.size(); i++) this->cameraPosesLinearization_[i] = cameras[i].pose(); if (!doLinearize) { // return the previous Hessian factor std::cout << "=============================" << std::endl; std::cout << "doLinearize " << doLinearize << std::endl; - std::cout << "this->linearizationThreshold_ " - << this->linearizationThreshold_ << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; + std::cout << "linearizationThreshold_ " << linearizationThreshold_ + << std::endl; + std::cout << "valid: " << isValid() << std::endl; std::cout << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" << std::endl; @@ -404,7 +314,7 @@ public: } } // ================================================================== - if (this->linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables + if (linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables this->state_->Gs = Gs; this->state_->gs = gs; this->state_->f = f; @@ -417,7 +327,7 @@ public: boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) - return Base::createRegularImplicitSchurFactor(cameras, point_, lambda); + return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda); else return boost::shared_ptr >(); } @@ -426,7 +336,7 @@ public: boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) - return Base::createJacobianQFactor(cameras, point_, lambda); + return Base::createJacobianQFactor(cameras, *result_, lambda); else return boost::make_shared >(this->keys_); } @@ -434,63 +344,27 @@ public: /// Create a factor, takes values boost::shared_ptr > createJacobianQFactor( const Values& values, double lambda) const { - Cameras cameras; - // TODO triangulate twice ?? - bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); - if (nonDegenerate) - return createJacobianQFactor(cameras, lambda); - else - return boost::make_shared >(this->keys_); + return createJacobianQFactor(this->cameras(values),lambda); } /// different (faster) way to compute Jacobian factor boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) - return Base::createJacobianSVDFactor(cameras, point_, lambda); + return Base::createJacobianSVDFactor(cameras, *result_, lambda); else return boost::make_shared >(this->keys_); } - /// Returns true if nonDegenerate - bool computeCamerasAndTriangulate(const Values& values, - Cameras& cameras) const { - Values valuesFactor; - - // Select only the cameras - BOOST_FOREACH(const Key key, this->keys_) - valuesFactor.insert(key, values.at(key)); - - cameras = this->cameras(valuesFactor); - size_t nrCameras = this->triangulateSafe(cameras); - - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) - return false; - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - - if (this->degenerate_) { - std::cout << "SmartProjectionFactor: this is not ready" << std::endl; - std::cout << "this->cheiralityException_ " << this->cheiralityException_ - << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; - } - return true; - } - /** * Triangulate and compute derivative of error with respect to point * @return whether triangulation worked */ bool triangulateAndComputeE(Matrix& E, const Values& values) const { - Cameras cameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - cameras.project2(point_, boost::none, E); + cameras.project2(*result_, boost::none, E); return nonDegenerate; } @@ -501,31 +375,18 @@ public: std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras) const { - if (this->degenerate_) { - std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl; - std::cout << "point " << point_ << std::endl; - std::cout - << "SmartProjectionFactor: Management of degeneracy is disabled - not ready to be used" - << std::endl; - if (Base::Dim > 6) { - std::cout - << "Management of degeneracy is not yet ready when one also optimizes for the calibration " - << std::endl; - } - + if (!result_) { + // TODO Luca clarify whether this works or not + result_ = TriangulationResult( + cameras[0].backprojectPointAtInfinity(this->measured_.at(0))); // TODO replace all this by Call to CameraSet int m = this->keys_.size(); E = zeros(2 * m, 2); b = zero(2 * m); double f = 0; for (size_t i = 0; i < this->measured_.size(); i++) { - if (i == 0) { // first pose - this->point_ = cameras[i].backprojectPointAtInfinity( - this->measured_.at(i)); - // 3D parametrization of point at infinity: [px py 1] - } Matrix Fi, Ei; - Vector bi = -(cameras[i].projectPointAtInfinity(this->point_, Fi, Ei) + Vector bi = -(cameras[i].projectPointAtInfinity(*result_, Fi, Ei) - this->measured_.at(i)).vector(); f += bi.squaredNorm(); @@ -535,17 +396,17 @@ public: } return f; } else { - // nondegenerate: just return Base version - return Base::computeJacobians(Fblocks, E, b, cameras, point_); - } // end else + // valid result: just return Base version + return Base::computeJacobians(Fblocks, E, b, cameras, *result_); + } } /// Version that takes values, and creates the point bool triangulateAndComputeJacobians( std::vector& Fblocks, Matrix& E, Vector& b, const Values& values) const { - Cameras cameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); return nonDegenerate; @@ -555,19 +416,19 @@ public: bool triangulateAndComputeJacobiansSVD( std::vector& Fblocks, Matrix& Enull, Vector& b, const Values& values) const { - typename Base::Cameras cameras; - double good = computeCamerasAndTriangulate(values, cameras); - if (good) - Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_); - return true; + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); + if (nonDegenerate) + Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, *result_); + return nonDegenerate; } /// Calculate vector of re-projection errors, before applying noise model Vector reprojectionErrorAfterTriangulation(const Values& values) const { - Cameras cameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - return Base::reprojectionError(cameras, point_); + return Base::reprojectionError(cameras, *result_); else return zero(cameras.size() * 2); } @@ -581,65 +442,59 @@ public: double totalReprojectionError(const Cameras& cameras, boost::optional externalPoint = boost::none) const { - size_t nrCameras; - if (externalPoint) { - nrCameras = this->keys_.size(); - point_ = *externalPoint; - degenerate_ = false; - cheiralityException_ = false; - } else { - nrCameras = this->triangulateSafe(cameras); - } + if (externalPoint) + result_ = TriangulationResult(*externalPoint); - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { - // if we don't want to manage the exceptions we discard the factor - // std::cout << "In error evaluation: exception" << std::endl; + // if we don't want to manage the exceptions we discard the factor + if (!manageDegeneracy_ && !result_) return 0.0; - } - if (this->cheiralityException_) { // if we want to manage the exceptions with rotation-only factors + if (isPointBehindCamera()) { // if we want to manage the exceptions with rotation-only factors std::cout << "SmartProjectionHessianFactor: cheirality exception (this should not happen if CheiralityException is disabled)!" << std::endl; - this->degenerate_ = true; } - if (this->degenerate_) { + if (isDegenerate()) { // return 0.0; // TODO: this maybe should be zero? std::cout << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" << std::endl; // 3D parameterization of point at infinity - const Point2& zi = this->measured_.at(0); - this->point_ = cameras.front().backprojectPointAtInfinity(zi); - return Base::totalReprojectionErrorAtInfinity(cameras, this->point_); + const Point2& z0 = this->measured_.at(0); + result_ = TriangulationResult( + cameras.front().backprojectPointAtInfinity(z0)); + return Base::totalReprojectionErrorAtInfinity(cameras, *result_); } else { // Just use version in base class - return Base::totalReprojectionError(cameras, point_); + return Base::totalReprojectionError(cameras, *result_); } } /** return the landmark */ - boost::optional point() const { - return point_; + TriangulationResult point() const { + return result_; } /** COMPUTE the landmark */ - boost::optional point(const Values& values) const { - triangulateSafe(values); - return point_; + TriangulationResult point(const Values& values) const { + Cameras cameras = this->cameras(values); + return triangulateSafe(cameras); + } + + /// Is result valid? + inline bool isValid() const { + return result_; } /** return the degenerate state */ inline bool isDegenerate() const { - return (cheiralityException_ || degenerate_); + return result_.degenerate(); } /** return the cheirality status flag */ inline bool isPointBehindCamera() const { - return cheiralityException_; + return result_.behindCamera(); } /** return cheirality verbosity */ From 2cc0223624fc6b33bc74264ad6e1d850de38dda8 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 12:06:46 +0100 Subject: [PATCH 056/173] Made tests compile with TriangulationResult changes --- .../tests/testSmartProjectionCameraFactor.cpp | 96 ++++++------------- .../tests/testSmartProjectionPoseFactor.cpp | 2 +- 2 files changed, 29 insertions(+), 69 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index ba7b7bf51..750751935 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -27,7 +27,7 @@ using namespace boost::assign; -static bool isDebugTest = false; +static bool isDebugTest = true; static double rankTol = 1.0; static double linThreshold = -1.0; @@ -133,9 +133,8 @@ TEST( SmartProjectionCameraFactor, noisy ) { using namespace vanilla; - // 1. Project two landmarks into two cameras and triangulate - Point2 pixelError(0.2, 0.2); - Point2 level_uv = level_camera.project(landmark1) + pixelError; + // Project one landmark into two cameras and add noise on first + Point2 level_uv = level_camera.project(landmark1) + Point2(0.2, 0.2); Point2 level_uv_right = level_camera_right.project(landmark1); Values values; @@ -165,7 +164,6 @@ TEST( SmartProjectionCameraFactor, noisy ) { factor2->add(measurements, views, noises); double actualError2 = factor2->error(values); - DOUBLES_EQUAL(actualError1, actualError2, 1e-7); } @@ -174,68 +172,58 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { using namespace vanilla; + // Project three landmarks into three cameras vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + // Create and fill smartfactors + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); vector views; views.push_back(c1); views.push_back(c2); views.push_back(c3); - - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); smartFactor1->add(measurements_cam1, views, unit2); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); smartFactor2->add(measurements_cam2, views, unit2); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); smartFactor3->add(measurements_cam3, views, unit2); - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); - + // Create factor graph and add priors on two cameras NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); graph.push_back(PriorFactor(c1, cam1, noisePrior)); graph.push_back(PriorFactor(c2, cam2, noisePrior)); - Values values; - values.insert(c1, cam1); - values.insert(c2, cam2); - values.insert(c3, perturbCameraPose(cam3)); + // Create initial estimate + Values initialEstimate; + initialEstimate.insert(c1, cam1); + initialEstimate.insert(c2, cam2); + initialEstimate.insert(c3, perturbCameraPose(cam3)); if (isDebugTest) - values.at(c3).print("Smart: Pose3 before optimization: "); + initialEstimate.at(c3).print("Smart: Pose3 before optimization: "); + // Optimize LevenbergMarquardtParams params; - if (isDebugTest) + if (isDebugTest) { params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + } + LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, params); + Values result = optimizer.optimize(); - Values result; - gttic_(SmartProjectionCameraFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionCameraFactor); - tictoc_finishedIteration_(); - - // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(initialEstimate); // VectorValues delta = GFG->optimize(); if (isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1))); EXPECT(assert_equal(cam2, result.at(c2))); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); - EXPECT( - assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); - if (isDebugTest) - tictoc_print_(); + EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); } /* *************************************************************************/ @@ -243,8 +231,8 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { using namespace vanilla; + // Project three landmarks into three cameras vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -300,11 +288,8 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionCameraFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionCameraFactor); - tictoc_finishedIteration_(); // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); // VectorValues delta = GFG->optimize(); @@ -313,11 +298,7 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1))); EXPECT(assert_equal(cam2, result.at(c2))); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); - EXPECT( - assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); - if (isDebugTest) - tictoc_print_(); + EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); } /* *************************************************************************/ @@ -383,11 +364,8 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionCameraFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionCameraFactor); - tictoc_finishedIteration_(); // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); // VectorValues delta = GFG->optimize(); @@ -396,11 +374,7 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1))); EXPECT(assert_equal(cam2, result.at(c2))); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); - EXPECT( - assert_equal(result.at(c3).calibration(), cam3.calibration(), 20)); - if (isDebugTest) - tictoc_print_(); + EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); } /* *************************************************************************/ @@ -465,21 +439,14 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionCameraFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionCameraFactor); - tictoc_finishedIteration_(); if (isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); - EXPECT( - assert_equal(result.at(c3).calibration(), cam3.calibration(), 1)); - if (isDebugTest) - tictoc_print_(); + EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); } /* *************************************************************************/ @@ -544,21 +511,14 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionCameraFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionCameraFactor); - tictoc_finishedIteration_(); if (isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); - EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); - EXPECT( - assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); - if (isDebugTest) - tictoc_print_(); + EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); } /* *************************************************************************/ diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index b235d8e2b..d03db7ab1 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -289,7 +289,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { cameras.push_back(cam2); // Make sure triangulation works - LONGS_EQUAL(2, smartFactor1->triangulateSafe(cameras)); + CHECK(smartFactor1->triangulateSafe(cameras)); CHECK(!smartFactor1->isDegenerate()); CHECK(!smartFactor1->isPointBehindCamera()); boost::optional p = smartFactor1->point(); From 47ea3834dfe3e03f5a14131658b9a9a6241b112e Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 13:13:31 +0100 Subject: [PATCH 057/173] Extra tests --- .../tests/testSmartProjectionCameraFactor.cpp | 48 ++++++++++++++++++- 1 file changed, 46 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index ba7b7bf51..4a27f7724 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -147,7 +147,24 @@ TEST( SmartProjectionCameraFactor, noisy ) { factor1->add(level_uv, c1, unit2); factor1->add(level_uv_right, c2, unit2); + // check point before triangulation + EXPECT(factor1->point()); + EXPECT(assert_equal(Point3(),*factor1->point(), 1e-7)); + + double expectedError = 58640; double actualError1 = factor1->error(values); + EXPECT_DOUBLES_EQUAL(expectedError, actualError1, 1); + + // Check triangulated point + EXPECT(assert_equal(Point3(13.7587, 1.43851, -1.14274),*factor1->point(), 1e-4)); + + // Check whitened errors + Vector expected(4); + expected << -7, 235, 58, -242; + SmartFactor::Cameras cameras1 = factor1->cameras(values); + Point3 point1 = *factor1->point(); + Vector actual = factor1->whitenedErrors(cameras1, point1); + EXPECT(assert_equal(expected, actual, 1)); SmartFactor::shared_ptr factor2(new SmartFactor()); vector measurements; @@ -165,8 +182,7 @@ TEST( SmartProjectionCameraFactor, noisy ) { factor2->add(measurements, views, noises); double actualError2 = factor2->error(values); - - DOUBLES_EQUAL(actualError1, actualError2, 1e-7); + EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1); } /* *************************************************************************/ @@ -211,6 +227,30 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { if (isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); + EXPECT(smartFactor1->point()); + EXPECT(smartFactor2->point()); + EXPECT(smartFactor3->point()); + + EXPECT(assert_equal(Point3(),*smartFactor1->point(), 1e-7)); + EXPECT(assert_equal(Point3(),*smartFactor2->point(), 1e-7)); + EXPECT(assert_equal(Point3(),*smartFactor3->point(), 1e-7)); + + EXPECT_DOUBLES_EQUAL(75711, smartFactor1->error(values), 1); + EXPECT_DOUBLES_EQUAL(58524, smartFactor2->error(values), 1); + EXPECT_DOUBLES_EQUAL(77564, smartFactor3->error(values), 1); + + EXPECT(assert_equal(Point3(2.57696, -0.182566, 1.04085),*smartFactor1->point(), 1e-4)); + EXPECT(assert_equal(Point3(2.80114, -0.702153, 1.06594),*smartFactor2->point(), 1e-4)); + EXPECT(assert_equal(Point3(1.82593, -0.289569, 2.13438),*smartFactor3->point(), 1e-4)); + + // Check whitened errors + Vector expected(6); + expected << 256, 29, -26, 29, -206, -202; + SmartFactor::Cameras cameras1 = smartFactor1->cameras(values); + Point3 point1 = *smartFactor1->point(); + Vector actual = smartFactor1->whitenedErrors(cameras1, point1); + EXPECT(assert_equal(expected, actual, 1)); + LevenbergMarquardtParams params; if (isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; @@ -224,6 +264,10 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { gttoc_(SmartProjectionCameraFactor); tictoc_finishedIteration_(); + EXPECT(assert_equal(landmark1,*smartFactor1->point(), 1e-7)); + EXPECT(assert_equal(landmark2,*smartFactor2->point(), 1e-7)); + EXPECT(assert_equal(landmark3,*smartFactor3->point(), 1e-7)); + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); // VectorValues delta = GFG->optimize(); From e15231fb3ed49ac6b452c371af722f73b952d81b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 13:48:17 +0100 Subject: [PATCH 058/173] Fixed bug (restored omitted triangulateSafe call) --- gtsam/slam/SmartProjectionFactor.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 13d17f683..4c0d1f4a2 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -344,7 +344,7 @@ public: /// Create a factor, takes values boost::shared_ptr > createJacobianQFactor( const Values& values, double lambda) const { - return createJacobianQFactor(this->cameras(values),lambda); + return createJacobianQFactor(this->cameras(values), lambda); } /// different (faster) way to compute Jacobian factor @@ -444,6 +444,8 @@ public: if (externalPoint) result_ = TriangulationResult(*externalPoint); + else + result_ = triangulateSafe(cameras); // if we don't want to manage the exceptions we discard the factor if (!manageDegeneracy_ && !result_) From 754e8447b16c553f63bbb08b145725019cfc0637 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 13:48:47 +0100 Subject: [PATCH 059/173] Made tests compile and succeed --- .../tests/testSmartProjectionCameraFactor.cpp | 82 +++++++++++-------- 1 file changed, 48 insertions(+), 34 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 782f31c49..a4ed72f4b 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -27,7 +27,7 @@ using namespace boost::assign; -static bool isDebugTest = true; +static bool isDebugTest = false; static double rankTol = 1.0; static double linThreshold = -1.0; @@ -146,15 +146,15 @@ TEST( SmartProjectionCameraFactor, noisy ) { factor1->add(level_uv, c1, unit2); factor1->add(level_uv_right, c2, unit2); - // check point before triangulation - EXPECT(factor1->point()); - EXPECT(assert_equal(Point3(),*factor1->point(), 1e-7)); + // Point is now uninitialized before a triangulation event + EXPECT(!factor1->point()); double expectedError = 58640; double actualError1 = factor1->error(values); EXPECT_DOUBLES_EQUAL(expectedError, actualError1, 1); // Check triangulated point + CHECK(factor1->point()); EXPECT(assert_equal(Point3(13.7587, 1.43851, -1.14274),*factor1->point(), 1e-4)); // Check whitened errors @@ -217,24 +217,26 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { graph.push_back(PriorFactor(c2, cam2, noisePrior)); // Create initial estimate - Values initialEstimate; - initialEstimate.insert(c1, cam1); - initialEstimate.insert(c2, cam2); - initialEstimate.insert(c3, perturbCameraPose(cam3)); + Values initial; + initial.insert(c1, cam1); + initial.insert(c2, cam2); + initial.insert(c3, perturbCameraPose(cam3)); if (isDebugTest) - initialEstimate.at(c3).print("Smart: Pose3 before optimization: "); + initial.at(c3).print("Smart: Pose3 before optimization: "); - EXPECT(smartFactor1->point()); - EXPECT(smartFactor2->point()); - EXPECT(smartFactor3->point()); + // Points are now uninitialized before a triangulation event + EXPECT(!smartFactor1->point()); + EXPECT(!smartFactor2->point()); + EXPECT(!smartFactor3->point()); - EXPECT(assert_equal(Point3(),*smartFactor1->point(), 1e-7)); - EXPECT(assert_equal(Point3(),*smartFactor2->point(), 1e-7)); - EXPECT(assert_equal(Point3(),*smartFactor3->point(), 1e-7)); + EXPECT_DOUBLES_EQUAL(75711, smartFactor1->error(initial), 1); + EXPECT_DOUBLES_EQUAL(58524, smartFactor2->error(initial), 1); + EXPECT_DOUBLES_EQUAL(77564, smartFactor3->error(initial), 1); - EXPECT_DOUBLES_EQUAL(75711, smartFactor1->error(values), 1); - EXPECT_DOUBLES_EQUAL(58524, smartFactor2->error(values), 1); - EXPECT_DOUBLES_EQUAL(77564, smartFactor3->error(values), 1); + // Error should trigger this and initialize the points, abort if not so + CHECK(smartFactor1->point()); + CHECK(smartFactor2->point()); + CHECK(smartFactor3->point()); EXPECT(assert_equal(Point3(2.57696, -0.182566, 1.04085),*smartFactor1->point(), 1e-4)); EXPECT(assert_equal(Point3(2.80114, -0.702153, 1.06594),*smartFactor2->point(), 1e-4)); @@ -243,7 +245,7 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { // Check whitened errors Vector expected(6); expected << 256, 29, -26, 29, -206, -202; - SmartFactor::Cameras cameras1 = smartFactor1->cameras(values); + SmartFactor::Cameras cameras1 = smartFactor1->cameras(initial); Point3 point1 = *smartFactor1->point(); Vector actual = smartFactor1->whitenedErrors(cameras1, point1); EXPECT(assert_equal(expected, actual, 1)); @@ -254,29 +256,25 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; params.verbosity = NonlinearOptimizerParams::ERROR; } - LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, params); + LevenbergMarquardtOptimizer optimizer(graph, initial, params); Values result = optimizer.optimize(); - - Values result; - gttic_(SmartProjectionCameraFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionCameraFactor); - tictoc_finishedIteration_(); - EXPECT(assert_equal(landmark1,*smartFactor1->point(), 1e-7)); EXPECT(assert_equal(landmark2,*smartFactor2->point(), 1e-7)); EXPECT(assert_equal(landmark3,*smartFactor3->point(), 1e-7)); - // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(initial); // VectorValues delta = GFG->optimize(); if (isDebugTest) result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1))); EXPECT(assert_equal(cam2, result.at(c2))); - EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ @@ -351,7 +349,11 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1))); EXPECT(assert_equal(cam2, result.at(c2))); - EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ @@ -427,7 +429,11 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1))); EXPECT(assert_equal(cam2, result.at(c2))); - EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 20)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ @@ -499,7 +505,11 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); - EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 1)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ @@ -571,7 +581,11 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { result.at(c3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); - EXPECT(assert_equal(cam3, result.at(c3), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); } /* *************************************************************************/ From 8fe612ca719d85918b2c74698f8f8bd17aa4d802 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 14:25:32 +0100 Subject: [PATCH 060/173] whitenJacobians --- gtsam/slam/SmartFactorBase.h | 14 ++++++++++---- gtsam/slam/SmartProjectionFactor.h | 1 + 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 417ba1354..59a267278 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -487,6 +487,15 @@ public: updateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... } + /// Whiten the Jacobians computed by computeJacobians using noiseModel_ + void whitenJacobians(std::vector& F, Matrix& E, + Vector& b) const { + noiseModel_->WhitenSystem(E, b); + // TODO make WhitenInPlace work with any dense matrix type + BOOST_FOREACH(KeyMatrix2D& Fblock,F) + Fblock.second = noiseModel_->Whiten(Fblock.second); + } + /** * Return Jacobians as RegularImplicitSchurFactor with raw access */ @@ -497,11 +506,8 @@ public: Matrix E; Vector b; computeJacobians(F, E, b, cameras, point); - noiseModel_->WhitenSystem(E, b); + whitenJacobians(F, E, b); Matrix3 P = PointCov(E, lambda, diagonalDamping); - // TODO make WhitenInPlace work with any dense matrix type - BOOST_FOREACH(KeyMatrix2D& Fblock,F) - Fblock.second = noiseModel_->Whiten(Fblock.second); return boost::make_shared >(F, E, P, b); } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 4c0d1f4a2..51f892a6d 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -280,6 +280,7 @@ public: { std::vector Fblocks; f = computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + Base::whitenJacobians(Fblocks,E,b); Base::FillDiagonalF(Fblocks, F); // expensive ! } From 575a06b0427aafa40d6d38d9dd0b7344092ce60f Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 14:27:37 +0100 Subject: [PATCH 061/173] Added my name --- gtsam/slam/SmartProjectionCameraFactor.h | 1 + gtsam/slam/tests/testSmartProjectionCameraFactor.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/gtsam/slam/SmartProjectionCameraFactor.h b/gtsam/slam/SmartProjectionCameraFactor.h index f10681ab8..3afd04188 100644 --- a/gtsam/slam/SmartProjectionCameraFactor.h +++ b/gtsam/slam/SmartProjectionCameraFactor.h @@ -15,6 +15,7 @@ * @author Luca Carlone * @author Chris Beall * @author Zsolt Kira + * @author Frank Dellaert */ #pragma once diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index a4ed72f4b..56ff47c3e 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -15,6 +15,7 @@ * @author Chris Beall * @author Luca Carlone * @author Zsolt Kira + * @author Frank Dellaert * @date Sept 2013 */ From 6a024259e59826ca0d88ef43bd1728c8bc99597b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 14:28:13 +0100 Subject: [PATCH 062/173] Switched to (i,j) instead of (i1,i2) --- gtsam/slam/SmartFactorBase.h | 73 +++++++++---------- .../tests/testSmartProjectionPoseFactor.cpp | 1 + 2 files changed, 36 insertions(+), 38 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 59a267278..5a757d998 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -367,28 +367,27 @@ public: size_t numKeys = this->keys_.size(); // Blockwise Schur complement - for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera + for (size_t i = 0; i < numKeys; i++) { // for each camera - const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; + const Matrix2D& Fi = Fblocks.at(i).second; + const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; // Dim = (Dx2) * (2) - // (augmentedHessian.matrix()).block (i1,numKeys+1) = Fi1.transpose() * b.segment < 2 > (2 * i1); // F' * b - augmentedHessian(i1, numKeys) = Fi1.transpose() - * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + // (augmentedHessian.matrix()).block (i,numKeys+1) = Fi.transpose() * b.segment < 2 > (2 * i); // F' * b + augmentedHessian(i, numKeys) = Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - augmentedHessian(i1, i1) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1); + augmentedHessian(i, i) = Fi.transpose() + * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi); // upper triangular part of the hessian - for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera - const Matrix2D& Fi2 = Fblocks.at(i2).second; + for (size_t j = i + 1; j < numKeys; j++) { // for each camera + const Matrix2D& Fj = Fblocks.at(j).second; // (DxD) = (Dx2) * ( (2x2) * (2xD) ) - augmentedHessian(i1, i2) = -Fi1.transpose() - * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); + augmentedHessian(i, j) = -Fi.transpose() + * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); } } // end of for over cameras } @@ -417,50 +416,48 @@ public: size_t aug_numKeys = (augmentedHessian.rows() - 1) / Dim; // all cameras in the group // Blockwise Schur complement - for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera in the current factor + for (size_t i = 0; i < numKeys; i++) { // for each camera in the current factor - const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; + const Matrix2D& Fi = Fblocks.at(i).second; + const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; // Dim = (DxZDim) * (ZDim) // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) - // Key cameraKey_i1 = this->keys_[i1]; - DenseIndex aug_i1 = KeySlotMap[this->keys_[i1]]; + // Key cameraKey_i = this->keys_[i]; + DenseIndex aug_i = KeySlotMap[this->keys_[i]]; // information vector - store previous vector - // vectorBlock = augmentedHessian(aug_i1, aug_numKeys).knownOffDiagonal(); + // vectorBlock = augmentedHessian(aug_i, aug_numKeys).knownOffDiagonal(); // add contribution of current factor - augmentedHessian(aug_i1, aug_numKeys) = augmentedHessian(aug_i1, + augmentedHessian(aug_i, aug_numKeys) = augmentedHessian(aug_i, aug_numKeys).knownOffDiagonal() - + Fi1.transpose() * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + + Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) // main block diagonal - store previous block - matrixBlock = augmentedHessian(aug_i1, aug_i1); + matrixBlock = augmentedHessian(aug_i, aug_i); // add contribution of current factor - augmentedHessian(aug_i1, aug_i1) = - matrixBlock - + (Fi1.transpose() - * (Fi1 - - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1)); + augmentedHessian(aug_i, aug_i) = matrixBlock + + (Fi.transpose() + * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi)); // upper triangular part of the hessian - for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera - const Matrix2D& Fi2 = Fblocks.at(i2).second; + for (size_t j = i + 1; j < numKeys; j++) { // for each camera + const Matrix2D& Fj = Fblocks.at(j).second; - //Key cameraKey_i2 = this->keys_[i2]; - DenseIndex aug_i2 = KeySlotMap[this->keys_[i2]]; + //Key cameraKey_j = this->keys_[j]; + DenseIndex aug_j = KeySlotMap[this->keys_[j]]; // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) // off diagonal block - store previous block - // matrixBlock = augmentedHessian(aug_i1, aug_i2).knownOffDiagonal(); + // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal(); // add contribution of current factor - augmentedHessian(aug_i1, aug_i2) = - augmentedHessian(aug_i1, aug_i2).knownOffDiagonal() - - Fi1.transpose() - * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); + augmentedHessian(aug_i, aug_j) = + augmentedHessian(aug_i, aug_j).knownOffDiagonal() + - Fi.transpose() + * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); } } // end of for over cameras @@ -484,7 +481,7 @@ public: Vector b; double f = computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - updateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... + updateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, augmentedHessian); // augmentedHessian.matrix().block (i,j) = ... } /// Whiten the Jacobians computed by computeJacobians using noiseModel_ diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index d03db7ab1..0e1c3ff46 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -15,6 +15,7 @@ * @author Chris Beall * @author Luca Carlone * @author Zsolt Kira + * @author Frank Dellaert * @date Sept 2013 */ From cee64e385393f09738f45d23bf14da5df7042ae8 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 14:28:31 +0100 Subject: [PATCH 063/173] Made sure all refer to the same information matrix --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 0e1c3ff46..b0c310a36 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -301,6 +301,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { Matrix16 A1, A2; A1 << -1000, 0, 0, 0, 100, 0; A2 << 1000, 0, 100, 0, -100, 0; + Matrix expectedInformation; // filled below { // createHessianFactor Matrix66 G11 = 0.5 * A1.transpose() * A1; @@ -315,10 +316,11 @@ TEST( SmartProjectionPoseFactor, Factors ) { double f = 0; RegularHessianFactor<6> expected(x1, x2, G11, G12, g1, G22, g2, f); + expectedInformation = expected.information(); boost::shared_ptr > actual = smartFactor1->createHessianFactor(cameras, 0.0); - EXPECT(assert_equal(expected.information(), actual->information(), 1e-8)); + EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); EXPECT(assert_equal(expected, *actual, 1e-8)); } @@ -356,16 +358,19 @@ TEST( SmartProjectionPoseFactor, Factors ) { boost::shared_ptr > actual = smartFactor1->createRegularImplicitSchurFactor(cameras, 0.0); CHECK(actual); + EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); + EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); EXPECT(assert_equal(expected, *actual)); // createJacobianQFactor SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b, n); + EXPECT(assert_equal(expectedInformation, expectedQ.information(), 1e-8)); boost::shared_ptr > actualQ = smartFactor1->createJacobianQFactor(cameras, 0.0); CHECK(actual); - EXPECT(assert_equal(expectedQ.information(), actualQ->information(), 1e-8)); + EXPECT(assert_equal(expectedInformation, actualQ->information(), 1e-8)); EXPECT(assert_equal(expectedQ, *actualQ)); } @@ -375,11 +380,12 @@ TEST( SmartProjectionPoseFactor, Factors ) { b.setZero(); double s = sin(M_PI_4); JacobianFactor expected(x1, s * A1, x2, s * A2, b); + EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); boost::shared_ptr actual = smartFactor1->createJacobianSVDFactor(cameras, 0.0); CHECK(actual); - EXPECT(assert_equal(expected.information(), actual->information(), 1e-8)); + EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); EXPECT(assert_equal(expected, *actual)); } } From b94279f37fbec5b53001ee35fdbf9a9be885f0ba Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 14:35:54 +0100 Subject: [PATCH 064/173] numKeys -> m --- gtsam/slam/SmartFactorBase.h | 43 +++++++++++++++++------------------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 5a757d998..9a53957a5 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -360,21 +360,20 @@ public: const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, /*output ->*/SymmetricBlockMatrix& augmentedHessian) const { // Schur complement trick - // Gs = F' * F - F' * E * P * E' * F - // gs = F' * (b - E * P * E' * b) + // G = F' * F - F' * E * P * E' * F + // g = F' * (b - E * P * E' * b) - // a single point is observed in numKeys cameras - size_t numKeys = this->keys_.size(); + // a single point is observed in m cameras + size_t m = this->keys_.size(); // Blockwise Schur complement - for (size_t i = 0; i < numKeys; i++) { // for each camera + for (size_t i = 0; i < m; i++) { // for each camera const Matrix2D& Fi = Fblocks.at(i).second; const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; // Dim = (Dx2) * (2) - // (augmentedHessian.matrix()).block (i,numKeys+1) = Fi.transpose() * b.segment < 2 > (2 * i); // F' * b - augmentedHessian(i, numKeys) = Fi.transpose() * b.segment(ZDim * i) // F' * b + augmentedHessian(i, m) = Fi.transpose() * b.segment(ZDim * i) // F' * b - Fi.transpose() * (Ei_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) @@ -382,7 +381,7 @@ public: * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi); // upper triangular part of the hessian - for (size_t j = i + 1; j < numKeys; j++) { // for each camera + for (size_t j = i + 1; j < m; j++) { // for each camera const Matrix2D& Fj = Fblocks.at(j).second; // (DxD) = (Dx2) * ( (2x2) * (2xD) ) @@ -411,12 +410,12 @@ public: for (size_t slot = 0; slot < allKeys.size(); slot++) KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); - // a single point is observed in numKeys cameras - size_t numKeys = this->keys_.size(); // cameras observing current point - size_t aug_numKeys = (augmentedHessian.rows() - 1) / Dim; // all cameras in the group + // a single point is observed in m cameras + size_t m = this->keys_.size(); // cameras observing current point + size_t aug_m = (augmentedHessian.rows() - 1) / Dim; // all cameras in the group // Blockwise Schur complement - for (size_t i = 0; i < numKeys; i++) { // for each camera in the current factor + for (size_t i = 0; i < m; i++) { // for each camera in the current factor const Matrix2D& Fi = Fblocks.at(i).second; const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; @@ -428,15 +427,15 @@ public: DenseIndex aug_i = KeySlotMap[this->keys_[i]]; // information vector - store previous vector - // vectorBlock = augmentedHessian(aug_i, aug_numKeys).knownOffDiagonal(); + // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); // add contribution of current factor - augmentedHessian(aug_i, aug_numKeys) = augmentedHessian(aug_i, - aug_numKeys).knownOffDiagonal() - + Fi.transpose() * b.segment(ZDim * i) // F' * b - - Fi.transpose() * (Ei_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + augmentedHessian(aug_i, aug_m) = + augmentedHessian(aug_i, aug_m).knownOffDiagonal() + + Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - // main block diagonal - store previous block + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) + // main block diagonal - store previous block matrixBlock = augmentedHessian(aug_i, aug_i); // add contribution of current factor augmentedHessian(aug_i, aug_i) = matrixBlock @@ -444,7 +443,7 @@ public: * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi)); // upper triangular part of the hessian - for (size_t j = i + 1; j < numKeys; j++) { // for each camera + for (size_t j = i + 1; j < m; j++) { // for each camera const Matrix2D& Fj = Fblocks.at(j).second; //Key cameraKey_j = this->keys_[j]; @@ -461,7 +460,7 @@ public: } } // end of for over cameras - augmentedHessian(aug_numKeys, aug_numKeys)(0, 0) += f; + augmentedHessian(aug_m, aug_m)(0, 0) += f; } /** @@ -474,8 +473,6 @@ public: SymmetricBlockMatrix& augmentedHessian, const FastVector allKeys) const { - // int numKeys = this->keys_.size(); - std::vector Fblocks; Matrix E; Vector b; From d732a01e0376351b340f37828173ee3703b8c550 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 15:03:18 +0100 Subject: [PATCH 065/173] Convert to static functions --- gtsam/slam/SmartFactorBase.h | 43 ++++++++++++++++++++++-------------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 9a53957a5..9542a4067 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -356,15 +356,15 @@ public: * Do Schur complement, given Jacobian as F,E,P, return SymmetricBlockMatrix * Fast version - works on with sparsity */ - void sparseSchurComplement(const std::vector& Fblocks, + static void sparseSchurComplement(const std::vector& Fblocks, const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) const { + /*output ->*/SymmetricBlockMatrix& augmentedHessian) { // Schur complement trick // G = F' * F - F' * E * P * E' * F // g = F' * (b - E * P * E' * b) // a single point is observed in m cameras - size_t m = this->keys_.size(); + size_t m = Fblocks.size(); // Blockwise Schur complement for (size_t i = 0; i < m; i++) { // for each camera @@ -395,23 +395,20 @@ public: * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. */ - void updateSparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - const double f, const FastVector allKeys, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) const { + static void updateSparseSchurComplement( + const std::vector& Fblocks, const Matrix& E, + const Matrix3& P /*Point Covariance*/, const Vector& b, const double f, + const FastVector& keys, const FastMap& KeySlotMap, + /*output ->*/SymmetricBlockMatrix& augmentedHessian) { // Schur complement trick - // Gs = F' * F - F' * E * P * E' * F - // gs = F' * (b - E * P * E' * b) + // G = F' * F - F' * E * P * E' * F + // g = F' * (b - E * P * E' * b) MatrixDD matrixBlock; typedef SymmetricBlockMatrix::Block Block; ///< A block from the Hessian matrix - FastMap KeySlotMap; - for (size_t slot = 0; slot < allKeys.size(); slot++) - KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); - // a single point is observed in m cameras - size_t m = this->keys_.size(); // cameras observing current point + size_t m = Fblocks.size(); // cameras observing current point size_t aug_m = (augmentedHessian.rows() - 1) / Dim; // all cameras in the group // Blockwise Schur complement @@ -424,7 +421,7 @@ public: // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) // Key cameraKey_i = this->keys_[i]; - DenseIndex aug_i = KeySlotMap[this->keys_[i]]; + DenseIndex aug_i = KeySlotMap.at(keys[i]); // information vector - store previous vector // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); @@ -447,7 +444,7 @@ public: const Matrix2D& Fj = Fblocks.at(j).second; //Key cameraKey_j = this->keys_[j]; - DenseIndex aug_j = KeySlotMap[this->keys_[j]]; + DenseIndex aug_j = KeySlotMap.at(keys[j]); // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) // off diagonal block - store previous block @@ -463,6 +460,20 @@ public: augmentedHessian(aug_m, aug_m)(0, 0) += f; } + /** + * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, + * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. + */ + void updateSparseSchurComplement(const std::vector& Fblocks, + const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, + const double f, const FastVector& allKeys, + /*output ->*/SymmetricBlockMatrix& augmentedHessian) const { + FastMap KeySlotMap; + for (size_t slot = 0; slot < allKeys.size(); slot++) + KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); + updateSparseSchurComplement(Fblocks, E, P, b, f, augmentedHessian); + } + /** * Add the contribution of the smart factor to a pre-allocated Hessian, * using sparse linear algebra. More efficient than the creation of the From e30919bc2755371aac5d494c0678619828e763f6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 15:42:21 +0100 Subject: [PATCH 066/173] Moved static functions here, templated on measurement dimension Z --- .cproject | 24 +--- gtsam/slam/RegularImplicitSchurFactor.h | 164 ++++++++++++++++++++---- 2 files changed, 144 insertions(+), 44 deletions(-) diff --git a/.cproject b/.cproject index 94e8c3a50..7111b0a6b 100644 --- a/.cproject +++ b/.cproject @@ -1309,6 +1309,7 @@ make + testSimulated2DOriented.run true false @@ -1348,6 +1349,7 @@ make + testSimulated2D.run true false @@ -1355,6 +1357,7 @@ make + testSimulated3D.run true false @@ -1458,7 +1461,6 @@ make - testErrors.run true false @@ -1536,10 +1538,10 @@ true true - + make - -j5 - testImplicitSchurFactor.run + -j4 + testRegularImplicitSchurFactor.run true true true @@ -1793,7 +1795,6 @@ cpack - -G DEB true false @@ -1801,7 +1802,6 @@ cpack - -G RPM true false @@ -1809,7 +1809,6 @@ cpack - -G TGZ true false @@ -1817,7 +1816,6 @@ cpack - --config CPackSourceConfig.cmake true false @@ -2009,6 +2007,7 @@ make + tests/testGaussianISAM2 true false @@ -2160,7 +2159,6 @@ make - tests/testBayesTree.run true false @@ -2168,7 +2166,6 @@ make - testBinaryBayesNet.run true false @@ -2216,7 +2213,6 @@ make - testSymbolicBayesNet.run true false @@ -2224,7 +2220,6 @@ make - tests/testSymbolicFactor.run true false @@ -2232,7 +2227,6 @@ make - testSymbolicFactorGraph.run true false @@ -2248,7 +2242,6 @@ make - tests/testBayesTree true false @@ -3392,7 +3385,6 @@ make - testGraph.run true false @@ -3400,7 +3392,6 @@ make - testJunctionTree.run true false @@ -3408,7 +3399,6 @@ make - testSymbolicBayesNetB.run true false diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index 731db479f..24033678d 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -9,6 +9,7 @@ #include #include +#include #include #include @@ -17,7 +18,7 @@ namespace gtsam { /** * RegularImplicitSchurFactor */ -template // +template // class RegularImplicitSchurFactor: public GaussianFactor { public: @@ -26,12 +27,12 @@ public: protected: - typedef Eigen::Matrix Matrix2D; ///< type of an F block + typedef Eigen::Matrix Matrix2D; ///< type of an F block typedef Eigen::Matrix MatrixDD; ///< camera hessian typedef std::pair KeyMatrix2D; ///< named F block - const std::vector Fblocks_; ///< All 2*D F blocks (one for each camera) - const Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (2*2 if degenerate) + const std::vector Fblocks_; ///< All Z*D F blocks (one for each camera) + const Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (Z*Z if degenerate) const Matrix E_; ///< The 2m*3 E Jacobian with respect to the point const Vector b_; ///< 2m-dimensional RHS vector @@ -122,6 +123,115 @@ public: "RegularImplicitSchurFactor::jacobian non implemented"); return std::make_pair(Matrix(), Vector()); } + + /** + * Do Schur complement, given Jacobian as F,E,P, return SymmetricBlockMatrix + * Fast version - works on with sparsity + */ + static void sparseSchurComplement(const std::vector& Fblocks, + const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, + /*output ->*/SymmetricBlockMatrix& augmentedHessian) { + // Schur complement trick + // G = F' * F - F' * E * P * E' * F + // g = F' * (b - E * P * E' * b) + + // a single point is observed in m cameras + size_t m = Fblocks.size(); + + // Blockwise Schur complement + for (size_t i = 0; i < m; i++) { // for each camera + + const Matrix2D& Fi = Fblocks.at(i).second; + const Matrix23 Ei_P = E.block(Z * i, 0) * P; + + // D = (Dx2) * (Z) + augmentedHessian(i, m) = Fi.transpose() * b.segment(Z * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) + augmentedHessian(i, i) = Fi.transpose() + * (Fi - Ei_P * E.block(Z * i, 0).transpose() * Fi); + + // upper triangular part of the hessian + for (size_t j = i + 1; j < m; j++) { // for each camera + const Matrix2D& Fj = Fblocks.at(j).second; + + // (DxD) = (Dx2) * ( (2x2) * (2xD) ) + augmentedHessian(i, j) = -Fi.transpose() + * (Ei_P * E.block(Z * j, 0).transpose() * Fj); + } + } // end of for over cameras + } + + /** + * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, + * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. + */ + static void updateSparseSchurComplement( + const std::vector& Fblocks, const Matrix& E, + const Matrix3& P /*Point Covariance*/, const Vector& b, const double f, + const FastVector& keys, const FastMap& KeySlotMap, + /*output ->*/SymmetricBlockMatrix& augmentedHessian) { + // Schur complement trick + // G = F' * F - F' * E * P * E' * F + // g = F' * (b - E * P * E' * b) + + MatrixDD matrixBlock; + typedef SymmetricBlockMatrix::Block Block; ///< A block from the Hessian matrix + + // a single point is observed in m cameras + size_t m = Fblocks.size(); // cameras observing current point + size_t aug_m = (augmentedHessian.rows() - 1) / D; // all cameras in the group + + // Blockwise Schur complement + for (size_t i = 0; i < m; i++) { // for each camera in the current factor + + const Matrix2D& Fi = Fblocks.at(i).second; + const Matrix23 Ei_P = E.block(Z * i, 0) * P; + + // D = (DxZDim) * (Z) + // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) + // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) + // Key cameraKey_i = this->keys_[i]; + DenseIndex aug_i = KeySlotMap.at(keys[i]); + + // information vector - store previous vector + // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); + // add contribution of current factor + augmentedHessian(aug_i, aug_m) = + augmentedHessian(aug_i, aug_m).knownOffDiagonal() + + Fi.transpose() * b.segment(Z * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) + // main block diagonal - store previous block + matrixBlock = augmentedHessian(aug_i, aug_i); + // add contribution of current factor + augmentedHessian(aug_i, aug_i) = matrixBlock + + (Fi.transpose() + * (Fi - Ei_P * E.block(Z * i, 0).transpose() * Fi)); + + // upper triangular part of the hessian + for (size_t j = i + 1; j < m; j++) { // for each camera + const Matrix2D& Fj = Fblocks.at(j).second; + + //Key cameraKey_j = this->keys_[j]; + DenseIndex aug_j = KeySlotMap.at(keys[j]); + + // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) + // off diagonal block - store previous block + // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal(); + // add contribution of current factor + augmentedHessian(aug_i, aug_j) = + augmentedHessian(aug_i, aug_j).knownOffDiagonal() + - Fi.transpose() + * (Ei_P * E.block(Z * j, 0).transpose() * Fj); + } + } // end of for over cameras + + augmentedHessian(aug_m, aug_m)(0, 0) += f; + } + virtual Matrix augmentedInformation() const { throw std::runtime_error( "RegularImplicitSchurFactor::augmentedInformation non implemented"); @@ -142,10 +252,10 @@ public: Key j = keys_[pos]; // Calculate Fj'*Ej for the current camera (observing a single point) - // D x 3 = (D x 2) * (2 x 3) + // D x 3 = (D x Z) * (Z x 3) const Matrix2D& Fj = Fblocks_[pos].second; Eigen::Matrix FtE = Fj.transpose() - * E_.block<2, 3>(2 * pos, 0); + * E_.block(Z * pos, 0); Eigen::Matrix dj; for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian @@ -174,10 +284,10 @@ public: Key j = keys_[pos]; // Calculate Fj'*Ej for the current camera (observing a single point) - // D x 3 = (D x 2) * (2 x 3) + // D x 3 = (D x Z) * (Z x 3) const Matrix2D& Fj = Fblocks_[pos].second; Eigen::Matrix FtE = Fj.transpose() - * E_.block<2, 3>(2 * pos, 0); + * E_.block(Z * pos, 0); DVector dj; for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian @@ -195,28 +305,28 @@ public: // F'*(I - E*P*E')*F for (size_t pos = 0; pos < size(); ++pos) { Key j = keys_[pos]; - // F'*F - F'*E*P*E'*F (9*2)*(2*9) - (9*2)*(2*3)*(3*3)*(3*2)*(2*9) + // F'*F - F'*E*P*E'*F e.g. (9*2)*(2*9) - (9*2)*(2*3)*(3*3)*(3*2)*(2*9) const Matrix2D& Fj = Fblocks_[pos].second; // Eigen::Matrix FtE = Fj.transpose() - // * E_.block<2, 3>(2 * pos, 0); + // * E_.block(Z * pos, 0); // blocks[j] = Fj.transpose() * Fj // - FtE * PointCovariance_ * FtE.transpose(); - const Matrix23& Ej = E_.block<2, 3>(2 * pos, 0); + const Matrix23& Ej = E_.block(Z * pos, 0); blocks[j] = Fj.transpose() * (Fj - Ej * PointCovariance_ * Ej.transpose() * Fj); // F'*(I - E*P*E')*F, TODO: this should work, but it does not :-( - // static const Eigen::Matrix I2 = eye(2); + // static const Eigen::Matrix I2 = eye(Z); // Matrix2 Q = // - // I2 - E_.block<2, 3>(2 * pos, 0) * PointCovariance_ * E_.block<2, 3>(2 * pos, 0).transpose(); + // I2 - E_.block(Z * pos, 0) * PointCovariance_ * E_.block(Z * pos, 0).transpose(); // blocks[j] = Fj.transpose() * Q * Fj; } return blocks; } virtual GaussianFactor::shared_ptr clone() const { - return boost::make_shared >(Fblocks_, + return boost::make_shared >(Fblocks_, PointCovariance_, E_, b_); throw std::runtime_error( "RegularImplicitSchurFactor::clone non implemented"); @@ -226,7 +336,7 @@ public: } virtual GaussianFactor::shared_ptr negate() const { - return boost::make_shared >(Fblocks_, + return boost::make_shared >(Fblocks_, PointCovariance_, E_, b_); throw std::runtime_error( "RegularImplicitSchurFactor::negate non implemented"); @@ -247,23 +357,23 @@ public: typedef std::vector Error2s; /** - * @brief Calculate corrected error Q*(e-2*b) = (I - E*P*E')*(e-2*b) + * @brief Calculate corrected error Q*(e-Z*b) = (I - E*P*E')*(e-Z*b) */ void projectError2(const Error2s& e1, Error2s& e2) const { - // d1 = E.transpose() * (e1-2*b) = (3*2m)*2m + // d1 = E.transpose() * (e1-Z*b) = (3*2m)*2m Vector3 d1; d1.setZero(); for (size_t k = 0; k < size(); k++) - d1 += E_.block<2, 3>(2 * k, 0).transpose() - * (e1[k] - 2 * b_.segment<2>(k * 2)); + d1 += E_.block(Z * k, 0).transpose() + * (e1[k] - Z * b_.segment(k * Z)); // d2 = E.transpose() * e1 = (3*2m)*2m Vector3 d2 = PointCovariance_ * d1; // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - 2 * b_.segment<2>(k * 2) - E_.block<2, 3>(2 * k, 0) * d2; + e2[k] = e1[k] - Z * b_.segment(k * Z) - E_.block(Z * k, 0) * d2; } /* @@ -305,7 +415,7 @@ public: // e1 = F * x - b = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment<2>(k * 2); + e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment(k * Z); projectError(e1, e2); double result = 0; @@ -324,14 +434,14 @@ public: Vector3 d1; d1.setZero(); for (size_t k = 0; k < size(); k++) - d1 += E_.block<2, 3>(2 * k, 0).transpose() * e1[k]; + d1 += E_.block(Z * k, 0).transpose() * e1[k]; // d2 = E.transpose() * e1 = (3*2m)*2m Vector3 d2 = PointCovariance_ * d1; // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - E_.block<2, 3>(2 * k, 0) * d2; + e2[k] = e1[k] - E_.block(Z * k, 0) * d2; } /// Scratch space for multiplyHessianAdd @@ -426,7 +536,7 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment<2>(2 * k); + e1[k] = b_.segment(Z * k); projectError(e1, e2); // g = F.transpose()*e2 @@ -453,7 +563,7 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment<2>(2 * k); + e1[k] = b_.segment(Z * k); projectError(e1, e2); for (size_t k = 0; k < size(); ++k) { // for each camera in the factor @@ -472,8 +582,8 @@ public: // end class RegularImplicitSchurFactor // traits -template struct traits > : public Testable< - RegularImplicitSchurFactor > { +template struct traits > : public Testable< + RegularImplicitSchurFactor > { }; } From 94c70dd7bced2b920cbb1800ea98f54c18bcbb0a Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 15:43:53 +0100 Subject: [PATCH 067/173] Now a function --- gtsam/geometry/tests/testPinholeSet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp index 5de2b5f4d..1e5426f33 100644 --- a/gtsam/geometry/tests/testPinholeSet.cpp +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -129,7 +129,7 @@ TEST(PinholeSet, Pinhole) { // Instantiate triangulateSafe TriangulationParameters params; TriangulationResult actual = set.triangulateSafe(z,params); - CHECK(actual.degenerate); + CHECK(actual.degenerate()); } /* ************************************************************************* */ From bb58814f1c0f58ac0b9baf2dfc50ccf15fd0ee4b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 15:48:11 +0100 Subject: [PATCH 068/173] Moved static functions to RegularImplicit and now use templates --- gtsam/slam/SmartFactorBase.h | 120 ++--------------------------------- 1 file changed, 7 insertions(+), 113 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 9542a4067..1a78f1050 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -352,114 +352,6 @@ public: augmentedHessian); } - /** - * Do Schur complement, given Jacobian as F,E,P, return SymmetricBlockMatrix - * Fast version - works on with sparsity - */ - static void sparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) { - // Schur complement trick - // G = F' * F - F' * E * P * E' * F - // g = F' * (b - E * P * E' * b) - - // a single point is observed in m cameras - size_t m = Fblocks.size(); - - // Blockwise Schur complement - for (size_t i = 0; i < m; i++) { // for each camera - - const Matrix2D& Fi = Fblocks.at(i).second; - const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; - - // Dim = (Dx2) * (2) - augmentedHessian(i, m) = Fi.transpose() * b.segment(ZDim * i) // F' * b - - Fi.transpose() * (Ei_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - augmentedHessian(i, i) = Fi.transpose() - * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi); - - // upper triangular part of the hessian - for (size_t j = i + 1; j < m; j++) { // for each camera - const Matrix2D& Fj = Fblocks.at(j).second; - - // (DxD) = (Dx2) * ( (2x2) * (2xD) ) - augmentedHessian(i, j) = -Fi.transpose() - * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); - } - } // end of for over cameras - } - - /** - * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, - * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. - */ - static void updateSparseSchurComplement( - const std::vector& Fblocks, const Matrix& E, - const Matrix3& P /*Point Covariance*/, const Vector& b, const double f, - const FastVector& keys, const FastMap& KeySlotMap, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) { - // Schur complement trick - // G = F' * F - F' * E * P * E' * F - // g = F' * (b - E * P * E' * b) - - MatrixDD matrixBlock; - typedef SymmetricBlockMatrix::Block Block; ///< A block from the Hessian matrix - - // a single point is observed in m cameras - size_t m = Fblocks.size(); // cameras observing current point - size_t aug_m = (augmentedHessian.rows() - 1) / Dim; // all cameras in the group - - // Blockwise Schur complement - for (size_t i = 0; i < m; i++) { // for each camera in the current factor - - const Matrix2D& Fi = Fblocks.at(i).second; - const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; - - // Dim = (DxZDim) * (ZDim) - // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) - // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) - // Key cameraKey_i = this->keys_[i]; - DenseIndex aug_i = KeySlotMap.at(keys[i]); - - // information vector - store previous vector - // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); - // add contribution of current factor - augmentedHessian(aug_i, aug_m) = - augmentedHessian(aug_i, aug_m).knownOffDiagonal() - + Fi.transpose() * b.segment(ZDim * i) // F' * b - - Fi.transpose() * (Ei_P * (E.transpose() * b)); // Dim = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - // main block diagonal - store previous block - matrixBlock = augmentedHessian(aug_i, aug_i); - // add contribution of current factor - augmentedHessian(aug_i, aug_i) = matrixBlock - + (Fi.transpose() - * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi)); - - // upper triangular part of the hessian - for (size_t j = i + 1; j < m; j++) { // for each camera - const Matrix2D& Fj = Fblocks.at(j).second; - - //Key cameraKey_j = this->keys_[j]; - DenseIndex aug_j = KeySlotMap.at(keys[j]); - - // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) - // off diagonal block - store previous block - // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal(); - // add contribution of current factor - augmentedHessian(aug_i, aug_j) = - augmentedHessian(aug_i, aug_j).knownOffDiagonal() - - Fi.transpose() - * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); - } - } // end of for over cameras - - augmentedHessian(aug_m, aug_m)(0, 0) += f; - } - /** * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. @@ -471,7 +363,8 @@ public: FastMap KeySlotMap; for (size_t slot = 0; slot < allKeys.size(); slot++) KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); - updateSparseSchurComplement(Fblocks, E, P, b, f, augmentedHessian); + RegularImplicitSchurFactor::updateSparseSchurComplement(Fblocks, E, P, + b, f, this->keys_, KeySlotMap, augmentedHessian); } /** @@ -504,16 +397,17 @@ public: /** * Return Jacobians as RegularImplicitSchurFactor with raw access */ - boost::shared_ptr > createRegularImplicitSchurFactor( - const Cameras& cameras, const Point3& point, double lambda = 0.0, - bool diagonalDamping = false) const { + boost::shared_ptr > // + createRegularImplicitSchurFactor(const Cameras& cameras, const Point3& point, + double lambda = 0.0, bool diagonalDamping = false) const { std::vector F; Matrix E; Vector b; computeJacobians(F, E, b, cameras, point); whitenJacobians(F, E, b); Matrix3 P = PointCov(E, lambda, diagonalDamping); - return boost::make_shared >(F, E, P, b); + return boost::make_shared >(F, E, P, + b); } /** From 05fcbe6556ae7b72b4fff099990a5cbfbd140cf2 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 1 Mar 2015 17:15:42 +0100 Subject: [PATCH 069/173] Augmented and regular information now implemented --- gtsam/slam/RegularImplicitSchurFactor.h | 33 ++++++++++++++----- .../tests/testRegularImplicitSchurFactor.cpp | 12 +++++++ 2 files changed, 37 insertions(+), 8 deletions(-) diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index 24033678d..88fb4b6e1 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -18,7 +18,7 @@ namespace gtsam { /** * RegularImplicitSchurFactor */ -template // +template // class RegularImplicitSchurFactor: public GaussianFactor { public: @@ -170,8 +170,12 @@ public: static void updateSparseSchurComplement( const std::vector& Fblocks, const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, const double f, - const FastVector& keys, const FastMap& KeySlotMap, + const FastVector& allKeys, const FastVector& keys, /*output ->*/SymmetricBlockMatrix& augmentedHessian) { + + FastMap KeySlotMap; + for (size_t slot = 0; slot < allKeys.size(); slot++) + KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); // Schur complement trick // G = F' * F - F' * E * P * E' * F // g = F' * (b - E * P * E' * b) @@ -232,15 +236,28 @@ public: augmentedHessian(aug_m, aug_m)(0, 0) += f; } + /// *Compute* full augmented information matrix virtual Matrix augmentedInformation() const { - throw std::runtime_error( - "RegularImplicitSchurFactor::augmentedInformation non implemented"); - return Matrix(); + + // Create a SymmetricBlockMatrix + int m = this->keys_.size(); + size_t M1 = D * m + 1; + std::vector dims(m + 1); // this also includes the b term + std::fill(dims.begin(), dims.end() - 1, D); + dims.back() = 1; + SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); + + // Do the Schur complement + sparseSchurComplement(Fblocks_, E_, PointCovariance_, b_, augmentedHessian); + return augmentedHessian.matrix(); } + + /// *Compute* full information matrix virtual Matrix information() const { - throw std::runtime_error( - "RegularImplicitSchurFactor::information non implemented"); - return Matrix(); + Matrix augmented = augmentedInformation(); + int m = this->keys_.size(); + size_t M = D * m; + return augmented.block(0,0,M,M); } /// Return the diagonal of the Hessian for this factor diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 8571a345d..3575a0286 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -255,6 +255,18 @@ TEST(regularImplicitSchurFactor, hessianDiagonal) EXPECT(assert_equal(F0t*(I2-E0*P*E0.transpose())*F0,actualBD[0])); EXPECT(assert_equal(F1.transpose()*F1-FtE1*P*FtE1.transpose(),actualBD[1])); EXPECT(assert_equal(F3.transpose()*F3-FtE3*P*FtE3.transpose(),actualBD[3])); + + // augmentedInformation (test just checks diagonals) + Matrix actualInfo = factor.augmentedInformation(); + EXPECT(assert_equal(actualBD[0],actualInfo.block<6,6>(0,0))); + EXPECT(assert_equal(actualBD[1],actualInfo.block<6,6>(6,6))); + EXPECT(assert_equal(actualBD[3],actualInfo.block<6,6>(12,12))); + + // information (test just checks diagonals) + Matrix actualInfo2 = factor.information(); + EXPECT(assert_equal(actualBD[0],actualInfo2.block<6,6>(0,0))); + EXPECT(assert_equal(actualBD[1],actualInfo2.block<6,6>(6,6))); + EXPECT(assert_equal(actualBD[3],actualInfo2.block<6,6>(12,12))); } /* ************************************************************************* */ From 11a6ba412ca1eb0d5abc6db96d31a447f081a7b4 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 2 Mar 2015 08:52:35 -0800 Subject: [PATCH 070/173] Smore more refactoring to RegularImplicit.. --- gtsam/slam/SmartFactorBase.h | 30 +++++++----------------------- 1 file changed, 7 insertions(+), 23 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 1a78f1050..d1c0d76e2 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -337,14 +337,14 @@ public: double f = computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - // we create directly a SymmetricBlockMatrix + // Create a SymmetricBlockMatrix size_t M1 = Dim * m + 1; std::vector dims(m + 1); // this also includes the b term std::fill(dims.begin(), dims.end() - 1, Dim); dims.back() = 1; + SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); // build augmented hessian - SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); augmentedHessian(m, m)(0, 0) = f; @@ -352,21 +352,6 @@ public: augmentedHessian); } - /** - * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, - * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. - */ - void updateSparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - const double f, const FastVector& allKeys, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) const { - FastMap KeySlotMap; - for (size_t slot = 0; slot < allKeys.size(); slot++) - KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); - RegularImplicitSchurFactor::updateSparseSchurComplement(Fblocks, E, P, - b, f, this->keys_, KeySlotMap, augmentedHessian); - } - /** * Add the contribution of the smart factor to a pre-allocated Hessian, * using sparse linear algebra. More efficient than the creation of the @@ -376,13 +361,13 @@ public: const double lambda, bool diagonalDamping, SymmetricBlockMatrix& augmentedHessian, const FastVector allKeys) const { - - std::vector Fblocks; Matrix E; Vector b; + std::vector Fblocks; double f = computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - updateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, augmentedHessian); // augmentedHessian.matrix().block (i,j) = ... + RegularImplicitSchurFactor::updateSparseSchurComplement(Fblocks, + E, P, b, f, allKeys, keys_, augmentedHessian); } /// Whiten the Jacobians computed by computeJacobians using noiseModel_ @@ -400,9 +385,9 @@ public: boost::shared_ptr > // createRegularImplicitSchurFactor(const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - std::vector F; Matrix E; Vector b; + std::vector F; computeJacobians(F, E, b, cameras, point); whitenJacobians(F, E, b); Matrix3 P = PointCov(E, lambda, diagonalDamping); @@ -416,12 +401,11 @@ public: boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - std::vector F; Matrix E; Vector b; + std::vector F; computeJacobians(F, E, b, cameras, point); const size_t M = b.size(); - std::cout << M << std::endl; Matrix3 P = PointCov(E, lambda, diagonalDamping); SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); return boost::make_shared >(F, E, P, b, n); From ca18c13cd2da1a46a46fea872cc9a71abe647621 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 2 Mar 2015 08:53:07 -0800 Subject: [PATCH 071/173] Most factors now work out for sigma=1 and sigma=0.1 --- .../tests/testSmartProjectionPoseFactor.cpp | 86 ++++++++++--------- 1 file changed, 47 insertions(+), 39 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index b0c310a36..fae17b9a2 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -39,7 +39,7 @@ static const bool manageDegeneracy = true; // Create a noise model for the pixel error static const double sigma = 0.1; -static SharedNoiseModel model(noiseModel::Isotropic::Sigma(2, sigma)); +static SharedIsotropic model(noiseModel::Isotropic::Sigma(2, sigma)); // Convenience for named keys using symbol_shorthand::X; @@ -299,8 +299,10 @@ TEST( SmartProjectionPoseFactor, Factors ) { // After eliminating the point, A1 and A2 contain 2-rank information on cameras: Matrix16 A1, A2; - A1 << -1000, 0, 0, 0, 100, 0; - A2 << 1000, 0, 100, 0, -100, 0; + A1 << -10, 0, 0, 0, 1, 0; + A2 << 10, 0, 1, 0, -1, 0; + A1 *= 10. / sigma; + A2 *= 10. / sigma; Matrix expectedInformation; // filled below { // createHessianFactor @@ -339,21 +341,38 @@ TEST( SmartProjectionPoseFactor, Factors ) { F2(1, 0) = 100; F2(1, 2) = 10; F2(1, 4) = -10; - Matrix43 E; + Matrix E(4, 3); E.setZero(); - E(0, 0) = 100; - E(1, 1) = 100; - E(2, 0) = 100; - E(2, 2) = 10; - E(3, 1) = 100; - const vector > Fblocks = list_of > // + E(0, 0) = 10; + E(1, 1) = 10; + E(2, 0) = 10; + E(2, 2) = 1; + E(3, 1) = 10; + vector > Fblocks = list_of > // (make_pair(x1, F1))(make_pair(x2, F2)); - Matrix3 P = (E.transpose() * E).inverse(); - Vector4 b; + Vector b(4); b.setZero(); + // createJacobianQFactor + SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); + Matrix3 P = (E.transpose() * E).inverse(); + JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b, n); + EXPECT(assert_equal(expectedInformation, expectedQ.information(), 1e-8)); + + boost::shared_ptr > actualQ = + smartFactor1->createJacobianQFactor(cameras, 0.0); + CHECK(actualQ); + EXPECT(assert_equal(expectedInformation, actualQ->information(), 1e-8)); + EXPECT(assert_equal(expectedQ, *actualQ)); + + // Whiten for RegularImplicitSchurFactor (does not have noise model) + model->WhitenSystem(E, b); + Matrix3 whiteP = (E.transpose() * E).inverse(); + BOOST_FOREACH(SmartFactor::KeyMatrix2D& Fblock,Fblocks) + Fblock.second = model->Whiten(Fblock.second); + // createRegularImplicitSchurFactor - RegularImplicitSchurFactor<6> expected(Fblocks, E, P, b); + RegularImplicitSchurFactor<6> expected(Fblocks, E, whiteP, b); boost::shared_ptr > actual = smartFactor1->createRegularImplicitSchurFactor(cameras, 0.0); @@ -361,17 +380,6 @@ TEST( SmartProjectionPoseFactor, Factors ) { EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); EXPECT(assert_equal(expected, *actual)); - - // createJacobianQFactor - SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); - JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b, n); - EXPECT(assert_equal(expectedInformation, expectedQ.information(), 1e-8)); - - boost::shared_ptr > actualQ = - smartFactor1->createJacobianQFactor(cameras, 0.0); - CHECK(actual); - EXPECT(assert_equal(expectedInformation, actualQ->information(), 1e-8)); - EXPECT(assert_equal(expectedQ, *actualQ)); } { @@ -983,7 +991,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) values.insert(x1, cam2); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose,sharedK)); + values.insert(x3, Camera(pose_above * noise_pose, sharedK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1077,9 +1085,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, Camera(poseDrift.compose(level_pose),sharedK)); - rotValues.insert(x2, Camera(poseDrift.compose(pose_right),sharedK)); - rotValues.insert(x3, Camera(poseDrift.compose(pose_above),sharedK)); + rotValues.insert(x1, Camera(poseDrift.compose(level_pose), sharedK)); + rotValues.insert(x2, Camera(poseDrift.compose(pose_right), sharedK)); + rotValues.insert(x3, Camera(poseDrift.compose(pose_above), sharedK)); boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); @@ -1093,9 +1101,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, Camera(poseDrift2.compose(level_pose),sharedK)); - tranValues.insert(x2, Camera(poseDrift2.compose(pose_right),sharedK)); - tranValues.insert(x3, Camera(poseDrift2.compose(pose_above),sharedK)); + tranValues.insert(x1, Camera(poseDrift2.compose(level_pose), sharedK)); + tranValues.insert(x2, Camera(poseDrift2.compose(pose_right), sharedK)); + tranValues.insert(x3, Camera(poseDrift2.compose(pose_above), sharedK)); boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); @@ -1137,9 +1145,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, Camera(poseDrift.compose(level_pose),sharedK2)); - rotValues.insert(x2, Camera(poseDrift.compose(pose_right),sharedK2)); - rotValues.insert(x3, Camera(poseDrift.compose(pose_above),sharedK2)); + rotValues.insert(x1, Camera(poseDrift.compose(level_pose), sharedK2)); + rotValues.insert(x2, Camera(poseDrift.compose(pose_right), sharedK2)); + rotValues.insert(x3, Camera(poseDrift.compose(pose_above), sharedK2)); boost::shared_ptr hessianFactorRot = smartFactor->linearize( rotValues); @@ -1155,9 +1163,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, Camera(poseDrift2.compose(level_pose),sharedK2)); - tranValues.insert(x2, Camera(poseDrift2.compose(pose_right),sharedK2)); - tranValues.insert(x3, Camera(poseDrift2.compose(pose_above),sharedK2)); + tranValues.insert(x1, Camera(poseDrift2.compose(level_pose), sharedK2)); + tranValues.insert(x2, Camera(poseDrift2.compose(pose_right), sharedK2)); + tranValues.insert(x3, Camera(poseDrift2.compose(pose_above), sharedK2)); boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); @@ -1237,7 +1245,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { values.insert(x1, cam2); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose,sharedBundlerK)); + values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); @@ -1343,7 +1351,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { values.insert(x1, cam2); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose,sharedBundlerK)); + values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); From c4e1c1fdadc1ce7ebd50ee5b710b5ae0f37a8a5b Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 3 Mar 2015 19:18:46 -0800 Subject: [PATCH 072/173] Excepted cmake line on Mac - generates error --- cmake/GtsamTesting.cmake | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/cmake/GtsamTesting.cmake b/cmake/GtsamTesting.cmake index 4b3af9810..3e5cadd32 100644 --- a/cmake/GtsamTesting.cmake +++ b/cmake/GtsamTesting.cmake @@ -195,7 +195,9 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries) add_test(NAME ${target_name} COMMAND ${target_name}) add_dependencies(check.${groupName} ${target_name}) add_dependencies(check ${target_name}) - add_dependencies(all.tests ${script_name}) + if(NOT XCODE_VERSION) + add_dependencies(all.tests ${script_name}) + endif() # Add TOPSRCDIR set_property(SOURCE ${script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"") From 8e818a4cfd644f968819f51436db7e5a03fc1e94 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 3 Mar 2015 22:24:48 -0800 Subject: [PATCH 073/173] Fixed types in debug mode --- .../tests/testSmartProjectionPoseFactor.cpp | 54 +++++++++---------- 1 file changed, 27 insertions(+), 27 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index fae17b9a2..b014191b2 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -31,7 +31,7 @@ using namespace boost::assign; -static bool isDebugTest = false; +static bool isDebugTest = true; static const double rankTol = 1.0; static const double linThreshold = -1.0; @@ -233,7 +233,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK2)); if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + values.at(x3).print("Camera before optimization: "); LevenbergMarquardtParams params; if (isDebugTest) @@ -253,8 +253,8 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); + result.at(x3).print("Camera after optimization: "); + EXPECT(assert_equal(cam3, result.at(x3), 1e-8)); if (isDebugTest) tictoc_print_(); } @@ -443,7 +443,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK)); if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + values.at(x3).print("Camera before optimization: "); LevenbergMarquardtParams params; if (isDebugTest) @@ -460,8 +460,8 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); + result.at(x3).print("Camera after optimization: "); + EXPECT(assert_equal(cam3, result.at(x3), 1e-7)); if (isDebugTest) tictoc_print_(); } @@ -516,7 +516,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); + EXPECT(assert_equal(cam3, result.at(x3), 1e-8)); } /* *************************************************************************/ @@ -575,7 +575,7 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(values.at(x3), result.at(x3))); + EXPECT(assert_equal(values.at(x3), result.at(x3))); } /* *************************************************************************/ @@ -646,7 +646,7 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose_above, result.at(x3))); + EXPECT(assert_equal(cam3, result.at(x3))); } /* *************************************************************************/ @@ -698,7 +698,7 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); + EXPECT(assert_equal(cam3, result.at(x3), 1e-8)); } /* *************************************************************************/ @@ -751,7 +751,7 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { values.insert(L(2), landmark2); values.insert(L(3), landmark3); if (isDebugTest) - values.at(x3).print("Pose3 before optimization: "); + values.at(x3).print("Pose3 before optimization: "); LevenbergMarquardtParams params; if (isDebugTest) @@ -762,8 +762,8 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { Values result = optimizer.optimize(); if (isDebugTest) - result.at(x3).print("Pose3 after optimization: "); - EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); + result.at(x3).print("Pose3 after optimization: "); + EXPECT(assert_equal(cam3, result.at(x3), 1e-7)); } /* *************************************************************************/ @@ -816,7 +816,7 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK)); if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + values.at(x3).print("Camera before optimization: "); boost::shared_ptr hessianFactor1 = smartFactor1->linearize( values); @@ -903,7 +903,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose * noise_pose, sharedK2)); if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + values.at(x3).print("Camera before optimization: "); LevenbergMarquardtParams params; if (isDebugTest) @@ -920,11 +920,11 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); + result.at(x3).print("Camera after optimization: "); cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; - // EXPECT(assert_equal(pose_above,result.at(x3))); + // EXPECT(assert_equal(pose_above,result.at(x3))); if (isDebugTest) tictoc_print_(); } @@ -993,7 +993,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK)); if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + values.at(x3).print("Camera before optimization: "); LevenbergMarquardtParams params; if (isDebugTest) @@ -1010,11 +1010,11 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); + result.at(x3).print("Camera after optimization: "); cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; - // EXPECT(assert_equal(pose_above,result.at(x3))); + // EXPECT(assert_equal(pose_above,result.at(x3))); if (isDebugTest) tictoc_print_(); } @@ -1247,7 +1247,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + values.at(x3).print("Camera before optimization: "); LevenbergMarquardtParams params; if (isDebugTest) @@ -1264,8 +1264,8 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose_above, result.at(x3), 1e-6)); + result.at(x3).print("Camera after optimization: "); + EXPECT(assert_equal(cam3, result.at(x3), 1e-6)); if (isDebugTest) tictoc_print_(); } @@ -1353,7 +1353,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + values.at(x3).print("Camera before optimization: "); LevenbergMarquardtParams params; if (isDebugTest) @@ -1370,11 +1370,11 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); + result.at(x3).print("Camera after optimization: "); cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; - // EXPECT(assert_equal(pose_above,result.at(x3))); + // EXPECT(assert_equal(pose_above,result.at(x3))); if (isDebugTest) tictoc_print_(); } From 6fc208b8d202fa17fab8911ee5d366c558abc800 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 3 Mar 2015 22:27:23 -0800 Subject: [PATCH 074/173] Comment out linear solve (throws) --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index b014191b2..2384e1b7c 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -248,8 +248,8 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { gttoc_(SmartProjectionPoseFactor); tictoc_finishedIteration_(); - GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); - VectorValues delta = GFG->optimize(); +// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); +// VectorValues delta = GFG->optimize(); // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) From bcae38554c9790722e586718e651ab17af6160ee Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 10:20:59 -0800 Subject: [PATCH 075/173] Fixed formatting --- gtsam/geometry/PinholePose.h | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 6f2f7dca0..019cc2609 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -33,12 +33,14 @@ namespace gtsam { template class GTSAM_EXPORT PinholeBaseK: public PinholeBase { - GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration) +private: + + GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration); // Get dimensions of calibration type at compile time -static const int DimK = FixedDimension::value; + static const int DimK = FixedDimension::value; -public : +public: /// @name Standard Constructors /// @{ From 32722fcd8396ea2182b5199d445d78f001442339 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 10:21:22 -0800 Subject: [PATCH 076/173] Got rid of linking mess, made Pose concept --- gtsam/geometry/CalibratedCamera.cpp | 3 - gtsam/geometry/CalibratedCamera.h | 154 +++++----------------------- 2 files changed, 26 insertions(+), 131 deletions(-) diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp index e0d57feff..33f2c84eb 100644 --- a/gtsam/geometry/CalibratedCamera.cpp +++ b/gtsam/geometry/CalibratedCamera.cpp @@ -23,7 +23,6 @@ using namespace std; namespace gtsam { -#ifndef PINHOLEBASE_LINKING_FIX /* ************************************************************************* */ Matrix26 PinholeBase::Dpose(const Point2& pn, double d) { // optimized version of derivatives, see CalibratedCamera.nb @@ -130,8 +129,6 @@ Point3 PinholeBase::backproject_from_camera(const Point2& p, return Point3(p.x() * depth, p.y() * depth, depth); } -#endif - /* ************************************************************************* */ CalibratedCamera CalibratedCamera::Level(const Pose2& pose2, double height) { return CalibratedCamera(LevelPose(pose2, height)); diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 6d08f2160..35789053e 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -19,10 +19,7 @@ #pragma once #include -#define PINHOLEBASE_LINKING_FIX -#ifdef PINHOLEBASE_LINKING_FIX -#include -#endif + namespace gtsam { class Point2; @@ -44,6 +41,10 @@ class GTSAM_EXPORT PinholeBase { public: + /** Pose Concept requirements */ + typedef Rot3 Rotation; + typedef Point3 Translation; + /** * Some classes template on either PinholeCamera or StereoCamera, * and this typedef informs those classes what "project" returns. @@ -54,8 +55,6 @@ private: Pose3 pose_; ///< 3D pose of camera -#ifndef PINHOLEBASE_LINKING_FIX - protected: /// @name Derivatives @@ -143,6 +142,16 @@ public: return pose_; } + /// get rotation + const Rot3& rotation() const { + return pose_.rotation(); + } + + /// get translation + const Point3& translation() const { + return pose_.translation(); + } + /// return pose, with derivative const Pose3& getPose(OptionalJacobian<6, 6> H) const; @@ -173,132 +182,21 @@ public: /// backproject a 2-dimensional point to a 3-dimensional point at given depth static Point3 backproject_from_camera(const Point2& p, const double depth); -#else + /// @} + /// @name Advanced interface + /// @{ -public: - - PinholeBase() { + /** + * Return the start and end indices (inclusive) of the translation component of the + * exponential map parameterization + * @return a pair of [start, end] indices into the tangent space vector + */ + inline static std::pair translationInterval() { + return std::make_pair(3, 5); } - explicit PinholeBase(const Pose3& pose) : - pose_(pose) { - } + /// @} - explicit PinholeBase(const Vector &v) : - pose_(Pose3::Expmap(v)) { - } - - const Pose3& pose() const { - return pose_; - } - - /* ************************************************************************* */ - static Matrix26 Dpose(const Point2& pn, double d) { - // optimized version of derivatives, see CalibratedCamera.nb - const double u = pn.x(), v = pn.y(); - double uv = u * v, uu = u * u, vv = v * v; - Matrix26 Dpn_pose; - Dpn_pose << uv, -1 - uu, v, -d, 0, d * u, 1 + vv, -uv, -u, 0, -d, d * v; - return Dpn_pose; - } - - /* ************************************************************************* */ - static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt) { - // optimized version of derivatives, see CalibratedCamera.nb - const double u = pn.x(), v = pn.y(); - Matrix23 Dpn_point; - Dpn_point << // - Rt(0, 0) - u * Rt(2, 0), Rt(0, 1) - u * Rt(2, 1), Rt(0, 2) - u * Rt(2, 2), // - /**/Rt(1, 0) - v * Rt(2, 0), Rt(1, 1) - v * Rt(2, 1), Rt(1, 2) - v * Rt(2, 2); - Dpn_point *= d; - return Dpn_point; - } - - /* ************************************************************************* */ - static Pose3 LevelPose(const Pose2& pose2, double height) { - const double st = sin(pose2.theta()), ct = cos(pose2.theta()); - const Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0); - const Rot3 wRc(x, y, z); - const Point3 t(pose2.x(), pose2.y(), height); - return Pose3(wRc, t); - } - - /* ************************************************************************* */ - static Pose3 LookatPose(const Point3& eye, const Point3& target, - const Point3& upVector) { - Point3 zc = target - eye; - zc = zc / zc.norm(); - Point3 xc = (-upVector).cross(zc); // minus upVector since yc is pointing down - xc = xc / xc.norm(); - Point3 yc = zc.cross(xc); - return Pose3(Rot3(xc, yc, zc), eye); - } - - /* ************************************************************************* */ - bool equals(const PinholeBase &camera, double tol=1e-9) const { - return pose_.equals(camera.pose(), tol); - } - - /* ************************************************************************* */ - void print(const std::string& s) const { - pose_.print(s + ".pose"); - } - - /* ************************************************************************* */ - const Pose3& getPose(OptionalJacobian<6, 6> H) const { - if (H) { - H->setZero(); - H->block(0, 0, 6, 6) = I_6x6; - } - return pose_; - } - - /* ************************************************************************* */ - static Point2 project_to_camera(const Point3& pc, - OptionalJacobian<2, 3> Dpoint = boost::none) { - double d = 1.0 / pc.z(); - const double u = pc.x() * d, v = pc.y() * d; - if (Dpoint) - *Dpoint << d, 0.0, -u * d, 0.0, d, -v * d; - return Point2(u, v); - } - - /* ************************************************************************* */ - std::pair projectSafe(const Point3& pw) const { - const Point3 pc = pose().transform_to(pw); - const Point2 pn = project_to_camera(pc); - return std::make_pair(pn, pc.z() > 0); - } - - /* ************************************************************************* */ - Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none) const { - - Matrix3 Rt; // calculated by transform_to if needed - const Point3 q = pose().transform_to(point, boost::none, Dpoint ? &Rt : 0); - #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - if (q.z() <= 0) - throw CheiralityException(); - #endif - const Point2 pn = project_to_camera(q); - - if (Dpose || Dpoint) { - const double d = 1.0 / q.z(); - if (Dpose) - *Dpose = PinholeBase::Dpose(pn, d); - if (Dpoint) - *Dpoint = PinholeBase::Dpoint(pn, d, Rt); - } - return pn; - } - - /* ************************************************************************* */ - static Point3 backproject_from_camera(const Point2& p, - const double depth) { - return Point3(p.x() * depth, p.y() * depth, depth); - } - -#endif private: From f3c8b1ac9a4a8c99b8787f5eca6c6cc19720e623 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 10:21:32 -0800 Subject: [PATCH 077/173] Removed print --- gtsam/slam/SmartFactorBase.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index d1c0d76e2..02cd68304 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -423,8 +423,7 @@ public: const size_t M = ZDim * m; Matrix E0(M, M - 3); computeJacobiansSVD(F, E0, b, cameras, point); - std::cout << M << std::endl; - SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); + SharedIsotropic n = noiseModel::Isotropic::Sigma(M-3, noiseModel_->sigma()); return boost::make_shared >(F, E0, b, n); } From 216b5ae62bb05c459c8bd7722a91e830c16d3c92 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 10:21:58 -0800 Subject: [PATCH 078/173] Fixed a large number of issues in test with switch to PinholePose --- .../tests/testSmartProjectionPoseFactor.cpp | 128 ++++++++---------- 1 file changed, 60 insertions(+), 68 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 2384e1b7c..f90eccc82 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -160,7 +160,7 @@ TEST( SmartProjectionPoseFactor, noisy ) { Point2 level_uv_right = level_camera_right.project(landmark1); Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); values.insert(x2, Camera(pose_right.compose(noise_pose), sharedK)); @@ -228,7 +228,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK2)); @@ -242,7 +242,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -438,7 +438,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK)); @@ -452,7 +452,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -508,7 +508,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); values.insert(x3, Camera(pose_above * noise_pose, sharedK)); @@ -566,7 +566,7 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); values.insert(x3, Camera(pose_above * noise_pose, sharedK)); @@ -637,7 +637,7 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); values.insert(x3, Camera(pose_above * noise_pose, sharedK)); @@ -690,7 +690,7 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); values.insert(x3, Camera(pose_above * noise_pose, sharedK)); @@ -738,20 +738,22 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { ProjectionFactor(cam3.project(landmark3), model, x3, L(3), sharedK2)); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, cam2); - values.insert(x2, cam2); - values.insert(x3, Camera(pose_above * noise_pose, sharedK2)); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above * noise_pose); values.insert(L(1), landmark1); values.insert(L(2), landmark2); values.insert(L(3), landmark3); if (isDebugTest) - values.at(x3).print("Pose3 before optimization: "); + values.at(x3).print("Pose3 before optimization: "); + + DOUBLES_EQUAL(48406055, graph.error(values), 1); LevenbergMarquardtParams params; if (isDebugTest) @@ -761,9 +763,11 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { LevenbergMarquardtOptimizer optimizer(graph, values, params); Values result = optimizer.optimize(); + DOUBLES_EQUAL(0, graph.error(result), 1e-9); + if (isDebugTest) - result.at(x3).print("Pose3 after optimization: "); - EXPECT(assert_equal(cam3, result.at(x3), 1e-7)); + result.at(x3).print("Pose3 after optimization: "); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); } /* *************************************************************************/ @@ -811,22 +815,19 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK)); if (isDebugTest) values.at(x3).print("Camera before optimization: "); - boost::shared_ptr hessianFactor1 = smartFactor1->linearize( - values); - boost::shared_ptr hessianFactor2 = smartFactor2->linearize( - values); - boost::shared_ptr hessianFactor3 = smartFactor3->linearize( - values); + boost::shared_ptr factor1 = smartFactor1->linearize(values); + boost::shared_ptr factor2 = smartFactor2->linearize(values); + boost::shared_ptr factor3 = smartFactor3->linearize(values); - Matrix CumulativeInformation = hessianFactor1->information() - + hessianFactor2->information() + hessianFactor3->information(); + Matrix CumulativeInformation = factor1->information() + factor2->information() + + factor3->information(); boost::shared_ptr GaussianGraph = graph.linearize( values); @@ -835,9 +836,8 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { // Check Hessian EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); - Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() - + hessianFactor2->augmentedInformation() - + hessianFactor3->augmentedInformation(); + Matrix AugInformationMatrix = factor1->augmentedInformation() + + factor2->augmentedInformation() + factor3->augmentedInformation(); // Check Information vector // cout << AugInformationMatrix.size() << endl; @@ -891,14 +891,14 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac graph.push_back(smartFactor2); graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back( - PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( - PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, Camera(pose_right * noise_pose, sharedK2)); // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose * noise_pose, sharedK2)); @@ -912,7 +912,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -988,7 +988,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedK)); @@ -1002,7 +1002,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -1042,17 +1042,16 @@ TEST( SmartProjectionPoseFactor, Hessian ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); - boost::shared_ptr hessianFactor = smartFactor1->linearize( - values); + boost::shared_ptr factor = smartFactor1->linearize(values); if (isDebugTest) - hessianFactor->print("Hessian factor \n"); + factor->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) + // compare with factor.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] } @@ -1075,12 +1074,12 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { smartFactorInstance->add(measurements_cam1, views, model); Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); values.insert(x3, cam3); - boost::shared_ptr hessianFactor = - smartFactorInstance->linearize(values); + boost::shared_ptr factor = smartFactorInstance->linearize( + values); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); @@ -1089,13 +1088,11 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { rotValues.insert(x2, Camera(poseDrift.compose(pose_right), sharedK)); rotValues.insert(x3, Camera(poseDrift.compose(pose_above), sharedK)); - boost::shared_ptr hessianFactorRot = - smartFactorInstance->linearize(rotValues); + boost::shared_ptr factorRot = smartFactorInstance->linearize( + rotValues); // Hessian is invariant to rotations in the nondegenerate case - EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRot->information(), 1e-7)); + EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-7)); Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); @@ -1105,13 +1102,12 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { tranValues.insert(x2, Camera(poseDrift2.compose(pose_right), sharedK)); tranValues.insert(x3, Camera(poseDrift2.compose(pose_above), sharedK)); - boost::shared_ptr hessianFactorRotTran = + boost::shared_ptr factorRotTran = smartFactorInstance->linearize(tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRotTran->information(), 1e-7)); + assert_equal(factor->information(), factorRotTran->information(), 1e-7)); } /* *************************************************************************/ @@ -1133,14 +1129,13 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { smartFactor->add(measurements_cam1, views, model); Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); values.insert(x3, cam3); - boost::shared_ptr hessianFactor = smartFactor->linearize( - values); + boost::shared_ptr factor = smartFactor->linearize(values); if (isDebugTest) - hessianFactor->print("Hessian factor \n"); + factor->print("Hessian factor \n"); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); @@ -1149,15 +1144,13 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { rotValues.insert(x2, Camera(poseDrift.compose(pose_right), sharedK2)); rotValues.insert(x3, Camera(poseDrift.compose(pose_above), sharedK2)); - boost::shared_ptr hessianFactorRot = smartFactor->linearize( + boost::shared_ptr factorRot = smartFactor->linearize( rotValues); if (isDebugTest) - hessianFactorRot->print("Hessian factor \n"); + factorRot->print("Hessian factor \n"); // Hessian is invariant to rotations in the nondegenerate case - EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRot->information(), 1e-8)); + EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-8)); Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); @@ -1167,13 +1160,12 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { tranValues.insert(x2, Camera(poseDrift2.compose(pose_right), sharedK2)); tranValues.insert(x3, Camera(poseDrift2.compose(pose_above), sharedK2)); - boost::shared_ptr hessianFactorRotTran = - smartFactor->linearize(tranValues); + boost::shared_ptr factorRotTran = smartFactor->linearize( + tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRotTran->information(), 1e-8)); + assert_equal(factor->information(), factorRotTran->information(), 1e-8)); } /* ************************************************************************* */ @@ -1242,7 +1234,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); @@ -1256,7 +1248,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -1348,7 +1340,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam2); + values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); @@ -1362,7 +1354,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); From cc4083d33e4f6087db98347a255985390afe1ae2 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 10:28:26 -0800 Subject: [PATCH 079/173] Fixed global replace error --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index f90eccc82..bf5354606 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -859,10 +859,8 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac views.push_back(x3); // Two different cameras - Pose3 pose2 = level_pose - * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose - * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3()); + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3()); Camera cam2(pose2, sharedK2); Camera cam3(pose3, sharedK2); @@ -899,9 +897,9 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1); - values.insert(x2, Camera(pose_right * noise_pose, sharedK2)); + values.insert(x2, Camera(pose2 * noise_pose, sharedK2)); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose * noise_pose, sharedK2)); + values.insert(x3, Camera(pose3 * noise_pose * noise_pose, sharedK2)); if (isDebugTest) values.at(x3).print("Camera before optimization: "); From 2f2cc078dc8da918db7556f5586c3c754dbbfc48 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 10:55:39 -0800 Subject: [PATCH 080/173] Deal with possibility of degenerate E version (M*2 rather than M*3) --- gtsam/slam/SmartFactorBase.h | 15 ++++----- gtsam/slam/SmartProjectionFactor.h | 49 +++++++++++++++--------------- 2 files changed, 31 insertions(+), 33 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 02cd68304..c9421e173 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -258,24 +258,21 @@ public: } /// Computes Point Covariance P from E - static Matrix3 PointCov(Matrix& E) { + static Matrix PointCov(Matrix& E) { return (E.transpose() * E).inverse(); } /// Computes Point Covariance P, with lambda parameter - static Matrix3 PointCov(Matrix& E, double lambda, + static Matrix PointCov(Matrix& E, double lambda, bool diagonalDamping = false) { - Matrix3 EtE = E.transpose() * E; + Matrix EtE = E.transpose() * E; if (diagonalDamping) { // diagonal of the hessian - EtE(0, 0) += lambda * EtE(0, 0); - EtE(1, 1) += lambda * EtE(1, 1); - EtE(2, 2) += lambda * EtE(2, 2); + EtE.diagonal() += lambda * EtE.diagonal(); } else { - EtE(0, 0) += lambda; - EtE(1, 1) += lambda; - EtE(2, 2) += lambda; + DenseIndex n = E.cols(); + EtE += lambda * Eigen::MatrixXd::Identity(n,n); } return (EtE).inverse(); diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 51f892a6d..7ab26c0a1 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -280,7 +280,7 @@ public: { std::vector Fblocks; f = computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); - Base::whitenJacobians(Fblocks,E,b); + Base::whitenJacobians(Fblocks, E, b); Base::FillDiagonalF(Fblocks, F); // expensive ! } @@ -290,7 +290,8 @@ public: Matrix H(Base::Dim * numKeys, Base::Dim * numKeys); Vector gs_vector; - Matrix3 P = Base::PointCov(E, lambda); + // Note P can 2*2 or 3*3 + Matrix P = Base::PointCov(E, lambda); // Create reduced Hessian matrix via Schur complement F'*F - F'*E*P*E'*F H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); @@ -448,29 +449,29 @@ public: else result_ = triangulateSafe(cameras); - // if we don't want to manage the exceptions we discard the factor - if (!manageDegeneracy_ && !result_) - return 0.0; - - if (isPointBehindCamera()) { // if we want to manage the exceptions with rotation-only factors - std::cout - << "SmartProjectionHessianFactor: cheirality exception (this should not happen if CheiralityException is disabled)!" - << std::endl; - } - - if (isDegenerate()) { - // return 0.0; // TODO: this maybe should be zero? - std::cout - << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" - << std::endl; - // 3D parameterization of point at infinity - const Point2& z0 = this->measured_.at(0); - result_ = TriangulationResult( - cameras.front().backprojectPointAtInfinity(z0)); - return Base::totalReprojectionErrorAtInfinity(cameras, *result_); - } else { - // Just use version in base class + if (result_) + // All good, just use version in base class return Base::totalReprojectionError(cameras, *result_); + else { + // if we don't want to manage the exceptions we discard the factor + if (!manageDegeneracy_) + return 0.0; + + if (isPointBehindCamera()) { // if we want to manage the exceptions with rotation-only factors + throw std::runtime_error( + "SmartProjectionFactor::totalReprojectionError does not handle point behind camera yet"); + } + + if (isDegenerate()) { + // 3D parameterization of point at infinity + const Point2& z0 = this->measured_.at(0); + result_ = TriangulationResult( + cameras.front().backprojectPointAtInfinity(z0)); + return Base::totalReprojectionErrorAtInfinity(cameras, *result_); + } + // should not reach here. TODO use switch + throw std::runtime_error( + "SmartProjectionFactor::totalReprojectionError internal error"); } } From 48d8de50d095841d2c7e7b28676605be53dd15ff Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 16:38:02 -0800 Subject: [PATCH 081/173] Fixed SVD unit test --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 28b5b8c89..30636c58c 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -388,8 +388,9 @@ TEST( SmartProjectionPoseFactor, Factors ) { // createJacobianSVDFactor Vector1 b; b.setZero(); - double s = sin(M_PI_4); - JacobianFactor expected(x1, s * A1, x2, s * A2, b); + double s = sigma * sin(M_PI_4); + SharedIsotropic n = noiseModel::Isotropic::Sigma(4-3, sigma); + JacobianFactor expected(x1, s * A1, x2, s * A2, b, n); EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); boost::shared_ptr actual = From a95e5c7e051846ca8e05aa3a134658f84d8e298a Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 17:21:11 -0800 Subject: [PATCH 082/173] Fixed another test --- .../tests/testSmartProjectionPoseFactor.cpp | 36 +++++++++++-------- 1 file changed, 22 insertions(+), 14 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 30636c58c..46a9fe98c 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -246,7 +246,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionPoseFactor); + gttic_ (SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -256,7 +256,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { // VectorValues delta = GFG->optimize(); // result.print("results of 3 camera, 3 landmark optimization \n"); - EXPECT(assert_equal(cam3, result.at(x3), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); if (isDebugTest) tictoc_print_(); } @@ -389,7 +389,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { Vector1 b; b.setZero(); double s = sigma * sin(M_PI_4); - SharedIsotropic n = noiseModel::Isotropic::Sigma(4-3, sigma); + SharedIsotropic n = noiseModel::Isotropic::Sigma(4 - 3, sigma); JacobianFactor expected(x1, s * A1, x2, s * A2, b, n); EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); @@ -460,14 +460,14 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionPoseFactor); + gttic_ (SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); tictoc_finishedIteration_(); // result.print("results of 3 camera, 3 landmark optimization \n"); - EXPECT(assert_equal(cam3, result.at(x3), 1e-7)); + EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-7)); if (isDebugTest) tictoc_print_(); } @@ -519,10 +519,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { values.insert(x3, Camera(pose_above * noise_pose, sharedK)); LevenbergMarquardtParams params; + if (isDebugTest) + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + params.verbosity = NonlinearOptimizerParams::ERROR; + Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(cam3, result.at(x3), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); } /* *************************************************************************/ @@ -640,12 +645,10 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back(PriorFactor(x2, cam2, noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), - Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1); values.insert(x2, cam2); - values.insert(x3, Camera(pose_above * noise_pose, sharedK)); + values.insert(x3, cam3); // All factors are disabled and pose should remain where it is LevenbergMarquardtParams params; @@ -701,10 +704,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { values.insert(x3, Camera(pose_above * noise_pose, sharedK)); LevenbergMarquardtParams params; + if (isDebugTest) + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + params.verbosity = NonlinearOptimizerParams::ERROR; + Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(cam3, result.at(x3), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); } /* *************************************************************************/ @@ -928,7 +936,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionPoseFactor); + gttic_ (SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -1029,7 +1037,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionPoseFactor); + gttic_ (SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -1283,7 +1291,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionPoseFactor); + gttic_ (SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -1392,7 +1400,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionPoseFactor); + gttic_ (SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); From f2a5e5c68390273edf70a1230261cdacfde5692d Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 17:21:22 -0800 Subject: [PATCH 083/173] Case change --- gtsam/slam/JacobianFactorSVD.h | 2 +- gtsam/slam/RegularImplicitSchurFactor.h | 8 ++++---- gtsam/slam/SmartFactorBase.h | 10 ++++++---- 3 files changed, 11 insertions(+), 9 deletions(-) diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index e5e39d1a1..0b0d76fda 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -63,7 +63,7 @@ public: QF.push_back( KeyMatrix(it.first, (Enull.transpose()).block(0, ZDim * j++, m2, ZDim) * it.second)); - JacobianFactor::fillTerms(QF, Enull.transpose() * b, model); + JacobianFactor::fillTerms(QF, - Enull.transpose() * b, model); } }; diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index 88fb4b6e1..fd1a5764d 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -128,7 +128,7 @@ public: * Do Schur complement, given Jacobian as F,E,P, return SymmetricBlockMatrix * Fast version - works on with sparsity */ - static void sparseSchurComplement(const std::vector& Fblocks, + static void SparseSchurComplement(const std::vector& Fblocks, const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, /*output ->*/SymmetricBlockMatrix& augmentedHessian) { // Schur complement trick @@ -167,7 +167,7 @@ public: * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. */ - static void updateSparseSchurComplement( + static void UpdateSparseSchurComplement( const std::vector& Fblocks, const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, const double f, const FastVector& allKeys, const FastVector& keys, @@ -248,7 +248,7 @@ public: SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); // Do the Schur complement - sparseSchurComplement(Fblocks_, E_, PointCovariance_, b_, augmentedHessian); + SparseSchurComplement(Fblocks_, E_, PointCovariance_, b_, augmentedHessian); return augmentedHessian.matrix(); } @@ -257,7 +257,7 @@ public: Matrix augmented = augmentedInformation(); int m = this->keys_.size(); size_t M = D * m; - return augmented.block(0,0,M,M); + return augmented.block(0, 0, M, M); } /// Return the diagonal of the Hessian for this factor diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index c9421e173..60e939a89 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -272,7 +272,7 @@ public: EtE.diagonal() += lambda * EtE.diagonal(); } else { DenseIndex n = E.cols(); - EtE += lambda * Eigen::MatrixXd::Identity(n,n); + EtE += lambda * Eigen::MatrixXd::Identity(n, n); } return (EtE).inverse(); @@ -342,7 +342,8 @@ public: SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); // build augmented hessian - sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); + RegularImplicitSchurFactor::SparseSchurComplement(Fblocks, E, P, b, + augmentedHessian); augmentedHessian(m, m)(0, 0) = f; return boost::make_shared >(keys_, @@ -363,7 +364,7 @@ public: std::vector Fblocks; double f = computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - RegularImplicitSchurFactor::updateSparseSchurComplement(Fblocks, + RegularImplicitSchurFactor::UpdateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, keys_, augmentedHessian); } @@ -420,7 +421,8 @@ public: const size_t M = ZDim * m; Matrix E0(M, M - 3); computeJacobiansSVD(F, E0, b, cameras, point); - SharedIsotropic n = noiseModel::Isotropic::Sigma(M-3, noiseModel_->sigma()); + SharedIsotropic n = noiseModel::Isotropic::Sigma(M - 3, + noiseModel_->sigma()); return boost::make_shared >(F, E0, b, n); } From 000d14c09a77ab11f73a1ac8f392ec3f2e0b06c4 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 19:28:24 -0800 Subject: [PATCH 084/173] comment --- gtsam/geometry/PinholePose.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 019cc2609..b5daaebc5 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -136,6 +136,7 @@ public: Matrix3 Dpc_rot, Dpc_point; const Point3 pc = this->pose().rotation().unrotate(pw, Dpc_rot, Dpc_point); + // only rotation is important Matrix36 Dpc_pose; Dpc_pose.setZero(); Dpc_pose.leftCols<3>() = Dpc_rot; From 0a287e25e797a3041371bbddc862b74322bf883f Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 20:43:27 -0800 Subject: [PATCH 085/173] Moved SchurComplement here, as well as UpdateSchurComplement --- gtsam/geometry/CameraSet.h | 144 +++++++++++++++++++++++-- gtsam/geometry/tests/testCameraSet.cpp | 63 ++++++++--- 2 files changed, 184 insertions(+), 23 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 7e9062a8d..dd58f8e69 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -21,6 +21,8 @@ #include #include // for Cheirality exception #include +#include +#include #include namespace gtsam { @@ -39,8 +41,8 @@ protected: */ typedef typename CAMERA::Measurement Z; + static const int D = traits::dimension; ///< Camera dimension static const int ZDim = traits::dimension; ///< Measurement dimension - static const int Dim = traits::dimension; ///< Camera dimension /// Make a vector of re-projection errors static Vector ErrorVector(const std::vector& predicted, @@ -63,7 +65,7 @@ protected: public: /// Definitions for blocks of F - typedef Eigen::Matrix MatrixZD; // F + typedef Eigen::Matrix MatrixZD; typedef std::vector FBlocks; /** @@ -97,7 +99,7 @@ public: * throws CheiralityException */ std::vector project2(const Point3& point, // - boost::optional F = boost::none, // + boost::optional Fs = boost::none, // boost::optional E = boost::none) const { // Allocate result @@ -110,11 +112,11 @@ public: // Project and fill derivatives for (size_t i = 0; i < m; i++) { - Eigen::Matrix Fi; + MatrixZD Fi; Eigen::Matrix Ei; - z[i] = this->at(i).project2(point, F ? &Fi : 0, E ? &Ei : 0); - if (F) - F->push_back(Fi); + z[i] = this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0); + if (Fs) + Fs->push_back(Fi); if (E) E->block(ZDim * i, 0) = Ei; } @@ -141,9 +143,9 @@ public: /// Calculate vector of re-projection errors Vector reprojectionError(const Point3& point, const std::vector& measured, - boost::optional F = boost::none, // + boost::optional Fs = boost::none, // boost::optional E = boost::none) const { - return ErrorVector(project2(point, F, E), measured); + return ErrorVector(project2(point, Fs, E), measured); } /// Calculate vector of re-projection errors, from point at infinity @@ -153,6 +155,127 @@ public: return ErrorVector(projectAtInfinity(point), measured); } + /** + * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix + * G = F' * F - F' * E * P * E' * F + * g = F' * (b - E * P * E' * b) + */ + static SymmetricBlockMatrix SchurComplement(const FBlocks& Fs, + const Matrix& E, const Matrix3& P, const Vector& b) { + + // a single point is observed in m cameras + int m = Fs.size(); + + // Create a SymmetricBlockMatrix + size_t M1 = D * m + 1; + std::vector dims(m + 1); // this also includes the b term + std::fill(dims.begin(), dims.end() - 1, D); + dims.back() = 1; + SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); + + // Blockwise Schur complement + for (size_t i = 0; i < m; i++) { // for each camera + + const MatrixZD& Fi = Fs[i]; + const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; + + // D = (Dx2) * ZDim + augmentedHessian(i, m) = Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) + augmentedHessian(i, i) = Fi.transpose() + * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi); + + // upper triangular part of the hessian + for (size_t j = i + 1; j < m; j++) { // for each camera + const MatrixZD& Fj = Fs[j]; + + // (DxD) = (Dx2) * ( (2x2) * (2xD) ) + augmentedHessian(i, j) = -Fi.transpose() + * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); + } + } // end of for over cameras + + augmentedHessian(m, m)(0, 0) += b.squaredNorm(); + return augmentedHessian; + } + + /** + * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, + * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. + */ + static void UpdateSchurComplement(const FBlocks& Fs, const Matrix& E, + const Matrix3& P /*Point Covariance*/, const Vector& b, + const FastVector& allKeys, const FastVector& keys, + /*output ->*/SymmetricBlockMatrix& augmentedHessian) { + + assert(keys.size()==Fs.size()); + assert(keys.size()<=allKeys.size()); + + FastMap KeySlotMap; + for (size_t slot = 0; slot < allKeys.size(); slot++) + KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); + + // Schur complement trick + // G = F' * F - F' * E * P * E' * F + // g = F' * (b - E * P * E' * b) + + Eigen::Matrix matrixBlock; + typedef SymmetricBlockMatrix::Block Block; ///< A block from the Hessian matrix + + // a single point is observed in m cameras + size_t m = Fs.size(); // cameras observing current point + size_t M = (augmentedHessian.rows() - 1) / D; // all cameras in the group + assert(allKeys.size()==M); + + // Blockwise Schur complement + for (size_t i = 0; i < m; i++) { // for each camera in the current factor + + const MatrixZD& Fi = Fs[i]; + const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; + + // D = (DxZDim) * (ZDim) + // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) + // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) + // Key cameraKey_i = this->keys_[i]; + DenseIndex aug_i = KeySlotMap.at(keys[i]); + + // information vector - store previous vector + // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); + // add contribution of current factor + augmentedHessian(aug_i, M) = augmentedHessian(aug_i, M).knownOffDiagonal() + + Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) + // main block diagonal - store previous block + matrixBlock = augmentedHessian(aug_i, aug_i); + // add contribution of current factor + augmentedHessian(aug_i, aug_i) = matrixBlock + + (Fi.transpose() + * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi)); + + // upper triangular part of the hessian + for (size_t j = i + 1; j < m; j++) { // for each camera + const MatrixZD& Fj = Fs[j]; + + DenseIndex aug_j = KeySlotMap.at(keys[j]); + + // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) + // off diagonal block - store previous block + // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal(); + // add contribution of current factor + augmentedHessian(aug_i, aug_j) = + augmentedHessian(aug_i, aug_j).knownOffDiagonal() + - Fi.transpose() + * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); + } + } // end of for over cameras + + augmentedHessian(M, M)(0, 0) += b.squaredNorm(); + } + private: /// Serialization function @@ -163,6 +286,9 @@ private: } }; +template +const int CameraSet::D; + template const int CameraSet::ZDim; diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 25a6da5b2..05ffc275c 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -31,14 +31,15 @@ using namespace gtsam; #include TEST(CameraSet, Pinhole) { typedef PinholeCamera Camera; + typedef CameraSet Set; typedef vector ZZ; - CameraSet set; + Set set; Camera camera; set.push_back(camera); set.push_back(camera); Point3 p(0, 0, 1); EXPECT(assert_equal(set, set)); - CameraSet set2 = set; + Set set2 = set; set2.push_back(camera); EXPECT(!set.equals(set2)); @@ -50,7 +51,7 @@ TEST(CameraSet, Pinhole) { // Calculate expected derivatives using Pinhole Matrix43 actualE; - Matrix F1; + Matrix29 F1; { Matrix23 E1; Matrix23 H1; @@ -59,12 +60,12 @@ TEST(CameraSet, Pinhole) { } // Check computed derivatives - CameraSet::FBlocks F; - Matrix E, H; - set.project2(p, F, E); - LONGS_EQUAL(2,F.size()); - EXPECT(assert_equal(F1, F[0])); - EXPECT(assert_equal(F1, F[1])); + Set::FBlocks Fs; + Matrix E; + set.project2(p, Fs, E); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); EXPECT(assert_equal(actualE, E)); // Check errors @@ -78,6 +79,40 @@ TEST(CameraSet, Pinhole) { Vector actualV = set.reprojectionError(p, measured); EXPECT(assert_equal(expectedV, actualV)); + // Check Schur complement + Matrix F(4, 18); + F << F1, Matrix29::Zero(), Matrix29::Zero(), F1; + Matrix Ft = F.transpose(); + Matrix34 Et = E.transpose(); + Matrix3 P = Et * E; + Matrix schur(19, 19); + Vector4 b = actualV; + Vector v = Ft * (b - E * P * Et * b); + schur << Ft * F - Ft * E * P * Et * F, v, v.transpose(), 30; + SymmetricBlockMatrix actualReduced = Set::SchurComplement(Fs, E, P, b); + EXPECT(assert_equal(schur, actualReduced.matrix())); + + // Check Schur complement update, same order, should just double + FastVector allKeys, keys; + allKeys.push_back(1); + allKeys.push_back(2); + keys.push_back(1); + keys.push_back(2); + Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys, actualReduced); + EXPECT(assert_equal((Matrix )(2.0 * schur), actualReduced.matrix())); + + // Check Schur complement update, keys reversed + FastVector keys2; + keys2.push_back(2); + keys2.push_back(1); + Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys2, actualReduced); + Vector4 reverse_b; + reverse_b << b.tail<2>(), b.head<2>(); + Vector reverse_v = Ft * (reverse_b - E * P * Et * reverse_b); + Matrix A(19, 19); + A << Ft * F - Ft * E * P * Et * F, reverse_v, reverse_v.transpose(), 30; + EXPECT(assert_equal((Matrix )(2.0 * schur + A), actualReduced.matrix())); + // reprojectionErrorAtInfinity EXPECT( assert_equal(Point3(0, 0, 1), @@ -113,12 +148,12 @@ TEST(CameraSet, Stereo) { } // Check computed derivatives - CameraSet::FBlocks F; + CameraSet::FBlocks Fs; Matrix E; - set.project2(p, F, E); - LONGS_EQUAL(2,F.size()); - EXPECT(assert_equal(F1, F[0])); - EXPECT(assert_equal(F1, F[1])); + set.project2(p, Fs, E); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); EXPECT(assert_equal(actualE, E)); } From 175dae30ec72be180ee41d4bad751df0bf4ec57a Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 21:39:35 -0800 Subject: [PATCH 086/173] Switched to non-keyed Fblocks --- gtsam/slam/JacobianFactorQ.h | 16 +- gtsam/slam/JacobianFactorQR.h | 17 +- gtsam/slam/RegularImplicitSchurFactor.h | 274 +++++------------- gtsam/slam/SmartFactorBase.h | 57 ++-- .../tests/testRegularImplicitSchurFactor.cpp | 28 +- 5 files changed, 130 insertions(+), 262 deletions(-) diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index 5e8693541..5dd7582cd 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -28,7 +28,7 @@ class JacobianFactorQ: public RegularJacobianFactor { typedef RegularJacobianFactor Base; typedef Eigen::Matrix MatrixZD; - typedef std::pair KeyMatrixZD; + typedef std::pair KeyMatrix; public: @@ -42,7 +42,6 @@ public: Base() { Matrix zeroMatrix = Matrix::Zero(0, D); Vector zeroVector = Vector::Zero(0); - typedef std::pair KeyMatrix; std::vector QF; QF.reserve(keys.size()); BOOST_FOREACH(const Key& key, keys) @@ -51,22 +50,23 @@ public: } /// Constructor - JacobianFactorQ(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b, const SharedDiagonal& model = - SharedDiagonal()) : + JacobianFactorQ(const FastVector& keys, + const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : Base() { size_t j = 0, m2 = E.rows(), m = m2 / ZDim; // Calculate projector Q Matrix Q = eye(m2) - E * P * E.transpose(); // Calculate pre-computed Jacobian matrices // TODO: can we do better ? - typedef std::pair KeyMatrix; std::vector QF; QF.reserve(m); // Below, we compute each mZDim*D block A_j = Q_j * F_j = (mZDim*ZDim) * (Zdim*D) - BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) + for (size_t k = 0; k < FBlocks.size(); ++k) { + Key key = keys[k]; QF.push_back( - KeyMatrix(it.first, Q.block(0, ZDim * j++, m2, ZDim) * it.second)); + KeyMatrix(key, Q.block(0, ZDim * j++, m2, ZDim) * FBlocks[k])); + } // Which is then passed to the normal JacobianFactor constructor JacobianFactor::fillTerms(QF, Q * b, model); } diff --git a/gtsam/slam/JacobianFactorQR.h b/gtsam/slam/JacobianFactorQR.h index 9c3f8be4a..77102c24b 100644 --- a/gtsam/slam/JacobianFactorQR.h +++ b/gtsam/slam/JacobianFactorQR.h @@ -7,8 +7,8 @@ #pragma once #include -#include #include +#include namespace gtsam { @@ -22,25 +22,24 @@ class JacobianFactorQR: public RegularJacobianFactor { typedef RegularJacobianFactor Base; typedef Eigen::Matrix MatrixZD; - typedef std::pair KeyMatrixZD; public: /** * Constructor */ - JacobianFactorQR(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b, // + JacobianFactorQR(const FastVector& keys, + const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const Vector& b, // const SharedDiagonal& model = SharedDiagonal()) : Base() { // Create a number of Jacobian factors in a factor graph GaussianFactorGraph gfg; Symbol pointKey('p', 0); - size_t i = 0; - BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) { - gfg.add(pointKey, E.block(ZDim * i, 0), it.first, it.second, - b.segment(ZDim * i), model); - i += 1; + for (size_t k = 0; k < FBlocks.size(); ++k) { + Key key = keys[k]; + gfg.add(pointKey, E.block(ZDim * k, 0), key, FBlocks[k], + b.segment < ZDim > (ZDim * k), model); } //gfg.print("gfg"); diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index fd1a5764d..dac5ad153 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -7,9 +7,9 @@ #pragma once +#include #include #include -#include #include #include @@ -18,7 +18,7 @@ namespace gtsam { /** * RegularImplicitSchurFactor */ -template // +template class RegularImplicitSchurFactor: public GaussianFactor { public: @@ -27,22 +27,21 @@ public: protected: - typedef Eigen::Matrix Matrix2D; ///< type of an F block - typedef Eigen::Matrix MatrixDD; ///< camera hessian - typedef std::pair KeyMatrix2D; ///< named F block + // This factor is closely related to a CameraSet + typedef CameraSet Set; - const std::vector Fblocks_; ///< All Z*D F blocks (one for each camera) - const Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (Z*Z if degenerate) + typedef typename CAMERA::Measurement Z; + static const int D = traits::dimension; ///< Camera dimension + static const int ZDim = traits::dimension; ///< Measurement dimension + + typedef Eigen::Matrix MatrixZD; ///< type of an F block + typedef Eigen::Matrix MatrixDD; ///< camera hessian + + const std::vector FBlocks_; ///< All ZDim*D F blocks (one for each camera) + const Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (ZDim*ZDim if degenerate) const Matrix E_; ///< The 2m*3 E Jacobian with respect to the point const Vector b_; ///< 2m-dimensional RHS vector - /// initialize keys from Fblocks - void initKeys() { - keys_.reserve(Fblocks_.size()); - BOOST_FOREACH(const KeyMatrix2D& it, Fblocks_) - keys_.push_back(it.first); - } - public: /// Constructor @@ -50,29 +49,29 @@ public: } /// Construct from blocks of F, E, inv(E'*E), and RHS vector b - RegularImplicitSchurFactor(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P, const Vector& b) : - Fblocks_(Fblocks), PointCovariance_(P), E_(E), b_(b) { - initKeys(); + RegularImplicitSchurFactor(const FastVector& keys, + const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const Vector& b) : + GaussianFactor(keys), FBlocks_(FBlocks), PointCovariance_(P), E_(E), b_(b) { } /// Destructor virtual ~RegularImplicitSchurFactor() { } - inline std::vector& Fblocks() const { - return Fblocks_; + std::vector& FBlocks() const { + return FBlocks_; } - inline const Matrix& E() const { + const Matrix& E() const { return E_; } - inline const Vector& b() const { + const Vector& b() const { return b_; } - inline const Matrix3& getPointCovariance() const { + const Matrix3& getPointCovariance() const { return PointCovariance_; } @@ -82,7 +81,7 @@ public: std::cout << " RegularImplicitSchurFactor " << std::endl; Factor::print(s); for (size_t pos = 0; pos < size(); ++pos) { - std::cout << "Fblock:\n" << Fblocks_[pos].second << std::endl; + std::cout << "Fblock:\n" << FBlocks_[pos] << std::endl; } std::cout << "PointCovariance:\n" << PointCovariance_ << std::endl; std::cout << "E:\n" << E_ << std::endl; @@ -94,13 +93,12 @@ public: const This* f = dynamic_cast(&lf); if (!f) return false; - for (size_t pos = 0; pos < size(); ++pos) { - if (keys_[pos] != f->keys_[pos]) + for (size_t k = 0; k < FBlocks_.size(); ++k) { + if (keys_[k] != f->keys_[k]) return false; - if (Fblocks_[pos].first != f->Fblocks_[pos].first) + if (FBlocks_[k] != f->FBlocks_[k]) return false; - if (!equal_with_abs_tol(Fblocks_[pos].second, f->Fblocks_[pos].second, - tol)) + if (!equal_with_abs_tol(FBlocks_[k], f->FBlocks_[k], tol)) return false; } return equal_with_abs_tol(PointCovariance_, f->PointCovariance_, tol) @@ -124,131 +122,12 @@ public: return std::make_pair(Matrix(), Vector()); } - /** - * Do Schur complement, given Jacobian as F,E,P, return SymmetricBlockMatrix - * Fast version - works on with sparsity - */ - static void SparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) { - // Schur complement trick - // G = F' * F - F' * E * P * E' * F - // g = F' * (b - E * P * E' * b) - - // a single point is observed in m cameras - size_t m = Fblocks.size(); - - // Blockwise Schur complement - for (size_t i = 0; i < m; i++) { // for each camera - - const Matrix2D& Fi = Fblocks.at(i).second; - const Matrix23 Ei_P = E.block(Z * i, 0) * P; - - // D = (Dx2) * (Z) - augmentedHessian(i, m) = Fi.transpose() * b.segment(Z * i) // F' * b - - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - augmentedHessian(i, i) = Fi.transpose() - * (Fi - Ei_P * E.block(Z * i, 0).transpose() * Fi); - - // upper triangular part of the hessian - for (size_t j = i + 1; j < m; j++) { // for each camera - const Matrix2D& Fj = Fblocks.at(j).second; - - // (DxD) = (Dx2) * ( (2x2) * (2xD) ) - augmentedHessian(i, j) = -Fi.transpose() - * (Ei_P * E.block(Z * j, 0).transpose() * Fj); - } - } // end of for over cameras - } - - /** - * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, - * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. - */ - static void UpdateSparseSchurComplement( - const std::vector& Fblocks, const Matrix& E, - const Matrix3& P /*Point Covariance*/, const Vector& b, const double f, - const FastVector& allKeys, const FastVector& keys, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) { - - FastMap KeySlotMap; - for (size_t slot = 0; slot < allKeys.size(); slot++) - KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); - // Schur complement trick - // G = F' * F - F' * E * P * E' * F - // g = F' * (b - E * P * E' * b) - - MatrixDD matrixBlock; - typedef SymmetricBlockMatrix::Block Block; ///< A block from the Hessian matrix - - // a single point is observed in m cameras - size_t m = Fblocks.size(); // cameras observing current point - size_t aug_m = (augmentedHessian.rows() - 1) / D; // all cameras in the group - - // Blockwise Schur complement - for (size_t i = 0; i < m; i++) { // for each camera in the current factor - - const Matrix2D& Fi = Fblocks.at(i).second; - const Matrix23 Ei_P = E.block(Z * i, 0) * P; - - // D = (DxZDim) * (Z) - // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) - // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) - // Key cameraKey_i = this->keys_[i]; - DenseIndex aug_i = KeySlotMap.at(keys[i]); - - // information vector - store previous vector - // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); - // add contribution of current factor - augmentedHessian(aug_i, aug_m) = - augmentedHessian(aug_i, aug_m).knownOffDiagonal() - + Fi.transpose() * b.segment(Z * i) // F' * b - - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - // main block diagonal - store previous block - matrixBlock = augmentedHessian(aug_i, aug_i); - // add contribution of current factor - augmentedHessian(aug_i, aug_i) = matrixBlock - + (Fi.transpose() - * (Fi - Ei_P * E.block(Z * i, 0).transpose() * Fi)); - - // upper triangular part of the hessian - for (size_t j = i + 1; j < m; j++) { // for each camera - const Matrix2D& Fj = Fblocks.at(j).second; - - //Key cameraKey_j = this->keys_[j]; - DenseIndex aug_j = KeySlotMap.at(keys[j]); - - // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) - // off diagonal block - store previous block - // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal(); - // add contribution of current factor - augmentedHessian(aug_i, aug_j) = - augmentedHessian(aug_i, aug_j).knownOffDiagonal() - - Fi.transpose() - * (Ei_P * E.block(Z * j, 0).transpose() * Fj); - } - } // end of for over cameras - - augmentedHessian(aug_m, aug_m)(0, 0) += f; - } - /// *Compute* full augmented information matrix virtual Matrix augmentedInformation() const { - // Create a SymmetricBlockMatrix - int m = this->keys_.size(); - size_t M1 = D * m + 1; - std::vector dims(m + 1); // this also includes the b term - std::fill(dims.begin(), dims.end() - 1, D); - dims.back() = 1; - SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); - // Do the Schur complement - SparseSchurComplement(Fblocks_, E_, PointCovariance_, b_, augmentedHessian); + SymmetricBlockMatrix augmentedHessian = Set::SchurComplement(FBlocks_, E_, + PointCovariance_, b_); return augmentedHessian.matrix(); } @@ -265,14 +144,14 @@ public: // diag(Hessian) = diag(F' * (I - E * PointCov * E') * F); VectorValues d; - for (size_t pos = 0; pos < size(); ++pos) { // for each camera - Key j = keys_[pos]; + for (size_t k = 0; k < size(); ++k) { // for each camera + Key j = keys_[k]; // Calculate Fj'*Ej for the current camera (observing a single point) - // D x 3 = (D x Z) * (Z x 3) - const Matrix2D& Fj = Fblocks_[pos].second; + // D x 3 = (D x ZDim) * (ZDim x 3) + const MatrixZD& Fj = FBlocks_[k]; Eigen::Matrix FtE = Fj.transpose() - * E_.block(Z * pos, 0); + * E_.block(ZDim * k, 0); Eigen::Matrix dj; for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian @@ -301,10 +180,10 @@ public: Key j = keys_[pos]; // Calculate Fj'*Ej for the current camera (observing a single point) - // D x 3 = (D x Z) * (Z x 3) - const Matrix2D& Fj = Fblocks_[pos].second; + // D x 3 = (D x ZDim) * (ZDim x 3) + const MatrixZD& Fj = FBlocks_[pos]; Eigen::Matrix FtE = Fj.transpose() - * E_.block(Z * pos, 0); + * E_.block(ZDim * pos, 0); DVector dj; for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian @@ -323,28 +202,28 @@ public: for (size_t pos = 0; pos < size(); ++pos) { Key j = keys_[pos]; // F'*F - F'*E*P*E'*F e.g. (9*2)*(2*9) - (9*2)*(2*3)*(3*3)*(3*2)*(2*9) - const Matrix2D& Fj = Fblocks_[pos].second; + const MatrixZD& Fj = FBlocks_[pos]; // Eigen::Matrix FtE = Fj.transpose() - // * E_.block(Z * pos, 0); + // * E_.block(ZDim * pos, 0); // blocks[j] = Fj.transpose() * Fj // - FtE * PointCovariance_ * FtE.transpose(); - const Matrix23& Ej = E_.block(Z * pos, 0); + const Matrix23& Ej = E_.block(ZDim * pos, 0); blocks[j] = Fj.transpose() * (Fj - Ej * PointCovariance_ * Ej.transpose() * Fj); // F'*(I - E*P*E')*F, TODO: this should work, but it does not :-( - // static const Eigen::Matrix I2 = eye(Z); + // static const Eigen::Matrix I2 = eye(ZDim); // Matrix2 Q = // - // I2 - E_.block(Z * pos, 0) * PointCovariance_ * E_.block(Z * pos, 0).transpose(); + // I2 - E_.block(ZDim * pos, 0) * PointCovariance_ * E_.block(ZDim * pos, 0).transpose(); // blocks[j] = Fj.transpose() * Q * Fj; } return blocks; } virtual GaussianFactor::shared_ptr clone() const { - return boost::make_shared >(Fblocks_, - PointCovariance_, E_, b_); + return boost::make_shared >(keys_, + FBlocks_, PointCovariance_, E_, b_); throw std::runtime_error( "RegularImplicitSchurFactor::clone non implemented"); } @@ -353,8 +232,8 @@ public: } virtual GaussianFactor::shared_ptr negate() const { - return boost::make_shared >(Fblocks_, - PointCovariance_, E_, b_); + return boost::make_shared >(keys_, + FBlocks_, PointCovariance_, E_, b_); throw std::runtime_error( "RegularImplicitSchurFactor::negate non implemented"); } @@ -374,23 +253,24 @@ public: typedef std::vector Error2s; /** - * @brief Calculate corrected error Q*(e-Z*b) = (I - E*P*E')*(e-Z*b) + * @brief Calculate corrected error Q*(e-ZDim*b) = (I - E*P*E')*(e-ZDim*b) */ void projectError2(const Error2s& e1, Error2s& e2) const { - // d1 = E.transpose() * (e1-Z*b) = (3*2m)*2m + // d1 = E.transpose() * (e1-ZDim*b) = (3*2m)*2m Vector3 d1; d1.setZero(); for (size_t k = 0; k < size(); k++) - d1 += E_.block(Z * k, 0).transpose() - * (e1[k] - Z * b_.segment(k * Z)); + d1 += E_.block(ZDim * k, 0).transpose() + * (e1[k] - ZDim * b_.segment(k * ZDim)); // d2 = E.transpose() * e1 = (3*2m)*2m Vector3 d2 = PointCovariance_ * d1; // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - Z * b_.segment(k * Z) - E_.block(Z * k, 0) * d2; + e2[k] = e1[k] - ZDim * b_.segment(k * ZDim) + - E_.block(ZDim * k, 0) * d2; } /* @@ -410,7 +290,7 @@ public: // e1 = F * x - b = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]); + e1[k] = FBlocks_[k] * x.at(keys_[k]); projectError2(e1, e2); double result = 0; @@ -432,7 +312,7 @@ public: // e1 = F * x - b = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment(k * Z); + e1[k] = FBlocks_[k] * x.at(keys_[k]) - b_.segment(k * ZDim); projectError(e1, e2); double result = 0; @@ -451,14 +331,14 @@ public: Vector3 d1; d1.setZero(); for (size_t k = 0; k < size(); k++) - d1 += E_.block(Z * k, 0).transpose() * e1[k]; + d1 += E_.block(ZDim * k, 0).transpose() * e1[k]; // d2 = E.transpose() * e1 = (3*2m)*2m Vector3 d2 = PointCovariance_ * d1; // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - E_.block(Z * k, 0) * d2; + e2[k] = e1[k] - E_.block(ZDim * k, 0) * d2; } /// Scratch space for multiplyHessianAdd @@ -480,19 +360,17 @@ public: e2.resize(size()); // e1 = F * x = (2m*dm)*dm - size_t k = 0; - BOOST_FOREACH(const KeyMatrix2D& it, Fblocks_) { - Key key = it.first; - e1[k++] = it.second * ConstDMap(x + D * key); + for (size_t k = 0; k < size(); ++k) { + Key key = keys_[k]; + e1[k] = FBlocks_[k] * ConstDMap(x + D * key); } projectError(e1, e2); // y += F.transpose()*e2 = (2d*2m)*2m - k = 0; - BOOST_FOREACH(const KeyMatrix2D& it, Fblocks_) { - Key key = it.first; - DMap(y + D * key) += it.second.transpose() * alpha * e2[k++]; + for (size_t k = 0; k < size(); ++k) { + Key key = keys_[k]; + DMap(y + D * key) += FBlocks_[k].transpose() * alpha * e2[k]; } } @@ -513,7 +391,7 @@ public: // e1 = F * x = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]); + e1[k] = FBlocks_[k] * x.at(keys_[k]); projectError(e1, e2); @@ -525,8 +403,8 @@ public: Vector& yi = it.first->second; // Create the value as a zero vector if it does not exist. if (it.second) - yi = Vector::Zero(Fblocks_[k].second.cols()); - yi += Fblocks_[k].second.transpose() * alpha * e2[k]; + yi = Vector::Zero(FBlocks_[k].cols()); + yi += FBlocks_[k].transpose() * alpha * e2[k]; } } @@ -536,9 +414,9 @@ public: void multiplyHessianDummy(double alpha, const VectorValues& x, VectorValues& y) const { - BOOST_FOREACH(const KeyMatrix2D& Fi, Fblocks_) { + for (size_t k = 0; k < size(); ++k) { static const Vector empty; - Key key = Fi.first; + Key key = keys_[k]; std::pair it = y.tryInsert(key, empty); Vector& yi = it.first->second; yi = x.at(key); @@ -553,14 +431,14 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment(Z * k); + e1[k] = b_.segment(ZDim * k); projectError(e1, e2); // g = F.transpose()*e2 VectorValues g; for (size_t k = 0; k < size(); ++k) { Key key = keys_[k]; - g.insert(key, -Fblocks_[k].second.transpose() * e2[k]); + g.insert(key, -FBlocks_[k].transpose() * e2[k]); } // return it @@ -580,12 +458,12 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment(Z * k); + e1[k] = b_.segment(ZDim * k); projectError(e1, e2); for (size_t k = 0; k < size(); ++k) { // for each camera in the factor Key j = keys_[k]; - DMap(d + D * j) += -Fblocks_[k].second.transpose() * e2[k]; + DMap(d + D * j) += -FBlocks_[k].transpose() * e2[k]; } } @@ -598,9 +476,15 @@ public: }; // end class RegularImplicitSchurFactor +template +const int RegularImplicitSchurFactor::D; + +template +const int RegularImplicitSchurFactor::ZDim; + // traits -template struct traits > : public Testable< - RegularImplicitSchurFactor > { +template struct traits > : public Testable< + RegularImplicitSchurFactor > { }; } diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 60e939a89..947c81385 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -95,8 +95,7 @@ protected: public: // Definitions for blocks of F, externally visible - typedef Eigen::Matrix Matrix2D; // F - typedef std::pair KeyMatrix2D; // Fblocks + typedef Eigen::Matrix MatrixZD; // F EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -283,29 +282,16 @@ public: * F is a vector of derivatives wrpt the cameras, and E the stacked derivatives * with respect to the point. The value of cameras/point are passed as parameters. */ - double computeJacobians(std::vector& Fblocks, Matrix& E, - Vector& b, const Cameras& cameras, const Point3& point) const { - + double computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, + const Cameras& cameras, const Point3& point) const { // Project into Camera set and calculate derivatives typename Cameras::FBlocks F; b = reprojectionError(cameras, point, F, E); - - // Now calculate f and divide up the F derivatives into Fblocks - double f = 0.0; - size_t m = keys_.size(); - for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { - - // Accumulate normalized error - f += b.segment(row).squaredNorm(); - - // Push piece of F onto Fblocks with associated key - Fblocks.push_back(KeyMatrix2D(keys_[i], F[i])); - } - return f; + return b.squaredNorm(); } /// SVD version - double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, + double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, Vector& b, const Cameras& cameras, const Point3& point) const { Matrix E; @@ -328,7 +314,7 @@ public: bool diagonalDamping = false) const { int m = this->keys_.size(); - std::vector Fblocks; + std::vector Fblocks; Matrix E; Vector b; double f = computeJacobians(Fblocks, E, b, cameras, point); @@ -342,8 +328,7 @@ public: SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); // build augmented hessian - RegularImplicitSchurFactor::SparseSchurComplement(Fblocks, E, P, b, - augmentedHessian); + CameraSet::SchurComplement(Fblocks, E, P, b, augmentedHessian); augmentedHessian(m, m)(0, 0) = f; return boost::make_shared >(keys_, @@ -361,36 +346,35 @@ public: const FastVector allKeys) const { Matrix E; Vector b; - std::vector Fblocks; - double f = computeJacobians(Fblocks, E, b, cameras, point); + std::vector Fblocks; + computeJacobians(Fblocks, E, b, cameras, point); Matrix3 P = PointCov(E, lambda, diagonalDamping); - RegularImplicitSchurFactor::UpdateSparseSchurComplement(Fblocks, - E, P, b, f, allKeys, keys_, augmentedHessian); + CameraSet::UpdateSchurComplement(Fblocks, E, P, b, allKeys, keys_, + augmentedHessian); } /// Whiten the Jacobians computed by computeJacobians using noiseModel_ - void whitenJacobians(std::vector& F, Matrix& E, - Vector& b) const { + void whitenJacobians(std::vector& F, Matrix& E, Vector& b) const { noiseModel_->WhitenSystem(E, b); // TODO make WhitenInPlace work with any dense matrix type - BOOST_FOREACH(KeyMatrix2D& Fblock,F) + BOOST_FOREACH(MatrixZD& Fblock,F) Fblock.second = noiseModel_->Whiten(Fblock.second); } /** * Return Jacobians as RegularImplicitSchurFactor with raw access */ - boost::shared_ptr > // + boost::shared_ptr > // createRegularImplicitSchurFactor(const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { Matrix E; Vector b; - std::vector F; + std::vector F; computeJacobians(F, E, b, cameras, point); whitenJacobians(F, E, b); Matrix3 P = PointCov(E, lambda, diagonalDamping); - return boost::make_shared >(F, E, P, - b); + return boost::make_shared >(keys_, F, E, + P, b); } /** @@ -401,7 +385,7 @@ public: bool diagonalDamping = false) const { Matrix E; Vector b; - std::vector F; + std::vector F; computeJacobians(F, E, b, cameras, point); const size_t M = b.size(); Matrix3 P = PointCov(E, lambda, diagonalDamping); @@ -416,7 +400,7 @@ public: boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0) const { size_t m = this->keys_.size(); - std::vector F; + std::vector F; Vector b; const size_t M = ZDim * m; Matrix E0(M, M - 3); @@ -427,8 +411,7 @@ public: } /// Create BIG block-diagonal matrix F from Fblocks - static void FillDiagonalF(const std::vector& Fblocks, - Matrix& F) { + static void FillDiagonalF(const std::vector& Fblocks, Matrix& F) { size_t m = Fblocks.size(); F.resize(ZDim * m, Dim * m); F.setZero(); diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 3575a0286..4e7e0fa17 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -19,11 +19,13 @@ #include #include #include +#include +#include -#include #include #include #include +#include #include #include @@ -39,8 +41,8 @@ using namespace gtsam; const Matrix26 F0 = Matrix26::Ones(); const Matrix26 F1 = 2 * Matrix26::Ones(); const Matrix26 F3 = 3 * Matrix26::Ones(); -const vector > Fblocks = list_of > // - (make_pair(0, F0))(make_pair(1, F1))(make_pair(3, F3)); +const vector FBlocks = list_of(F0)(F1)(F3); +const FastVector keys = list_of(0)(1)(3); // RHS and sigmas const Vector b = (Vector(6) << 1., 2., 3., 4., 5., 6.).finished(); @@ -51,7 +53,7 @@ TEST( regularImplicitSchurFactor, creation ) { E.block<2,2>(0, 0) = eye(2); E.block<2,3>(2, 0) = 2 * ones(2, 3); Matrix3 P = (E.transpose() * E).inverse(); - RegularImplicitSchurFactor<6> expected(Fblocks, E, P, b); + RegularImplicitSchurFactor expected(keys, FBlocks, E, P, b); Matrix expectedP = expected.getPointCovariance(); EXPECT(assert_equal(expectedP, P)); } @@ -84,15 +86,15 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { F << F0, zeros(2, d * 3), zeros(2, d), F1, zeros(2, d*2), zeros(2, d * 3), F3; // Calculate expected result F'*alpha*(I - E*P*E')*F*x - FastVector keys; - keys += 0,1,2,3; - Vector x = xvalues.vector(keys); + FastVector keys2; + keys2 += 0,1,2,3; + Vector x = xvalues.vector(keys2); Vector expected = zero(24); - RegularImplicitSchurFactor<6>::multiplyHessianAdd(F, E, P, alpha, x, expected); - EXPECT(assert_equal(expected, yExpected.vector(keys), 1e-8)); + RegularImplicitSchurFactor::multiplyHessianAdd(F, E, P, alpha, x, expected); + EXPECT(assert_equal(expected, yExpected.vector(keys2), 1e-8)); // Create ImplicitSchurFactor - RegularImplicitSchurFactor<6> implicitFactor(Fblocks, E, P, b); + RegularImplicitSchurFactor implicitFactor(keys, FBlocks, E, P, b); VectorValues zero = 0 * yExpected;// quick way to get zero w right structure { // First Version @@ -122,7 +124,7 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { // Create JacobianFactor with same error const SharedDiagonal model; - JacobianFactorQ<6, 2> jf(Fblocks, E, P, b, model); + JacobianFactorQ<6, 2> jf(keys, FBlocks, E, P, b, model); { // error double expectedError = jf.error(xvalues); @@ -172,7 +174,7 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { } // Create JacobianFactorQR - JacobianFactorQR<6, 2> jfq(Fblocks, E, P, b, model); + JacobianFactorQR<6, 2> jfq(keys, FBlocks, E, P, b, model); { const SharedDiagonal model; VectorValues yActual = zero; @@ -214,7 +216,7 @@ TEST(regularImplicitSchurFactor, hessianDiagonal) E.block<2,3>(2, 0) << 1,2,3,4,5,6; E.block<2,3>(4, 0) << 0.5,1,2,3,4,5; Matrix3 P = (E.transpose() * E).inverse(); - RegularImplicitSchurFactor<6> factor(Fblocks, E, P, b); + RegularImplicitSchurFactor factor(keys, FBlocks, E, P, b); // hessianDiagonal VectorValues expected; From 23cf0a49f5fc26dd52ff2f03b0d3fc570e958d9b Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 22:53:17 -0800 Subject: [PATCH 087/173] Fixed another test case --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 46a9fe98c..fcebd12a7 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -797,7 +797,7 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { // Two slightly different cameras Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); @@ -832,7 +832,7 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose, sharedK)); + values.insert(x3, Camera(pose3 * noise_pose, sharedK)); EXPECT( assert_equal( Pose3( From d0e075466822a0b020d41c0f25f5005a0ab92e82 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:00:17 -0800 Subject: [PATCH 088/173] Fixed equals --- gtsam/slam/RegularImplicitSchurFactor.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index dac5ad153..ca333134e 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -96,8 +96,6 @@ public: for (size_t k = 0; k < FBlocks_.size(); ++k) { if (keys_[k] != f->keys_[k]) return false; - if (FBlocks_[k] != f->FBlocks_[k]) - return false; if (!equal_with_abs_tol(FBlocks_[k], f->FBlocks_[k], tol)) return false; } From 26f2b33c4717f89569963be3b4a794a438beccfa Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:01:47 -0800 Subject: [PATCH 089/173] Migrated to non-keyed Fblocks --- gtsam/slam/JacobianFactorSVD.h | 18 ++++++------ gtsam/slam/SmartFactorBase.h | 14 +++++----- gtsam/slam/SmartProjectionCameraFactor.h | 2 +- gtsam/slam/SmartProjectionFactor.h | 21 ++++++-------- .../tests/testSmartProjectionCameraFactor.cpp | 4 +-- .../tests/testSmartProjectionPoseFactor.cpp | 28 ++++++++++--------- 6 files changed, 44 insertions(+), 43 deletions(-) diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index 0b0d76fda..aac946901 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -16,7 +16,6 @@ class JacobianFactorSVD: public RegularJacobianFactor { typedef RegularJacobianFactor Base; typedef Eigen::Matrix MatrixZD; // e.g 2 x 6 with Z=Point2 - typedef std::pair KeyMatrixZD; typedef std::pair KeyMatrix; public: @@ -46,12 +45,13 @@ public: * * @Fblocks: */ - JacobianFactorSVD(const std::vector& Fblocks, - const Matrix& Enull, const Vector& b, // + JacobianFactorSVD(const FastVector& keys, + const std::vector& Fblocks, const Matrix& Enull, + const Vector& b, // const SharedDiagonal& model = SharedDiagonal()) : Base() { size_t numKeys = Enull.rows() / ZDim; - size_t j = 0, m2 = ZDim * numKeys - 3; + size_t m2 = ZDim * numKeys - 3; // PLAIN NULL SPACE TRICK // Matrix Q = Enull * Enull.transpose(); // BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) @@ -59,11 +59,13 @@ public: // JacobianFactor factor(QF, Q * b); std::vector QF; QF.reserve(numKeys); - BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) + for (size_t k = 0; k < Fblocks.size(); ++k) { + Key key = keys[k]; QF.push_back( - KeyMatrix(it.first, - (Enull.transpose()).block(0, ZDim * j++, m2, ZDim) * it.second)); - JacobianFactor::fillTerms(QF, - Enull.transpose() * b, model); + KeyMatrix(key, + (Enull.transpose()).block(0, ZDim * k, m2, ZDim) * Fblocks[k])); + } + JacobianFactor::fillTerms(QF, -Enull.transpose() * b, model); } }; diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 947c81385..53a86abe0 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -281,12 +281,12 @@ public: * Compute F, E, and b (called below in both vanilla and SVD versions), where * F is a vector of derivatives wrpt the cameras, and E the stacked derivatives * with respect to the point. The value of cameras/point are passed as parameters. + * TODO: Kill this obsolete method */ double computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras, const Point3& point) const { // Project into Camera set and calculate derivatives - typename Cameras::FBlocks F; - b = reprojectionError(cameras, point, F, E); + b = reprojectionError(cameras, point, Fblocks, E); return b.squaredNorm(); } @@ -357,8 +357,8 @@ public: void whitenJacobians(std::vector& F, Matrix& E, Vector& b) const { noiseModel_->WhitenSystem(E, b); // TODO make WhitenInPlace work with any dense matrix type - BOOST_FOREACH(MatrixZD& Fblock,F) - Fblock.second = noiseModel_->Whiten(Fblock.second); + for (size_t i = 0; i < F.size(); i++) + F[i] = noiseModel_->Whiten(F[i]); } /** @@ -390,7 +390,7 @@ public: const size_t M = b.size(); Matrix3 P = PointCov(E, lambda, diagonalDamping); SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); - return boost::make_shared >(F, E, P, b, n); + return boost::make_shared >(keys_, F, E, P, b, n); } /** @@ -407,7 +407,7 @@ public: computeJacobiansSVD(F, E0, b, cameras, point); SharedIsotropic n = noiseModel::Isotropic::Sigma(M - 3, noiseModel_->sigma()); - return boost::make_shared >(F, E0, b, n); + return boost::make_shared >(keys_, F, E0, b, n); } /// Create BIG block-diagonal matrix F from Fblocks @@ -416,7 +416,7 @@ public: F.resize(ZDim * m, Dim * m); F.setZero(); for (size_t i = 0; i < m; ++i) - F.block(This::ZDim * i, Dim * i) = Fblocks.at(i).second; + F.block(ZDim * i, Dim * i) = Fblocks.at(i); } private: diff --git a/gtsam/slam/SmartProjectionCameraFactor.h b/gtsam/slam/SmartProjectionCameraFactor.h index 3afd04188..b2eeba3e1 100644 --- a/gtsam/slam/SmartProjectionCameraFactor.h +++ b/gtsam/slam/SmartProjectionCameraFactor.h @@ -112,7 +112,7 @@ public: } /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr > linearizeToImplicit( + virtual boost::shared_ptr > linearizeToImplicit( const Values& values, double lambda=0.0) const { return Base::createRegularImplicitSchurFactor(Base::cameras(values),lambda); } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 7ab26c0a1..5f9a6750a 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -278,7 +278,7 @@ public: Vector b; double f; { - std::vector Fblocks; + std::vector Fblocks; f = computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); Base::whitenJacobians(Fblocks, E, b); Base::FillDiagonalF(Fblocks, F); // expensive ! @@ -326,12 +326,12 @@ public: } // create factor - boost::shared_ptr > createRegularImplicitSchurFactor( + boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda); else - return boost::shared_ptr >(); + return boost::shared_ptr >(); } /// create factor @@ -374,7 +374,7 @@ public: /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate double computeJacobiansWithTriangulatedPoint( - std::vector& Fblocks, Matrix& E, Vector& b, + std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras) const { if (!result_) { @@ -385,18 +385,15 @@ public: int m = this->keys_.size(); E = zeros(2 * m, 2); b = zero(2 * m); - double f = 0; for (size_t i = 0; i < this->measured_.size(); i++) { Matrix Fi, Ei; Vector bi = -(cameras[i].projectPointAtInfinity(*result_, Fi, Ei) - this->measured_.at(i)).vector(); - - f += bi.squaredNorm(); - Fblocks.push_back(typename Base::KeyMatrix2D(this->keys_[i], Fi)); + Fblocks.push_back(Fi); E.block<2, 2>(2 * i, 0) = Ei; subInsert(b, bi, 2 * i); } - return f; + return b.squaredNorm(); } else { // valid result: just return Base version return Base::computeJacobians(Fblocks, E, b, cameras, *result_); @@ -405,7 +402,7 @@ public: /// Version that takes values, and creates the point bool triangulateAndComputeJacobians( - std::vector& Fblocks, Matrix& E, Vector& b, + std::vector& Fblocks, Matrix& E, Vector& b, const Values& values) const { Cameras cameras = this->cameras(values); bool nonDegenerate = triangulateForLinearize(cameras); @@ -416,8 +413,8 @@ public: /// takes values bool triangulateAndComputeJacobiansSVD( - std::vector& Fblocks, Matrix& Enull, - Vector& b, const Values& values) const { + std::vector& Fblocks, Matrix& Enull, Vector& b, + const Values& values) const { Cameras cameras = this->cameras(values); bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 56ff47c3e..c7cf0283f 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -772,7 +772,7 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { Point3 point; if (factor1->point()) point = *(factor1->point()); - vector Fblocks; + vector Fblocks; factor1->computeJacobians(Fblocks, expectedE, expectedb, cameras, point); NonlinearFactorGraph generalGraph; @@ -823,7 +823,7 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { implicitFactor->add(level_uv_right, c2, unit2); GaussianFactor::shared_ptr gaussianImplicitSchurFactor = implicitFactor->linearize(values); - typedef RegularImplicitSchurFactor<9> Implicit9; + typedef RegularImplicitSchurFactor Implicit9; Implicit9& implicitSchurFactor = dynamic_cast(*gaussianImplicitSchurFactor); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index fcebd12a7..71d30b6d8 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -142,7 +142,7 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // Calculate using computeJacobians Vector b; - vector Fblocks; + vector Fblocks; double actualError3 = factor.computeJacobians(Fblocks, E, b, cameras, *point); EXPECT(assert_equal(expectedE, E, 1e-7)); EXPECT_DOUBLES_EQUAL(expectedError, actualError3, 1e-8); @@ -264,10 +264,12 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Factors ) { + typedef PinholePose Camera; + // Default cameras for simple derivatives Rot3 R; static Cal3_S2::shared_ptr sharedK(new Cal3_S2(100, 100, 0, 0, 0)); - PinholePose cam1(Pose3(R, Point3(0, 0, 0)), sharedK), cam2( + Camera cam1(Pose3(R, Point3(0, 0, 0)), sharedK), cam2( Pose3(R, Point3(1, 0, 0)), sharedK); // one landmarks 1m in front of camera @@ -350,15 +352,19 @@ TEST( SmartProjectionPoseFactor, Factors ) { E(2, 0) = 10; E(2, 2) = 1; E(3, 1) = 10; - vector > Fblocks = list_of > // - (make_pair(x1, F1))(make_pair(x2, F2)); + vector Fblocks = list_of(F1)(F2); Vector b(4); b.setZero(); + // Create smart factors + FastVector keys; + keys.push_back(x1); + keys.push_back(x2); + // createJacobianQFactor SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); Matrix3 P = (E.transpose() * E).inverse(); - JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b, n); + JacobianFactorQ<6, 2> expectedQ(keys, Fblocks, E, P, b, n); EXPECT(assert_equal(expectedInformation, expectedQ.information(), 1e-8)); boost::shared_ptr > actualQ = @@ -370,13 +376,13 @@ TEST( SmartProjectionPoseFactor, Factors ) { // Whiten for RegularImplicitSchurFactor (does not have noise model) model->WhitenSystem(E, b); Matrix3 whiteP = (E.transpose() * E).inverse(); - BOOST_FOREACH(SmartFactor::KeyMatrix2D& Fblock,Fblocks) - Fblock.second = model->Whiten(Fblock.second); + Fblocks[0] = model->Whiten(Fblocks[0]); + Fblocks[1] = model->Whiten(Fblocks[1]); // createRegularImplicitSchurFactor - RegularImplicitSchurFactor<6> expected(Fblocks, E, whiteP, b); + RegularImplicitSchurFactor expected(keys, Fblocks, E, whiteP, b); - boost::shared_ptr > actual = + boost::shared_ptr > actual = smartFactor1->createRegularImplicitSchurFactor(cameras, 0.0); CHECK(actual); EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); @@ -764,8 +770,6 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { values.insert(L(1), landmark1); values.insert(L(2), landmark2); values.insert(L(3), landmark3); - if (isDebugTest) - values.at(x3).print("Pose3 before optimization: "); DOUBLES_EQUAL(48406055, graph.error(values), 1); @@ -779,8 +783,6 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { DOUBLES_EQUAL(0, graph.error(result), 1e-9); - if (isDebugTest) - result.at(x3).print("Pose3 after optimization: "); EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); } From 485fabeae6902add8799f473bcb38d6dcf743e35 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:04:32 -0800 Subject: [PATCH 090/173] Fixed another test case --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 71d30b6d8..c5aa4b810 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -1317,7 +1317,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { // Two different cameras Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedBundlerK); Camera cam3(pose3, sharedBundlerK); @@ -1385,7 +1385,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); + values.insert(x3, Camera(pose3 * noise_pose, sharedBundlerK)); EXPECT( assert_equal( Pose3( From e6a90db2d595efe61f60e2daa36f8645c740cb00 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:11:01 -0800 Subject: [PATCH 091/173] Migrated to non-keyed Fblocks --- .../slam/SmartStereoProjectionFactor.h | 78 +++++++++++-------- 1 file changed, 44 insertions(+), 34 deletions(-) diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 68b396cd6..0b134c401 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -106,7 +106,9 @@ protected: /// shorthand for this class typedef SmartStereoProjectionFactor This; - enum {ZDim = 3}; ///< Dimension trait of measurement type + enum { + ZDim = 3 + }; ///< Dimension trait of measurement type public: @@ -156,7 +158,8 @@ public: std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; std::cout << "degenerate_ = " << degenerate_ << std::endl; std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; - std::cout << "linearizationThreshold_ = " << linearizationThreshold_ << std::endl; + std::cout << "linearizationThreshold_ = " << linearizationThreshold_ + << std::endl; Base::print("", keyFormatter); } @@ -280,11 +283,11 @@ public: // Check landmark distance and reprojection errors to avoid outliers double totalReprojError = 0.0; - size_t i=0; + size_t i = 0; BOOST_FOREACH(const Camera& camera, cameras) { Point3 cameraTranslation = camera.pose().translation(); // we discard smart factors corresponding to points that are far away - if(cameraTranslation.distance(point_) > landmarkDistanceThreshold_){ + if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { degenerate_ = true; break; } @@ -299,8 +302,8 @@ public: } //std::cout << "totalReprojError error: " << totalReprojError << std::endl; // we discard smart factors that have large reprojection error - if(dynamicOutlierRejectionThreshold_ > 0 && - totalReprojError/m > dynamicOutlierRejectionThreshold_) + if (dynamicOutlierRejectionThreshold_ > 0 + && totalReprojError / m > dynamicOutlierRejectionThreshold_) degenerate_ = true; } catch (TriangulationUnderconstrainedException&) { @@ -350,9 +353,9 @@ public: bool isDebug = false; size_t numKeys = this->keys_.size(); // Create structures for Hessian Factors - std::vector < Key > js; - std::vector < Matrix > Gs(numKeys * (numKeys + 1) / 2); - std::vector < Vector > gs(numKeys); + std::vector js; + std::vector Gs(numKeys * (numKeys + 1) / 2); + std::vector gs(numKeys); if (this->measured_.size() != cameras.size()) { std::cout @@ -362,12 +365,14 @@ public: } this->triangulateSafe(cameras); - if (isDebug) std::cout << "point_ = " << point_ << std::endl; + if (isDebug) + std::cout << "point_ = " << point_ << std::endl; if (numKeys < 2 || (!this->manageDegeneracy_ && (this->cheiralityException_ || this->degenerate_))) { - if (isDebug) std::cout << "In linearize: exception" << std::endl; + if (isDebug) + std::cout << "In linearize: exception" << std::endl; BOOST_FOREACH(Matrix& m, Gs) m = zeros(D, D); BOOST_FOREACH(Vector& v, gs) @@ -379,12 +384,14 @@ public: // instead, if we want to manage the exception.. if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors this->degenerate_ = true; - if (isDebug) std::cout << "degenerate_ = true" << std::endl; + if (isDebug) + std::cout << "degenerate_ = true" << std::endl; } bool doLinearize = this->decideIfLinearize(cameras); - if (isDebug) std::cout << "doLinearize = " << doLinearize << std::endl; + if (isDebug) + std::cout << "doLinearize = " << doLinearize << std::endl; if (this->linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize for (size_t i = 0; i < cameras.size(); i++) @@ -405,11 +412,11 @@ public: } // ================================================================== - std::vector Fblocks; + std::vector Fblocks; Matrix F, E; Vector b; double f = computeJacobians(Fblocks, E, b, cameras); - Base::FillDiagonalF(Fblocks,F); // expensive !!! + Base::FillDiagonalF(Fblocks, F); // expensive !!! // Schur complement trick // Frank says: should be possible to do this more efficiently? @@ -417,21 +424,23 @@ public: Matrix H(D * numKeys, D * numKeys); Vector gs_vector; - Matrix3 P = Base::PointCov(E,lambda); + Matrix3 P = Base::PointCov(E, lambda); H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); - if (isDebug) std::cout << "gs_vector size " << gs_vector.size() << std::endl; - if (isDebug) std::cout << "H:\n" << H << std::endl; + if (isDebug) + std::cout << "gs_vector size " << gs_vector.size() << std::endl; + if (isDebug) + std::cout << "H:\n" << H << std::endl; // Populate Gs and gs int GsCount2 = 0; - for (DenseIndex i1 = 0; i1 < (DenseIndex)numKeys; i1++) { // for each camera + for (DenseIndex i1 = 0; i1 < (DenseIndex) numKeys; i1++) { // for each camera DenseIndex i1D = i1 * D; - gs.at(i1) = gs_vector.segment < D > (i1D); - for (DenseIndex i2 = 0; i2 < (DenseIndex)numKeys; i2++) { + gs.at(i1) = gs_vector.segment(i1D); + for (DenseIndex i2 = 0; i2 < (DenseIndex) numKeys; i2++) { if (i2 >= i1) { - Gs.at(GsCount2) = H.block < D, D > (i1D, i2 * D); + Gs.at(GsCount2) = H.block(i1D, i2 * D); GsCount2++; } } @@ -476,12 +485,12 @@ public: // } // /// different (faster) way to compute Jacobian factor - boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, - double lambda) const { + boost::shared_ptr createJacobianSVDFactor( + const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared< JacobianFactorSVD >(this->keys_); + return boost::make_shared >(this->keys_); } /// Returns true if nonDegenerate @@ -506,7 +515,8 @@ public: this->degenerate_ = true; if (this->degenerate_) { - std::cout << "SmartStereoProjectionFactor: this is not ready" << std::endl; + std::cout << "SmartStereoProjectionFactor: this is not ready" + << std::endl; std::cout << "this->cheiralityException_ " << this->cheiralityException_ << std::endl; std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; @@ -527,7 +537,7 @@ public: } /// Version that takes values, and creates the point - bool computeJacobians(std::vector& Fblocks, + bool computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, const Values& values) const { Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); @@ -539,7 +549,7 @@ public: /// Compute F, E only (called below in both vanilla and SVD versions) /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate - double computeJacobians(std::vector& Fblocks, + double computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras) const { if (this->degenerate_) { throw("FIXME: computeJacobians degenerate case commented out!"); @@ -570,7 +580,7 @@ public: // // this->noise_.at(i)->WhitenSystem(Fi, Ei, bi); // f += bi.squaredNorm(); -// Fblocks.push_back(typename Base::KeyMatrix2D(this->keys_[i], Fi)); +// Fblocks.push_back(typename Base::MatrixZD(this->keys_[i], Fi)); // E.block < 2, 2 > (2 * i, 0) = Ei; // subInsert(b, bi, 2 * i); // } @@ -583,8 +593,8 @@ public: /// takes values bool triangulateAndComputeJacobiansSVD( - std::vector& Fblocks, Matrix& Enull, - Vector& b, const Values& values) const { + std::vector& Fblocks, Matrix& Enull, Vector& b, + const Values& values) const { typename Base::Cameras cameras; double good = computeCamerasAndTriangulate(values, cameras); if (good) @@ -637,7 +647,7 @@ public: } if (this->degenerate_) { - return 0.0; // TODO: this maybe should be zero? + return 0.0; // TODO: this maybe should be zero? // std::cout // << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" // << std::endl; @@ -707,8 +717,8 @@ private: /// traits template -struct traits > : - public Testable > { +struct traits > : public Testable< + SmartStereoProjectionFactor > { }; } // \ namespace gtsam From 91f3cd9e63645fa9345a92322d7736979decf8fc Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:34:26 -0800 Subject: [PATCH 092/173] Handled both degeneracies same way --- gtsam/slam/SmartProjectionFactor.h | 28 ++++++++-------------------- 1 file changed, 8 insertions(+), 20 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 5f9a6750a..7578507dc 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -449,27 +449,15 @@ public: if (result_) // All good, just use version in base class return Base::totalReprojectionError(cameras, *result_); - else { + else if (manageDegeneracy_) { + // Otherwise, manage the exceptions with rotation-only factors + const Point2& z0 = this->measured_.at(0); + result_ = TriangulationResult( + cameras.front().backprojectPointAtInfinity(z0)); + return Base::totalReprojectionErrorAtInfinity(cameras, *result_); + } else // if we don't want to manage the exceptions we discard the factor - if (!manageDegeneracy_) - return 0.0; - - if (isPointBehindCamera()) { // if we want to manage the exceptions with rotation-only factors - throw std::runtime_error( - "SmartProjectionFactor::totalReprojectionError does not handle point behind camera yet"); - } - - if (isDegenerate()) { - // 3D parameterization of point at infinity - const Point2& z0 = this->measured_.at(0); - result_ = TriangulationResult( - cameras.front().backprojectPointAtInfinity(z0)); - return Base::totalReprojectionErrorAtInfinity(cameras, *result_); - } - // should not reach here. TODO use switch - throw std::runtime_error( - "SmartProjectionFactor::totalReprojectionError internal error"); - } + return 0.0; } /** return the landmark */ From 3b144a9cab436d2f5c701420c776f74c5f7ce895 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:34:43 -0800 Subject: [PATCH 093/173] Fixed priors --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index c5aa4b810..c544ef3c1 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -31,7 +31,7 @@ using namespace boost::assign; -static bool isDebugTest = true; +static bool isDebugTest = false; static const double rankTol = 1.0; static const double linThreshold = -1.0; @@ -1374,9 +1374,9 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { graph.push_back(smartFactor3); graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back( - PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( - PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), From 5dda36a4d6a90331ef3c6456b5c484bd2b321b77 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:38:55 -0800 Subject: [PATCH 094/173] Fixed 3 more test cases --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index c544ef3c1..9008fc464 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -974,7 +974,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) // Two different cameras Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = level_pose + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); @@ -1011,9 +1011,9 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) graph.push_back(smartFactor3); graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back( - PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( - PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), @@ -1022,7 +1022,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) values.insert(x1, cam1); values.insert(x2, cam2); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose, sharedK)); + values.insert(x3, Camera(pose3 * noise_pose, sharedK)); EXPECT( assert_equal( Pose3( From 7f27a594d27fe2788d2e8eaf67f40243914ca18d Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:45:27 -0800 Subject: [PATCH 095/173] Fixed degeernate test-case --- .../slam/tests/testSmartProjectionPoseFactor.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 9008fc464..dcfb52e03 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -1162,9 +1162,12 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { views.push_back(x1); views.push_back(x2); views.push_back(x3); + + // All cameras have the same pose so will be degenerate ! + Camera cam2(level_pose, sharedK2); + Camera cam3(level_pose, sharedK2); - vector measurements_cam1, measurements_cam2, measurements_cam3; - + vector measurements_cam1; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); SmartFactor::shared_ptr smartFactor(new SmartFactor()); @@ -1183,8 +1186,8 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Values rotValues; rotValues.insert(x1, Camera(poseDrift.compose(level_pose), sharedK2)); - rotValues.insert(x2, Camera(poseDrift.compose(pose_right), sharedK2)); - rotValues.insert(x3, Camera(poseDrift.compose(pose_above), sharedK2)); + rotValues.insert(x2, Camera(poseDrift.compose(level_pose), sharedK2)); + rotValues.insert(x3, Camera(poseDrift.compose(level_pose), sharedK2)); boost::shared_ptr factorRot = smartFactor->linearize( rotValues); @@ -1199,8 +1202,8 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Values tranValues; tranValues.insert(x1, Camera(poseDrift2.compose(level_pose), sharedK2)); - tranValues.insert(x2, Camera(poseDrift2.compose(pose_right), sharedK2)); - tranValues.insert(x3, Camera(poseDrift2.compose(pose_above), sharedK2)); + tranValues.insert(x2, Camera(poseDrift2.compose(level_pose), sharedK2)); + tranValues.insert(x3, Camera(poseDrift2.compose(level_pose), sharedK2)); boost::shared_ptr factorRotTran = smartFactor->linearize( tranValues); From 014159de44f1b7ac6667dbc794c63055bcdbd5c9 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:47:27 -0800 Subject: [PATCH 096/173] Fixed sign (might need to be rethought?) --- gtsam/slam/JacobianFactorQ.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index 5dd7582cd..12f8a4c71 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -68,7 +68,7 @@ public: KeyMatrix(key, Q.block(0, ZDim * j++, m2, ZDim) * FBlocks[k])); } // Which is then passed to the normal JacobianFactor constructor - JacobianFactor::fillTerms(QF, Q * b, model); + JacobianFactor::fillTerms(QF, - Q * b, model); } }; // end class JacobianFactorQ From daf16acdfac45fcfe33bdda6a5f5ae6f82948e59 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 4 Mar 2015 23:56:18 -0800 Subject: [PATCH 097/173] Get rid of debugging fluff and more copy/paste --- .../tests/testSmartProjectionPoseFactor.cpp | 193 ++++-------------- 1 file changed, 38 insertions(+), 155 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index dcfb52e03..5d9dc4c5f 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -31,8 +31,6 @@ using namespace boost::assign; -static bool isDebugTest = false; - static const double rankTol = 1.0; static const double linThreshold = -1.0; static const bool manageDegeneracy = true; @@ -54,6 +52,11 @@ static Point2 measurement1(323.0, 240.0); typedef SmartProjectionPoseFactor SmartFactor; typedef SmartProjectionPoseFactor SmartFactorBundler; +LevenbergMarquardtParams params; +// Make more verbose like so (in tests): +// params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; +// params.verbosity = NonlinearOptimizerParams::ERROR; + /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor) { SmartFactor::shared_ptr factor1(new SmartFactor()); @@ -154,7 +157,7 @@ TEST( SmartProjectionPoseFactor, noisy ) { using namespace vanillaPose; - // Project two landmarks into two cameras and triangulate + // Project two landmarks into two cameras Point2 pixelError(0.2, 0.2); Point2 level_uv = level_camera.project(landmark1) + pixelError; Point2 level_uv_right = level_camera_right.project(landmark1); @@ -196,7 +199,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { using namespace vanillaPose2; vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // 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); @@ -239,14 +242,8 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -257,8 +254,6 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { // result.print("results of 3 camera, 3 landmark optimization \n"); EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); - if (isDebugTest) - tictoc_print_(); } /* *************************************************************************/ @@ -360,7 +355,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { FastVector keys; keys.push_back(x1); keys.push_back(x2); - + // createJacobianQFactor SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); Matrix3 P = (E.transpose() * E).inverse(); @@ -420,7 +415,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // 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); @@ -459,14 +454,8 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { -0.0313952598), Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); @@ -474,8 +463,6 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { // result.print("results of 3 camera, 3 landmark optimization \n"); EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-7)); - if (isDebugTest) - tictoc_print_(); } /* *************************************************************************/ @@ -490,7 +477,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // 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); @@ -524,12 +511,6 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { values.insert(x2, cam2); values.insert(x3, Camera(pose_above * noise_pose, sharedK)); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -550,7 +531,7 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // 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); @@ -588,7 +569,6 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { values.insert(x3, Camera(pose_above * noise_pose, sharedK)); // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -614,7 +594,7 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; - // Project three landmarks into three cameras and triangulate + // Project 4 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); @@ -657,7 +637,6 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { values.insert(x3, cam3); // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -676,7 +655,7 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // 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); @@ -709,12 +688,6 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { values.insert(x2, cam2); values.insert(x3, Camera(pose_above * noise_pose, sharedK)); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -735,7 +708,7 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { typedef GenericProjectionFactor ProjectionFactor; NonlinearFactorGraph graph; - // Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras graph.push_back( ProjectionFactor(cam1.project(landmark1), model, x1, L(1), sharedK2)); graph.push_back( @@ -773,11 +746,6 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { DOUBLES_EQUAL(48406055, graph.error(values), 1); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; LevenbergMarquardtOptimizer optimizer(graph, values, params); Values result = optimizer.optimize(); @@ -799,14 +767,13 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { // Two slightly different cameras Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = pose2 - * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // 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); @@ -888,7 +855,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); @@ -931,23 +898,13 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac Point3(0.145118171, -0.252907438, 0.819956033)), values.at(x3).pose())); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); tictoc_finishedIteration_(); - // result.print("results of 3 camera, 3 landmark optimization \n"); - cout - << "TEST COMMENTED: rotation only version of smart factors has been deprecated " - << endl; EXPECT( assert_equal( Pose3( @@ -956,8 +913,6 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac -0.564921063), Point3(0.145118171, -0.252907438, 0.819956033)), result.at(x3).pose())); - if (isDebugTest) - tictoc_print_(); } /* *************************************************************************/ @@ -974,14 +929,13 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) // Two different cameras Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = pose2 - * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; - // Project three landmarks into three cameras and triangulate + // 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); @@ -1032,23 +986,13 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3).pose())); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); tictoc_finishedIteration_(); - // result.print("results of 3 camera, 3 landmark optimization \n"); - cout - << "TEST COMMENTED: rotation only version of smart factors has been deprecated " - << endl; EXPECT( assert_equal( Pose3( @@ -1057,8 +1001,6 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), result.at(x3).pose())); - if (isDebugTest) - tictoc_print_(); } /* *************************************************************************/ @@ -1071,7 +1013,7 @@ TEST( SmartProjectionPoseFactor, Hessian ) { views.push_back(x1); views.push_back(x2); - // Project three landmarks into 2 cameras and triangulate + // Project three landmarks into 2 cameras Point2 cam1_uv1 = cam1.project(landmark1); Point2 cam2_uv1 = cam2.project(landmark1); vector measurements_cam1; @@ -1088,8 +1030,6 @@ TEST( SmartProjectionPoseFactor, Hessian ) { values.insert(x2, cam2); boost::shared_ptr factor = smartFactor1->linearize(values); - if (isDebugTest) - factor->print("Hessian factor \n"); // compute triangulation from linearization point // compute reprojection errors (sum squared) @@ -1162,7 +1102,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { views.push_back(x1); views.push_back(x2); views.push_back(x3); - + // All cameras have the same pose so will be degenerate ! Camera cam2(level_pose, sharedK2); Camera cam3(level_pose, sharedK2); @@ -1179,8 +1119,6 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { values.insert(x3, cam3); boost::shared_ptr factor = smartFactor->linearize(values); - if (isDebugTest) - factor->print("Hessian factor \n"); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); @@ -1189,10 +1127,8 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { rotValues.insert(x2, Camera(poseDrift.compose(level_pose), sharedK2)); rotValues.insert(x3, Camera(poseDrift.compose(level_pose), sharedK2)); - boost::shared_ptr factorRot = smartFactor->linearize( - rotValues); - if (isDebugTest) - factorRot->print("Hessian factor \n"); + boost::shared_ptr factorRot = // + smartFactor->linearize(rotValues); // Hessian is invariant to rotations in the nondegenerate case EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-8)); @@ -1230,27 +1166,10 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { vector measurements_cam1, measurements_cam2, measurements_cam3; - // 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); + // 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); vector views; views.push_back(x1); @@ -1289,22 +1208,15 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); tictoc_finishedIteration_(); EXPECT(assert_equal(cam3, result.at(x3), 1e-6)); - if (isDebugTest) - tictoc_print_(); } /* *************************************************************************/ @@ -1320,8 +1232,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { // Two different cameras Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - Pose3 pose3 = pose2 - * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Camera cam2(pose2, sharedBundlerK); Camera cam3(pose3, sharedBundlerK); @@ -1330,27 +1241,10 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { vector measurements_cam1, measurements_cam2, measurements_cam3; - // 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); + // 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); double rankTol = 10; @@ -1398,22 +1292,13 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3).pose())); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_ (SmartProjectionPoseFactor); + gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartProjectionPoseFactor); tictoc_finishedIteration_(); - cout - << "TEST COMMENTED: rotation only version of smart factors has been deprecated " - << endl; EXPECT( assert_equal( Pose3( @@ -1422,8 +1307,6 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3).pose())); - if (isDebugTest) - tictoc_print_(); } /* ************************************************************************* */ From dc3d5f77fe605e7bd90cc59c8d441ccab057afd3 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 10:35:54 -0800 Subject: [PATCH 098/173] Extra stereo tests --- .../testSmartStereoProjectionPoseFactor.cpp | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 48dfa1ff0..7e2a1a468 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -279,6 +279,14 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { values.insert(x3, pose3 * noise_pose); if (isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); + EXPECT( + assert_equal( + Pose3( + Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, + -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), + Point3(0.1, -0.1, 1.9)), values.at(x3))); + + EXPECT_DOUBLES_EQUAL(1888864, graph.error(values), 1); LevenbergMarquardtParams params; if (isDebugTest) @@ -293,8 +301,12 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { gttoc_(SmartStereoProjectionPoseFactor); tictoc_finishedIteration_(); -// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); -// VectorValues delta = GFG->optimize(); + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-6); + + GaussianFactorGraph::shared_ptr GFG = graph.linearize(result); + VectorValues delta = GFG->optimize(); + VectorValues expected = VectorValues::Zero(delta); + EXPECT(assert_equal(expected, delta,1e-6)); // result.print("results of 3 camera, 3 landmark optimization \n"); if (isDebugTest) From b40c0f7f154ea6ae459b31f898db47d5125cd789 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 10:36:03 -0800 Subject: [PATCH 099/173] Fixed sign --- gtsam_unstable/slam/SmartStereoProjectionFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 0b134c401..65036edfe 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -426,7 +426,7 @@ public: Matrix3 P = Base::PointCov(E, lambda); H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); + gs_vector.noalias() = - F.transpose() * (b - (E * (P * (E.transpose() * b)))); if (isDebug) std::cout << "gs_vector size " << gs_vector.size() << std::endl; From 758aab6e808f8658d7555871b0533bf41010dfa8 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 10:41:49 -0800 Subject: [PATCH 100/173] Cleaned up test --- .../testSmartStereoProjectionPoseFactor.cpp | 74 ++----------------- 1 file changed, 6 insertions(+), 68 deletions(-) diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 7e2a1a468..497f2205c 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -18,8 +18,8 @@ * @date Sept 2013 */ +// TODO #include #include - #include #include #include @@ -32,8 +32,6 @@ using namespace std; using namespace boost::assign; using namespace gtsam; -static bool isDebugTest = false; - // make a realistic calibration matrix static double fov = 60; // degrees static size_t w = 640, h = 480; @@ -83,9 +81,10 @@ vector stereo_projectToMultipleCameras(const StereoCamera& cam1, return measurements_cam; } +LevenbergMarquardtParams params; + /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor) { - fprintf(stderr, "Test 1 Complete"); SmartFactor::shared_ptr factor1(new SmartFactor()); } @@ -119,8 +118,6 @@ TEST( SmartStereoProjectionPoseFactor, Equals ) { /* *************************************************************************/ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: noisy ****************************" << endl; - // 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), Point3(0, 0, 1)); @@ -160,8 +157,6 @@ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, noisy ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: noisy ****************************" << endl; - // 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), Point3(0, 0, 1)); @@ -217,10 +212,6 @@ TEST( SmartStereoProjectionPoseFactor, noisy ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { - cout - << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks **********************" - << endl; - // 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), Point3(0, 0, 1)); StereoCamera cam1(pose1, K2); @@ -277,8 +268,6 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { 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: "); EXPECT( assert_equal( Pose3( @@ -288,14 +277,8 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { EXPECT_DOUBLES_EQUAL(1888864, graph.error(values), 1); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_ (SmartStereoProjectionPoseFactor); + gttic_(SmartStereoProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); gttoc_(SmartStereoProjectionPoseFactor); @@ -306,14 +289,10 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { GaussianFactorGraph::shared_ptr GFG = graph.linearize(result); VectorValues delta = GFG->optimize(); VectorValues expected = VectorValues::Zero(delta); - EXPECT(assert_equal(expected, delta,1e-6)); + EXPECT(assert_equal(expected, delta, 1e-6)); // 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_(); } /* *************************************************************************/ @@ -376,7 +355,6 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { values.insert(x2, pose2); values.insert(x3, pose3 * noise_pose); - LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -449,7 +427,6 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { values.insert(x3, pose3 * noise_pose); // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -533,7 +510,6 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { values.insert(x3, pose3); // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -595,8 +571,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // values.insert(x2, pose2); // values.insert(x3, pose3*noise_pose); // -// LevenbergMarquardtParams params; -// Values result; +//// Values result; // LevenbergMarquardtOptimizer optimizer(graph, values, params); // result = optimizer.optimize(); // EXPECT(assert_equal(pose3,result.at(x3))); @@ -604,7 +579,6 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ -// // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; // // vector views; // views.push_back(x1); @@ -656,15 +630,10 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // values.insert(L(1), landmark1); // values.insert(L(2), landmark2); // values.insert(L(3), landmark3); -// if(isDebugTest) values.at(x3).print("Pose3 before optimization: "); // -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; // LevenbergMarquardtOptimizer optimizer(graph, values, params); // Values result = optimizer.optimize(); // -// if(isDebugTest) result.at(x3).print("Pose3 after optimization: "); // EXPECT(assert_equal(pose3,result.at(x3))); //} // @@ -726,8 +695,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise values.insert(x3, pose3 * noise_pose); - if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); // TODO: next line throws Cheirality exception on Mac boost::shared_ptr hessianFactor1 = smartFactor1->linearize( @@ -752,7 +719,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { + hessianFactor3->augmentedInformation(); // Check Information vector - // cout << AugInformationMatrix.size() << endl; Vector InfoVector = AugInformationMatrix.block(0, 18, 18, 1); // 18x18 Hessian + information vector // Check Hessian @@ -761,7 +727,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; // // vector views; // views.push_back(x1); @@ -814,11 +779,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // 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); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; // // Values result; // gttic_(SmartStereoProjectionPoseFactor); @@ -828,15 +788,11 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // tictoc_finishedIteration_(); // // // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; // // EXPECT(assert_equal(pose3,result.at(x3))); -// if(isDebugTest) tictoc_print_(); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks: Rotation Only**********************" << endl; // // vector views; // views.push_back(x1); @@ -897,11 +853,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // 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::TRYDELTA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; // // Values result; // gttic_(SmartStereoProjectionPoseFactor); @@ -911,15 +862,11 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // tictoc_finishedIteration_(); // // // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; // // EXPECT(assert_equal(pose3,result.at(x3))); -// if(isDebugTest) tictoc_print_(); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, Hessian ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: Hessian **********************" << endl; // // vector views; // views.push_back(x1); @@ -952,7 +899,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // values.insert(x2, pose2); // // boost::shared_ptr hessianFactor = smartFactor1->linearize(values); -// if(isDebugTest) hessianFactor->print("Hessian factor \n"); // // // compute triangulation from linearization point // // compute reprojection errors (sum squared) @@ -963,8 +909,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; - vector views; views.push_back(x1); views.push_back(x2); @@ -1034,8 +978,6 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; - vector views; views.push_back(x1); views.push_back(x2); @@ -1066,8 +1008,6 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { boost::shared_ptr hessianFactor = smartFactor->linearize( values); - if (isDebugTest) - hessianFactor->print("Hessian factor \n"); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); @@ -1078,8 +1018,6 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { boost::shared_ptr hessianFactorRot = smartFactor->linearize( rotValues); - if (isDebugTest) - hessianFactorRot->print("Hessian factor \n"); // Hessian is invariant to rotations in the nondegenerate case EXPECT( From 2f8d12b9ba4491775f015ed155cea7e5bd747e6e Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 12:41:01 -0800 Subject: [PATCH 101/173] Added more tests to diagnose Regular-Q inconsistency --- .../slam/tests/testRegularImplicitSchurFactor.cpp | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 4e7e0fa17..0063326fe 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -126,13 +126,14 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { const SharedDiagonal model; JacobianFactorQ<6, 2> jf(keys, FBlocks, E, P, b, model); +// TODO(frank) Neither tests pass, should get to bottom, possibly remove errorJF? { // error double expectedError = jf.error(xvalues); - double actualError = implicitFactor.errorJF(xvalues); - DOUBLES_EQUAL(expectedError,actualError,1e-7) + EXPECT_DOUBLES_EQUAL(expectedError,implicitFactor.error(xvalues),1e-7) + EXPECT_DOUBLES_EQUAL(expectedError,implicitFactor.errorJF(xvalues),1e-7) } - { // JacobianFactor with same error + { VectorValues yActual = zero; jf.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(yExpected, yActual, 1e-8)); @@ -175,6 +176,13 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { // Create JacobianFactorQR JacobianFactorQR<6, 2> jfq(keys, FBlocks, E, P, b, model); + { // error + double expectedError = jfq.error(xvalues); + EXPECT_DOUBLES_EQUAL(expectedError, jf.error(xvalues),1e-7) + double actualError = implicitFactor.errorJF(xvalues); + EXPECT_DOUBLES_EQUAL(expectedError,actualError,1e-7) + } + { const SharedDiagonal model; VectorValues yActual = zero; From d095933527fc9adb523d1cfbd7d76ed581bc1231 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 12:53:10 -0800 Subject: [PATCH 102/173] Refactor --- .../tests/testRegularImplicitSchurFactor.cpp | 46 +++++++++---------- 1 file changed, 21 insertions(+), 25 deletions(-) diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 0063326fe..8ece637e7 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -124,33 +124,34 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { // Create JacobianFactor with same error const SharedDiagonal model; - JacobianFactorQ<6, 2> jf(keys, FBlocks, E, P, b, model); + JacobianFactorQ<6, 2> jfQ(keys, FBlocks, E, P, b, model); -// TODO(frank) Neither tests pass, should get to bottom, possibly remove errorJF? +// Calculate expected error + double expectedError = 1000; { // error - double expectedError = jf.error(xvalues); + EXPECT_DOUBLES_EQUAL(expectedError,jfQ.error(xvalues),1e-7) EXPECT_DOUBLES_EQUAL(expectedError,implicitFactor.error(xvalues),1e-7) EXPECT_DOUBLES_EQUAL(expectedError,implicitFactor.errorJF(xvalues),1e-7) } { VectorValues yActual = zero; - jf.multiplyHessianAdd(alpha, xvalues, yActual); + jfQ.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(yExpected, yActual, 1e-8)); - jf.multiplyHessianAdd(alpha, xvalues, yActual); + jfQ.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(2 * yExpected, yActual, 1e-8)); - jf.multiplyHessianAdd(-1, xvalues, yActual); + jfQ.multiplyHessianAdd(-1, xvalues, yActual); EXPECT(assert_equal(zero, yActual, 1e-8)); } { // check hessian Diagonal - VectorValues diagExpected = jf.hessianDiagonal(); + VectorValues diagExpected = jfQ.hessianDiagonal(); VectorValues diagActual = implicitFactor.hessianDiagonal(); EXPECT(assert_equal(diagExpected, diagActual, 1e-8)); } { // check hessian Block Diagonal - map BD = jf.hessianBlockDiagonal(); + map BD = jfQ.hessianBlockDiagonal(); map actualBD = implicitFactor.hessianBlockDiagonal(); LONGS_EQUAL(3,actualBD.size()); EXPECT(assert_equal(BD[0],actualBD[0])); @@ -160,47 +161,42 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { { // Raw memory Version std::fill(y, y + 24, 0);// zero y ! - jf.multiplyHessianAdd(alpha, xdata, y); + jfQ.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(expected, XMap(y), 1e-8)); - jf.multiplyHessianAdd(alpha, xdata, y); + jfQ.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(Vector(2 * expected), XMap(y), 1e-8)); - jf.multiplyHessianAdd(-1, xdata, y); + jfQ.multiplyHessianAdd(-1, xdata, y); EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); } { // Check gradientAtZero - VectorValues expected = jf.gradientAtZero(); + VectorValues expected = jfQ.gradientAtZero(); VectorValues actual = implicitFactor.gradientAtZero(); EXPECT(assert_equal(expected, actual, 1e-8)); } // Create JacobianFactorQR - JacobianFactorQR<6, 2> jfq(keys, FBlocks, E, P, b, model); - { // error - double expectedError = jfq.error(xvalues); - EXPECT_DOUBLES_EQUAL(expectedError, jf.error(xvalues),1e-7) - double actualError = implicitFactor.errorJF(xvalues); - EXPECT_DOUBLES_EQUAL(expectedError,actualError,1e-7) - } + JacobianFactorQR<6, 2> jfQR(keys, FBlocks, E, P, b, model); + EXPECT_DOUBLES_EQUAL(expectedError, jfQR.error(xvalues),1e-7) { const SharedDiagonal model; VectorValues yActual = zero; - jfq.multiplyHessianAdd(alpha, xvalues, yActual); + jfQR.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(yExpected, yActual, 1e-8)); - jfq.multiplyHessianAdd(alpha, xvalues, yActual); + jfQR.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(2 * yExpected, yActual, 1e-8)); - jfq.multiplyHessianAdd(-1, xvalues, yActual); + jfQR.multiplyHessianAdd(-1, xvalues, yActual); EXPECT(assert_equal(zero, yActual, 1e-8)); } { // Raw memory Version std::fill(y, y + 24, 0);// zero y ! - jfq.multiplyHessianAdd(alpha, xdata, y); + jfQR.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(expected, XMap(y), 1e-8)); - jfq.multiplyHessianAdd(alpha, xdata, y); + jfQR.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(Vector(2 * expected), XMap(y), 1e-8)); - jfq.multiplyHessianAdd(-1, xdata, y); + jfQR.multiplyHessianAdd(-1, xdata, y); EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); } delete [] y; From 1d8b14384b67d1a04c5cc74f811019a47fc88548 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 12:53:25 -0800 Subject: [PATCH 103/173] GradientAtZero now negative --- gtsam/slam/RegularImplicitSchurFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index ca333134e..ae42d3087 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -436,7 +436,7 @@ public: VectorValues g; for (size_t k = 0; k < size(); ++k) { Key key = keys_[k]; - g.insert(key, -FBlocks_[k].transpose() * e2[k]); + g.insert(key, FBlocks_[k].transpose() * e2[k]); } // return it From befdfd1f09a88d2d3a9f1545d87fab5eb68c1eea Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 14:49:11 -0800 Subject: [PATCH 104/173] extra tests with actual values --- .../tests/testRegularImplicitSchurFactor.cpp | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 8ece637e7..77944da83 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -126,12 +126,12 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { const SharedDiagonal model; JacobianFactorQ<6, 2> jfQ(keys, FBlocks, E, P, b, model); -// Calculate expected error - double expectedError = 1000; - { // error + // error + double expectedError = 11875.083333333334; + { EXPECT_DOUBLES_EQUAL(expectedError,jfQ.error(xvalues),1e-7) - EXPECT_DOUBLES_EQUAL(expectedError,implicitFactor.error(xvalues),1e-7) EXPECT_DOUBLES_EQUAL(expectedError,implicitFactor.errorJF(xvalues),1e-7) + EXPECT_DOUBLES_EQUAL(11903.500000000007,implicitFactor.error(xvalues),1e-7) } { @@ -169,16 +169,20 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); } + VectorValues expectedVV; + expectedVV.insert(0,-3.5*ones(6)); + expectedVV.insert(1,10*ones(6)/3); + expectedVV.insert(3,-19.5*ones(6)); { // Check gradientAtZero - VectorValues expected = jfQ.gradientAtZero(); VectorValues actual = implicitFactor.gradientAtZero(); - EXPECT(assert_equal(expected, actual, 1e-8)); + EXPECT(assert_equal(expectedVV, jfQ.gradientAtZero(), 1e-8)); + EXPECT(assert_equal(expectedVV, implicitFactor.gradientAtZero(), 1e-8)); } // Create JacobianFactorQR JacobianFactorQR<6, 2> jfQR(keys, FBlocks, E, P, b, model); EXPECT_DOUBLES_EQUAL(expectedError, jfQR.error(xvalues),1e-7) - + EXPECT(assert_equal(expectedVV, jfQR.gradientAtZero(), 1e-8)); { const SharedDiagonal model; VectorValues yActual = zero; From 36be55e92c7df27757f473756a131ebaf251c279 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 15:48:55 -0800 Subject: [PATCH 105/173] Fix gradientAtZero --- gtsam/slam/RegularImplicitSchurFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index ae42d3087..e773efc5d 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -436,7 +436,7 @@ public: VectorValues g; for (size_t k = 0; k < size(); ++k) { Key key = keys_[k]; - g.insert(key, FBlocks_[k].transpose() * e2[k]); + g.insert(key, - FBlocks_[k].transpose() * e2[k]); } // return it From 5cdb8ddb761d3fa1245afd7505eefc725d895840 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 15:53:29 -0800 Subject: [PATCH 106/173] Negated meaning of reprojectionError --- gtsam/geometry/CameraSet.h | 8 ++++---- gtsam/geometry/tests/testCameraSet.cpp | 2 +- gtsam/geometry/tests/testPinholeSet.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index dd58f8e69..ecdc7c007 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -141,18 +141,18 @@ public: return z; } - /// Calculate vector of re-projection errors + /// Calculate vector [z-project2(point)] of re-projection errors Vector reprojectionError(const Point3& point, const std::vector& measured, boost::optional Fs = boost::none, // boost::optional E = boost::none) const { - return ErrorVector(project2(point, Fs, E), measured); + return ErrorVector(measured, project2(point, Fs, E)); } - /// Calculate vector of re-projection errors, from point at infinity + /// Calculate vector [z-project2(point)] of re-projection errors, from point at infinity // TODO: take Unit3 instead Vector reprojectionErrorAtInfinity(const Point3& point, const std::vector& measured) const { - return ErrorVector(projectAtInfinity(point), measured); + return ErrorVector(measured, projectAtInfinity(point)); } /** diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 05ffc275c..f34809ae6 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -75,7 +75,7 @@ TEST(CameraSet, Pinhole) { Vector4 expectedV; // reprojectionError - expectedV << -1, -2, -3, -4; + expectedV << 1, 2, 3, 4; Vector actualV = set.reprojectionError(p, measured); EXPECT(assert_equal(expectedV, actualV)); diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp index 1e5426f33..a8e43003d 100644 --- a/gtsam/geometry/tests/testPinholeSet.cpp +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -115,7 +115,7 @@ TEST(PinholeSet, Pinhole) { Vector4 expectedV; // reprojectionError - expectedV << -1, -2, -3, -4; + expectedV << 1, 2, 3, 4; Vector actualV = set.reprojectionError(p, measured); EXPECT(assert_equal(expectedV, actualV)); From 62120349760d8c9ab0d2e554e4bdd954b9def9aa Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 16:59:10 -0800 Subject: [PATCH 107/173] Added comments to be explicit about b = z - h(x_bar) --- gtsam/nonlinear/ExpressionFactor.h | 27 ++++++++++++++++----------- 1 file changed, 16 insertions(+), 11 deletions(-) diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 4769e5048..21c709bcf 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -66,20 +66,23 @@ public: virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { if (H) { - const T value = expression_.value(x, keys_, dims_, *H); - return traits::Local(measurement_, value); + const T hx = expression_.value(x, keys_, dims_, *H); // h(x) + return traits::Local(measurement_, hx); // h(x) - z } else { - const T value = expression_.value(x); - return traits::Local(measurement_, value); + const T hx = expression_.value(x); // h(x) + return traits::Local(measurement_, hx); // h(x) - z } } - virtual boost::shared_ptr linearize(const Values& x) const { + /** + * Linearize the factor into a JacobianFactor + */ + virtual boost::shared_ptr linearize(const Values& x_bar) const { // Only linearize if the factor is active - if (!active(x)) + if (!active(x_bar)) return boost::shared_ptr(); - // Create a writeable JacobianFactor in advance + // Create a writable JacobianFactor in advance // In case noise model is constrained, we need to provide a noise model bool constrained = noiseModel_->isConstrained(); boost::shared_ptr factor( @@ -88,17 +91,19 @@ public: new JacobianFactor(keys_, dims_, Dim)); // Wrap keys and VerticalBlockMatrix into structure passed to expression_ - VerticalBlockMatrix& Ab = factor->matrixObject(); + VerticalBlockMatrix& Ab = factor->matrixObject(); // reference, no malloc ! JacobianMap jacobianMap(keys_, Ab); // Zero out Jacobian so we can simply add to it Ab.matrix().setZero(); // Get value and Jacobians, writing directly into JacobianFactor - T value = expression_.value(x, jacobianMap); // <<< Reverse AD happens here ! + T hx = expression_.value(x_bar, jacobianMap); // <<< Reverse AD happens here ! - // Evaluate error and set RHS vector b - Ab(size()).col(0) = -traits::Local(measurement_, value); + // Evaluate error and set RHS vector b = - (h(x_bar) - z) = z-h(x_bar) + // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z| + // = |A*dx - (z-h(x_bar))| + Ab(size()).col(0) = - traits::Local(measurement_, hx); // - unwhitenedError(x_bar) // Whiten the corresponding system, Ab already contains RHS Vector dummy(Dim); From 1620b9056ad71a0c7198b1f0046cd797d9b8a367 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 17:06:44 -0800 Subject: [PATCH 108/173] Reverted back to [h(x)-z] with Luca --- gtsam/geometry/CameraSet.h | 10 +++++----- gtsam/geometry/tests/testCameraSet.cpp | 2 +- gtsam/geometry/tests/testPinholeSet.cpp | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index ecdc7c007..3bbcb8c0d 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -53,7 +53,7 @@ protected: if (measured.size() != m) throw std::runtime_error("CameraSet::errors: size mismatch"); - // Project and fill derivatives + // Project and fill error vector Vector b(ZDim * m); for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { Z e = predicted[i] - measured[i]; @@ -141,18 +141,18 @@ public: return z; } - /// Calculate vector [z-project2(point)] of re-projection errors + /// Calculate vector [project2(point)-z] of re-projection errors Vector reprojectionError(const Point3& point, const std::vector& measured, boost::optional Fs = boost::none, // boost::optional E = boost::none) const { - return ErrorVector(measured, project2(point, Fs, E)); + return ErrorVector(project2(point, Fs, E), measured); } - /// Calculate vector [z-project2(point)] of re-projection errors, from point at infinity + /// Calculate vector [project2(point)-z] of re-projection errors, from point at infinity // TODO: take Unit3 instead Vector reprojectionErrorAtInfinity(const Point3& point, const std::vector& measured) const { - return ErrorVector(measured, projectAtInfinity(point)); + return ErrorVector(projectAtInfinity(point), measured); } /** diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index f34809ae6..05ffc275c 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -75,7 +75,7 @@ TEST(CameraSet, Pinhole) { Vector4 expectedV; // reprojectionError - expectedV << 1, 2, 3, 4; + expectedV << -1, -2, -3, -4; Vector actualV = set.reprojectionError(p, measured); EXPECT(assert_equal(expectedV, actualV)); diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp index a8e43003d..1e5426f33 100644 --- a/gtsam/geometry/tests/testPinholeSet.cpp +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -115,7 +115,7 @@ TEST(PinholeSet, Pinhole) { Vector4 expectedV; // reprojectionError - expectedV << 1, 2, 3, 4; + expectedV << -1, -2, -3, -4; Vector actualV = set.reprojectionError(p, measured); EXPECT(assert_equal(expectedV, actualV)); From 4a6801cfe1d49d7bb6f9e79c4b3c5124f82f8db4 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 19:29:47 -0800 Subject: [PATCH 109/173] Calibration -> CALIBRATION --- gtsam/geometry/PinholePose.h | 46 ++++++++++++++++++------------------ 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index b5daaebc5..0b7184e2b 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -30,15 +30,15 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -template +template class GTSAM_EXPORT PinholeBaseK: public PinholeBase { private: - GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration); + GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION); // Get dimensions of calibration type at compile time - static const int DimK = FixedDimension::value; + static const int DimK = FixedDimension::value; public: @@ -70,7 +70,7 @@ public: } /// return calibration - virtual const Calibration& calibration() const = 0; + virtual const CALIBRATION& calibration() const = 0; /// @} /// @name Transformations and measurement functions @@ -235,13 +235,13 @@ private: * @addtogroup geometry * \nosubgrouping */ -template -class GTSAM_EXPORT PinholePose: public PinholeBaseK { +template +class GTSAM_EXPORT PinholePose: public PinholeBaseK { private: - typedef PinholeBaseK Base; ///< base class has 3D pose as private member - boost::shared_ptr K_; ///< shared pointer to fixed calibration + typedef PinholeBaseK Base; ///< base class has 3D pose as private member + boost::shared_ptr K_; ///< shared pointer to fixed calibration public: @@ -258,11 +258,11 @@ public: /** constructor with pose, uses default calibration */ explicit PinholePose(const Pose3& pose) : - Base(pose), K_(new Calibration()) { + Base(pose), K_(new CALIBRATION()) { } /** constructor with pose and calibration */ - PinholePose(const Pose3& pose, const boost::shared_ptr& K) : + PinholePose(const Pose3& pose, const boost::shared_ptr& K) : Base(pose), K_(K) { } @@ -277,14 +277,14 @@ public: * (theta 0 = looking in direction of positive X axis) * @param height camera height */ - static PinholePose Level(const boost::shared_ptr& K, + static PinholePose Level(const boost::shared_ptr& K, const Pose2& pose2, double height) { return PinholePose(Base::LevelPose(pose2, height), K); } /// PinholePose::level with default calibration static PinholePose Level(const Pose2& pose2, double height) { - return PinholePose::Level(boost::make_shared(), pose2, height); + return PinholePose::Level(boost::make_shared(), pose2, height); } /** @@ -297,8 +297,8 @@ public: * @param K optional calibration parameter */ static PinholePose Lookat(const Point3& eye, const Point3& target, - const Point3& upVector, const boost::shared_ptr& K = - boost::make_shared()) { + const Point3& upVector, const boost::shared_ptr& K = + boost::make_shared()) { return PinholePose(Base::LookatPose(eye, target, upVector), K); } @@ -308,12 +308,12 @@ public: /// Init from 6D vector explicit PinholePose(const Vector &v) : - Base(v), K_(new Calibration()) { + Base(v), K_(new CALIBRATION()) { } /// Init from Vector and calibration PinholePose(const Vector &v, const Vector &K) : - Base(v), K_(new Calibration(K)) { + Base(v), K_(new CALIBRATION(K)) { } /// @} @@ -340,7 +340,7 @@ public: } /// return calibration - virtual const Calibration& calibration() const { + virtual const CALIBRATION& calibration() const { return *K_; } @@ -390,14 +390,14 @@ private: }; // end of class PinholePose -template -struct traits > : public internal::Manifold< - PinholePose > { +template +struct traits > : public internal::Manifold< + PinholePose > { }; -template -struct traits > : public internal::Manifold< - PinholePose > { +template +struct traits > : public internal::Manifold< + PinholePose > { }; } // \ gtsam From 95e00d305200065c28743fb20a20bc380853c0cf Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 19:34:34 -0800 Subject: [PATCH 110/173] Moved project2 to its rightful place in PinholePose (as opposed to PinholeBaseK) --- gtsam/geometry/PinholePose.h | 42 ++++++++++++++++++------------------ 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 0b7184e2b..2ef008a94 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -95,27 +95,6 @@ public: return calibration().uncalibrate(pn); } - /** project a point from world coordinate to the image, w 2 derivatives - * @param pw is a point in the world coordinates - */ - Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none) const { - - // project to normalized coordinates - const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - - // uncalibrate to pixel coordinates - Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, boost::none, - Dpose || Dpoint ? &Dpi_pn : 0); - - // If needed, apply chain rule - if (Dpose) *Dpose = Dpi_pn * (*Dpose); - if (Dpoint) *Dpoint = Dpi_pn * (*Dpoint); - - return pi; - } - /** project a point at infinity from world coordinate to the image * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) * @param Dpose is the Jacobian w.r.t. pose3 @@ -344,6 +323,27 @@ public: return *K_; } + /** project a point from world coordinate to the image, w 2 derivatives + * @param pw is a point in the world coordinates + */ + Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 3> Dpoint = boost::none) const { + + // project to normalized coordinates + const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); + + // uncalibrate to pixel coordinates + Matrix2 Dpi_pn; + const Point2 pi = calibration().uncalibrate(pn, boost::none, + Dpose || Dpoint ? &Dpi_pn : 0); + + // If needed, apply chain rule + if (Dpose) *Dpose = Dpi_pn * (*Dpose); + if (Dpoint) *Dpoint = Dpi_pn * (*Dpoint); + + return pi; + } + /// @} /// @name Manifold /// @{ From f3f09b17a76079e9deb854a15eb514c250e27634 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 20:26:47 -0800 Subject: [PATCH 111/173] project_to_camera for Unit3 (points at infinity) --- gtsam/geometry/CalibratedCamera.cpp | 13 +++++++++++ gtsam/geometry/CalibratedCamera.h | 8 +++++++ gtsam/geometry/tests/testCalibratedCamera.cpp | 22 ++++++++++++++++--- 3 files changed, 40 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp index 33f2c84eb..213cae978 100644 --- a/gtsam/geometry/CalibratedCamera.cpp +++ b/gtsam/geometry/CalibratedCamera.cpp @@ -94,6 +94,19 @@ Point2 PinholeBase::project_to_camera(const Point3& pc, return Point2(u, v); } +/* ************************************************************************* */ +Point2 PinholeBase::project_to_camera(const Unit3& pc, + OptionalJacobian<2, 2> Dpoint) { + if (Dpoint) { + Matrix32 Dpoint3_pc; + Matrix23 Duv_point3; + Point2 uv = project_to_camera(pc.point3(Dpoint3_pc), Duv_point3); + *Dpoint = Duv_point3 * Dpoint3_pc; + return uv; + } else + return project_to_camera(pc.point3()); +} + /* ************************************************************************* */ pair PinholeBase::projectSafe(const Point3& pw) const { const Point3 pc = pose().transform_to(pw); diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 35789053e..56a42f3de 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -167,6 +167,14 @@ public: static Point2 project_to_camera(const Point3& pc, // OptionalJacobian<2, 3> Dpoint = boost::none); + /** + * Project from 3D point at infinity in camera coordinates into image + * Does *not* throw a CheiralityException, even if pc behind image plane + * @param pc point in camera coordinates + */ + static Point2 project_to_camera(const Unit3& pc, // + OptionalJacobian<2, 2> Dpoint = boost::none); + /// Project a point into the image and check depth std::pair projectSafe(const Point3& pw) const; diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index b1e265266..3b2f35031 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -88,12 +88,28 @@ TEST( CalibratedCamera, project) } /* ************************************************************************* */ +static Point2 project_to_camera1(const Point3& point) { + return PinholeBase::project_to_camera(point); +} + TEST( CalibratedCamera, Dproject_to_camera1) { - Point3 pp(155,233,131); + Point3 pp(155, 233, 131); Matrix test1; CalibratedCamera::project_to_camera(pp, test1); - Matrix test2 = numericalDerivative11( - boost::bind(CalibratedCamera::project_to_camera, _1, boost::none), pp); + Matrix test2 = numericalDerivative11(project_to_camera1, pp); + CHECK(assert_equal(test1, test2)); +} + +/* ************************************************************************* */ +static Point2 project_to_camera2(const Unit3& point) { + return PinholeBase::project_to_camera(point); +} + +TEST( CalibratedCamera, Dproject_to_cameraInfinity) { + Unit3 pp(0, 0, 1000); + Matrix test1; + CalibratedCamera::project_to_camera(pp, test1); + Matrix test2 = numericalDerivative11(project_to_camera2, pp); CHECK(assert_equal(test1, test2)); } From 3f94791b3bba015d49da7cac8679665b6451fbf1 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 22:10:30 -0800 Subject: [PATCH 112/173] project2 of point at infinity --- gtsam/geometry/CalibratedCamera.cpp | 29 ++++++++++++++- gtsam/geometry/CalibratedCamera.h | 9 +++++ gtsam/geometry/tests/testCalibratedCamera.cpp | 37 +++++++++++++++++-- 3 files changed, 71 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp index 213cae978..fb518f2e3 100644 --- a/gtsam/geometry/CalibratedCamera.cpp +++ b/gtsam/geometry/CalibratedCamera.cpp @@ -122,7 +122,7 @@ Point2 PinholeBase::project2(const Point3& point, OptionalJacobian<2, 6> Dpose, const Point3 q = pose().transform_to(point, boost::none, Dpoint ? &Rt : 0); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION if (q.z() <= 0) - throw CheiralityException(); + throw CheiralityException(); #endif const Point2 pn = project_to_camera(q); @@ -136,6 +136,33 @@ Point2 PinholeBase::project2(const Point3& point, OptionalJacobian<2, 6> Dpose, return pn; } +/* ************************************************************************* */ +Point2 PinholeBase::project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 2> Dpoint) const { + + // world to camera coordinate + Matrix23 Dpc_rot; + Matrix2 Dpc_point; + const Unit3 pc = pose().rotation().unrotate(pw, Dpose ? &Dpc_rot : 0, + Dpose ? &Dpc_point : 0); + + // camera to normalized image coordinate + Matrix2 Dpn_pc; + const Point2 pn = PinholeBase::project_to_camera(pc, + Dpose || Dpoint ? &Dpn_pc : 0); + + // chain the Jacobian matrices + if (Dpose) { + // only rotation is important + Matrix26 Dpc_pose; + Dpc_pose.setZero(); + Dpc_pose.leftCols<3>() = Dpc_rot; + *Dpose = Dpn_pc * Dpc_pose; // 2x2 * 2x6 + } + if (Dpoint) + *Dpoint = Dpn_pc * Dpc_point; // 2x2 * 2*2 + return pn; +} /* ************************************************************************* */ Point3 PinholeBase::backproject_from_camera(const Point2& p, const double depth) { diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 56a42f3de..e43cafcc2 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -187,6 +187,15 @@ public: Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose = boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const; + /** + * Project point at infinity into the image + * Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION + * @param point 3D point in world coordinates + * @return the intrinsic coordinates of the projected point + */ + Point2 project2(const Unit3& point, OptionalJacobian<2, 6> Dpose = + boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const; + /// backproject a 2-dimensional point to a 3-dimensional point at given depth static Point3 backproject_from_camera(const Point2& p, const double depth); diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index 3b2f35031..af4c65127 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -105,11 +105,12 @@ static Point2 project_to_camera2(const Unit3& point) { return PinholeBase::project_to_camera(point); } +Unit3 pointAtInfinity(0, 0, 1000); TEST( CalibratedCamera, Dproject_to_cameraInfinity) { - Unit3 pp(0, 0, 1000); Matrix test1; - CalibratedCamera::project_to_camera(pp, test1); - Matrix test2 = numericalDerivative11(project_to_camera2, pp); + CalibratedCamera::project_to_camera(pointAtInfinity, test1); + Matrix test2 = numericalDerivative11(project_to_camera2, + pointAtInfinity); CHECK(assert_equal(test1, test2)); } @@ -144,6 +145,36 @@ TEST( CalibratedCamera, Dproject_point_pose2) CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); } +/* ************************************************************************* */ +static Point2 projectAtInfinity(const CalibratedCamera& camera, const Unit3& point) { + return camera.project2(point); +} + +TEST( CalibratedCamera, Dproject_point_pose_infinity) +{ + Matrix Dpose, Dpoint; + Point2 result = camera.project2(pointAtInfinity, Dpose, Dpoint); + Matrix numerical_pose = numericalDerivative21(projectAtInfinity, camera, pointAtInfinity); + Matrix numerical_point = numericalDerivative22(projectAtInfinity, camera, pointAtInfinity); + CHECK(assert_equal(Point2(), result)); + CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); +} + +/* ************************************************************************* */ +// Add a test with more arbitrary rotation +TEST( CalibratedCamera, Dproject_point_pose2_infinity) +{ + static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const CalibratedCamera camera(pose1); + Matrix Dpose, Dpoint; + camera.project2(pointAtInfinity, Dpose, Dpoint); + Matrix numerical_pose = numericalDerivative21(projectAtInfinity, camera, pointAtInfinity); + Matrix numerical_point = numericalDerivative22(projectAtInfinity, camera, pointAtInfinity); + CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From 5cc4513ddb72ed7b0dab51d885f6086d26ebce66 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 22:14:03 -0800 Subject: [PATCH 113/173] PinholeBaseK::project and PinholePose::project2 of Unit3 --- gtsam/geometry/PinholePose.h | 90 ++++++++++++++++-------- gtsam/geometry/tests/testPinholePose.cpp | 79 +++++++++++++-------- 2 files changed, 110 insertions(+), 59 deletions(-) diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 2ef008a94..c23cbd4f5 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -95,45 +95,66 @@ public: return calibration().uncalibrate(pn); } + /** project a point from world coordinate to the image + * @param pw is a point at infinity in the world coordinates + */ + Point2 project(const Unit3& pw) const { + const Unit3 pc = pose().rotation().unrotate(pw); // convert to camera frame + const Point2 pn = PinholeBase::project_to_camera(pc); + return calibration().uncalibrate(pn); + } + + /** project a point from world coordinate to the image + * @param pw is a point in world coordinates + * @param Dpose is the Jacobian w.r.t. pose3 + * @param Dpoint is the Jacobian w.r.t. point3 + * @param Dcal is the Jacobian w.r.t. calibration + */ + Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 3> Dpoint = boost::none, + OptionalJacobian<2, DimK> Dcal = boost::none) const { + + // project to normalized coordinates + const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); + + // uncalibrate to pixel coordinates + Matrix2 Dpi_pn; + const Point2 pi = calibration().uncalibrate(pn, Dcal, + Dpose || Dpoint ? &Dpi_pn : 0); + + // If needed, apply chain rule + if (Dpose) + *Dpose = Dpi_pn * *Dpose; + if (Dpoint) + *Dpoint = Dpi_pn * *Dpoint; + + return pi; + } + /** project a point at infinity from world coordinate to the image * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) * @param Dpose is the Jacobian w.r.t. pose3 * @param Dpoint is the Jacobian w.r.t. point3 * @param Dcal is the Jacobian w.r.t. calibration */ - Point2 projectPointAtInfinity(const Point3& pw, OptionalJacobian<2, 6> Dpose = - boost::none, OptionalJacobian<2, 2> Dpoint = boost::none, + Point2 project(const Unit3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 2> Dpoint = boost::none, OptionalJacobian<2, DimK> Dcal = boost::none) const { - if (!Dpose && !Dpoint && !Dcal) { - const Point3 pc = this->pose().rotation().unrotate(pw); // get direction in camera frame (translation does not matter) - const Point2 pn = PinholeBase::project_to_camera(pc);// project the point to the camera - return calibration().uncalibrate(pn); - } + // project to normalized coordinates + const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - // world to camera coordinate - Matrix3 Dpc_rot, Dpc_point; - const Point3 pc = this->pose().rotation().unrotate(pw, Dpc_rot, Dpc_point); + // uncalibrate to pixel coordinates + Matrix2 Dpi_pn; + const Point2 pi = calibration().uncalibrate(pn, Dcal, + Dpose || Dpoint ? &Dpi_pn : 0); - // only rotation is important - Matrix36 Dpc_pose; - Dpc_pose.setZero(); - Dpc_pose.leftCols<3>() = Dpc_rot; - - // camera to normalized image coordinate - Matrix23 Dpn_pc;// 2*3 - const Point2 pn = PinholeBase::project_to_camera(pc, Dpn_pc); - - // uncalibration - Matrix2 Dpi_pn;// 2*2 - const Point2 pi = calibration().uncalibrate(pn, Dcal, Dpi_pn); - - // chain the Jacobian matrices - const Matrix23 Dpi_pc = Dpi_pn * Dpn_pc; + // If needed, apply chain rule if (Dpose) - *Dpose = Dpi_pc * Dpc_pose; + *Dpose = Dpi_pn * *Dpose; if (Dpoint) - *Dpoint = (Dpi_pc * Dpc_point).leftCols<2>();// only 2dof are important for the point (direction-only) + *Dpoint = Dpi_pn * *Dpoint; + return pi; } @@ -144,9 +165,9 @@ public: } /// backproject a 2-dimensional point to a 3-dimensional point at infinity - Point3 backprojectPointAtInfinity(const Point2& p) const { + Unit3 backprojectPointAtInfinity(const Point2& p) const { const Point2 pn = calibration().calibrate(p); - const Point3 pc(pn.x(), pn.y(), 1.0); //by convention the last element is 1 + const Unit3 pc(pn.x(), pn.y(), 1.0); //by convention the last element is 1 return pose().rotation().rotate(pc); } @@ -344,6 +365,17 @@ public: return pi; } + /** project a point at infinity from world coordinate to the image, 2 derivatives only + * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) + * @param Dpose is the Jacobian w.r.t. the whole camera (realy only the pose) + * @param Dpoint is the Jacobian w.r.t. point3 + * TODO should use Unit3 + */ + Point2 project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 2> Dpoint = boost::none) const { + return Base::project(pw, Dpose, Dpoint); + } + /// @} /// @name Manifold /// @{ diff --git a/gtsam/geometry/tests/testPinholePose.cpp b/gtsam/geometry/tests/testPinholePose.cpp index 411273c1f..dc294899f 100644 --- a/gtsam/geometry/tests/testPinholePose.cpp +++ b/gtsam/geometry/tests/testPinholePose.cpp @@ -46,10 +46,10 @@ static const Point3 point2(-0.08, 0.08, 0.0); static const Point3 point3( 0.08, 0.08, 0.0); static const Point3 point4( 0.08,-0.08, 0.0); -static const Point3 point1_inf(-0.16,-0.16, -1.0); -static const Point3 point2_inf(-0.16, 0.16, -1.0); -static const Point3 point3_inf( 0.16, 0.16, -1.0); -static const Point3 point4_inf( 0.16,-0.16, -1.0); +static const Unit3 point1_inf(-0.16,-0.16, -1.0); +static const Unit3 point2_inf(-0.16, 0.16, -1.0); +static const Unit3 point3_inf( 0.16, 0.16, -1.0); +static const Unit3 point4_inf( 0.16,-0.16, -1.0); /* ************************************************************************* */ TEST( PinholePose, constructor) @@ -144,11 +144,11 @@ TEST( PinholePose, Dproject) { Matrix Dpose, Dpoint; Point2 result = camera.project2(point1, Dpose, Dpoint); - Matrix numerical_pose = numericalDerivative31(project3, pose, point1, K); - Matrix Hexpected2 = numericalDerivative32(project3, pose, point1, K); + Matrix expectedDcamera = numericalDerivative31(project3, pose, point1, K); + Matrix expectedDpoint = numericalDerivative32(project3, pose, point1, K); EXPECT(assert_equal(Point2(-100, 100), result)); - EXPECT(assert_equal(numerical_pose, Dpose, 1e-7)); - EXPECT(assert_equal(Hexpected2, Dpoint, 1e-7)); + EXPECT(assert_equal(expectedDcamera, Dpose, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); } /* ************************************************************************* */ @@ -161,11 +161,11 @@ TEST( PinholePose, Dproject2) { Matrix Dcamera, Dpoint; Point2 result = camera.project2(point1, Dcamera, Dpoint); - Matrix Hexpected1 = numericalDerivative21(project4, camera, point1); - Matrix Hexpected2 = numericalDerivative22(project4, camera, point1); + Matrix expectedDcamera = numericalDerivative21(project4, camera, point1); + Matrix expectedDpoint = numericalDerivative22(project4, camera, point1); EXPECT(assert_equal(result, Point2(-100, 100) )); - EXPECT(assert_equal(Hexpected1, Dcamera, 1e-7)); - EXPECT(assert_equal(Hexpected2, Dpoint, 1e-7)); + EXPECT(assert_equal(expectedDcamera, Dcamera, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); } /* ************************************************************************* */ @@ -176,12 +176,31 @@ TEST( CalibratedCamera, Dproject3) static const Camera camera(pose1); Matrix Dpose, Dpoint; camera.project2(point1, Dpose, Dpoint); - Matrix numerical_pose = numericalDerivative21(project4, camera, point1); + Matrix expectedDcamera = numericalDerivative21(project4, camera, point1); Matrix numerical_point = numericalDerivative22(project4, camera, point1); - CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(expectedDcamera, Dpose, 1e-7)); CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); } +/* ************************************************************************* */ +static Point2 project(const Pose3& pose, const Unit3& pointAtInfinity, + const Cal3_S2::shared_ptr& cal) { + return Camera(pose, cal).project(pointAtInfinity); +} + +/* ************************************************************************* */ +TEST( PinholePose, DprojectAtInfinity2) +{ + Unit3 pointAtInfinity(0,0,1000); + Matrix Dpose, Dpoint; + Point2 result = camera.project2(pointAtInfinity, Dpose, Dpoint); + Matrix expectedDcamera = numericalDerivative31(project, pose, pointAtInfinity, K); + Matrix expectedDpoint = numericalDerivative32(project, pose, pointAtInfinity, K); + EXPECT(assert_equal(Point2(0,0), result)); + EXPECT(assert_equal(expectedDcamera, Dpose, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); +} + /* ************************************************************************* */ static double range0(const Camera& camera, const Point3& point) { return camera.range(point); @@ -191,12 +210,12 @@ static double range0(const Camera& camera, const Point3& point) { TEST( PinholePose, range0) { Matrix D1; Matrix D2; double result = camera.range(point1, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range0, camera, point1); - Matrix Hexpected2 = numericalDerivative22(range0, camera, point1); + Matrix expectedDcamera = numericalDerivative21(range0, camera, point1); + Matrix expectedDpoint = numericalDerivative22(range0, camera, point1); EXPECT_DOUBLES_EQUAL(point1.distance(camera.pose().translation()), result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ @@ -208,11 +227,11 @@ static double range1(const Camera& camera, const Pose3& pose) { TEST( PinholePose, range1) { Matrix D1; Matrix D2; double result = camera.range(pose1, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range1, camera, pose1); - Matrix Hexpected2 = numericalDerivative22(range1, camera, pose1); + Matrix expectedDcamera = numericalDerivative21(range1, camera, pose1); + Matrix expectedDpoint = numericalDerivative22(range1, camera, pose1); EXPECT_DOUBLES_EQUAL(1, result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ @@ -228,11 +247,11 @@ static double range2(const Camera& camera, const Camera2& camera2) { TEST( PinholePose, range2) { Matrix D1; Matrix D2; double result = camera.range(camera2, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range2, camera, camera2); - Matrix Hexpected2 = numericalDerivative22(range2, camera, camera2); + Matrix expectedDcamera = numericalDerivative21(range2, camera, camera2); + Matrix expectedDpoint = numericalDerivative22(range2, camera, camera2); EXPECT_DOUBLES_EQUAL(1, result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ @@ -245,11 +264,11 @@ static double range3(const Camera& camera, const CalibratedCamera& camera3) { TEST( PinholePose, range3) { Matrix D1; Matrix D2; double result = camera.range(camera3, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range3, camera, camera3); - Matrix Hexpected2 = numericalDerivative22(range3, camera, camera3); + Matrix expectedDcamera = numericalDerivative21(range3, camera, camera3); + Matrix expectedDpoint = numericalDerivative22(range3, camera, camera3); EXPECT_DOUBLES_EQUAL(1, result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ From 6f36bbf4565be0f1bcdb15d817e516a70f53f960 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 22:16:47 -0800 Subject: [PATCH 114/173] Better project2 for Point3 and (new) Unit3 --- gtsam/geometry/PinholeCamera.h | 60 +++++++--------------- gtsam/geometry/tests/testPinholeCamera.cpp | 28 +++++----- 2 files changed, 32 insertions(+), 56 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 632f6de86..e900d5a85 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -200,57 +200,33 @@ public: typedef Eigen::Matrix Matrix2K; - /** project a point from world coordinate to the image - * @param pw is a point in world coordinates - * @param Dpose is the Jacobian w.r.t. pose3 - * @param Dpoint is the Jacobian w.r.t. point3 - * @param Dcal is the Jacobian w.r.t. calibration + /** project a point from world coordinate to the image, fixed Jacobians + * @param pw is a point in the world coordinate */ - Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none, - OptionalJacobian<2, DimK> Dcal = boost::none) const { - - // project to normalized coordinates - const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - - // uncalibrate to pixel coordinates - Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, Dcal, - Dpose || Dpoint ? &Dpi_pn : 0); - - // If needed, apply chain rule - if (Dpose) - *Dpose = Dpi_pn * *Dpose; - if (Dpoint) - *Dpoint = Dpi_pn * *Dpoint; - + Point2 project2(const Point3& pw, OptionalJacobian<2, dimension> Dcamera = + boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const { + // We just call 3-derivative version in Base + Matrix26 Dpose; + Eigen::Matrix Dcal; + Point2 pi = Base::project(pw, Dcamera ? &Dpose : 0, Dpoint, + Dcamera ? &Dcal : 0); + if (Dcamera) + *Dcamera << Dpose, Dcal; return pi; } /** project a point from world coordinate to the image, fixed Jacobians * @param pw is a point in the world coordinate */ - Point2 project2( - const Point3& pw, // - OptionalJacobian<2, dimension> Dcamera = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none) const { - - // project to normalized coordinates + Point2 project2(const Unit3& pw, OptionalJacobian<2, dimension> Dcamera = + boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const { + // We just call 3-derivative version in Base Matrix26 Dpose; - const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - - // uncalibrate to pixel coordinates - Matrix2K Dcal; - Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, Dcamera ? &Dcal : 0, - Dcamera || Dpoint ? &Dpi_pn : 0); - - // If needed, calculate derivatives + Eigen::Matrix Dcal; + Point2 pi = Base::project(pw, Dcamera ? &Dpose : 0, Dpoint, + Dcamera ? &Dcal : 0); if (Dcamera) - *Dcamera << Dpi_pn * Dpose, Dcal; - if (Dpoint) - *Dpoint = Dpi_pn * (*Dpoint); - + *Dcamera << Dpose, Dcal; return pi; } diff --git a/gtsam/geometry/tests/testPinholeCamera.cpp b/gtsam/geometry/tests/testPinholeCamera.cpp index 0e610d8d6..74bc4ca2a 100644 --- a/gtsam/geometry/tests/testPinholeCamera.cpp +++ b/gtsam/geometry/tests/testPinholeCamera.cpp @@ -45,10 +45,10 @@ static const Point3 point2(-0.08, 0.08, 0.0); static const Point3 point3( 0.08, 0.08, 0.0); static const Point3 point4( 0.08,-0.08, 0.0); -static const Point3 point1_inf(-0.16,-0.16, -1.0); -static const Point3 point2_inf(-0.16, 0.16, -1.0); -static const Point3 point3_inf( 0.16, 0.16, -1.0); -static const Point3 point4_inf( 0.16,-0.16, -1.0); +static const Unit3 point1_inf(-0.16,-0.16, -1.0); +static const Unit3 point2_inf(-0.16, 0.16, -1.0); +static const Unit3 point3_inf( 0.16, 0.16, -1.0); +static const Unit3 point4_inf( 0.16,-0.16, -1.0); /* ************************************************************************* */ TEST( PinholeCamera, constructor) @@ -154,9 +154,9 @@ TEST( PinholeCamera, backprojectInfinity2) Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.); // a camera1 looking down Camera camera(Pose3(rot, origin), K); - Point3 actual = camera.backprojectPointAtInfinity(Point2()); - Point3 expected(0., 1., 0.); - Point2 x = camera.projectPointAtInfinity(expected); + Unit3 actual = camera.backprojectPointAtInfinity(Point2()); + Unit3 expected(0., 1., 0.); + Point2 x = camera.project(expected); EXPECT(assert_equal(expected, actual)); EXPECT(assert_equal(Point2(), x)); @@ -169,9 +169,9 @@ TEST( PinholeCamera, backprojectInfinity3) Rot3 rot(1., 0., 0., 0., 1., 0., 0., 0., 1.); // identity Camera camera(Pose3(rot, origin), K); - Point3 actual = camera.backprojectPointAtInfinity(Point2()); - Point3 expected(0., 0., 1.); - Point2 x = camera.projectPointAtInfinity(expected); + Unit3 actual = camera.backprojectPointAtInfinity(Point2()); + Unit3 expected(0., 0., 1.); + Point2 x = camera.project(expected); EXPECT(assert_equal(expected, actual)); EXPECT(assert_equal(Point2(), x)); @@ -197,17 +197,17 @@ TEST( PinholeCamera, Dproject) } /* ************************************************************************* */ -static Point2 projectInfinity3(const Pose3& pose, const Point3& point3D, const Cal3_S2& cal) { - return Camera(pose,cal).projectPointAtInfinity(point3D); +static Point2 projectInfinity3(const Pose3& pose, const Unit3& point3D, const Cal3_S2& cal) { + return Camera(pose,cal).project(point3D); } TEST( PinholeCamera, Dproject_Infinity) { Matrix Dpose, Dpoint, Dcal; - Point3 point3D(point1.x(), point1.y(), -10.0); // a point in front of the camera1 + Unit3 point3D(point1.x(), point1.y(), -10.0); // a point in front of the camera1 // test Projection - Point2 actual = camera.projectPointAtInfinity(point3D, Dpose, Dpoint, Dcal); + Point2 actual = camera.project(point3D, Dpose, Dpoint, Dcal); Point2 expected(-5.0, 5.0); EXPECT(assert_equal(actual, expected, 1e-7)); From 4594c2dee550af2484f397bc3292249932332a57 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 22:20:51 -0800 Subject: [PATCH 115/173] Templated instead of two identical functions --- gtsam/geometry/PinholeCamera.h | 24 +++--------- gtsam/geometry/PinholePose.h | 68 ++++++---------------------------- 2 files changed, 17 insertions(+), 75 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index e900d5a85..4775e732f 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -200,26 +200,14 @@ public: typedef Eigen::Matrix Matrix2K; - /** project a point from world coordinate to the image, fixed Jacobians + /** project a point from world coordinate to the image (possibly a Unit3) * @param pw is a point in the world coordinate */ - Point2 project2(const Point3& pw, OptionalJacobian<2, dimension> Dcamera = - boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const { - // We just call 3-derivative version in Base - Matrix26 Dpose; - Eigen::Matrix Dcal; - Point2 pi = Base::project(pw, Dcamera ? &Dpose : 0, Dpoint, - Dcamera ? &Dcal : 0); - if (Dcamera) - *Dcamera << Dpose, Dcal; - return pi; - } - - /** project a point from world coordinate to the image, fixed Jacobians - * @param pw is a point in the world coordinate - */ - Point2 project2(const Unit3& pw, OptionalJacobian<2, dimension> Dcamera = - boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const { + template + Point2 project2( + const POINT& pw, // + OptionalJacobian<2, dimension> Dcamera = boost::none, + OptionalJacobian<2, FixedDimension::value> Dpoint = boost::none) const { // We just call 3-derivative version in Base Matrix26 Dpose; Eigen::Matrix Dcal; diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index c23cbd4f5..a2449871a 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -104,14 +104,15 @@ public: return calibration().uncalibrate(pn); } - /** project a point from world coordinate to the image + /** project a point (possibly at infinity) from world coordinate to the image * @param pw is a point in world coordinates * @param Dpose is the Jacobian w.r.t. pose3 * @param Dpoint is the Jacobian w.r.t. point3 * @param Dcal is the Jacobian w.r.t. calibration */ - Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose, - OptionalJacobian<2, 3> Dpoint = boost::none, + template + Point2 project(const POINT& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, FixedDimension::value> Dpoint = boost::none, OptionalJacobian<2, DimK> Dcal = boost::none) const { // project to normalized coordinates @@ -124,36 +125,9 @@ public: // If needed, apply chain rule if (Dpose) - *Dpose = Dpi_pn * *Dpose; + *Dpose = Dpi_pn * *Dpose; if (Dpoint) - *Dpoint = Dpi_pn * *Dpoint; - - return pi; - } - - /** project a point at infinity from world coordinate to the image - * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) - * @param Dpose is the Jacobian w.r.t. pose3 - * @param Dpoint is the Jacobian w.r.t. point3 - * @param Dcal is the Jacobian w.r.t. calibration - */ - Point2 project(const Unit3& pw, OptionalJacobian<2, 6> Dpose, - OptionalJacobian<2, 2> Dpoint = boost::none, - OptionalJacobian<2, DimK> Dcal = boost::none) const { - - // project to normalized coordinates - const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - - // uncalibrate to pixel coordinates - Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, Dcal, - Dpose || Dpoint ? &Dpi_pn : 0); - - // If needed, apply chain rule - if (Dpose) - *Dpose = Dpi_pn * *Dpose; - if (Dpoint) - *Dpoint = Dpi_pn * *Dpoint; + *Dpoint = Dpi_pn * *Dpoint; return pi; } @@ -344,35 +318,15 @@ public: return *K_; } - /** project a point from world coordinate to the image, w 2 derivatives - * @param pw is a point in the world coordinates - */ - Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none) const { - - // project to normalized coordinates - const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - - // uncalibrate to pixel coordinates - Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, boost::none, - Dpose || Dpoint ? &Dpi_pn : 0); - - // If needed, apply chain rule - if (Dpose) *Dpose = Dpi_pn * (*Dpose); - if (Dpoint) *Dpoint = Dpi_pn * (*Dpoint); - - return pi; - } - - /** project a point at infinity from world coordinate to the image, 2 derivatives only - * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) + /** project a point (possibly at infinity) from world coordinate to the image, 2 derivatives only + * @param pw is a point in world coordinates * @param Dpose is the Jacobian w.r.t. the whole camera (realy only the pose) * @param Dpoint is the Jacobian w.r.t. point3 * TODO should use Unit3 */ - Point2 project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, 2> Dpoint = boost::none) const { + template + Point2 project2(const POINT& pw, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, FixedDimension::value> Dpoint = boost::none) const { return Base::project(pw, Dpose, Dpoint); } From 7366549c7f69de959f93807d36c877447d6844f6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 22:44:05 -0800 Subject: [PATCH 116/173] project2 on Unit3, with derivatives --- gtsam/geometry/CameraSet.h | 43 ++++++++++++++------- gtsam/geometry/tests/testCameraSet.cpp | 19 +++++++-- gtsam/geometry/tests/testPinholeSet.cpp | 51 ++++++++++++++++--------- 3 files changed, 79 insertions(+), 34 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 3bbcb8c0d..123d45e1e 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -57,7 +57,7 @@ protected: Vector b(ZDim * m); for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { Z e = predicted[i] - measured[i]; - b.segment(row) = e.vector(); + b.segment < ZDim > (row) = e.vector(); } return b; } @@ -109,6 +109,8 @@ public: // Allocate derivatives if (E) E->resize(ZDim * m, 3); + if (Fs) + Fs->resize(m); // Project and fill derivatives for (size_t i = 0; i < m; i++) { @@ -116,7 +118,7 @@ public: Eigen::Matrix Ei; z[i] = this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0); if (Fs) - Fs->push_back(Fi); + (*Fs)[i] = Fi; if (E) E->block(ZDim * i, 0) = Ei; } @@ -125,18 +127,33 @@ public: } /** - * Project a point, with derivatives in this, point, and calibration + * Project a point at infinity, with derivatives in this, point, and calibration * throws CheiralityException */ - std::vector projectAtInfinity(const Point3& point) const { + std::vector project2(const Unit3& point, // + boost::optional Fs = boost::none, // + boost::optional E = boost::none) const { // Allocate result size_t m = this->size(); std::vector z(m); + // Allocate derivatives + if (E) + E->resize(ZDim * m, 2); + if (Fs) + Fs->resize(m); + // Project and fill derivatives - for (size_t i = 0; i < m; i++) - z[i] = this->at(i).projectPointAtInfinity(point); + for (size_t i = 0; i < m; i++) { + MatrixZD Fi; + Eigen::Matrix Ei; + z[i] = this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0); + if (Fs) + (*Fs)[i] = Fi; + if (E) + E->block(ZDim * i, 0) = Ei; + } return z; } @@ -149,10 +166,10 @@ public: } /// Calculate vector [project2(point)-z] of re-projection errors, from point at infinity - // TODO: take Unit3 instead - Vector reprojectionErrorAtInfinity(const Point3& point, - const std::vector& measured) const { - return ErrorVector(projectAtInfinity(point), measured); + Vector reprojectionError(const Unit3& point, const std::vector& measured, + boost::optional Fs = boost::none, // + boost::optional E = boost::none) const { + return ErrorVector(project2(point,Fs,E), measured); } /** @@ -180,7 +197,7 @@ public: const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; // D = (Dx2) * ZDim - augmentedHessian(i, m) = Fi.transpose() * b.segment(ZDim * i) // F' * b + augmentedHessian(i, m) = Fi.transpose() * b.segment < ZDim > (ZDim * i) // F' * b - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) @@ -212,7 +229,7 @@ public: assert(keys.size()==Fs.size()); assert(keys.size()<=allKeys.size()); - + FastMap KeySlotMap; for (size_t slot = 0; slot < allKeys.size(); slot++) KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); @@ -245,7 +262,7 @@ public: // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); // add contribution of current factor augmentedHessian(aug_i, M) = augmentedHessian(aug_i, M).knownOffDiagonal() - + Fi.transpose() * b.segment(ZDim * i) // F' * b + + Fi.transpose() * b.segment < ZDim > (ZDim * i) // F' * b - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 05ffc275c..0afa04411 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -50,12 +50,12 @@ TEST(CameraSet, Pinhole) { EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole - Matrix43 actualE; + Matrix actualE; Matrix29 F1; { Matrix23 E1; - Matrix23 H1; camera.project2(p, F1, E1); + actualE.resize(4,3); actualE << E1, E1; } @@ -114,11 +114,22 @@ TEST(CameraSet, Pinhole) { EXPECT(assert_equal((Matrix )(2.0 * schur + A), actualReduced.matrix())); // reprojectionErrorAtInfinity + Unit3 pointAtInfinity(0, 0, 1000); EXPECT( - assert_equal(Point3(0, 0, 1), + assert_equal(pointAtInfinity, camera.backprojectPointAtInfinity(Point2()))); - actualV = set.reprojectionErrorAtInfinity(p, measured); + actualV = set.reprojectionError(pointAtInfinity, measured, Fs, E); EXPECT(assert_equal(expectedV, actualV)); + LONGS_EQUAL(2, Fs.size()); + { + Matrix22 E1; + camera.project2(pointAtInfinity, F1, E1); + actualE.resize(4,2); + actualE << E1, E1; + } + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + EXPECT(assert_equal(actualE, E)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp index 1e5426f33..b8f001f1c 100644 --- a/gtsam/geometry/tests/testPinholeSet.cpp +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -53,12 +53,12 @@ TEST(PinholeSet, Stereo) { } // Check computed derivatives - PinholeSet::FBlocks F; + PinholeSet::FBlocks Fs; Matrix E; - set.project2(p, F, E); - LONGS_EQUAL(2, F.size()); - EXPECT(assert_equal(F1, F[0])); - EXPECT(assert_equal(F1, F[1])); + set.project2(p, Fs, E); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); EXPECT(assert_equal(actualE, E)); // Instantiate triangulateSafe @@ -90,23 +90,25 @@ TEST(PinholeSet, Pinhole) { EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole - Matrix43 actualE; + Matrix actualE; Matrix F1; { Matrix23 E1; - Matrix23 H1; camera.project2(p, F1, E1); + actualE.resize(4, 3); actualE << E1, E1; } // Check computed derivatives - PinholeSet::FBlocks F; - Matrix E, H; - set.project2(p, F, E); - LONGS_EQUAL(2, F.size()); - EXPECT(assert_equal(F1, F[0])); - EXPECT(assert_equal(F1, F[1])); - EXPECT(assert_equal(actualE, E)); + { + PinholeSet::FBlocks Fs; + Matrix E; + set.project2(p, Fs, E); + EXPECT(assert_equal(actualE, E)); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + } // Check errors ZZ measured; @@ -120,15 +122,30 @@ TEST(PinholeSet, Pinhole) { EXPECT(assert_equal(expectedV, actualV)); // reprojectionErrorAtInfinity + Unit3 pointAtInfinity(0, 0, 1000); + { + Matrix22 E1; + camera.project2(pointAtInfinity, F1, E1); + actualE.resize(4, 2); + actualE << E1, E1; + } EXPECT( - assert_equal(Point3(0, 0, 1), + assert_equal(pointAtInfinity, camera.backprojectPointAtInfinity(Point2()))); - actualV = set.reprojectionErrorAtInfinity(p, measured); + { + PinholeSet::FBlocks Fs; + Matrix E; + actualV = set.reprojectionError(pointAtInfinity, measured, Fs, E); + EXPECT(assert_equal(actualE, E)); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + } EXPECT(assert_equal(expectedV, actualV)); // Instantiate triangulateSafe TriangulationParameters params; - TriangulationResult actual = set.triangulateSafe(z,params); + TriangulationResult actual = set.triangulateSafe(z, params); CHECK(actual.degenerate()); } From 6c72c29a563d960219005383c0724fdc7095b714 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 22:47:28 -0800 Subject: [PATCH 117/173] Templated instead of two identical functions --- gtsam/geometry/CameraSet.h | 55 +++++++------------------------------- 1 file changed, 10 insertions(+), 45 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 123d45e1e..60af8beef 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -93,85 +93,50 @@ public: } /** - * Project a point, with derivatives in CameraSet and Point3 + * Project a point (posibly Unit3 at infinity), with derivatives * Note that F is a sparse block-diagonal matrix, so instead of a large dense * matrix this function returns the diagonal blocks. * throws CheiralityException */ - std::vector project2(const Point3& point, // + template + std::vector project2(const POINT& point, // boost::optional Fs = boost::none, // boost::optional E = boost::none) const { + static const int N = FixedDimension::value; + // Allocate result size_t m = this->size(); std::vector z(m); // Allocate derivatives if (E) - E->resize(ZDim * m, 3); + E->resize(ZDim * m, N); if (Fs) Fs->resize(m); // Project and fill derivatives for (size_t i = 0; i < m; i++) { MatrixZD Fi; - Eigen::Matrix Ei; + Eigen::Matrix Ei; z[i] = this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0); if (Fs) (*Fs)[i] = Fi; if (E) - E->block(ZDim * i, 0) = Ei; - } - - return z; - } - - /** - * Project a point at infinity, with derivatives in this, point, and calibration - * throws CheiralityException - */ - std::vector project2(const Unit3& point, // - boost::optional Fs = boost::none, // - boost::optional E = boost::none) const { - - // Allocate result - size_t m = this->size(); - std::vector z(m); - - // Allocate derivatives - if (E) - E->resize(ZDim * m, 2); - if (Fs) - Fs->resize(m); - - // Project and fill derivatives - for (size_t i = 0; i < m; i++) { - MatrixZD Fi; - Eigen::Matrix Ei; - z[i] = this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0); - if (Fs) - (*Fs)[i] = Fi; - if (E) - E->block(ZDim * i, 0) = Ei; + E->block(ZDim * i, 0) = Ei; } return z; } /// Calculate vector [project2(point)-z] of re-projection errors - Vector reprojectionError(const Point3& point, const std::vector& measured, + template + Vector reprojectionError(const POINT& point, const std::vector& measured, boost::optional Fs = boost::none, // boost::optional E = boost::none) const { return ErrorVector(project2(point, Fs, E), measured); } - /// Calculate vector [project2(point)-z] of re-projection errors, from point at infinity - Vector reprojectionError(const Unit3& point, const std::vector& measured, - boost::optional Fs = boost::none, // - boost::optional E = boost::none) const { - return ErrorVector(project2(point,Fs,E), measured); - } - /** * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix * G = F' * F - F' * E * P * E' * F From 861ee8fef38f4a902dbfdd283b87695ee126b9de Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 5 Mar 2015 23:22:24 -0800 Subject: [PATCH 118/173] Made work with Unit3 --- gtsam/slam/SmartFactorBase.h | 104 ++++++++++++----------------- gtsam/slam/SmartProjectionFactor.h | 35 +++------- 2 files changed, 53 insertions(+), 86 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 53a86abe0..a024ea4fc 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -205,55 +205,39 @@ public: return e && Base::equals(p, tol) && areMeasurementsEqual; } - /// Compute reprojection errors - Vector reprojectionError(const Cameras& cameras, const Point3& point) const { - return cameras.reprojectionError(point, measured_); + /** + * 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 { + return cameras.reprojectionError(point, measured_, Fs, E); } /** - * Compute reprojection errors and derivatives + * Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z] + * Noise model applied */ - Vector reprojectionError(const Cameras& cameras, const Point3& point, - typename Cameras::FBlocks& F, Matrix& E) const { - return cameras.reprojectionError(point, measured_, F, E); - } - - /// Calculate vector of re-projection errors, noise model applied - Vector whitenedErrors(const Cameras& cameras, const Point3& point) const { - Vector b = cameras.reprojectionError(point, measured_); + template + Vector whitenedError(const Cameras& cameras, const POINT& point) const { + Vector e = cameras.reprojectionError(point, measured_); if (noiseModel_) - noiseModel_->whitenInPlace(b); - return b; - } - - /// Calculate vector of re-projection errors, noise model applied - // TODO: Unit3 - Vector whitenedErrorsAtInfinity(const Cameras& cameras, - const Point3& point) const { - Vector b = cameras.reprojectionErrorAtInfinity(point, measured_); - if (noiseModel_) - noiseModel_->whitenInPlace(b); - return b; + noiseModel_->whitenInPlace(e); + return e; } /** Calculate the error of the factor. * This is the log-likelihood, e.g. \f$ 0.5(h(x)-z)^2/\sigma^2 \f$ in case of Gaussian. * In this class, we take the raw prediction error \f$ h(x)-z \f$, ask the noise model * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. - * This is different from reprojectionError(cameras,point) as each point is whitened + * Will be used in "error(Values)" function required by NonlinearFactor base class */ + template double totalReprojectionError(const Cameras& cameras, - const Point3& point) const { - Vector b = whitenedErrors(cameras, point); - return 0.5 * b.dot(b); - } - - /// Version for infinity - // TODO: Unit3 - double totalReprojectionErrorAtInfinity(const Cameras& cameras, - const Point3& point) const { - Vector b = whitenedErrorsAtInfinity(cameras, point); - return 0.5 * b.dot(b); + const POINT& point) const { + Vector e = whitenedError(cameras, point); + return 0.5 * e.dot(e); } /// Computes Point Covariance P from E @@ -283,53 +267,49 @@ public: * with respect to the point. The value of cameras/point are passed as parameters. * TODO: Kill this obsolete method */ - double computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, - const Cameras& cameras, const Point3& point) const { + template + void computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, + const Cameras& cameras, const POINT& point) const { // Project into Camera set and calculate derivatives - b = reprojectionError(cameras, point, Fblocks, E); - return b.squaredNorm(); + // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar) + // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z| + // = |A*dx - (z-h(x_bar))| + b = -unwhitenedError(cameras, point, Fblocks, E); } /// SVD version - double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, - Vector& b, const Cameras& cameras, const Point3& point) const { + template + void computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, + Vector& b, const Cameras& cameras, const POINT& point) const { Matrix E; - double f = computeJacobians(Fblocks, E, b, cameras, point); + computeJacobians(Fblocks, E, b, cameras, point); + + static const int N = FixedDimension::value; // 2 (Unit3) or 3 (Point3) // Do SVD on A Eigen::JacobiSVD svd(E, Eigen::ComputeFullU); Vector s = svd.singularValues(); size_t m = this->keys_.size(); - Enull = svd.matrixU().block(0, 3, ZDim * m, ZDim * m - 3); // last ZDim*m-3 columns - - return f; + Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns } /** - * Linearize returns a Hessianfactor that is an approximation of error(p) + * Linearize to a Hessianfactor */ boost::shared_ptr > createHessianFactor( const Cameras& cameras, const Point3& point, const double lambda = 0.0, bool diagonalDamping = false) const { - int m = this->keys_.size(); std::vector Fblocks; Matrix E; Vector b; - double f = computeJacobians(Fblocks, E, b, cameras, point); - Matrix3 P = PointCov(E, lambda, diagonalDamping); - - // Create a SymmetricBlockMatrix - size_t M1 = Dim * m + 1; - std::vector dims(m + 1); // this also includes the b term - std::fill(dims.begin(), dims.end() - 1, Dim); - dims.back() = 1; - SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); + computeJacobians(Fblocks, E, b, cameras, point); + Matrix P = PointCov(E, lambda, diagonalDamping); // build augmented hessian - CameraSet::SchurComplement(Fblocks, E, P, b, augmentedHessian); - augmentedHessian(m, m)(0, 0) = f; + SymmetricBlockMatrix augmentedHessian = CameraSet::SchurComplement( + Fblocks, E, P, b); return boost::make_shared >(keys_, augmentedHessian); @@ -348,7 +328,7 @@ public: Vector b; std::vector Fblocks; computeJacobians(Fblocks, E, b, cameras, point); - Matrix3 P = PointCov(E, lambda, diagonalDamping); + Matrix P = PointCov(E, lambda, diagonalDamping); CameraSet::UpdateSchurComplement(Fblocks, E, P, b, allKeys, keys_, augmentedHessian); } @@ -372,7 +352,7 @@ public: std::vector F; computeJacobians(F, E, b, cameras, point); whitenJacobians(F, E, b); - Matrix3 P = PointCov(E, lambda, diagonalDamping); + Matrix P = PointCov(E, lambda, diagonalDamping); return boost::make_shared >(keys_, F, E, P, b); } @@ -388,7 +368,7 @@ public: std::vector F; computeJacobians(F, E, b, cameras, point); const size_t M = b.size(); - Matrix3 P = PointCov(E, lambda, diagonalDamping); + Matrix P = PointCov(E, lambda, diagonalDamping); SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); return boost::make_shared >(keys_, F, E, P, b, n); } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 7578507dc..6a9088e25 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -276,13 +276,13 @@ public: // ================================================================== Matrix F, E; Vector b; - double f; { std::vector Fblocks; - f = computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); Base::whitenJacobians(Fblocks, E, b); Base::FillDiagonalF(Fblocks, F); // expensive ! } + double f = b.squaredNorm(); // Schur complement trick // Frank says: should be possible to do this more efficiently? @@ -373,30 +373,18 @@ public: /// Compute F, E only (called below in both vanilla and SVD versions) /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate - double computeJacobiansWithTriangulatedPoint( + void computeJacobiansWithTriangulatedPoint( std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras) const { if (!result_) { - // TODO Luca clarify whether this works or not - result_ = TriangulationResult( - cameras[0].backprojectPointAtInfinity(this->measured_.at(0))); - // TODO replace all this by Call to CameraSet - int m = this->keys_.size(); - E = zeros(2 * m, 2); - b = zero(2 * m); - for (size_t i = 0; i < this->measured_.size(); i++) { - Matrix Fi, Ei; - Vector bi = -(cameras[i].projectPointAtInfinity(*result_, Fi, Ei) - - this->measured_.at(i)).vector(); - Fblocks.push_back(Fi); - E.block<2, 2>(2 * i, 0) = Ei; - subInsert(b, bi, 2 * i); - } - return b.squaredNorm(); + // Handle degeneracy + // TODO check flag whether we should do this + Unit3 backProjected = cameras[0].backprojectPointAtInfinity(this->measured_.at(0)); + Base::computeJacobians(Fblocks, E, b, cameras, backProjected); } else { // valid result: just return Base version - return Base::computeJacobians(Fblocks, E, b, cameras, *result_); + Base::computeJacobians(Fblocks, E, b, cameras, *result_); } } @@ -427,7 +415,7 @@ public: Cameras cameras = this->cameras(values); bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - return Base::reprojectionError(cameras, *result_); + return Base::unwhitenedError(cameras, *result_); else return zero(cameras.size() * 2); } @@ -452,9 +440,8 @@ public: else if (manageDegeneracy_) { // Otherwise, manage the exceptions with rotation-only factors const Point2& z0 = this->measured_.at(0); - result_ = TriangulationResult( - cameras.front().backprojectPointAtInfinity(z0)); - return Base::totalReprojectionErrorAtInfinity(cameras, *result_); + Unit3 backprojected = cameras.front().backprojectPointAtInfinity(z0); + return Base::totalReprojectionError(cameras, backprojected); } else // if we don't want to manage the exceptions we discard the factor return 0.0; From 61e8b422491926a80a114b41be66d62bd3ea25ec Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 6 Mar 2015 08:46:56 -0800 Subject: [PATCH 119/173] Renamed project_to_camera to PinholeBase::Project --- gtsam.h | 6 +- gtsam/geometry/CalibratedCamera.cpp | 23 +- gtsam/geometry/CalibratedCamera.h | 14 +- gtsam/geometry/PinholePose.h | 2 +- gtsam/geometry/tests/testCalibratedCamera.cpp | 20 +- gtsam/nonlinear/tests/testExpression.cpp | 3 +- .../nonlinear/tests/testExpressionFactor.cpp | 502 ------------------ gtsam/slam/EssentialMatrixFactor.h | 4 +- gtsam/slam/expressions.h | 50 +- 9 files changed, 75 insertions(+), 549 deletions(-) delete mode 100644 gtsam/nonlinear/tests/testExpressionFactor.cpp diff --git a/gtsam.h b/gtsam.h index 1aee996dc..33e95b558 100644 --- a/gtsam.h +++ b/gtsam.h @@ -778,7 +778,7 @@ class CalibratedCamera { // Action on Point3 gtsam::Point2 project(const gtsam::Point3& point) const; - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); // Standard Interface gtsam::Pose3 pose() const; @@ -815,7 +815,7 @@ class SimpleCamera { static size_t Dim(); // Transformations and measurement functions - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); pair projectSafe(const gtsam::Point3& pw) const; gtsam::Point2 project(const gtsam::Point3& point); gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; @@ -854,7 +854,7 @@ class PinholeCamera { static size_t Dim(); // Transformations and measurement functions - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); pair projectSafe(const gtsam::Point3& pw) const; gtsam::Point2 project(const gtsam::Point3& point); gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp index fb518f2e3..6fbef721c 100644 --- a/gtsam/geometry/CalibratedCamera.cpp +++ b/gtsam/geometry/CalibratedCamera.cpp @@ -85,8 +85,7 @@ const Pose3& PinholeBase::getPose(OptionalJacobian<6, 6> H) const { } /* ************************************************************************* */ -Point2 PinholeBase::project_to_camera(const Point3& pc, - OptionalJacobian<2, 3> Dpoint) { +Point2 PinholeBase::Project(const Point3& pc, OptionalJacobian<2, 3> Dpoint) { double d = 1.0 / pc.z(); const double u = pc.x() * d, v = pc.y() * d; if (Dpoint) @@ -95,22 +94,27 @@ Point2 PinholeBase::project_to_camera(const Point3& pc, } /* ************************************************************************* */ -Point2 PinholeBase::project_to_camera(const Unit3& pc, - OptionalJacobian<2, 2> Dpoint) { +Point2 PinholeBase::project_to_camera_old(const Point3& pc, + OptionalJacobian<2, 3> Dpoint) { + return Project(pc); +} + +/* ************************************************************************* */ +Point2 PinholeBase::Project(const Unit3& pc, OptionalJacobian<2, 2> Dpoint) { if (Dpoint) { Matrix32 Dpoint3_pc; Matrix23 Duv_point3; - Point2 uv = project_to_camera(pc.point3(Dpoint3_pc), Duv_point3); + Point2 uv = Project(pc.point3(Dpoint3_pc), Duv_point3); *Dpoint = Duv_point3 * Dpoint3_pc; return uv; } else - return project_to_camera(pc.point3()); + return Project(pc.point3()); } /* ************************************************************************* */ pair PinholeBase::projectSafe(const Point3& pw) const { const Point3 pc = pose().transform_to(pw); - const Point2 pn = project_to_camera(pc); + const Point2 pn = Project(pc); return make_pair(pn, pc.z() > 0); } @@ -124,7 +128,7 @@ Point2 PinholeBase::project2(const Point3& point, OptionalJacobian<2, 6> Dpose, if (q.z() <= 0) throw CheiralityException(); #endif - const Point2 pn = project_to_camera(q); + const Point2 pn = Project(q); if (Dpose || Dpoint) { const double d = 1.0 / q.z(); @@ -148,8 +152,7 @@ Point2 PinholeBase::project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose, // camera to normalized image coordinate Matrix2 Dpn_pc; - const Point2 pn = PinholeBase::project_to_camera(pc, - Dpose || Dpoint ? &Dpn_pc : 0); + const Point2 pn = Project(pc, Dpose || Dpoint ? &Dpn_pc : 0); // chain the Jacobian matrices if (Dpose) { diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index e43cafcc2..b4513a2a3 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -164,7 +164,11 @@ public: * Does *not* throw a CheiralityException, even if pc behind image plane * @param pc point in camera coordinates */ - static Point2 project_to_camera(const Point3& pc, // + static Point2 Project(const Point3& pc, // + OptionalJacobian<2, 3> Dpoint = boost::none); + + /// @deprecated not correct naming for static function, use Project above + static Point2 project_to_camera_old(const Point3& pc, // OptionalJacobian<2, 3> Dpoint = boost::none); /** @@ -172,7 +176,7 @@ public: * Does *not* throw a CheiralityException, even if pc behind image plane * @param pc point in camera coordinates */ - static Point2 project_to_camera(const Unit3& pc, // + static Point2 Project(const Unit3& pc, // OptionalJacobian<2, 2> Dpoint = boost::none); /// Project a point into the image and check depth @@ -193,8 +197,9 @@ public: * @param point 3D point in world coordinates * @return the intrinsic coordinates of the projected point */ - Point2 project2(const Unit3& point, OptionalJacobian<2, 6> Dpose = - boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const; + Point2 project2(const Unit3& point, + OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 2> Dpoint = boost::none) const; /// backproject a 2-dimensional point to a 3-dimensional point at given depth static Point3 backproject_from_camera(const Point2& p, const double depth); @@ -214,7 +219,6 @@ public: /// @} - private: /** Serialization function */ diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index a2449871a..d98f36b6e 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -100,7 +100,7 @@ public: */ Point2 project(const Unit3& pw) const { const Unit3 pc = pose().rotation().unrotate(pw); // convert to camera frame - const Point2 pn = PinholeBase::project_to_camera(pc); + const Point2 pn = PinholeBase::Project(pc); return calibration().uncalibrate(pn); } diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index af4c65127..199ae30ce 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -88,28 +88,28 @@ TEST( CalibratedCamera, project) } /* ************************************************************************* */ -static Point2 project_to_camera1(const Point3& point) { - return PinholeBase::project_to_camera(point); +static Point2 Project1(const Point3& point) { + return PinholeBase::Project(point); } -TEST( CalibratedCamera, Dproject_to_camera1) { +TEST( CalibratedCamera, DProject1) { Point3 pp(155, 233, 131); Matrix test1; - CalibratedCamera::project_to_camera(pp, test1); - Matrix test2 = numericalDerivative11(project_to_camera1, pp); + CalibratedCamera::Project(pp, test1); + Matrix test2 = numericalDerivative11(Project1, pp); CHECK(assert_equal(test1, test2)); } /* ************************************************************************* */ -static Point2 project_to_camera2(const Unit3& point) { - return PinholeBase::project_to_camera(point); +static Point2 Project2(const Unit3& point) { + return PinholeBase::Project(point); } Unit3 pointAtInfinity(0, 0, 1000); -TEST( CalibratedCamera, Dproject_to_cameraInfinity) { +TEST( CalibratedCamera, DProjectInfinity) { Matrix test1; - CalibratedCamera::project_to_camera(pointAtInfinity, test1); - Matrix test2 = numericalDerivative11(project_to_camera2, + CalibratedCamera::Project(pointAtInfinity, test1); + Matrix test2 = numericalDerivative11(Project2, pointAtInfinity); CHECK(assert_equal(test1, test2)); } diff --git a/gtsam/nonlinear/tests/testExpression.cpp b/gtsam/nonlinear/tests/testExpression.cpp index 80100af5e..1c97394e1 100644 --- a/gtsam/nonlinear/tests/testExpression.cpp +++ b/gtsam/nonlinear/tests/testExpression.cpp @@ -166,7 +166,8 @@ using namespace binary; Expression K(3); // Create expression tree -Expression projection(PinholeCamera::project_to_camera, p_cam); +Point2 (*f)(const Point3&, OptionalJacobian<2, 3>) = &PinholeBase::Project; +Expression projection(f, p_cam); Expression uv_hat(uncalibrate, K, projection); } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/tests/testExpressionFactor.cpp b/gtsam/nonlinear/tests/testExpressionFactor.cpp deleted file mode 100644 index 99b8120e3..000000000 --- a/gtsam/nonlinear/tests/testExpressionFactor.cpp +++ /dev/null @@ -1,502 +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 testExpressionFactor.cpp - * @date September 18, 2014 - * @author Frank Dellaert - * @author Paul Furgale - * @brief unit tests for Block Automatic Differentiation - */ - -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -using boost::assign::list_of; - -using namespace std; -using namespace gtsam; - -Point2 measured(-17, 30); -SharedNoiseModel model = noiseModel::Unit::Create(2); - -namespace leaf { -// Create some values -struct MyValues: public Values { - MyValues() { - insert(2, Point2(3, 5)); - } -} values; - -// Create leaf -Point2_ p(2); -} - -/* ************************************************************************* */ -// Leaf -TEST(ExpressionFactor, Leaf) { - using namespace leaf; - - // Create old-style factor to create expected value and derivatives - PriorFactor old(2, Point2(0, 0), model); - - // Concise version - ExpressionFactor f(model, Point2(0, 0), p); - EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9); - EXPECT_LONGS_EQUAL(2, f.dim()); - boost::shared_ptr gf2 = f.linearize(values); - EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9)); -} - -/* ************************************************************************* */ -// non-zero noise model -TEST(ExpressionFactor, Model) { - using namespace leaf; - - SharedNoiseModel model = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.01)); - - // Create old-style factor to create expected value and derivatives - PriorFactor old(2, Point2(0, 0), model); - - // Concise version - ExpressionFactor f(model, Point2(0, 0), p); - - // Check values and derivatives - EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9); - EXPECT_LONGS_EQUAL(2, f.dim()); - boost::shared_ptr gf2 = f.linearize(values); - EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9)); - EXPECT_CORRECT_FACTOR_JACOBIANS(f, values, 1e-5, 1e-5); // another way -} - -/* ************************************************************************* */ -// Constrained noise model -TEST(ExpressionFactor, Constrained) { - using namespace leaf; - - SharedDiagonal model = noiseModel::Constrained::MixedSigmas(Vector2(0.2, 0)); - - // Create old-style factor to create expected value and derivatives - PriorFactor old(2, Point2(0, 0), model); - - // Concise version - ExpressionFactor f(model, Point2(0, 0), p); - EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9); - EXPECT_LONGS_EQUAL(2, f.dim()); - boost::shared_ptr gf2 = f.linearize(values); - EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9)); -} - -/* ************************************************************************* */ -// Unary(Leaf)) -TEST(ExpressionFactor, Unary) { - - // Create some values - Values values; - values.insert(2, Point3(0, 0, 1)); - - JacobianFactor expected( // - 2, (Matrix(2, 3) << 1, 0, 0, 0, 1, 0).finished(), // - Vector2(-17, 30)); - - // Create leaves - Point3_ p(2); - - // Concise version - ExpressionFactor f(model, measured, project(p)); - EXPECT_LONGS_EQUAL(2, f.dim()); - boost::shared_ptr gf = f.linearize(values); - boost::shared_ptr jf = // - boost::dynamic_pointer_cast(gf); - EXPECT( assert_equal(expected, *jf, 1e-9)); -} - -/* ************************************************************************* */ -// Unary(Leaf)) and Unary(Unary(Leaf))) -// wide version (not handled in fixed-size pipeline) -typedef Eigen::Matrix Matrix93; -Vector9 wide(const Point3& p, OptionalJacobian<9,3> H) { - Vector9 v; - v << p.vector(), p.vector(), p.vector(); - if (H) *H << eye(3), eye(3), eye(3); - return v; -} -typedef Eigen::Matrix Matrix9; -Vector9 id9(const Vector9& v, OptionalJacobian<9,9> H) { - if (H) *H = Matrix9::Identity(); - return v; -} -TEST(ExpressionFactor, Wide) { - // Create some values - Values values; - values.insert(2, Point3(0, 0, 1)); - Point3_ point(2); - Vector9 measured; - measured.setZero(); - Expression expression(wide,point); - SharedNoiseModel model = noiseModel::Unit::Create(9); - - ExpressionFactor f1(model, measured, expression); - EXPECT_CORRECT_FACTOR_JACOBIANS(f1, values, 1e-5, 1e-9); - - Expression expression2(id9,expression); - ExpressionFactor f2(model, measured, expression2); - EXPECT_CORRECT_FACTOR_JACOBIANS(f2, values, 1e-5, 1e-9); -} - -/* ************************************************************************* */ -static Point2 myUncal(const Cal3_S2& K, const Point2& p, - OptionalJacobian<2,5> Dcal, OptionalJacobian<2,2> Dp) { - return K.uncalibrate(p, Dcal, Dp); -} - -// Binary(Leaf,Leaf) -TEST(ExpressionFactor, Binary) { - - typedef BinaryExpression Binary; - - Cal3_S2_ K_(1); - Point2_ p_(2); - Binary binary(myUncal, K_, p_); - - // Create some values - Values values; - values.insert(1, Cal3_S2()); - values.insert(2, Point2(0, 0)); - - // traceRaw will fill raw with [Trace | Binary::Record] - EXPECT_LONGS_EQUAL(8, sizeof(double)); - EXPECT_LONGS_EQUAL(16, sizeof(Point2)); - EXPECT_LONGS_EQUAL(40, sizeof(Cal3_S2)); - EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace)); - EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace)); - EXPECT_LONGS_EQUAL(2*5*8, sizeof(Jacobian::type)); - EXPECT_LONGS_EQUAL(2*2*8, sizeof(Jacobian::type)); - size_t expectedRecordSize = 16 + 16 + 40 + 2 * 16 + 80 + 32; - EXPECT_LONGS_EQUAL(expectedRecordSize + 8, sizeof(Binary::Record)); - - // Check size - size_t size = binary.traceSize(); - CHECK(size); - EXPECT_LONGS_EQUAL(expectedRecordSize + 8, size); - // Use Variable Length Array, allocated on stack by gcc - // Note unclear for Clang: http://clang.llvm.org/compatibility.html#vla - ExecutionTraceStorage traceStorage[size]; - ExecutionTrace trace; - Point2 value = binary.traceExecution(values, trace, traceStorage); - EXPECT(assert_equal(Point2(),value, 1e-9)); - // trace.print(); - - // Expected Jacobians - Matrix25 expected25; - expected25 << 0, 0, 0, 1, 0, 0, 0, 0, 0, 1; - Matrix2 expected22; - expected22 << 1, 0, 0, 1; - - // Check matrices - boost::optional r = trace.record(); - CHECK(r); - EXPECT( - assert_equal(expected25, (Matrix) (*r)-> jacobian(), 1e-9)); - EXPECT( assert_equal(expected22, (Matrix) (*r)->jacobian(), 1e-9)); -} -/* ************************************************************************* */ -// Unary(Binary(Leaf,Leaf)) -TEST(ExpressionFactor, Shallow) { - - // Create some values - Values values; - values.insert(1, Pose3()); - values.insert(2, Point3(0, 0, 1)); - - // Create old-style factor to create expected value and derivatives - GenericProjectionFactor old(measured, model, 1, 2, - boost::make_shared()); - double expected_error = old.error(values); - GaussianFactor::shared_ptr expected = old.linearize(values); - - // Create leaves - Pose3_ x_(1); - Point3_ p_(2); - - // Construct expression, concise evrsion - Point2_ expression = project(transform_to(x_, p_)); - - // Get and check keys and dims - FastVector keys; - FastVector dims; - boost::tie(keys, dims) = expression.keysAndDims(); - LONGS_EQUAL(2,keys.size()); - LONGS_EQUAL(2,dims.size()); - LONGS_EQUAL(1,keys[0]); - LONGS_EQUAL(2,keys[1]); - LONGS_EQUAL(6,dims[0]); - LONGS_EQUAL(3,dims[1]); - - // traceExecution of shallow tree - typedef UnaryExpression Unary; - typedef BinaryExpression Binary; - size_t expectedTraceSize = sizeof(Unary::Record) + sizeof(Binary::Record); - EXPECT_LONGS_EQUAL(112, sizeof(Unary::Record)); -#ifdef GTSAM_USE_QUATERNIONS - EXPECT_LONGS_EQUAL(352, sizeof(Binary::Record)); - LONGS_EQUAL(112+352, expectedTraceSize); -#else - EXPECT_LONGS_EQUAL(400, sizeof(Binary::Record)); - LONGS_EQUAL(112+400, expectedTraceSize); -#endif - size_t size = expression.traceSize(); - CHECK(size); - EXPECT_LONGS_EQUAL(expectedTraceSize, size); - ExecutionTraceStorage traceStorage[size]; - ExecutionTrace trace; - Point2 value = expression.traceExecution(values, trace, traceStorage); - EXPECT(assert_equal(Point2(),value, 1e-9)); - // trace.print(); - - // Expected Jacobians - Matrix23 expected23; - expected23 << 1, 0, 0, 0, 1, 0; - - // Check matrices - boost::optional r = trace.record(); - CHECK(r); - EXPECT(assert_equal(expected23, (Matrix)(*r)->jacobian(), 1e-9)); - - // Linearization - ExpressionFactor f2(model, measured, expression); - EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9); - EXPECT_LONGS_EQUAL(2, f2.dim()); - boost::shared_ptr gf2 = f2.linearize(values); - EXPECT( assert_equal(*expected, *gf2, 1e-9)); -} - -/* ************************************************************************* */ -// Binary(Leaf,Unary(Binary(Leaf,Leaf))) -TEST(ExpressionFactor, tree) { - - // Create some values - Values values; - values.insert(1, Pose3()); - values.insert(2, Point3(0, 0, 1)); - values.insert(3, Cal3_S2()); - - // Create old-style factor to create expected value and derivatives - GeneralSFMFactor2 old(measured, model, 1, 2, 3); - double expected_error = old.error(values); - GaussianFactor::shared_ptr expected = old.linearize(values); - - // Create leaves - Pose3_ x(1); - Point3_ p(2); - Cal3_S2_ K(3); - - // Create expression tree - Point3_ p_cam(x, &Pose3::transform_to, p); - Point2_ xy_hat(PinholeCamera::project_to_camera, p_cam); - Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat); - - // Create factor and check value, dimension, linearization - ExpressionFactor f(model, measured, uv_hat); - EXPECT_DOUBLES_EQUAL(expected_error, f.error(values), 1e-9); - EXPECT_LONGS_EQUAL(2, f.dim()); - boost::shared_ptr gf = f.linearize(values); - EXPECT( assert_equal(*expected, *gf, 1e-9)); - - // Concise version - ExpressionFactor f2(model, measured, - uncalibrate(K, project(transform_to(x, p)))); - EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9); - EXPECT_LONGS_EQUAL(2, f2.dim()); - boost::shared_ptr gf2 = f2.linearize(values); - EXPECT( assert_equal(*expected, *gf2, 1e-9)); - - TernaryExpression::Function fff = project6; - - // Try ternary version - ExpressionFactor f3(model, measured, project3(x, p, K)); - EXPECT_DOUBLES_EQUAL(expected_error, f3.error(values), 1e-9); - EXPECT_LONGS_EQUAL(2, f3.dim()); - boost::shared_ptr gf3 = f3.linearize(values); - EXPECT( assert_equal(*expected, *gf3, 1e-9)); -} - -/* ************************************************************************* */ - -TEST(ExpressionFactor, Compose1) { - - // Create expression - Rot3_ R1(1), R2(2); - Rot3_ R3 = R1 * R2; - - // Create factor - ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), R3); - - // Create some values - Values values; - values.insert(1, Rot3()); - values.insert(2, Rot3()); - - // Check unwhitenedError - std::vector H(2); - Vector actual = f.unwhitenedError(values, H); - EXPECT( assert_equal(eye(3), H[0],1e-9)); - EXPECT( assert_equal(eye(3), H[1],1e-9)); - - // Check linearization - JacobianFactor expected(1, eye(3), 2, eye(3), zero(3)); - boost::shared_ptr gf = f.linearize(values); - boost::shared_ptr jf = // - boost::dynamic_pointer_cast(gf); - EXPECT( assert_equal(expected, *jf,1e-9)); -} - -/* ************************************************************************* */ -// Test compose with arguments referring to the same rotation -TEST(ExpressionFactor, compose2) { - - // Create expression - Rot3_ R1(1), R2(1); - Rot3_ R3 = R1 * R2; - - // Create factor - ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), R3); - - // Create some values - Values values; - values.insert(1, Rot3()); - - // Check unwhitenedError - std::vector H(1); - Vector actual = f.unwhitenedError(values, H); - EXPECT_LONGS_EQUAL(1, H.size()); - EXPECT( assert_equal(2*eye(3), H[0],1e-9)); - - // Check linearization - JacobianFactor expected(1, 2 * eye(3), zero(3)); - boost::shared_ptr gf = f.linearize(values); - boost::shared_ptr jf = // - boost::dynamic_pointer_cast(gf); - EXPECT( assert_equal(expected, *jf,1e-9)); -} - -/* ************************************************************************* */ -// Test compose with one arguments referring to a constant same rotation -TEST(ExpressionFactor, compose3) { - - // Create expression - Rot3_ R1(Rot3::identity()), R2(3); - Rot3_ R3 = R1 * R2; - - // Create factor - ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), R3); - - // Create some values - Values values; - values.insert(3, Rot3()); - - // Check unwhitenedError - std::vector H(1); - Vector actual = f.unwhitenedError(values, H); - EXPECT_LONGS_EQUAL(1, H.size()); - EXPECT( assert_equal(eye(3), H[0],1e-9)); - - // Check linearization - JacobianFactor expected(3, eye(3), zero(3)); - boost::shared_ptr gf = f.linearize(values); - boost::shared_ptr jf = // - boost::dynamic_pointer_cast(gf); - EXPECT( assert_equal(expected, *jf,1e-9)); -} - -/* ************************************************************************* */ -// Test compose with three arguments -Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3, - OptionalJacobian<3, 3> H1, OptionalJacobian<3, 3> H2, OptionalJacobian<3, 3> H3) { - // return dummy derivatives (not correct, but that's ok for testing here) - if (H1) - *H1 = eye(3); - if (H2) - *H2 = eye(3); - if (H3) - *H3 = eye(3); - return R1 * (R2 * R3); -} - -TEST(ExpressionFactor, composeTernary) { - - // Create expression - Rot3_ A(1), B(2), C(3); - Rot3_ ABC(composeThree, A, B, C); - - // Create factor - ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), ABC); - - // Create some values - Values values; - values.insert(1, Rot3()); - values.insert(2, Rot3()); - values.insert(3, Rot3()); - - // Check unwhitenedError - std::vector H(3); - Vector actual = f.unwhitenedError(values, H); - EXPECT_LONGS_EQUAL(3, H.size()); - EXPECT( assert_equal(eye(3), H[0],1e-9)); - EXPECT( assert_equal(eye(3), H[1],1e-9)); - EXPECT( assert_equal(eye(3), H[2],1e-9)); - - // Check linearization - JacobianFactor expected(1, eye(3), 2, eye(3), 3, eye(3), zero(3)); - boost::shared_ptr gf = f.linearize(values); - boost::shared_ptr jf = // - boost::dynamic_pointer_cast(gf); - EXPECT( assert_equal(expected, *jf,1e-9)); -} - -TEST(ExpressionFactor, tree_finite_differences) { - - // Create some values - Values values; - values.insert(1, Pose3()); - values.insert(2, Point3(0, 0, 1)); - values.insert(3, Cal3_S2()); - - // Create leaves - Pose3_ x(1); - Point3_ p(2); - Cal3_S2_ K(3); - - // Create expression tree - Point3_ p_cam(x, &Pose3::transform_to, p); - Point2_ xy_hat(PinholeCamera::project_to_camera, p_cam); - Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat); - - const double fd_step = 1e-5; - const double tolerance = 1e-5; - EXPECT_CORRECT_EXPRESSION_JACOBIANS(uv_hat, values, fd_step, tolerance); -} - -/* ************************************************************************* */ -int main() { - TestResult tr; - return TestRegistry::runAllTests(tr); -} -/* ************************************************************************* */ - diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 9d4a8e6e5..da22225e5 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -173,7 +173,7 @@ public: Point3 _1T2 = E.direction().point3(); Point3 d1T2 = d * _1T2; Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2); // 2R1*((x,y,1)-d*1T2) - pn = SimpleCamera::project_to_camera(dP2); + pn = PinholeBase::Project(dP2); } else { @@ -186,7 +186,7 @@ public: Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2, DdP2_rot, DP2_point); Matrix23 Dpn_dP2; - pn = SimpleCamera::project_to_camera(dP2, Dpn_dP2); + pn = PinholeBase::Project(dP2, Dpn_dP2); if (DE) { Matrix DdP2_E(3, 5); diff --git a/gtsam/slam/expressions.h b/gtsam/slam/expressions.h index b819993ef..fac2cf03d 100644 --- a/gtsam/slam/expressions.h +++ b/gtsam/slam/expressions.h @@ -28,6 +28,7 @@ inline Point2_ transform_to(const Pose2_& x, const Point2_& p) { // 3D Geometry typedef Expression Point3_; +typedef Expression Unit3_; typedef Expression Rot3_; typedef Expression Pose3_; @@ -40,33 +41,52 @@ inline Point3_ transform_to(const Pose3_& x, const Point3_& p) { typedef Expression Cal3_S2_; typedef Expression Cal3Bundler_; +/// Expression version of PinholeBase::Project inline Point2_ project(const Point3_& p_cam) { - return Point2_(PinholeCamera::project_to_camera, p_cam); + Point2 (*f)(const Point3&, OptionalJacobian<2, 3>) = &PinholeBase::Project; + return Point2_(f, p_cam); } -template -Point2 project4(const CAMERA& camera, const Point3& p, - OptionalJacobian<2, CAMERA::dimension> Dcam, OptionalJacobian<2, 3> Dpoint) { +inline Point2_ project(const Unit3_& p_cam) { + Point2 (*f)(const Unit3&, OptionalJacobian<2, 2>) = &PinholeBase::Project; + return Point2_(f, p_cam); +} + +namespace internal { +// Helper template for project2 expression below +template +Point2 project4(const CAMERA& camera, const POINT& p, + OptionalJacobian<2, CAMERA::dimension> Dcam, + OptionalJacobian<2, FixedDimension::value> Dpoint) { return camera.project2(p, Dcam, Dpoint); } - -template -Point2_ project2(const Expression& camera_, const Point3_& p_) { - return Point2_(project4, camera_, p_); } +template +Point2_ project2(const Expression& camera_, + const Expression& p_) { + return Point2_(internal::project4, camera_, p_); +} + +namespace internal { +// Helper template for project3 expression below +template inline Point2 project6(const Pose3& x, const Point3& p, const Cal3_S2& K, - OptionalJacobian<2, 6> Dpose, OptionalJacobian<2, 3> Dpoint, OptionalJacobian<2, 5> Dcal) { + OptionalJacobian<2, 6> Dpose, OptionalJacobian<2, 3> Dpoint, + OptionalJacobian<2, 5> Dcal) { return PinholeCamera(x, K).project(p, Dpose, Dpoint, Dcal); } - -inline Point2_ project3(const Pose3_& x, const Point3_& p, const Cal3_S2_& K) { - return Point2_(project6, x, p, K); } -template -Point2_ uncalibrate(const Expression& K, const Point2_& xy_hat) { - return Point2_(K, &CAL::uncalibrate, xy_hat); +template +inline Point2_ project3(const Pose3_& x, const Expression& p, + const Expression& K) { + return Point2_(internal::project6, x, p, K); +} + +template +Point2_ uncalibrate(const Expression& K, const Point2_& xy_hat) { + return Point2_(K, &CALIBRATION::uncalibrate, xy_hat); } } // \namespace gtsam From 88d8543f12dd8885bb8a0a8647dc6dab321b9bcc Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 6 Mar 2015 08:47:54 -0800 Subject: [PATCH 120/173] Moved to tests --- tests/testExpressionFactor.cpp | 500 +++++++++++++++++++++++++++++++++ 1 file changed, 500 insertions(+) create mode 100644 tests/testExpressionFactor.cpp diff --git a/tests/testExpressionFactor.cpp b/tests/testExpressionFactor.cpp new file mode 100644 index 000000000..958087c32 --- /dev/null +++ b/tests/testExpressionFactor.cpp @@ -0,0 +1,500 @@ +/* ---------------------------------------------------------------------------- + + * 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 testExpressionFactor.cpp + * @date September 18, 2014 + * @author Frank Dellaert + * @author Paul Furgale + * @brief unit tests for Block Automatic Differentiation + */ + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +using boost::assign::list_of; + +using namespace std; +using namespace gtsam; + +Point2 measured(-17, 30); +SharedNoiseModel model = noiseModel::Unit::Create(2); + +namespace leaf { +// Create some values +struct MyValues: public Values { + MyValues() { + insert(2, Point2(3, 5)); + } +} values; + +// Create leaf +Point2_ p(2); +} + +/* ************************************************************************* */ +// Leaf +TEST(ExpressionFactor, Leaf) { + using namespace leaf; + + // Create old-style factor to create expected value and derivatives + PriorFactor old(2, Point2(0, 0), model); + + // Concise version + ExpressionFactor f(model, Point2(0, 0), p); + EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9); + EXPECT_LONGS_EQUAL(2, f.dim()); + boost::shared_ptr gf2 = f.linearize(values); + EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9)); +} + +/* ************************************************************************* */ +// non-zero noise model +TEST(ExpressionFactor, Model) { + using namespace leaf; + + SharedNoiseModel model = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.01)); + + // Create old-style factor to create expected value and derivatives + PriorFactor old(2, Point2(0, 0), model); + + // Concise version + ExpressionFactor f(model, Point2(0, 0), p); + + // Check values and derivatives + EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9); + EXPECT_LONGS_EQUAL(2, f.dim()); + boost::shared_ptr gf2 = f.linearize(values); + EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9)); + EXPECT_CORRECT_FACTOR_JACOBIANS(f, values, 1e-5, 1e-5); // another way +} + +/* ************************************************************************* */ +// Constrained noise model +TEST(ExpressionFactor, Constrained) { + using namespace leaf; + + SharedDiagonal model = noiseModel::Constrained::MixedSigmas(Vector2(0.2, 0)); + + // Create old-style factor to create expected value and derivatives + PriorFactor old(2, Point2(0, 0), model); + + // Concise version + ExpressionFactor f(model, Point2(0, 0), p); + EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9); + EXPECT_LONGS_EQUAL(2, f.dim()); + boost::shared_ptr gf2 = f.linearize(values); + EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9)); +} + +/* ************************************************************************* */ +// Unary(Leaf)) +TEST(ExpressionFactor, Unary) { + + // Create some values + Values values; + values.insert(2, Point3(0, 0, 1)); + + JacobianFactor expected( // + 2, (Matrix(2, 3) << 1, 0, 0, 0, 1, 0).finished(), // + Vector2(-17, 30)); + + // Create leaves + Point3_ p(2); + + // Concise version + ExpressionFactor f(model, measured, project(p)); + EXPECT_LONGS_EQUAL(2, f.dim()); + boost::shared_ptr gf = f.linearize(values); + boost::shared_ptr jf = // + boost::dynamic_pointer_cast(gf); + EXPECT( assert_equal(expected, *jf, 1e-9)); +} + +/* ************************************************************************* */ +// Unary(Leaf)) and Unary(Unary(Leaf))) +// wide version (not handled in fixed-size pipeline) +typedef Eigen::Matrix Matrix93; +Vector9 wide(const Point3& p, OptionalJacobian<9,3> H) { + Vector9 v; + v << p.vector(), p.vector(), p.vector(); + if (H) *H << eye(3), eye(3), eye(3); + return v; +} +typedef Eigen::Matrix Matrix9; +Vector9 id9(const Vector9& v, OptionalJacobian<9,9> H) { + if (H) *H = Matrix9::Identity(); + return v; +} +TEST(ExpressionFactor, Wide) { + // Create some values + Values values; + values.insert(2, Point3(0, 0, 1)); + Point3_ point(2); + Vector9 measured; + measured.setZero(); + Expression expression(wide,point); + SharedNoiseModel model = noiseModel::Unit::Create(9); + + ExpressionFactor f1(model, measured, expression); + EXPECT_CORRECT_FACTOR_JACOBIANS(f1, values, 1e-5, 1e-9); + + Expression expression2(id9,expression); + ExpressionFactor f2(model, measured, expression2); + EXPECT_CORRECT_FACTOR_JACOBIANS(f2, values, 1e-5, 1e-9); +} + +/* ************************************************************************* */ +static Point2 myUncal(const Cal3_S2& K, const Point2& p, + OptionalJacobian<2,5> Dcal, OptionalJacobian<2,2> Dp) { + return K.uncalibrate(p, Dcal, Dp); +} + +// Binary(Leaf,Leaf) +TEST(ExpressionFactor, Binary) { + + typedef BinaryExpression Binary; + + Cal3_S2_ K_(1); + Point2_ p_(2); + Binary binary(myUncal, K_, p_); + + // Create some values + Values values; + values.insert(1, Cal3_S2()); + values.insert(2, Point2(0, 0)); + + // traceRaw will fill raw with [Trace | Binary::Record] + EXPECT_LONGS_EQUAL(8, sizeof(double)); + EXPECT_LONGS_EQUAL(16, sizeof(Point2)); + EXPECT_LONGS_EQUAL(40, sizeof(Cal3_S2)); + EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace)); + EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace)); + EXPECT_LONGS_EQUAL(2*5*8, sizeof(Jacobian::type)); + EXPECT_LONGS_EQUAL(2*2*8, sizeof(Jacobian::type)); + size_t expectedRecordSize = 16 + 16 + 40 + 2 * 16 + 80 + 32; + EXPECT_LONGS_EQUAL(expectedRecordSize + 8, sizeof(Binary::Record)); + + // Check size + size_t size = binary.traceSize(); + CHECK(size); + EXPECT_LONGS_EQUAL(expectedRecordSize + 8, size); + // Use Variable Length Array, allocated on stack by gcc + // Note unclear for Clang: http://clang.llvm.org/compatibility.html#vla + ExecutionTraceStorage traceStorage[size]; + ExecutionTrace trace; + Point2 value = binary.traceExecution(values, trace, traceStorage); + EXPECT(assert_equal(Point2(),value, 1e-9)); + // trace.print(); + + // Expected Jacobians + Matrix25 expected25; + expected25 << 0, 0, 0, 1, 0, 0, 0, 0, 0, 1; + Matrix2 expected22; + expected22 << 1, 0, 0, 1; + + // Check matrices + boost::optional r = trace.record(); + CHECK(r); + EXPECT( + assert_equal(expected25, (Matrix) (*r)-> jacobian(), 1e-9)); + EXPECT( assert_equal(expected22, (Matrix) (*r)->jacobian(), 1e-9)); +} +/* ************************************************************************* */ +// Unary(Binary(Leaf,Leaf)) +TEST(ExpressionFactor, Shallow) { + + // Create some values + Values values; + values.insert(1, Pose3()); + values.insert(2, Point3(0, 0, 1)); + + // Create old-style factor to create expected value and derivatives + GenericProjectionFactor old(measured, model, 1, 2, + boost::make_shared()); + double expected_error = old.error(values); + GaussianFactor::shared_ptr expected = old.linearize(values); + + // Create leaves + Pose3_ x_(1); + Point3_ p_(2); + + // Construct expression, concise evrsion + Point2_ expression = project(transform_to(x_, p_)); + + // Get and check keys and dims + FastVector keys; + FastVector dims; + boost::tie(keys, dims) = expression.keysAndDims(); + LONGS_EQUAL(2,keys.size()); + LONGS_EQUAL(2,dims.size()); + LONGS_EQUAL(1,keys[0]); + LONGS_EQUAL(2,keys[1]); + LONGS_EQUAL(6,dims[0]); + LONGS_EQUAL(3,dims[1]); + + // traceExecution of shallow tree + typedef UnaryExpression Unary; + typedef BinaryExpression Binary; + size_t expectedTraceSize = sizeof(Unary::Record) + sizeof(Binary::Record); + EXPECT_LONGS_EQUAL(112, sizeof(Unary::Record)); +#ifdef GTSAM_USE_QUATERNIONS + EXPECT_LONGS_EQUAL(352, sizeof(Binary::Record)); + LONGS_EQUAL(112+352, expectedTraceSize); +#else + EXPECT_LONGS_EQUAL(400, sizeof(Binary::Record)); + LONGS_EQUAL(112+400, expectedTraceSize); +#endif + size_t size = expression.traceSize(); + CHECK(size); + EXPECT_LONGS_EQUAL(expectedTraceSize, size); + ExecutionTraceStorage traceStorage[size]; + ExecutionTrace trace; + Point2 value = expression.traceExecution(values, trace, traceStorage); + EXPECT(assert_equal(Point2(),value, 1e-9)); + // trace.print(); + + // Expected Jacobians + Matrix23 expected23; + expected23 << 1, 0, 0, 0, 1, 0; + + // Check matrices + boost::optional r = trace.record(); + CHECK(r); + EXPECT(assert_equal(expected23, (Matrix)(*r)->jacobian(), 1e-9)); + + // Linearization + ExpressionFactor f2(model, measured, expression); + EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9); + EXPECT_LONGS_EQUAL(2, f2.dim()); + boost::shared_ptr gf2 = f2.linearize(values); + EXPECT( assert_equal(*expected, *gf2, 1e-9)); +} + +/* ************************************************************************* */ +// Binary(Leaf,Unary(Binary(Leaf,Leaf))) +TEST(ExpressionFactor, tree) { + + // Create some values + Values values; + values.insert(1, Pose3()); + values.insert(2, Point3(0, 0, 1)); + values.insert(3, Cal3_S2()); + + // Create old-style factor to create expected value and derivatives + GeneralSFMFactor2 old(measured, model, 1, 2, 3); + double expected_error = old.error(values); + GaussianFactor::shared_ptr expected = old.linearize(values); + + // Create leaves + Pose3_ x(1); + Point3_ p(2); + Cal3_S2_ K(3); + + // Create expression tree + Point3_ p_cam(x, &Pose3::transform_to, p); + Point2_ xy_hat = project(p_cam); + Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat); + + // Create factor and check value, dimension, linearization + ExpressionFactor f(model, measured, uv_hat); + EXPECT_DOUBLES_EQUAL(expected_error, f.error(values), 1e-9); + EXPECT_LONGS_EQUAL(2, f.dim()); + boost::shared_ptr gf = f.linearize(values); + EXPECT( assert_equal(*expected, *gf, 1e-9)); + + // Concise version + ExpressionFactor f2(model, measured, + uncalibrate(K, project(transform_to(x, p)))); + EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9); + EXPECT_LONGS_EQUAL(2, f2.dim()); + boost::shared_ptr gf2 = f2.linearize(values); + EXPECT( assert_equal(*expected, *gf2, 1e-9)); + + // Try ternary version + ExpressionFactor f3(model, measured, project3(x, p, K)); + EXPECT_DOUBLES_EQUAL(expected_error, f3.error(values), 1e-9); + EXPECT_LONGS_EQUAL(2, f3.dim()); + boost::shared_ptr gf3 = f3.linearize(values); + EXPECT( assert_equal(*expected, *gf3, 1e-9)); +} + +/* ************************************************************************* */ + +TEST(ExpressionFactor, Compose1) { + + // Create expression + Rot3_ R1(1), R2(2); + Rot3_ R3 = R1 * R2; + + // Create factor + ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), R3); + + // Create some values + Values values; + values.insert(1, Rot3()); + values.insert(2, Rot3()); + + // Check unwhitenedError + std::vector H(2); + Vector actual = f.unwhitenedError(values, H); + EXPECT( assert_equal(eye(3), H[0],1e-9)); + EXPECT( assert_equal(eye(3), H[1],1e-9)); + + // Check linearization + JacobianFactor expected(1, eye(3), 2, eye(3), zero(3)); + boost::shared_ptr gf = f.linearize(values); + boost::shared_ptr jf = // + boost::dynamic_pointer_cast(gf); + EXPECT( assert_equal(expected, *jf,1e-9)); +} + +/* ************************************************************************* */ +// Test compose with arguments referring to the same rotation +TEST(ExpressionFactor, compose2) { + + // Create expression + Rot3_ R1(1), R2(1); + Rot3_ R3 = R1 * R2; + + // Create factor + ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), R3); + + // Create some values + Values values; + values.insert(1, Rot3()); + + // Check unwhitenedError + std::vector H(1); + Vector actual = f.unwhitenedError(values, H); + EXPECT_LONGS_EQUAL(1, H.size()); + EXPECT( assert_equal(2*eye(3), H[0],1e-9)); + + // Check linearization + JacobianFactor expected(1, 2 * eye(3), zero(3)); + boost::shared_ptr gf = f.linearize(values); + boost::shared_ptr jf = // + boost::dynamic_pointer_cast(gf); + EXPECT( assert_equal(expected, *jf,1e-9)); +} + +/* ************************************************************************* */ +// Test compose with one arguments referring to a constant same rotation +TEST(ExpressionFactor, compose3) { + + // Create expression + Rot3_ R1(Rot3::identity()), R2(3); + Rot3_ R3 = R1 * R2; + + // Create factor + ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), R3); + + // Create some values + Values values; + values.insert(3, Rot3()); + + // Check unwhitenedError + std::vector H(1); + Vector actual = f.unwhitenedError(values, H); + EXPECT_LONGS_EQUAL(1, H.size()); + EXPECT( assert_equal(eye(3), H[0],1e-9)); + + // Check linearization + JacobianFactor expected(3, eye(3), zero(3)); + boost::shared_ptr gf = f.linearize(values); + boost::shared_ptr jf = // + boost::dynamic_pointer_cast(gf); + EXPECT( assert_equal(expected, *jf,1e-9)); +} + +/* ************************************************************************* */ +// Test compose with three arguments +Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3, + OptionalJacobian<3, 3> H1, OptionalJacobian<3, 3> H2, OptionalJacobian<3, 3> H3) { + // return dummy derivatives (not correct, but that's ok for testing here) + if (H1) + *H1 = eye(3); + if (H2) + *H2 = eye(3); + if (H3) + *H3 = eye(3); + return R1 * (R2 * R3); +} + +TEST(ExpressionFactor, composeTernary) { + + // Create expression + Rot3_ A(1), B(2), C(3); + Rot3_ ABC(composeThree, A, B, C); + + // Create factor + ExpressionFactor f(noiseModel::Unit::Create(3), Rot3(), ABC); + + // Create some values + Values values; + values.insert(1, Rot3()); + values.insert(2, Rot3()); + values.insert(3, Rot3()); + + // Check unwhitenedError + std::vector H(3); + Vector actual = f.unwhitenedError(values, H); + EXPECT_LONGS_EQUAL(3, H.size()); + EXPECT( assert_equal(eye(3), H[0],1e-9)); + EXPECT( assert_equal(eye(3), H[1],1e-9)); + EXPECT( assert_equal(eye(3), H[2],1e-9)); + + // Check linearization + JacobianFactor expected(1, eye(3), 2, eye(3), 3, eye(3), zero(3)); + boost::shared_ptr gf = f.linearize(values); + boost::shared_ptr jf = // + boost::dynamic_pointer_cast(gf); + EXPECT( assert_equal(expected, *jf,1e-9)); +} + +TEST(ExpressionFactor, tree_finite_differences) { + + // Create some values + Values values; + values.insert(1, Pose3()); + values.insert(2, Point3(0, 0, 1)); + values.insert(3, Cal3_S2()); + + // Create leaves + Pose3_ x(1); + Point3_ p(2); + Cal3_S2_ K(3); + + // Create expression tree + Point3_ p_cam(x, &Pose3::transform_to, p); + Point2_ xy_hat = project(p_cam); + Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat); + + const double fd_step = 1e-5; + const double tolerance = 1e-5; + EXPECT_CORRECT_EXPRESSION_JACOBIANS(uv_hat, values, fd_step, tolerance); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + From faadf5b06fab8537482aa87c190d23a4d5b69ea1 Mon Sep 17 00:00:00 2001 From: dellaert Date: Fri, 6 Mar 2015 08:48:35 -0800 Subject: [PATCH 121/173] Fully compiles now --- gtsam/slam/JacobianFactorQ.h | 2 +- gtsam/slam/tests/testEssentialMatrixFactor.cpp | 2 +- gtsam/slam/tests/testSmartProjectionCameraFactor.cpp | 8 ++++---- gtsam_unstable/slam/SmartStereoProjectionFactor.h | 9 +++++---- 4 files changed, 11 insertions(+), 10 deletions(-) diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index 12f8a4c71..16560a43e 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -65,7 +65,7 @@ public: for (size_t k = 0; k < FBlocks.size(); ++k) { Key key = keys[k]; QF.push_back( - KeyMatrix(key, Q.block(0, ZDim * j++, m2, ZDim) * FBlocks[k])); + KeyMatrix(key, - Q.block(0, ZDim * j++, m2, ZDim) * FBlocks[k])); } // Which is then passed to the normal JacobianFactor constructor JacobianFactor::fillTerms(QF, - Q * b, model); diff --git a/gtsam/slam/tests/testEssentialMatrixFactor.cpp b/gtsam/slam/tests/testEssentialMatrixFactor.cpp index e0e26ecff..3bcc3eccd 100644 --- a/gtsam/slam/tests/testEssentialMatrixFactor.cpp +++ b/gtsam/slam/tests/testEssentialMatrixFactor.cpp @@ -160,7 +160,7 @@ TEST (EssentialMatrixFactor2, factor) { // Check evaluation Point3 P1 = data.tracks[i].p, P2 = data.cameras[1].pose().transform_to(P1); - const Point2 pi = SimpleCamera::project_to_camera(P2); + const Point2 pi = PinholeBase::Project(P2); Point2 reprojectionError(pi - pB(i)); Vector expected = reprojectionError.vector(); diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index c7cf0283f..964f3bca4 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -160,10 +160,10 @@ TEST( SmartProjectionCameraFactor, noisy ) { // Check whitened errors Vector expected(4); - expected << -7, 235, 58, -242; + expected << 7, -235, -58, 242; SmartFactor::Cameras cameras1 = factor1->cameras(values); Point3 point1 = *factor1->point(); - Vector actual = factor1->whitenedErrors(cameras1, point1); + Vector actual = factor1->whitenedError(cameras1, point1); EXPECT(assert_equal(expected, actual, 1)); SmartFactor::shared_ptr factor2(new SmartFactor()); @@ -245,10 +245,10 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { // Check whitened errors Vector expected(6); - expected << 256, 29, -26, 29, -206, -202; + expected << -256, -29, 26, -29, 206, 202; SmartFactor::Cameras cameras1 = smartFactor1->cameras(initial); Point3 point1 = *smartFactor1->point(); - Vector actual = smartFactor1->whitenedErrors(cameras1, point1); + Vector actual = smartFactor1->whitenedError(cameras1, point1); EXPECT(assert_equal(expected, actual, 1)); // Optimize diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 65036edfe..5e0898bfa 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -415,7 +415,7 @@ public: std::vector Fblocks; Matrix F, E; Vector b; - double f = computeJacobians(Fblocks, E, b, cameras); + computeJacobians(Fblocks, E, b, cameras); Base::FillDiagonalF(Fblocks, F); // expensive !!! // Schur complement trick @@ -446,6 +446,7 @@ public: } } // ================================================================== + double f = b.squaredNorm(); if (this->linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables this->state_->Gs = Gs; this->state_->gs = gs; @@ -549,7 +550,7 @@ public: /// Compute F, E only (called below in both vanilla and SVD versions) /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate - double computeJacobians(std::vector& Fblocks, + void computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras) const { if (this->degenerate_) { throw("FIXME: computeJacobians degenerate case commented out!"); @@ -587,7 +588,7 @@ public: // return f; } else { // nondegenerate: just return Base version - return Base::computeJacobians(Fblocks, E, b, cameras, point_); + Base::computeJacobians(Fblocks, E, b, cameras, point_); } // end else } @@ -607,7 +608,7 @@ public: Cameras cameras; bool nonDegenerate = computeCamerasAndTriangulate(values, cameras); if (nonDegenerate) - return Base::reprojectionError(cameras, point_); + return Base::unwhitenedError(cameras, point_); else return zero(cameras.size() * 3); } From 0ab1b8631a0fcee0c9e0ebf90f235a91e4be515a Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 9 Mar 2015 17:43:00 -0700 Subject: [PATCH 122/173] Fixed compilation issues due to renaming --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 5d9dc4c5f..722a8d0a0 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -121,7 +121,7 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // Calculate expected derivative for point (easiest to check) boost::function f = // - boost::bind(&SmartFactor::whitenedErrors, factor, cameras, _1); + boost::bind(&SmartFactor::whitenedError, factor, cameras, _1); // Calculate using computeEP Matrix actualE; @@ -138,7 +138,7 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // Calculate using reprojectionError SmartFactor::Cameras::FBlocks F; Matrix E; - Vector actualErrors = factor.reprojectionError(cameras, *point, F, E); + Vector actualErrors = factor.unwhitenedError(cameras, *point, F, E); EXPECT(assert_equal(expectedE, E, 1e-7)); EXPECT(assert_equal(zero(4), actualErrors, 1e-7)); @@ -146,7 +146,8 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { // Calculate using computeJacobians Vector b; vector Fblocks; - double actualError3 = factor.computeJacobians(Fblocks, E, b, cameras, *point); + factor.computeJacobians(Fblocks, E, b, cameras, *point); + double actualError3 = b.squaredNorm(); EXPECT(assert_equal(expectedE, E, 1e-7)); EXPECT_DOUBLES_EQUAL(expectedError, actualError3, 1e-8); } From 0f198dc1d63e9985af7e20d98454e8a3123bffcf Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 9 Mar 2015 18:00:25 -0700 Subject: [PATCH 123/173] Fixed sign of errors --- gtsam/slam/tests/testSmartProjectionCameraFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 964f3bca4..c4775521c 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -160,7 +160,7 @@ TEST( SmartProjectionCameraFactor, noisy ) { // Check whitened errors Vector expected(4); - expected << 7, -235, -58, 242; + expected << -7, 235, 58, -242; SmartFactor::Cameras cameras1 = factor1->cameras(values); Point3 point1 = *factor1->point(); Vector actual = factor1->whitenedError(cameras1, point1); From 1eec6748cb8cce41e55aea76fbd00ca908acc204 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 9 Mar 2015 18:00:47 -0700 Subject: [PATCH 124/173] Removed timing, added new SUMMARY stats on failing tests --- .../tests/testSmartProjectionPoseFactor.cpp | 25 ++++--------------- 1 file changed, 5 insertions(+), 20 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 722a8d0a0..06deb38e5 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -54,8 +54,7 @@ typedef SmartProjectionPoseFactor SmartFactorBundler; LevenbergMarquardtParams params; // Make more verbose like so (in tests): -// params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; -// params.verbosity = NonlinearOptimizerParams::ERROR; +// params.verbosityLM = LevenbergMarquardtParams::SUMMARY; /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor) { @@ -244,11 +243,9 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); Values result; - gttic_(SmartProjectionPoseFactor); + params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); // VectorValues delta = GFG->optimize(); @@ -456,11 +453,9 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { values.at(x3).pose())); Values result; - gttic_(SmartProjectionPoseFactor); + params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); // result.print("results of 3 camera, 3 landmark optimization \n"); EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-7)); @@ -513,6 +508,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { values.insert(x3, Camera(pose_above * noise_pose, sharedK)); Values result; + params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); @@ -900,11 +896,8 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac values.at(x3).pose())); Values result; - gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); EXPECT( assert_equal( @@ -988,11 +981,8 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) values.at(x3).pose())); Values result; - gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); EXPECT( assert_equal( @@ -1211,11 +1201,9 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); Values result; - gttic_(SmartProjectionPoseFactor); + params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); EXPECT(assert_equal(cam3, result.at(x3), 1e-6)); } @@ -1294,11 +1282,8 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { values.at(x3).pose())); Values result; - gttic_(SmartProjectionPoseFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); EXPECT( assert_equal( From a0470b7e1c65d20261343fd642df291e209126a7 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 12:44:19 -0700 Subject: [PATCH 125/173] Moved all linearize logic into SmartProjectionFactor and removed two subclasses --- gtsam/slam/SmartFactorBase.h | 18 +- gtsam/slam/SmartProjectionCameraFactor.h | 161 ------------------ gtsam/slam/SmartProjectionFactor.h | 96 +++++++++-- gtsam/slam/SmartProjectionPoseFactor.h | 146 ---------------- gtsam/slam/tests/smartFactorScenarios.h | 6 + .../tests/testSmartProjectionCameraFactor.cpp | 47 +++-- .../tests/testSmartProjectionPoseFactor.cpp | 94 ++++++---- 7 files changed, 176 insertions(+), 392 deletions(-) delete mode 100644 gtsam/slam/SmartProjectionCameraFactor.h delete mode 100644 gtsam/slam/SmartProjectionPoseFactor.h diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a024ea4fc..1f19d7848 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -189,7 +189,7 @@ public: std::cout << "measurement, p = " << measured_[k] << "\t"; noiseModel_->print("noise model = "); } - Base::print("", keyFormatter); + print("", keyFormatter); } /// equals @@ -202,12 +202,10 @@ public: areMeasurementsEqual = false; break; } - return e && Base::equals(p, tol) && areMeasurementsEqual; + return e && equals(p, tol) && areMeasurementsEqual; } - /** - * Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives - */ + ///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, // @@ -294,9 +292,7 @@ public: Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns } - /** - * Linearize to a Hessianfactor - */ + /// Linearize to a Hessianfactor boost::shared_ptr > createHessianFactor( const Cameras& cameras, const Point3& point, const double lambda = 0.0, bool diagonalDamping = false) const { @@ -341,9 +337,7 @@ public: F[i] = noiseModel_->Whiten(F[i]); } - /** - * Return Jacobians as RegularImplicitSchurFactor with raw access - */ + /// Return Jacobians as RegularImplicitSchurFactor with raw access boost::shared_ptr > // createRegularImplicitSchurFactor(const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { @@ -374,7 +368,7 @@ public: } /** - * Return Jacobians as JacobianFactor + * Return Jacobians as JacobianFactorSVD * TODO lambda is currently ignored */ boost::shared_ptr createJacobianSVDFactor( diff --git a/gtsam/slam/SmartProjectionCameraFactor.h b/gtsam/slam/SmartProjectionCameraFactor.h deleted file mode 100644 index b2eeba3e1..000000000 --- a/gtsam/slam/SmartProjectionCameraFactor.h +++ /dev/null @@ -1,161 +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 SmartProjectionCameraFactor.h - * @brief Produces an Hessian factors on CAMERAS (Pose3+CALIBRATION) from monocular measurements of a landmark - * @author Luca Carlone - * @author Chris Beall - * @author Zsolt Kira - * @author Frank Dellaert - */ - -#pragma once -#include - -namespace gtsam { - -/** - * @addtogroup SLAM - */ -template -class SmartProjectionCameraFactor: public SmartProjectionFactor< - PinholeCamera > { - -private: - typedef PinholeCamera Camera; - typedef SmartProjectionFactor Base; - typedef SmartProjectionCameraFactor This; - -protected: - - static const int Dim = traits::dimension; ///< CAMERA dimension - - bool isImplicit_; - -public: - - /// shorthand for a smart pointer to a factor - typedef boost::shared_ptr shared_ptr; - - // A set of cameras - typedef CameraSet Cameras; - - /** - * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param isImplicit if set to true linearize the factor to an implicit Schur factor - */ - SmartProjectionCameraFactor(const double rankTol = 1, - const double linThreshold = -1, const bool manageDegeneracy = false, - const bool enableEPI = false, const bool isImplicit = false) : - Base(rankTol, linThreshold, manageDegeneracy, enableEPI), isImplicit_( - isImplicit) { - if (linThreshold != -1) { - std::cout << "SmartProjectionCameraFactor: linThreshold " << linThreshold - << std::endl; - } - } - - /** Virtual destructor */ - virtual ~SmartProjectionCameraFactor() { - } - - /** - * print - * @param s optional string naming the factor - * @param keyFormatter optional formatter useful for printing Symbols - */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { - std::cout << s << "SmartProjectionCameraFactor, z = \n "; - Base::print("", keyFormatter); - } - - /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { - const This *e = dynamic_cast(&p); - - return e && Base::equals(p, tol); - } - - /// get the dimension of the factor (number of rows on linearization) - virtual size_t dim() const { - return Dim * this->keys_.size(); // 6 for the pose and 3 for the calibration - } - - /// linearize and adds damping on the points - boost::shared_ptr linearizeDamped(const Values& values, - const double lambda=0.0) const { - if (!isImplicit_) - return Base::createHessianFactor(Base::cameras(values), lambda); - else - return Base::createRegularImplicitSchurFactor(Base::cameras(values)); - } - - /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr > linearizeToHessian( - const Values& values, double lambda=0.0) const { - return Base::createHessianFactor(Base::cameras(values),lambda); - } - - /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr > linearizeToImplicit( - const Values& values, double lambda=0.0) const { - return Base::createRegularImplicitSchurFactor(Base::cameras(values),lambda); - } - - /// linearize returns a Jacobianfactor that is an approximation of error(p) - virtual boost::shared_ptr > linearizeToJacobian( - const Values& values, double lambda=0.0) const { - return Base::createJacobianQFactor(Base::cameras(values),lambda); - } - - /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr linearizeWithLambda( - const Values& values, double lambda) const { - if (isImplicit_) - return linearizeToImplicit(values,lambda); - else - return linearizeToHessian(values,lambda); - } - - /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr linearize( - const Values& values) const { - return linearizeWithLambda(values,0.0); - } - - /// Calculare total reprojection error - virtual double error(const Values& values) const { - if (this->active(values)) { - return Base::totalReprojectionError(Base::cameras(values)); - } else { // else of active flag - return 0.0; - } - } - -private: - - /// Serialization function - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - } - -}; - -} // \ namespace gtsam diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 6a9088e25..2101d041e 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -46,22 +46,27 @@ struct SmartProjectionFactorState { double f; }; -enum LinearizationMode { - HESSIAN, JACOBIAN_SVD, JACOBIAN_Q -}; - /** * SmartProjectionFactor: triangulates point and keeps an estimate of it around. */ template class SmartProjectionFactor: public SmartFactorBase { +public: + + /// Linearization mode: what factor to linearize to + enum LinearizationMode { + HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD + }; + private: typedef SmartFactorBase Base; typedef SmartProjectionFactor This; protected: + LinearizationMode linearizeTo_; ///< How to linearize the factor + /// @name Caching triangulation /// @{ const TriangulationParameters parameters_; @@ -104,16 +109,16 @@ public: * otherwise the factor is simply neglected * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations */ - SmartProjectionFactor(const double rankTolerance, const double linThreshold, - const bool manageDegeneracy, const bool enableEPI, + SmartProjectionFactor(LinearizationMode linearizationMode = HESSIAN, + double rankTolerance = 1, double linThreshold = -1, + bool manageDegeneracy = false, bool enableEPI = false, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1, SmartFactorStatePtr state = SmartFactorStatePtr(new SmartProjectionFactorState())) : - parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, - dynamicOutlierRejectionThreshold), // + linearizeTo_(linearizationMode), parameters_(rankTolerance, enableEPI, + landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), // result_(TriangulationResult::Degenerate()), // - retriangulationThreshold_(1e-5), // - manageDegeneracy_(manageDegeneracy), // + retriangulationThreshold_(1e-5), manageDegeneracy_(manageDegeneracy), // throwCheirality_(false), verboseCheirality_(false), // state_(state), linearizationThreshold_(linThreshold) { } @@ -135,6 +140,12 @@ public: Base::print("", keyFormatter); } + /// equals + virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + const This *e = dynamic_cast(&p); + return e && Base::equals(p, tol); + } + /// Check if the new linearization point is the same as the one used for previous triangulation bool decideIfTriangulate(const Cameras& cameras) const { // several calls to linearize will be done from the same linearization point, hence it is not needed to re-triangulate @@ -358,6 +369,53 @@ public: return boost::make_shared >(this->keys_); } + /// linearize to a Hessianfactor + virtual boost::shared_ptr > linearizeToHessian( + const Values& values, double lambda = 0.0) const { + return createHessianFactor(this->cameras(values), lambda); + } + + /// linearize to an Implicit Schur factor + virtual boost::shared_ptr > linearizeToImplicit( + const Values& values, double lambda = 0.0) const { + return createRegularImplicitSchurFactor(this->cameras(values), lambda); + } + + /// linearize to a JacobianfactorQ + virtual boost::shared_ptr > linearizeToJacobian( + const Values& values, double lambda = 0.0) const { + return createJacobianQFactor(this->cameras(values), lambda); + } + + /** + * Linearize to Gaussian Factor + * @param values Values structure which must contain camera poses for this factor + * @return a Gaussian factor + */ + boost::shared_ptr linearizeDamped(const Values& values, + const double lambda = 0.0) const { + // depending on flag set on construction we may linearize to different linear factors + Cameras cameras = this->cameras(values); + switch (linearizeTo_) { + case HESSIAN: + return createHessianFactor(cameras, lambda); + case IMPLICIT_SCHUR: + return createRegularImplicitSchurFactor(cameras, lambda); + case JACOBIAN_SVD: + return createJacobianSVDFactor(cameras, lambda); + case JACOBIAN_Q: + return createJacobianQFactor(cameras, lambda); + default: + throw std::runtime_error("SmartFactorlinearize: unknown mode"); + } + } + + /// linearize + virtual boost::shared_ptr linearize( + const Values& values) const { + return linearizeDamped(values); + } + /** * Triangulate and compute derivative of error with respect to point * @return whether triangulation worked @@ -380,7 +438,8 @@ public: if (!result_) { // Handle degeneracy // TODO check flag whether we should do this - Unit3 backProjected = cameras[0].backprojectPointAtInfinity(this->measured_.at(0)); + Unit3 backProjected = cameras[0].backprojectPointAtInfinity( + this->measured_.at(0)); Base::computeJacobians(Fblocks, E, b, cameras, backProjected); } else { // valid result: just return Base version @@ -447,6 +506,15 @@ public: return 0.0; } + /// Calculate total reprojection error + virtual double error(const Values& values) const { + if (this->active(values)) { + return totalReprojectionError(Base::cameras(values)); + } else { // else of active flag + return 0.0; + } + } + /** return the landmark */ TriangulationResult point() const { return result_; @@ -495,4 +563,10 @@ private: } }; +/// traits +template +struct traits > : public Testable< + SmartProjectionFactor > { +}; + } // \ namespace gtsam diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h deleted file mode 100644 index 851cfe030..000000000 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ /dev/null @@ -1,146 +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 SmartProjectionPoseFactor.h - * @brief Produces an Hessian factors on POSES from monocular measurements of a single landmark - * @author Luca Carlone - * @author Chris Beall - * @author Zsolt Kira - */ - -#pragma once - -#include - -namespace gtsam { -/** - * - * @addtogroup SLAM - * - * If you are using the factor, please cite: - * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally - * independent sets in factor graphs: a unifying perspective based on smart factors, - * Int. Conf. on Robotics and Automation (ICRA), 2014. - * - */ - -/** - * The calibration is known here. The factor only constraints poses (variable dimension is 6) - * @addtogroup SLAM - */ -template -class SmartProjectionPoseFactor: public SmartProjectionFactor< - PinholePose > { - -private: - typedef PinholePose Camera; - typedef SmartProjectionFactor Base; - typedef SmartProjectionPoseFactor This; - -protected: - - LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) - -public: - - /// shorthand for a smart pointer to a factor - typedef boost::shared_ptr shared_ptr; - - /** - * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - */ - SmartProjectionPoseFactor(const double rankTol = 1, - const double linThreshold = -1, const bool manageDegeneracy = false, - const bool enableEPI = false, LinearizationMode linearizeTo = HESSIAN, - double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1) : - Base(rankTol, linThreshold, manageDegeneracy, enableEPI, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_( - linearizeTo) { - } - - /** Virtual destructor */ - virtual ~SmartProjectionPoseFactor() {} - - /** - * print - * @param s optional string naming the factor - * @param keyFormatter optional formatter useful for printing Symbols - */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { - std::cout << s << "SmartProjectionPoseFactor, z = \n "; - Base::print("", keyFormatter); - } - - /// equals - virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { - const This *e = dynamic_cast(&p); - - return e && Base::equals(p, tol); - } - - /** - * Linearize to Gaussian Factor - * @param values Values structure which must contain camera poses for this factor - * @return - */ - virtual boost::shared_ptr linearize( - const Values& values) const { - // depending on flag set on construction we may linearize to different linear factors - switch(linearizeTo_){ - case JACOBIAN_SVD : - return this->createJacobianSVDFactor(Base::cameras(values), 0.0); - break; - case JACOBIAN_Q : - return this->createJacobianQFactor(Base::cameras(values), 0.0); - break; - default: - return this->createHessianFactor(Base::cameras(values)); - break; - } - } - - /** - * error calculates the error of the factor. - */ - virtual double error(const Values& values) const { - if (this->active(values)) { - return this->totalReprojectionError(Base::cameras(values)); - } else { // else of active flag - return 0.0; - } - } - -private: - - /// Serialization function - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - } - -}; // end of class declaration - -/// traits -template -struct traits > : public Testable< - SmartProjectionPoseFactor > { -}; - -} // \ namespace gtsam diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index 3c64e982c..c3598e4c1 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -17,6 +17,7 @@ */ #pragma once +#include #include #include #include @@ -48,6 +49,7 @@ static size_t w = 640, h = 480; // default Cal3_S2 cameras namespace vanilla { typedef PinholeCamera Camera; +typedef SmartProjectionFactor SmartFactor; static Cal3_S2 K(fov, w, h); static Cal3_S2 K2(1500, 1200, 0, w, h); Camera level_camera(level_pose, K2); @@ -64,6 +66,7 @@ typedef GeneralSFMFactor SFMFactor; // default Cal3_S2 poses namespace vanillaPose { typedef PinholePose Camera; +typedef SmartProjectionFactor SmartFactor; static Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); Camera level_camera(level_pose, sharedK); Camera level_camera_right(pose_right, sharedK); @@ -76,6 +79,7 @@ Camera cam3(pose_above, sharedK); // default Cal3_S2 poses namespace vanillaPose2 { typedef PinholePose Camera; +typedef SmartProjectionFactor SmartFactor; static Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); Camera level_camera(level_pose, sharedK2); Camera level_camera_right(pose_right, sharedK2); @@ -88,6 +92,7 @@ Camera cam3(pose_above, sharedK2); // Cal3Bundler cameras namespace bundler { typedef PinholeCamera Camera; +typedef SmartProjectionFactor SmartFactor; static Cal3Bundler K(500, 1e-3, 1e-3, 0, 0); Camera level_camera(level_pose, K); Camera level_camera_right(pose_right, K); @@ -103,6 +108,7 @@ typedef GeneralSFMFactor SFMFactor; // Cal3Bundler poses namespace bundlerPose { typedef PinholePose Camera; +typedef SmartProjectionFactor SmartFactor; static boost::shared_ptr sharedBundlerK( new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); Camera level_camera(level_pose, sharedBundlerK); diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index c4775521c..2f6bf9b00 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -20,7 +20,7 @@ */ #include "smartFactorScenarios.h" -#include +#include #include #include #include @@ -43,9 +43,6 @@ Key c1 = 1, c2 = 2, c3 = 3; static Point2 measurement1(323.0, 240.0); -typedef SmartProjectionCameraFactor SmartFactor; -typedef SmartProjectionCameraFactor SmartFactorBundler; - template PinholeCamera perturbCameraPoseAndCalibration( const PinholeCamera& camera) { @@ -82,7 +79,7 @@ TEST( SmartProjectionCameraFactor, Constructor) { /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor2) { using namespace vanilla; - SmartFactor factor1(rankTol, linThreshold); + SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); } /* ************************************************************************* */ @@ -95,7 +92,7 @@ TEST( SmartProjectionCameraFactor, Constructor3) { /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor4) { using namespace vanilla; - SmartFactor factor1(rankTol, linThreshold); + SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); factor1.add(measurement1, x1, unit2); } @@ -457,19 +454,19 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { views.push_back(c2); views.push_back(c3); - SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); smartFactor1->add(measurements_cam1, views, unit2); - SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); smartFactor2->add(measurements_cam2, views, unit2); - SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); smartFactor3->add(measurements_cam3, views, unit2); - SmartFactorBundler::shared_ptr smartFactor4(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor4(new SmartFactor()); smartFactor4->add(measurements_cam4, views, unit2); - SmartFactorBundler::shared_ptr smartFactor5(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor5(new SmartFactor()); smartFactor5->add(measurements_cam5, views, unit2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); @@ -533,19 +530,19 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { views.push_back(c2); views.push_back(c3); - SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); smartFactor1->add(measurements_cam1, views, unit2); - SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); smartFactor2->add(measurements_cam2, views, unit2); - SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); smartFactor3->add(measurements_cam3, views, unit2); - SmartFactorBundler::shared_ptr smartFactor4(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor4(new SmartFactor()); smartFactor4->add(measurements_cam4, views, unit2); - SmartFactorBundler::shared_ptr smartFactor5(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor5(new SmartFactor()); smartFactor5->add(measurements_cam5, views, unit2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); @@ -597,7 +594,7 @@ TEST( SmartProjectionCameraFactor, noiselessBundler ) { values.insert(c1, level_camera); values.insert(c2, level_camera_right); - SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + SmartFactor::shared_ptr factor1(new SmartFactor()); factor1->add(level_uv, c1, unit2); factor1->add(level_uv_right, c2, unit2); @@ -626,7 +623,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { values.insert(c2, level_camera_right); NonlinearFactorGraph smartGraph; - SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + SmartFactor::shared_ptr factor1(new SmartFactor()); factor1->add(level_uv, c1, unit2); factor1->add(level_uv_right, c2, unit2); smartGraph.push_back(factor1); @@ -667,7 +664,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { values.insert(c2, level_camera_right); NonlinearFactorGraph smartGraph; - SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + SmartFactor::shared_ptr factor1(new SmartFactor()); factor1->add(level_uv, c1, unit2); factor1->add(level_uv_right, c2, unit2); smartGraph.push_back(factor1); @@ -710,7 +707,7 @@ TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { // values.insert(c2, level_camera_right); // // NonlinearFactorGraph smartGraph; -// SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); +// SmartFactor::shared_ptr factor1(new SmartFactor()); // factor1->add(level_uv, c1, unit2); // factor1->add(level_uv_right, c2, unit2); // smartGraph.push_back(factor1); @@ -758,7 +755,7 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { values.insert(c1, level_camera); values.insert(c2, level_camera_right); - SmartFactorBundler::shared_ptr factor1(new SmartFactorBundler()); + SmartFactor::shared_ptr factor1(new SmartFactor()); factor1->add(level_uv, c1, unit2); factor1->add(level_uv_right, c2, unit2); Matrix expectedE; @@ -803,8 +800,8 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { bool isImplicit = false; // Hessian version - SmartFactorBundler::shared_ptr explicitFactor( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy, useEPI, + SmartFactor::shared_ptr explicitFactor( + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, manageDegeneracy, useEPI, isImplicit)); explicitFactor->add(level_uv, c1, unit2); explicitFactor->add(level_uv_right, c2, unit2); @@ -816,8 +813,8 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { // Implicit Schur version isImplicit = true; - SmartFactorBundler::shared_ptr implicitFactor( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy, useEPI, + SmartFactor::shared_ptr implicitFactor( + new SmartFactor(SmartFactor::IMPLICIT_SCHUR, rankTol, linThreshold, manageDegeneracy, useEPI, isImplicit)); implicitFactor->add(level_uv, c1, unit2); implicitFactor->add(level_uv_right, c2, unit2); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 06deb38e5..1d9ad0dc6 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -20,7 +20,6 @@ */ #include "smartFactorScenarios.h" -#include #include #include #include @@ -49,8 +48,6 @@ static Symbol x2('X', 2); static Symbol x3('X', 3); static Point2 measurement1(323.0, 240.0); -typedef SmartProjectionPoseFactor SmartFactor; -typedef SmartProjectionPoseFactor SmartFactorBundler; LevenbergMarquardtParams params; // Make more verbose like so (in tests): @@ -58,12 +55,14 @@ LevenbergMarquardtParams params; /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor) { + using namespace vanillaPose; SmartFactor::shared_ptr factor1(new SmartFactor()); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor2) { - SmartFactor factor1(rankTol, linThreshold); + using namespace vanillaPose; + SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); } /* ************************************************************************* */ @@ -76,7 +75,7 @@ TEST( SmartProjectionPoseFactor, Constructor3) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { using namespace vanillaPose; - SmartFactor factor1(rankTol, linThreshold); + SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); factor1.add(measurement1, x1, model); } @@ -227,6 +226,12 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { graph.push_back(PriorFactor(x1, cam1, noisePrior)); graph.push_back(PriorFactor(x2, cam2, noisePrior)); + Values groundTruth; + groundTruth.insert(x1, cam1); + groundTruth.insert(x2, cam2); + groundTruth.insert(x3, cam3); + DOUBLES_EQUAL(0, graph.error(groundTruth), 1e-9); + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise @@ -257,7 +262,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Factors ) { - typedef PinholePose Camera; + using namespace vanillaPose; // Default cameras for simple derivatives Rot3 R; @@ -479,15 +484,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -534,17 +539,17 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, excludeLandmarksFutherThanDist)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, excludeLandmarksFutherThanDist)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, excludeLandmarksFutherThanDist)); smartFactor3->add(measurements_cam3, views, model); @@ -599,22 +604,22 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model); @@ -658,15 +663,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, JACOBIAN_Q)); + new SmartFactor(SmartFactor::JACOBIAN_Q, 1, -1, false, false)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, JACOBIAN_Q)); + new SmartFactor(SmartFactor::JACOBIAN_Q, 1, -1, false, false)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, JACOBIAN_Q)); + new SmartFactor(SmartFactor::JACOBIAN_Q, 1, -1, false, false)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -743,8 +748,11 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { DOUBLES_EQUAL(48406055, graph.error(values), 1); + cout << "SUCCEEDS : ==============================================" << endl; + params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); Values result = optimizer.optimize(); + cout << "=========================================================" << endl; DOUBLES_EQUAL(0, graph.error(result), 1e-9); @@ -777,13 +785,16 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { double rankTol = 10; - SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); + SmartFactor::shared_ptr smartFactor1( + new SmartFactor(SmartFactor::HESSIAN, rankTol)); smartFactor1->add(measurements_cam1, views, model); - SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); + SmartFactor::shared_ptr smartFactor2( + new SmartFactor(SmartFactor::HESSIAN, rankTol)); smartFactor2->add(measurements_cam2, views, model); - SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); + SmartFactor::shared_ptr smartFactor3( + new SmartFactor(SmartFactor::HESSIAN, rankTol)); smartFactor3->add(measurements_cam3, views, model); NonlinearFactorGraph graph; @@ -858,11 +869,13 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -937,15 +950,18 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1142,7 +1158,8 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { - SmartFactorBundler factor(rankTol, linThreshold); + using namespace bundlerPose; + SmartFactor factor(SmartFactor::HESSIAN, rankTol, linThreshold); factor.add(measurement1, x1, model); } @@ -1167,13 +1184,13 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { views.push_back(x2); views.push_back(x3); - SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); smartFactor1->add(measurements_cam1, views, model); - SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); smartFactor2->add(measurements_cam2, views, model); - SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1237,16 +1254,19 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { double rankTol = 10; - SmartFactorBundler::shared_ptr smartFactor1( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); + SmartFactor::shared_ptr smartFactor1( + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor1->add(measurements_cam1, views, model); - SmartFactorBundler::shared_ptr smartFactor2( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); + SmartFactor::shared_ptr smartFactor2( + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor2->add(measurements_cam2, views, model); - SmartFactorBundler::shared_ptr smartFactor3( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); + SmartFactor::shared_ptr smartFactor3( + new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, + manageDegeneracy)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); From c177ca63ec23ad915657a4baf5eff47946aae033 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 14:43:39 -0700 Subject: [PATCH 126/173] Fixed infinite loop --- gtsam/slam/SmartFactorBase.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 1f19d7848..38512b1cb 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -202,7 +202,7 @@ public: areMeasurementsEqual = false; break; } - return e && equals(p, tol) && areMeasurementsEqual; + return e && Base::equals(p, tol) && areMeasurementsEqual; } ///Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives From 37f0c45716f9cf73cec09a86173845c3c4954779 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 14:44:02 -0700 Subject: [PATCH 127/173] Deal w linearizationMode in print and equals --- gtsam/slam/SmartProjectionFactor.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 2101d041e..ca5a7f480 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -135,6 +135,7 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionFactor\n"; + std::cout << "linearizationMode:\n" << linearizeTo_ << std::endl; std::cout << "triangulationParameters:\n" << parameters_ << std::endl; std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); @@ -143,7 +144,7 @@ public: /// equals virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { const This *e = dynamic_cast(&p); - return e && Base::equals(p, tol); + return e && linearizeTo_==e->linearizeTo_ && Base::equals(p, tol); } /// Check if the new linearization point is the same as the one used for previous triangulation From 9991240ae78b2f81f9c8467e4bf6e169b4fccd3f Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 15:24:00 -0700 Subject: [PATCH 128/173] Removed selective linearization mess - it was non-functional anyway, we can aleays re-add it if needed. --- gtsam/slam/SmartProjectionFactor.h | 154 ++---------------- .../tests/testSmartProjectionPoseFactor.cpp | 50 ++---- 2 files changed, 36 insertions(+), 168 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index ca5a7f480..535dab7f6 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -31,21 +31,6 @@ namespace gtsam { -/** - * Structure for storing some state memory, used to speed up optimization - * @addtogroup SLAM - */ -struct SmartProjectionFactorState { - - // Hessian representation (after Schur complement) - bool calculatedHessian; - Matrix H; - Vector gs_vector; - std::vector Gs; - std::vector gs; - double f; -}; - /** * SmartProjectionFactor: triangulates point and keeps an estimate of it around. */ @@ -83,16 +68,6 @@ protected: const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) /// @} - /// @name Caching linearization - /// @{ - /// shorthand for smart projection factor state variable - typedef boost::shared_ptr SmartFactorStatePtr; - SmartFactorStatePtr state_; ///< cached linearization - - const double linearizationThreshold_; ///< threshold to decide whether to re-linearize - mutable std::vector cameraPosesLinearization_; ///< current linearization poses - /// @} - public: /// shorthand for a smart pointer to a factor @@ -110,17 +85,14 @@ public: * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations */ SmartProjectionFactor(LinearizationMode linearizationMode = HESSIAN, - double rankTolerance = 1, double linThreshold = -1, - bool manageDegeneracy = false, bool enableEPI = false, - double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1, SmartFactorStatePtr state = - SmartFactorStatePtr(new SmartProjectionFactorState())) : + double rankTolerance = 1, bool manageDegeneracy = false, bool enableEPI = + false, double landmarkDistanceThreshold = 1e10, + double dynamicOutlierRejectionThreshold = -1) : linearizeTo_(linearizationMode), parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), // result_(TriangulationResult::Degenerate()), // retriangulationThreshold_(1e-5), manageDegeneracy_(manageDegeneracy), // - throwCheirality_(false), verboseCheirality_(false), // - state_(state), linearizationThreshold_(linThreshold) { + throwCheirality_(false), verboseCheirality_(false) { } /** Virtual destructor */ @@ -144,7 +116,7 @@ public: /// equals virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { const This *e = dynamic_cast(&p); - return e && linearizeTo_==e->linearizeTo_ && Base::equals(p, tol); + return e && linearizeTo_ == e->linearizeTo_ && Base::equals(p, tol); } /// Check if the new linearization point is the same as the one used for previous triangulation @@ -183,39 +155,6 @@ public: return retriangulate; // if we arrive to this point all poses are the same and we don't need re-triangulation } - /// This function checks if the new linearization point is 'close' to the previous one used for linearization - bool decideIfLinearize(const Cameras& cameras) const { - // "selective linearization" - // The function evaluates how close are the old and the new poses, transformed in the ref frame of the first pose - // (we only care about the "rigidity" of the poses, not about their absolute pose) - - if (linearizationThreshold_ < 0) //by convention if linearizationThreshold is negative we always relinearize - return true; - - // if we do not have a previous linearization point or the new linearization point includes more poses - if (cameraPosesLinearization_.empty() - || (cameras.size() != cameraPosesLinearization_.size())) - return true; - - Pose3 firstCameraPose, firstCameraPoseOld; - for (size_t i = 0; i < cameras.size(); i++) { - - if (i == 0) { // we store the initial pose, this is useful for selective re-linearization - firstCameraPose = cameras[i].pose(); - firstCameraPoseOld = cameraPosesLinearization_[i]; - continue; - } - - // we compare the poses in the frame of the first pose - Pose3 localCameraPose = firstCameraPose.between(cameras[i].pose()); - Pose3 localCameraPoseOld = firstCameraPoseOld.between( - cameraPosesLinearization_[i]); - if (!localCameraPose.equals(localCameraPoseOld, linearizationThreshold_)) - return true; // at least two "relative" poses are different, hence we re-linearize - } - return false; // if we arrive to this point all poses are the same and we don't need re-linearize - } - /// triangulateSafe TriangulationResult triangulateSafe(const Cameras& cameras) const { @@ -237,7 +176,8 @@ public: /// linearize returns a Hessianfactor that is an approximation of error(p) boost::shared_ptr > createHessianFactor( - const Cameras& cameras, const double lambda = 0.0) const { + const Cameras& cameras, const double lambda = 0.0, bool diagonalDamping = + false) const { size_t numKeys = this->keys_.size(); // Create structures for Hessian Factors @@ -264,77 +204,18 @@ public: Gs, gs, 0.0); } - // decide whether to re-linearize - bool doLinearize = this->decideIfLinearize(cameras); - - if (linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize - for (size_t i = 0; i < cameras.size(); i++) - this->cameraPosesLinearization_[i] = cameras[i].pose(); - - if (!doLinearize) { // return the previous Hessian factor - std::cout << "=============================" << std::endl; - std::cout << "doLinearize " << doLinearize << std::endl; - std::cout << "linearizationThreshold_ " << linearizationThreshold_ - << std::endl; - std::cout << "valid: " << isValid() << std::endl; - std::cout - << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" - << std::endl; - exit(1); - return boost::make_shared >(this->keys_, - this->state_->Gs, this->state_->gs, this->state_->f); - } - - // ================================================================== - Matrix F, E; + std::vector Fblocks; + Matrix E; Vector b; - { - std::vector Fblocks; - computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); - Base::whitenJacobians(Fblocks, E, b); - Base::FillDiagonalF(Fblocks, F); // expensive ! - } - double f = b.squaredNorm(); + computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + Matrix P = Base::PointCov(E, lambda, diagonalDamping); - // Schur complement trick - // Frank says: should be possible to do this more efficiently? - // And we care, as in grouped factors this is called repeatedly - Matrix H(Base::Dim * numKeys, Base::Dim * numKeys); - Vector gs_vector; + // build augmented hessian + SymmetricBlockMatrix augmentedHessian = CameraSet::SchurComplement( + Fblocks, E, P, b); - // Note P can 2*2 or 3*3 - Matrix P = Base::PointCov(E, lambda); - - // Create reduced Hessian matrix via Schur complement F'*F - F'*E*P*E'*F - H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - - // Create reduced gradient - (F'*b - F'*E*P*E'*b) - // Note the minus sign above! g has negative b. - // Informal reasoning: when we write the error as 0.5*|Ax-b|^2 - // the derivative is A'*(Ax-b), and at x=0, this becomes -A'*b - gs_vector.noalias() = -F.transpose() - * (b - (E * (P * (E.transpose() * b)))); - - // Populate Gs and gs - int GsCount2 = 0; - for (DenseIndex i1 = 0; i1 < (DenseIndex) numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * Base::Dim; - gs.at(i1) = gs_vector.segment(i1D); - for (DenseIndex i2 = 0; i2 < (DenseIndex) numKeys; i2++) { - if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * Base::Dim); - GsCount2++; - } - } - } - // ================================================================== - if (linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables - this->state_->Gs = Gs; - this->state_->gs = gs; - this->state_->f = f; - } - return boost::make_shared >(this->keys_, Gs, - gs, f); + return boost::make_shared >(this->keys_, + augmentedHessian); } // create factor @@ -562,7 +443,8 @@ private: ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } -}; +} +; /// traits template diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 1d9ad0dc6..67a885197 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -31,7 +31,6 @@ using namespace boost::assign; static const double rankTol = 1.0; -static const double linThreshold = -1.0; static const bool manageDegeneracy = true; // Create a noise model for the pixel error @@ -62,7 +61,7 @@ TEST( SmartProjectionPoseFactor, Constructor) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor2) { using namespace vanillaPose; - SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); + SmartFactor factor1(SmartFactor::HESSIAN, rankTol); } /* ************************************************************************* */ @@ -75,7 +74,7 @@ TEST( SmartProjectionPoseFactor, Constructor3) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { using namespace vanillaPose; - SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); + SmartFactor factor1(SmartFactor::HESSIAN, rankTol); factor1.add(measurement1, x1, model); } @@ -248,7 +247,6 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); Values result; - params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -458,7 +456,6 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { values.at(x3).pose())); Values result; - params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -513,7 +510,6 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { values.insert(x3, Camera(pose_above * noise_pose, sharedK)); Values result; - params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); @@ -604,22 +600,22 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model); @@ -663,15 +659,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_Q, 1, -1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_Q, 1, false, false)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_Q, 1, -1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_Q, 1, false, false)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_Q, 1, -1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_Q, 1, false, false)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -749,7 +745,6 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { DOUBLES_EQUAL(48406055, graph.error(values), 1); cout << "SUCCEEDS : ==============================================" << endl; - params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); Values result = optimizer.optimize(); cout << "=========================================================" << endl; @@ -869,13 +864,11 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -950,18 +943,15 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1159,7 +1149,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { using namespace bundlerPose; - SmartFactor factor(SmartFactor::HESSIAN, rankTol, linThreshold); + SmartFactor factor(SmartFactor::HESSIAN, rankTol); factor.add(measurement1, x1, model); } @@ -1218,7 +1208,6 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); Values result; - params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -1255,18 +1244,15 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, - manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); From fcc2470e28d675e9eac45d097ad04b39dd4496d6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 16:25:00 -0700 Subject: [PATCH 129/173] Fixed one test which had wrong signs --- gtsam/slam/tests/testSmartProjectionCameraFactor.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 2f6bf9b00..ca346e83e 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -242,9 +242,11 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { // Check whitened errors Vector expected(6); - expected << -256, -29, 26, -29, 206, 202; - SmartFactor::Cameras cameras1 = smartFactor1->cameras(initial); + expected << 256, 29, -26, 29, -206, -202; Point3 point1 = *smartFactor1->point(); + SmartFactor::Cameras cameras1 = smartFactor1->cameras(initial); + Vector reprojectionError = cameras1.reprojectionError(point1, measurements_cam1); + EXPECT(assert_equal(expected, reprojectionError, 1)); Vector actual = smartFactor1->whitenedError(cameras1, point1); EXPECT(assert_equal(expected, actual, 1)); From 28bb4f9673cb47ef3459334522613440fef667ab Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 18:57:56 -0700 Subject: [PATCH 130/173] Used more fixed-size math --- gtsam/geometry/PinholeCamera.h | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 4775e732f..cc903e7db 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -145,7 +145,7 @@ public: const Pose3& getPose(OptionalJacobian<6, dimension> H) const { if (H) { H->setZero(); - H->block(0, 0, 6, 6) = I_6x6; + H->template block<6,6>(0, 0) = I_6x6; } return Base::pose(); } @@ -176,16 +176,15 @@ public: if ((size_t) d.size() == 6) return PinholeCamera(this->pose().retract(d), calibration()); else - return PinholeCamera(this->pose().retract(d.head(6)), + return PinholeCamera(this->pose().retract(d.head<6>()), calibration().retract(d.tail(calibration().dim()))); } /// return canonical coordinate VectorK6 localCoordinates(const PinholeCamera& T2) const { VectorK6 d; - // TODO: why does d.head<6>() not compile?? - d.head(6) = this->pose().localCoordinates(T2.pose()); - d.tail(DimK) = calibration().localCoordinates(T2.calibration()); + d.template head<6>() = this->pose().localCoordinates(T2.pose()); + d.template tail() = calibration().localCoordinates(T2.calibration()); return d; } @@ -265,7 +264,7 @@ public: if (Dother) { Dother->resize(1, 6 + CalibrationB::dimension); Dother->setZero(); - Dother->block(0, 0, 1, 6) = Dother_; + Dother->block<1,6>(0, 0) = Dother_; } return result; } From eedfaabe372734151584fcbf22993916c8829362 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 22:08:12 -0700 Subject: [PATCH 131/173] Added fixed-size versions and a dynamic dispatcher for 2*2 and 3*3 variants. Also moved PointCov here, same idea. --- gtsam/geometry/CameraSet.h | 82 ++++++++++++++++++++++++++++++++------ 1 file changed, 69 insertions(+), 13 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 60af8beef..cd67187df 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -57,7 +57,7 @@ protected: Vector b(ZDim * m); for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { Z e = predicted[i] - measured[i]; - b.segment < ZDim > (row) = e.vector(); + b.segment(row) = e.vector(); } return b; } @@ -141,9 +141,11 @@ public: * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix * G = F' * F - F' * E * P * E' * F * g = F' * (b - E * P * E' * b) + * Fixed size version */ + template // N = 2 or 3 static SymmetricBlockMatrix SchurComplement(const FBlocks& Fs, - const Matrix& E, const Matrix3& P, const Vector& b) { + const Matrix& E, const Eigen::Matrix& P, const Vector& b) { // a single point is observed in m cameras int m = Fs.size(); @@ -159,15 +161,16 @@ public: for (size_t i = 0; i < m; i++) { // for each camera const MatrixZD& Fi = Fs[i]; - const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; + const Eigen::Matrix Ei_P = // + E.block(ZDim * i, 0, ZDim, N) * P; // D = (Dx2) * ZDim - augmentedHessian(i, m) = Fi.transpose() * b.segment < ZDim > (ZDim * i) // F' * b - - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + augmentedHessian(i, m) = Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) augmentedHessian(i, i) = Fi.transpose() - * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi); + * (Fi - Ei_P * E.block(ZDim * i, 0, ZDim, N).transpose() * Fi); // upper triangular part of the hessian for (size_t j = i + 1; j < m; j++) { // for each camera @@ -175,7 +178,7 @@ public: // (DxD) = (Dx2) * ( (2x2) * (2xD) ) augmentedHessian(i, j) = -Fi.transpose() - * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); + * (Ei_P * E.block(ZDim * j, 0, ZDim, N).transpose() * Fj); } } // end of for over cameras @@ -183,12 +186,64 @@ public: return augmentedHessian; } + /// Computes Point Covariance P, with lambda parameter + template // N = 2 or 3 + static void ComputePointCovariance(Eigen::Matrix& P, + const Matrix& E, double lambda, bool diagonalDamping = false) { + + Matrix EtE = E.transpose() * E; + + if (diagonalDamping) { // diagonal of the hessian + EtE.diagonal() += lambda * EtE.diagonal(); + } else { + DenseIndex n = E.cols(); + EtE += lambda * Eigen::MatrixXd::Identity(n, n); + } + + P = (EtE).inverse(); + } + + /// Computes Point Covariance P, with lambda parameter, dynamic version + static Matrix PointCov(const Matrix& E, const double lambda = 0.0, + bool diagonalDamping = false) { + if (E.cols() == 2) { + Matrix2 P2; + ComputePointCovariance(P2, E, lambda, diagonalDamping); + return P2; + } else { + Matrix3 P3; + ComputePointCovariance(P3, E, lambda, diagonalDamping); + return P3; + } + } + + /** + * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix + * Dynamic version + */ + static SymmetricBlockMatrix SchurComplement(const FBlocks& Fblocks, + const Matrix& E, const Vector& b, const double lambda = 0.0, + bool diagonalDamping = false) { + SymmetricBlockMatrix augmentedHessian; + if (E.cols() == 2) { + Matrix2 P; + ComputePointCovariance(P, E, lambda, diagonalDamping); + augmentedHessian = SchurComplement(Fblocks, E, P, b); + } else { + Matrix3 P; + ComputePointCovariance(P, E, lambda, diagonalDamping); + augmentedHessian = SchurComplement(Fblocks, E, P, b); + } + return augmentedHessian; + } + /** * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. */ + template // N = 2 or 3 static void UpdateSchurComplement(const FBlocks& Fs, const Matrix& E, - const Matrix3& P /*Point Covariance*/, const Vector& b, + const Eigen::Matrix& P, const Vector& b, const FastVector& allKeys, const FastVector& keys, /*output ->*/SymmetricBlockMatrix& augmentedHessian) { @@ -215,7 +270,8 @@ public: for (size_t i = 0; i < m; i++) { // for each camera in the current factor const MatrixZD& Fi = Fs[i]; - const Matrix23 Ei_P = E.block(ZDim * i, 0) * P; + const Eigen::Matrix Ei_P = E.template block( + ZDim * i, 0) * P; // D = (DxZDim) * (ZDim) // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) @@ -227,8 +283,8 @@ public: // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); // add contribution of current factor augmentedHessian(aug_i, M) = augmentedHessian(aug_i, M).knownOffDiagonal() - + Fi.transpose() * b.segment < ZDim > (ZDim * i) // F' * b - - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) + + Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1) // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) // main block diagonal - store previous block @@ -236,7 +292,7 @@ public: // add contribution of current factor augmentedHessian(aug_i, aug_i) = matrixBlock + (Fi.transpose() - * (Fi - Ei_P * E.block(ZDim * i, 0).transpose() * Fi)); + * (Fi - Ei_P * E.template block(ZDim * i, 0).transpose() * Fi)); // upper triangular part of the hessian for (size_t j = i + 1; j < m; j++) { // for each camera @@ -251,7 +307,7 @@ public: augmentedHessian(aug_i, aug_j) = augmentedHessian(aug_i, aug_j).knownOffDiagonal() - Fi.transpose() - * (Ei_P * E.block(ZDim * j, 0).transpose() * Fj); + * (Ei_P * E.template block(ZDim * j, 0).transpose() * Fj); } } // end of for over cameras From dd7d9cd6fc3d4899f83fc455e9ab222f6b1679bf Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 22:08:39 -0700 Subject: [PATCH 132/173] Got rid of hardcoded Matrix3, now call dispatched Schur complement --- gtsam/slam/RegularImplicitSchurFactor.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index e773efc5d..da1f5b785 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -38,7 +38,7 @@ protected: typedef Eigen::Matrix MatrixDD; ///< camera hessian const std::vector FBlocks_; ///< All ZDim*D F blocks (one for each camera) - const Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (ZDim*ZDim if degenerate) + const Matrix PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (2*2 if degenerate) const Matrix E_; ///< The 2m*3 E Jacobian with respect to the point const Vector b_; ///< 2m-dimensional RHS vector @@ -50,7 +50,7 @@ public: /// Construct from blocks of F, E, inv(E'*E), and RHS vector b RegularImplicitSchurFactor(const FastVector& keys, - const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const std::vector& FBlocks, const Matrix& E, const Matrix& P, const Vector& b) : GaussianFactor(keys), FBlocks_(FBlocks), PointCovariance_(P), E_(E), b_(b) { } @@ -71,7 +71,7 @@ public: return b_; } - const Matrix3& getPointCovariance() const { + const Matrix& getPointCovariance() const { return PointCovariance_; } @@ -124,8 +124,8 @@ public: virtual Matrix augmentedInformation() const { // Do the Schur complement - SymmetricBlockMatrix augmentedHessian = Set::SchurComplement(FBlocks_, E_, - PointCovariance_, b_); + SymmetricBlockMatrix augmentedHessian = // + Set::SchurComplement(FBlocks_, E_, b_); return augmentedHessian.matrix(); } @@ -436,7 +436,7 @@ public: VectorValues g; for (size_t k = 0; k < size(); ++k) { Key key = keys_[k]; - g.insert(key, - FBlocks_[k].transpose() * e2[k]); + g.insert(key, -FBlocks_[k].transpose() * e2[k]); } // return it From 421ad49048b64b360bb992d7873298cdeeba0e13 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 22:08:55 -0700 Subject: [PATCH 133/173] Moved PointCov to CameraSet --- gtsam/slam/SmartFactorBase.h | 28 +++++----------------------- 1 file changed, 5 insertions(+), 23 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 38512b1cb..e651244af 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -243,22 +243,6 @@ public: return (E.transpose() * E).inverse(); } - /// Computes Point Covariance P, with lambda parameter - static Matrix PointCov(Matrix& E, double lambda, - bool diagonalDamping = false) { - - Matrix EtE = E.transpose() * E; - - if (diagonalDamping) { // diagonal of the hessian - EtE.diagonal() += lambda * EtE.diagonal(); - } else { - DenseIndex n = E.cols(); - EtE += lambda * Eigen::MatrixXd::Identity(n, n); - } - - return (EtE).inverse(); - } - /** * Compute F, E, and b (called below in both vanilla and SVD versions), where * F is a vector of derivatives wrpt the cameras, and E the stacked derivatives @@ -301,11 +285,10 @@ public: Matrix E; Vector b; computeJacobians(Fblocks, E, b, cameras, point); - Matrix P = PointCov(E, lambda, diagonalDamping); // build augmented hessian - SymmetricBlockMatrix augmentedHessian = CameraSet::SchurComplement( - Fblocks, E, P, b); + SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fblocks, E, + b); return boost::make_shared >(keys_, augmentedHessian); @@ -324,8 +307,7 @@ public: Vector b; std::vector Fblocks; computeJacobians(Fblocks, E, b, cameras, point); - Matrix P = PointCov(E, lambda, diagonalDamping); - CameraSet::UpdateSchurComplement(Fblocks, E, P, b, allKeys, keys_, + Cameras::UpdateSchurComplement(Fblocks, E, b, allKeys, keys_, augmentedHessian); } @@ -346,7 +328,7 @@ public: std::vector F; computeJacobians(F, E, b, cameras, point); whitenJacobians(F, E, b); - Matrix P = PointCov(E, lambda, diagonalDamping); + Matrix P = Cameras::PointCov(E, lambda, diagonalDamping); return boost::make_shared >(keys_, F, E, P, b); } @@ -362,7 +344,7 @@ public: std::vector F; computeJacobians(F, E, b, cameras, point); const size_t M = b.size(); - Matrix P = PointCov(E, lambda, diagonalDamping); + Matrix P = Cameras::PointCov(E, lambda, diagonalDamping); SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); return boost::make_shared >(keys_, F, E, P, b, n); } From d924c11d413f6f18f9215d1bab2fe4a6e1893d7a Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 22:10:08 -0700 Subject: [PATCH 134/173] Call dispatched SchurComplement, now in CameraSet --- gtsam/slam/SmartProjectionFactor.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 535dab7f6..138a29f0a 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -208,11 +208,10 @@ public: Matrix E; Vector b; computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); - Matrix P = Base::PointCov(E, lambda, diagonalDamping); // build augmented hessian - SymmetricBlockMatrix augmentedHessian = CameraSet::SchurComplement( - Fblocks, E, P, b); + SymmetricBlockMatrix augmentedHessian = // + Cameras::SchurComplement(Fblocks, E, b, lambda, diagonalDamping); return boost::make_shared >(this->keys_, augmentedHessian); From 2d1126019a342e690568a93171ac9bbb32450c57 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 10 Mar 2015 22:32:30 -0700 Subject: [PATCH 135/173] Cleaned u uninitialized shared ptrs --- gtsam/slam/SmartProjectionFactor.h | 2 +- gtsam/slam/tests/testSmartProjectionCameraFactor.cpp | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 138a29f0a..bf6d20c45 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -171,7 +171,7 @@ public: /// triangulate bool triangulateForLinearize(const Cameras& cameras) const { triangulateSafe(cameras); // imperative, might reset result_ - return (manageDegeneracy_ || result_); + return (result_); } /// linearize returns a Hessianfactor that is an approximation of error(p) diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index ca346e83e..b5ddc4e25 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -822,6 +822,7 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { implicitFactor->add(level_uv_right, c2, unit2); GaussianFactor::shared_ptr gaussianImplicitSchurFactor = implicitFactor->linearize(values); + CHECK(gaussianImplicitSchurFactor); typedef RegularImplicitSchurFactor Implicit9; Implicit9& implicitSchurFactor = dynamic_cast(*gaussianImplicitSchurFactor); From 766a9622e89a24bf83c1996a60ea839e0e6d6c70 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 11 Mar 2015 06:33:16 -0700 Subject: [PATCH 136/173] Fixed Hessian by whitening... --- gtsam/slam/SmartProjectionFactor.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index bf6d20c45..067d30329 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -204,11 +204,15 @@ public: Gs, gs, 0.0); } + // Jacobian could be 3D Point3 OR 2D Unit3, difference is E.cols(). std::vector Fblocks; Matrix E; Vector b; computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + // Whiten using noise model + Base::whitenJacobians(Fblocks, E, b); + // build augmented hessian SymmetricBlockMatrix augmentedHessian = // Cameras::SchurComplement(Fblocks, E, b, lambda, diagonalDamping); From 62868b9071e9b14560b849d21d047a46afc76492 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 11 Mar 2015 06:50:15 -0700 Subject: [PATCH 137/173] Added linear error checks --- .../tests/testSmartProjectionPoseFactor.cpp | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 67a885197..526e9bfdb 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -297,6 +297,18 @@ TEST( SmartProjectionPoseFactor, Factors ) { CHECK(p); EXPECT(assert_equal(landmark1, *p)); + VectorValues zeroDelta; + Vector6 delta; + delta.setZero(); + zeroDelta.insert(x1, delta); + zeroDelta.insert(x2, delta); + + VectorValues perturbedDelta; + delta.setOnes(); + perturbedDelta.insert(x1, delta); + perturbedDelta.insert(x2, delta); + double expectedError = 2500; + // After eliminating the point, A1 and A2 contain 2-rank information on cameras: Matrix16 A1, A2; A1 << -10, 0, 0, 0, 1, 0; @@ -324,6 +336,8 @@ TEST( SmartProjectionPoseFactor, Factors ) { smartFactor1->createHessianFactor(cameras, 0.0); EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); EXPECT(assert_equal(expected, *actual, 1e-8)); + EXPECT_DOUBLES_EQUAL(0, actual->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actual->error(perturbedDelta), 1e-8); } { @@ -368,6 +382,8 @@ TEST( SmartProjectionPoseFactor, Factors ) { CHECK(actualQ); EXPECT(assert_equal(expectedInformation, actualQ->information(), 1e-8)); EXPECT(assert_equal(expectedQ, *actualQ)); + EXPECT_DOUBLES_EQUAL(0, actualQ->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actualQ->error(perturbedDelta), 1e-8); // Whiten for RegularImplicitSchurFactor (does not have noise model) model->WhitenSystem(E, b); @@ -384,6 +400,8 @@ TEST( SmartProjectionPoseFactor, Factors ) { EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); EXPECT(assert_equal(expected, *actual)); + EXPECT_DOUBLES_EQUAL(0, actual->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actual->error(perturbedDelta), 1e-8); } { @@ -400,6 +418,8 @@ TEST( SmartProjectionPoseFactor, Factors ) { CHECK(actual); EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); EXPECT(assert_equal(expected, *actual)); + EXPECT_DOUBLES_EQUAL(0, actual->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actual->error(perturbedDelta), 1e-8); } } From 3558da9c4cf55540db4a131527b2b93f6e568954 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 11 Mar 2015 07:04:02 -0700 Subject: [PATCH 138/173] Fixed SVD factor --- gtsam/slam/tests/testSmartProjectionPoseFactor.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 526e9bfdb..c77616793 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -501,15 +501,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -530,6 +530,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { values.insert(x3, Camera(pose_above * noise_pose, sharedK)); Values result; + params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); From f06c84b503481d2c8d497a1375d92ff5629b98b5 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 11 Mar 2015 16:51:24 -0700 Subject: [PATCH 139/173] Fixed sign in SVD --- gtsam/slam/JacobianFactorSVD.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index aac946901..86636c38f 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -65,7 +65,7 @@ public: KeyMatrix(key, (Enull.transpose()).block(0, ZDim * k, m2, ZDim) * Fblocks[k])); } - JacobianFactor::fillTerms(QF, -Enull.transpose() * b, model); + JacobianFactor::fillTerms(QF, Enull.transpose() * b, model); } }; From 2bdeac30f070900ad1914c5cfb843b1aa6a57af9 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 12 Mar 2015 07:56:47 -0700 Subject: [PATCH 140/173] Fixed compile error w PointCov --- gtsam_unstable/slam/SmartStereoProjectionFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 5e0898bfa..ce4d68b9a 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -424,7 +424,7 @@ public: Matrix H(D * numKeys, D * numKeys); Vector gs_vector; - Matrix3 P = Base::PointCov(E, lambda); + Matrix3 P = Cameras::PointCov(E, lambda); H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); gs_vector.noalias() = - F.transpose() * (b - (E * (P * (E.transpose() * b)))); From 695d080e4dd5f12701423855bacd68a8de34588b Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 12 Mar 2015 07:56:59 -0700 Subject: [PATCH 141/173] DegeneracyMode --- gtsam/slam/SmartProjectionFactor.h | 33 +++++---- .../tests/testSmartProjectionCameraFactor.cpp | 42 +++++------ .../tests/testSmartProjectionPoseFactor.cpp | 69 +++++++++++-------- 3 files changed, 84 insertions(+), 60 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 067d30329..7c137ad5c 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -44,13 +44,19 @@ public: HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD }; + /// How to manage degeneracy + enum DegeneracyMode { + IGNORE_DEGENERACY, ZERO_ON_DEGENERACY, HANDLE_INFINITY + }; + private: typedef SmartFactorBase Base; typedef SmartProjectionFactor This; protected: - LinearizationMode linearizeTo_; ///< How to linearize the factor + LinearizationMode linearizationMode_; ///< How to linearize the factor + DegeneracyMode degeneracyMode_; ///< How to linearize the factor /// @name Caching triangulation /// @{ @@ -63,7 +69,6 @@ protected: /// @name Parameters governing how triangulation result is treated /// @{ - const bool manageDegeneracy_; ///< if set to true will use the rotation-only version for degenerate cases const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) /// @} @@ -85,13 +90,16 @@ public: * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations */ SmartProjectionFactor(LinearizationMode linearizationMode = HESSIAN, - double rankTolerance = 1, bool manageDegeneracy = false, bool enableEPI = - false, double landmarkDistanceThreshold = 1e10, + double rankTolerance = 1, DegeneracyMode degeneracyMode = + IGNORE_DEGENERACY, bool enableEPI = false, + double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : - linearizeTo_(linearizationMode), parameters_(rankTolerance, enableEPI, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), // + linearizationMode_(linearizationMode), // + degeneracyMode_(degeneracyMode), // + parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, + dynamicOutlierRejectionThreshold), // result_(TriangulationResult::Degenerate()), // - retriangulationThreshold_(1e-5), manageDegeneracy_(manageDegeneracy), // + retriangulationThreshold_(1e-5), // throwCheirality_(false), verboseCheirality_(false) { } @@ -107,7 +115,7 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionFactor\n"; - std::cout << "linearizationMode:\n" << linearizeTo_ << std::endl; + std::cout << "linearizationMode:\n" << linearizationMode_ << std::endl; std::cout << "triangulationParameters:\n" << parameters_ << std::endl; std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); @@ -116,7 +124,8 @@ public: /// equals virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { const This *e = dynamic_cast(&p); - return e && linearizeTo_ == e->linearizeTo_ && Base::equals(p, tol); + return e && linearizationMode_ == e->linearizationMode_ + && Base::equals(p, tol); } /// Check if the new linearization point is the same as the one used for previous triangulation @@ -194,7 +203,7 @@ public: triangulateSafe(cameras); - if (!manageDegeneracy_ && !result_) { + if (degeneracyMode_ == ZERO_ON_DEGENERACY && !result_) { // put in "empty" Hessian BOOST_FOREACH(Matrix& m, Gs) m = zeros(Base::Dim, Base::Dim); @@ -281,7 +290,7 @@ public: const double lambda = 0.0) const { // depending on flag set on construction we may linearize to different linear factors Cameras cameras = this->cameras(values); - switch (linearizeTo_) { + switch (linearizationMode_) { case HESSIAN: return createHessianFactor(cameras, lambda); case IMPLICIT_SCHUR: @@ -381,7 +390,7 @@ public: if (result_) // All good, just use version in base class return Base::totalReprojectionError(cameras, *result_); - else if (manageDegeneracy_) { + else if (degeneracyMode_ == HANDLE_INFINITY) { // Otherwise, manage the exceptions with rotation-only factors const Point2& z0 = this->measured_.at(0); Unit3 backprojected = cameras.front().backprojectPointAtInfinity(z0); diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index b5ddc4e25..508182557 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -31,7 +31,6 @@ using namespace boost::assign; static bool isDebugTest = false; static double rankTol = 1.0; -static double linThreshold = -1.0; // Convenience for named keys using symbol_shorthand::X; @@ -79,7 +78,7 @@ TEST( SmartProjectionCameraFactor, Constructor) { /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor2) { using namespace vanilla; - SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); + SmartFactor factor1(SmartFactor::HESSIAN, rankTol); } /* ************************************************************************* */ @@ -92,7 +91,7 @@ TEST( SmartProjectionCameraFactor, Constructor3) { /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor4) { using namespace vanilla; - SmartFactor factor1(SmartFactor::HESSIAN, rankTol, linThreshold); + SmartFactor factor1(SmartFactor::HESSIAN, rankTol); factor1.add(measurement1, x1, unit2); } @@ -108,7 +107,6 @@ TEST( SmartProjectionCameraFactor, Equals ) { /* *************************************************************************/ TEST( SmartProjectionCameraFactor, noiseless ) { - // cout << " ************************ SmartProjectionCameraFactor: noisy ****************************" << endl; using namespace vanilla; Values values; @@ -153,7 +151,8 @@ TEST( SmartProjectionCameraFactor, noisy ) { // Check triangulated point CHECK(factor1->point()); - EXPECT(assert_equal(Point3(13.7587, 1.43851, -1.14274),*factor1->point(), 1e-4)); + EXPECT( + assert_equal(Point3(13.7587, 1.43851, -1.14274), *factor1->point(), 1e-4)); // Check whitened errors Vector expected(4); @@ -236,16 +235,23 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { CHECK(smartFactor2->point()); CHECK(smartFactor3->point()); - EXPECT(assert_equal(Point3(2.57696, -0.182566, 1.04085),*smartFactor1->point(), 1e-4)); - EXPECT(assert_equal(Point3(2.80114, -0.702153, 1.06594),*smartFactor2->point(), 1e-4)); - EXPECT(assert_equal(Point3(1.82593, -0.289569, 2.13438),*smartFactor3->point(), 1e-4)); + EXPECT( + assert_equal(Point3(2.57696, -0.182566, 1.04085), *smartFactor1->point(), + 1e-4)); + EXPECT( + assert_equal(Point3(2.80114, -0.702153, 1.06594), *smartFactor2->point(), + 1e-4)); + EXPECT( + assert_equal(Point3(1.82593, -0.289569, 2.13438), *smartFactor3->point(), + 1e-4)); // Check whitened errors Vector expected(6); expected << 256, 29, -26, 29, -206, -202; Point3 point1 = *smartFactor1->point(); SmartFactor::Cameras cameras1 = smartFactor1->cameras(initial); - Vector reprojectionError = cameras1.reprojectionError(point1, measurements_cam1); + Vector reprojectionError = cameras1.reprojectionError(point1, + measurements_cam1); EXPECT(assert_equal(expected, reprojectionError, 1)); Vector actual = smartFactor1->whitenedError(cameras1, point1); EXPECT(assert_equal(expected, actual, 1)); @@ -259,9 +265,9 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { LevenbergMarquardtOptimizer optimizer(graph, initial, params); Values result = optimizer.optimize(); - EXPECT(assert_equal(landmark1,*smartFactor1->point(), 1e-7)); - EXPECT(assert_equal(landmark2,*smartFactor2->point(), 1e-7)); - EXPECT(assert_equal(landmark3,*smartFactor3->point(), 1e-7)); + EXPECT(assert_equal(landmark1, *smartFactor1->point(), 1e-7)); + EXPECT(assert_equal(landmark2, *smartFactor2->point(), 1e-7)); + EXPECT(assert_equal(landmark3, *smartFactor3->point(), 1e-7)); // GaussianFactorGraph::shared_ptr GFG = graph.linearize(initial); // VectorValues delta = GFG->optimize(); @@ -796,15 +802,12 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { values.insert(c1, level_camera); values.insert(c2, level_camera_right); double rankTol = 1; - double linThreshold = -1; - bool manageDegeneracy = false; bool useEPI = false; - bool isImplicit = false; // Hessian version SmartFactor::shared_ptr explicitFactor( - new SmartFactor(SmartFactor::HESSIAN, rankTol, linThreshold, manageDegeneracy, useEPI, - isImplicit)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::IGNORE_DEGENERACY, useEPI)); explicitFactor->add(level_uv, c1, unit2); explicitFactor->add(level_uv_right, c2, unit2); @@ -814,10 +817,9 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { dynamic_cast(*gaussianHessianFactor); // Implicit Schur version - isImplicit = true; SmartFactor::shared_ptr implicitFactor( - new SmartFactor(SmartFactor::IMPLICIT_SCHUR, rankTol, linThreshold, manageDegeneracy, useEPI, - isImplicit)); + new SmartFactor(SmartFactor::IMPLICIT_SCHUR, rankTol, + SmartFactor::IGNORE_DEGENERACY, useEPI)); implicitFactor->add(level_uv, c1, unit2); implicitFactor->add(level_uv_right, c2, unit2); GaussianFactor::shared_ptr gaussianImplicitSchurFactor = diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index c77616793..6fb1652b0 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -31,8 +31,6 @@ using namespace boost::assign; static const double rankTol = 1.0; -static const bool manageDegeneracy = true; - // Create a noise model for the pixel error static const double sigma = 0.1; static SharedIsotropic model(noiseModel::Isotropic::Sigma(2, sigma)); @@ -501,15 +499,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_SVD)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_SVD)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_SVD)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -530,7 +528,6 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { values.insert(x3, Camera(pose_above * noise_pose, sharedK)); Values result; - params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); @@ -556,17 +553,20 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, + SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, + SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, -1, false, false, + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, + SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist)); smartFactor3->add(measurements_cam3, views, model); @@ -621,23 +621,27 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, + SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, + dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, + SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, + dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, + SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, + dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, false, false, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, + SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, + dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -680,15 +684,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_Q, 1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_Q)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_Q, 1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_Q)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_Q, 1, false, false)); + new SmartFactor(SmartFactor::JACOBIAN_Q)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -885,11 +889,13 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -923,6 +929,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac values.at(x3).pose())); Values result; + params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); @@ -964,15 +971,18 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1265,15 +1275,18 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::HESSIAN, rankTol, manageDegeneracy)); + new SmartFactor(SmartFactor::HESSIAN, rankTol, + SmartFactor::ZERO_ON_DEGENERACY)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); From 956b53dc3b026be57a9a78bd2a0bf13f2c8347ec Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 12 Mar 2015 09:51:44 -0700 Subject: [PATCH 142/173] Fixed sign in stereo version --- gtsam_unstable/slam/SmartStereoProjectionFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index ce4d68b9a..197ee82d2 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -426,7 +426,7 @@ public: Matrix3 P = Cameras::PointCov(E, lambda); H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - gs_vector.noalias() = - F.transpose() * (b - (E * (P * (E.transpose() * b)))); + gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); if (isDebug) std::cout << "gs_vector size " << gs_vector.size() << std::endl; From 3675754816786f950a66e86d6cbce3a602b76169 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 12 Mar 2015 10:00:29 -0700 Subject: [PATCH 143/173] Fixed two more tests: down to two ! --- .../tests/testSmartProjectionPoseFactor.cpp | 21 ++++--------------- 1 file changed, 4 insertions(+), 17 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 6fb1652b0..1e21a3afd 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -90,7 +90,6 @@ TEST( SmartProjectionPoseFactor, Equals ) { /* *************************************************************************/ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { - // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; using namespace vanillaPose; @@ -149,7 +148,6 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, noisy ) { - // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; using namespace vanillaPose; @@ -190,7 +188,6 @@ TEST( SmartProjectionPoseFactor, noisy ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; using namespace vanillaPose2; vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -423,7 +420,6 @@ TEST( SmartProjectionPoseFactor, Factors ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; using namespace vanillaPose; @@ -719,7 +715,6 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { - // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; using namespace vanillaPose2; @@ -769,10 +764,8 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { DOUBLES_EQUAL(48406055, graph.error(values), 1); - cout << "SUCCEEDS : ==============================================" << endl; LevenbergMarquardtOptimizer optimizer(graph, values, params); Values result = optimizer.optimize(); - cout << "=========================================================" << endl; DOUBLES_EQUAL(0, graph.error(result), 1e-9); @@ -866,8 +859,6 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; - using namespace vanillaPose2; vector views; @@ -890,12 +881,12 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + SmartFactor::HANDLE_INFINITY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + SmartFactor::HANDLE_INFINITY)); smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -945,7 +936,6 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks: Rotation Only**********************" << endl; using namespace vanillaPose; @@ -1033,7 +1023,6 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Hessian ) { - // cout << " ************************ SmartProjectionPoseFactor: Hessian **********************" << endl; using namespace vanillaPose2; @@ -1122,7 +1111,6 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { - // cout << " ************************ SmartProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; using namespace vanillaPose2; @@ -1159,7 +1147,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { smartFactor->linearize(rotValues); // Hessian is invariant to rotations in the nondegenerate case - EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-8)); + EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-7)); Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); @@ -1174,7 +1162,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { // Hessian is invariant to rotations and translations in the nondegenerate case EXPECT( - assert_equal(factor->information(), factorRotTran->information(), 1e-8)); + assert_equal(factor->information(), factorRotTran->information(), 1e-7)); } /* ************************************************************************* */ @@ -1186,7 +1174,6 @@ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { - // cout << " ************************ SmartProjectionPoseFactor: Cal3Bundler **********************" << endl; using namespace bundlerPose; From a920caf2ec98230000371e9b02e8ae20c19dff7b Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 14 Mar 2015 20:26:50 -0400 Subject: [PATCH 144/173] More deliberate testing of optimize on/off --- gtsam/geometry/tests/testTriangulation.cpp | 37 +++++++++++++++------- 1 file changed, 26 insertions(+), 11 deletions(-) diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index 3045668d5..d8f094f8e 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -50,6 +50,7 @@ Point2 z1 = camera1.project(landmark); Point2 z2 = camera2.project(landmark); //****************************************************************************** +// Simple test with a well-behaved two camera situation TEST( triangulation, twoPoses) { vector poses; @@ -58,24 +59,36 @@ TEST( triangulation, twoPoses) { poses += pose1, pose2; measurements += z1, z2; - bool optimize = true; double rank_tol = 1e-9; - boost::optional triangulated_landmark = triangulatePoint3(poses, - sharedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + // 1. Test simple DLT, perfect in no noise situation + bool optimize = false; + boost::optional actual1 = triangulatePoint3(poses, sharedCal, + measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual1, 1e-7)); - // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) + // 2. test with optimization on, same answer + optimize = true; + boost::optional actual2 = triangulatePoint3(poses, sharedCal, + measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual2, 1e-7)); + + // 3. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); + optimize = false; + boost::optional actual3 = triangulatePoint3(poses, sharedCal, + measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-4)); - boost::optional triangulated_landmark_noise = triangulatePoint3(poses, - sharedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + // 3. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) + optimize = true; + boost::optional actual4 = triangulatePoint3(poses, sharedCal, + measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-4)); } //****************************************************************************** - TEST( triangulation, twoPosesBundler) { boost::shared_ptr bundlerCal = // @@ -151,7 +164,8 @@ TEST( triangulation, fourPoses) { SimpleCamera camera4(pose4, *sharedCal); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - CHECK_EXCEPTION(camera4.project(landmark);, CheiralityException); + CHECK_EXCEPTION(camera4.project(landmark) + ;, CheiralityException); poses += pose4; measurements += Point2(400, 400); @@ -217,7 +231,8 @@ TEST( triangulation, fourPoses_distinct_Ks) { SimpleCamera camera4(pose4, K4); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - CHECK_EXCEPTION(camera4.project(landmark);, CheiralityException); + CHECK_EXCEPTION(camera4.project(landmark) + ;, CheiralityException); cameras += camera4; measurements += Point2(400, 400); From a3b6a47b2e77347757a845c324e51c9278767986 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 15 Mar 2015 07:09:55 -0400 Subject: [PATCH 145/173] Revived sole camera test --- gtsam/geometry/tests/testTriangulation.cpp | 78 ++++++++++------------ 1 file changed, 37 insertions(+), 41 deletions(-) diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index d8f094f8e..bc007314e 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -63,32 +63,33 @@ TEST( triangulation, twoPoses) { // 1. Test simple DLT, perfect in no noise situation bool optimize = false; - boost::optional actual1 = triangulatePoint3(poses, sharedCal, - measurements, rank_tol, optimize); + boost::optional actual1 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); EXPECT(assert_equal(landmark, *actual1, 1e-7)); // 2. test with optimization on, same answer optimize = true; - boost::optional actual2 = triangulatePoint3(poses, sharedCal, - measurements, rank_tol, optimize); + boost::optional actual2 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); EXPECT(assert_equal(landmark, *actual2, 1e-7)); // 3. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); optimize = false; - boost::optional actual3 = triangulatePoint3(poses, sharedCal, - measurements, rank_tol, optimize); + boost::optional actual3 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-4)); - // 3. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) + // 4. Now with optimization on optimize = true; - boost::optional actual4 = triangulatePoint3(poses, sharedCal, - measurements, rank_tol, optimize); + boost::optional actual4 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-4)); } //****************************************************************************** +// Similar, but now with Bundler calibration TEST( triangulation, twoPosesBundler) { boost::shared_ptr bundlerCal = // @@ -109,17 +110,17 @@ TEST( triangulation, twoPosesBundler) { bool optimize = true; double rank_tol = 1e-9; - boost::optional triangulated_landmark = triangulatePoint3(poses, - bundlerCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + boost::optional actual = // + triangulatePoint3(poses, bundlerCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual, 1e-7)); - // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) + // Add some noise and try again measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); - boost::optional triangulated_landmark_noise = triangulatePoint3(poses, - bundlerCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + boost::optional actual2 = // + triangulatePoint3(poses, bundlerCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19847), *actual2, 1e-4)); } //****************************************************************************** @@ -130,17 +131,17 @@ TEST( triangulation, fourPoses) { poses += pose1, pose2; measurements += z1, z2; - boost::optional triangulated_landmark = triangulatePoint3(poses, - sharedCal, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + boost::optional actual = triangulatePoint3(poses, sharedCal, + measurements); + EXPECT(assert_equal(landmark, *actual, 1e-2)); // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); - boost::optional triangulated_landmark_noise = // + boost::optional actual2 = // triangulatePoint3(poses, sharedCal, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + EXPECT(assert_equal(landmark, *actual2, 1e-2)); // 3. Add a slightly rotated third camera above, again with measurement noise Pose3 pose3 = pose1 * Pose3(Rot3::ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); @@ -164,8 +165,7 @@ TEST( triangulation, fourPoses) { SimpleCamera camera4(pose4, *sharedCal); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - CHECK_EXCEPTION(camera4.project(landmark) - ;, CheiralityException); + CHECK_EXCEPTION(camera4.project(landmark), CheiralityException); poses += pose4; measurements += Point2(400, 400); @@ -195,17 +195,17 @@ TEST( triangulation, fourPoses_distinct_Ks) { cameras += camera1, camera2; measurements += z1, z2; - boost::optional triangulated_landmark = // + boost::optional actual = // triangulatePoint3(cameras, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + EXPECT(assert_equal(landmark, *actual, 1e-2)); // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); - boost::optional triangulated_landmark_noise = // + boost::optional actual2 = // triangulatePoint3(cameras, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + EXPECT(assert_equal(landmark, *actual2, 1e-2)); // 3. Add a slightly rotated third camera above, again with measurement noise Pose3 pose3 = pose1 * Pose3(Rot3::ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); @@ -260,23 +260,19 @@ TEST( triangulation, twoIdenticalPoses) { } //****************************************************************************** -/* - TEST( triangulation, onePose) { - // we expect this test to fail with a TriangulationUnderconstrainedException - // because there's only one camera observation +TEST( triangulation, onePose) { + // we expect this test to fail with a TriangulationUnderconstrainedException + // because there's only one camera observation - Cal3_S2 *sharedCal(1500, 1200, 0, 640, 480); + vector poses; + vector measurements; - vector poses; - vector measurements; + poses += Pose3(); + measurements += Point2(); - poses += Pose3(); - measurements += Point2(); - - CHECK_EXCEPTION(triangulatePoint3(poses, measurements, *sharedCal), - TriangulationUnderconstrainedException); - } - */ + CHECK_EXCEPTION(triangulatePoint3(poses, sharedCal, measurements), + TriangulationUnderconstrainedException); +} //****************************************************************************** int main() { From 32c6453ee68353d2e292fd54bcaa98af9148bb0f Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 15 Mar 2015 07:42:01 -0400 Subject: [PATCH 146/173] Some refactoring and saving of computation under certain parameter combinations --- gtsam/geometry/tests/testTriangulation.cpp | 3 +- gtsam/geometry/triangulation.cpp | 1 - gtsam/geometry/triangulation.h | 56 ++++++++++++---------- 3 files changed, 33 insertions(+), 27 deletions(-) diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index bc007314e..352493683 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -231,8 +231,7 @@ TEST( triangulation, fourPoses_distinct_Ks) { SimpleCamera camera4(pose4, K4); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - CHECK_EXCEPTION(camera4.project(landmark) - ;, CheiralityException); + CHECK_EXCEPTION(camera4.project(landmark), CheiralityException); cameras += camera4; measurements += Point2(400, 400); diff --git a/gtsam/geometry/triangulation.cpp b/gtsam/geometry/triangulation.cpp index 474689525..f473b4010 100644 --- a/gtsam/geometry/triangulation.cpp +++ b/gtsam/geometry/triangulation.cpp @@ -52,7 +52,6 @@ Point3 triangulateDLT(const std::vector& projection_matrices, double error; Vector v; boost::tie(rank, error, v) = DLT(A, rank_tol); - // std::cout << "s " << s.transpose() << std:endl; if (rank < 3) throw(TriangulationUnderconstrainedException()); diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index a67f26bf2..e7b2a53f3 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -208,20 +208,20 @@ Point3 triangulatePoint3(const std::vector& poses, projection_matrices.push_back( sharedCal->K() * (pose.inverse().matrix()).block<3, 4>(0, 0)); } - // Triangulate linearly + // Do DLT: throws TriangulationUnderconstrainedException if rank<3 Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); - // The n refine using non-linear optimization + // Then refine using non-linear optimization if (optimize) point = triangulateNonlinear // (poses, sharedCal, measurements, point); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - // verify that the triangulated point lies infront of all cameras + // verify that the triangulated point lies in front of all cameras BOOST_FOREACH(const Pose3& pose, poses) { const Point3& p_local = pose.transform_to(point); if (p_local.z() <= 0) - throw(TriangulationCheiralityException()); + throw(TriangulationCheiralityException()); } #endif @@ -258,6 +258,7 @@ Point3 triangulatePoint3(const std::vector& cameras, projection_matrices.push_back( camera.calibration().K() * (P_.block<3, 4>(0, 0))); } + // Do DLT: throws TriangulationUnderconstrainedException if rank<3 Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); // The n refine using non-linear optimization @@ -265,11 +266,11 @@ Point3 triangulatePoint3(const std::vector& cameras, point = triangulateNonlinear(cameras, measurements, point); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - // verify that the triangulated point lies infront of all cameras + // verify that the triangulated point lies in front of all cameras BOOST_FOREACH(const CAMERA& camera, cameras) { const Point3& p_local = camera.pose().transform_to(point); if (p_local.z() <= 0) - throw(TriangulationCheiralityException()); + throw(TriangulationCheiralityException()); } #endif @@ -307,14 +308,17 @@ struct TriangulationParameters { /** * Constructor * @param rankTol tolerance used to check if point triangulation is degenerate - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations + * @param enableEPI if true refine triangulation with embedded LM iterations + * @param landmarkDistanceThreshold flag as degenerate if point further than this + * @param dynamicOutlierRejectionThreshold or if average error larger than this + * */ TriangulationParameters(const double _rankTolerance = 1.0, - const bool _enableEPI = false, double _landmarkDistanceThreshold = 1e10, + const bool _enableEPI = false, double _landmarkDistanceThreshold = -1, double _dynamicOutlierRejectionThreshold = -1) : - rankTolerance(_rankTolerance), enableEPI(_enableEPI), landmarkDistanceThreshold( - _landmarkDistanceThreshold), dynamicOutlierRejectionThreshold( - _dynamicOutlierRejectionThreshold) { + rankTolerance(_rankTolerance), enableEPI(_enableEPI), // + landmarkDistanceThreshold(_landmarkDistanceThreshold), // + dynamicOutlierRejectionThreshold(_dynamicOutlierRejectionThreshold) { } // stream to output @@ -386,25 +390,31 @@ TriangulationResult triangulateSafe(const std::vector& cameras, Point3 point = triangulatePoint3(cameras, measured, params.rankTolerance, params.enableEPI); - // Check landmark distance and reprojection errors to avoid outliers + // Check landmark distance and re-projection errors to avoid outliers size_t i = 0; double totalReprojError = 0.0; BOOST_FOREACH(const CAMERA& camera, cameras) { - // we discard smart factors corresponding to points that are far away - Point3 cameraTranslation = camera.pose().translation(); - if (cameraTranslation.distance(point) > params.landmarkDistanceThreshold) - return TriangulationResult::Degenerate(); - // Also flag if point is behind any of the cameras - try { + const Pose3& pose = camera.pose(); + if (params.landmarkDistanceThreshold > 0 + && pose.translation().distance(point) + > params.landmarkDistanceThreshold) + return TriangulationResult::Degenerate(); +#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION + // verify that the triangulated point lies in front of all cameras + // Only needed if this was not yet handled by exception + const Point3& p_local = pose.transform_to(point); + if (p_local.z() <= 0) + return TriangulationResult::BehindCamera(); +#endif + // Check reprojection error + if (params.dynamicOutlierRejectionThreshold > 0) { const Point2& zi = measured.at(i); Point2 reprojectionError(camera.project(point) - zi); totalReprojError += reprojectionError.vector().norm(); - } catch (CheiralityException) { - return TriangulationResult::BehindCamera(); } i += 1; } - // we discard smart factors that have large reprojection error + // Flag as degenerate if average reprojection error is too large if (params.dynamicOutlierRejectionThreshold > 0 && totalReprojError / m > params.dynamicOutlierRejectionThreshold) return TriangulationResult::Degenerate(); @@ -412,14 +422,12 @@ TriangulationResult triangulateSafe(const std::vector& cameras, // all good! return TriangulationResult(point); } catch (TriangulationUnderconstrainedException&) { - // if TriangulationUnderconstrainedException can be + // This exception is thrown if // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) - // in the second case we want to use a rotation-only smart factor return TriangulationResult::Degenerate(); } catch (TriangulationCheiralityException&) { // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers - // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint return TriangulationResult::BehindCamera(); } } From cdde34735051971fd7dd97aa968ad6985fa7c4e8 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 27 Mar 2015 18:39:37 -0400 Subject: [PATCH 147/173] fixed typo and warning (int VS size_t) --- gtsam/geometry/CameraSet.h | 4 ++-- gtsam/slam/RegularImplicitSchurFactor.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index cd67187df..1ee53d2c8 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -93,7 +93,7 @@ public: } /** - * Project a point (posibly Unit3 at infinity), with derivatives + * Project a point (possibly Unit3 at infinity), with derivatives * Note that F is a sparse block-diagonal matrix, so instead of a large dense * matrix this function returns the diagonal blocks. * throws CheiralityException @@ -148,7 +148,7 @@ public: const Matrix& E, const Eigen::Matrix& P, const Vector& b) { // a single point is observed in m cameras - int m = Fs.size(); + size_t m = Fs.size(); // Create a SymmetricBlockMatrix size_t M1 = D * m + 1; diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index da1f5b785..0e52d9ba7 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -152,7 +152,7 @@ public: * E_.block(ZDim * k, 0); Eigen::Matrix dj; - for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian + for (int k = 0; k < D; ++k) { // for each diagonal element of the camera hessian // Vector column_k_Fj = Fj.col(k); dj(k) = Fj.col(k).squaredNorm(); // dot(column_k_Fj, column_k_Fj); // Vector column_k_FtE = FtE.row(k); @@ -184,7 +184,7 @@ public: * E_.block(ZDim * pos, 0); DVector dj; - for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian + for (int k = 0; k < D; ++k) { // for each diagonal element of the camera hessian dj(k) = Fj.col(k).squaredNorm(); // (1 x 1) = (1 x 3) * (3 * 3) * (3 x 1) dj(k) -= FtE.row(k) * PointCovariance_ * FtE.row(k).transpose(); From 5ba16dc6212d1d7f1013945e72f6f65442a222e6 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 27 Mar 2015 18:40:14 -0400 Subject: [PATCH 148/173] minor re-formatting --- gtsam/geometry/CalibratedCamera.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index b4513a2a3..6e2f153c8 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -182,8 +182,7 @@ public: /// Project a point into the image and check depth std::pair projectSafe(const Point3& pw) const; - /** - * Project point into the image + /** Project point into the image * Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION * @param point 3D point in world coordinates * @return the intrinsic coordinates of the projected point @@ -191,8 +190,7 @@ public: Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose = boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const; - /** - * Project point at infinity into the image + /** Project point at infinity into the image * Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION * @param point 3D point in world coordinates * @return the intrinsic coordinates of the projected point From 067f2ed39edf56b616c3882815614b9e5fff0806 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 27 Mar 2015 18:40:37 -0400 Subject: [PATCH 149/173] Camera - > CAMERA (using directly template argument) --- gtsam/slam/TriangulationFactor.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 19615c8cc..8001357c9 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -31,7 +31,7 @@ class TriangulationFactor: public NoiseModelFactor1 { public: - /// Camera type + /// CAMERA type typedef CAMERA Camera; protected: @@ -43,7 +43,7 @@ protected: typedef TriangulationFactor This; // Keep a copy of measurement and calibration for I/O - const Camera camera_; ///< Camera in which this landmark was seen + const CAMERA camera_; ///< CAMERA in which this landmark was seen const Point2 measured_; ///< 2D measurement // verbosity handling for Cheirality Exceptions @@ -69,7 +69,7 @@ public: * @param throwCheirality determines whether Cheirality exceptions are rethrown * @param verboseCheirality determines whether exceptions are printed for Cheirality */ - TriangulationFactor(const Camera& camera, const Point2& measured, + TriangulationFactor(const CAMERA& camera, const Point2& measured, const SharedNoiseModel& model, Key pointKey, bool throwCheirality = false, bool verboseCheirality = false) : Base(model, pointKey), camera_(camera), measured_(measured), throwCheirality_( From 4b2eb2f7aaf4d23790a23778feaefece00b1fa16 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 27 Mar 2015 18:42:05 -0400 Subject: [PATCH 150/173] using overloading rather than templates to manage projection of Point3 and Unit3 (the templates worked on mac, but had issues compiling in ubuntu) --- gtsam/geometry/PinholeCamera.h | 26 +++++++++++------ gtsam/geometry/PinholePose.h | 52 +++++++++++++++++++++------------- 2 files changed, 51 insertions(+), 27 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index cc903e7db..6353ddcdc 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -145,7 +145,7 @@ public: const Pose3& getPose(OptionalJacobian<6, dimension> H) const { if (H) { H->setZero(); - H->template block<6,6>(0, 0) = I_6x6; + H->template block<6, 6>(0, 0) = I_6x6; } return Base::pose(); } @@ -199,14 +199,12 @@ public: typedef Eigen::Matrix Matrix2K; - /** project a point from world coordinate to the image (possibly a Unit3) - * @param pw is a point in the world coordinate + /** Templated projection of a 3D point or a point at infinity into the image + * @param pw either a Point3 or a Unit3, in world coordinates */ template - Point2 project2( - const POINT& pw, // - OptionalJacobian<2, dimension> Dcamera = boost::none, - OptionalJacobian<2, FixedDimension::value> Dpoint = boost::none) const { + Point2 _project2(const POINT& pw, OptionalJacobian<2, dimension> Dcamera, + OptionalJacobian<2, FixedDimension::value> Dpoint) const { // We just call 3-derivative version in Base Matrix26 Dpose; Eigen::Matrix Dcal; @@ -217,6 +215,18 @@ public: return pi; } + /// project a 3D point from world coordinates into the image + Point2 project2(const Point3& pw, OptionalJacobian<2, dimension> Dcamera = + boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const { + return _project2(pw, Dcamera, Dpoint); + } + + /// project a point at infinity from world coordinates into the image + Point2 project2(const Unit3& pw, OptionalJacobian<2, dimension> Dcamera = + boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const { + return _project2(pw, Dcamera, Dpoint); + } + /** * Calculate range to a landmark * @param point 3D location of landmark @@ -264,7 +274,7 @@ public: if (Dother) { Dother->resize(1, 6 + CalibrationB::dimension); Dother->setZero(); - Dother->block<1,6>(0, 0) = Dother_; + Dother->block<1, 6>(0, 0) = Dother_; } return result; } diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index d98f36b6e..247d11823 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -87,12 +87,8 @@ public: * @param pw is a point in the world coordinates */ Point2 project(const Point3& pw) const { - - // project to normalized coordinates - const Point2 pn = PinholeBase::project2(pw); - - // uncalibrate to pixel coordinates - return calibration().uncalibrate(pn); + const Point2 pn = PinholeBase::project2(pw); // project to normalized coordinates + return calibration().uncalibrate(pn); // uncalibrate to pixel coordinates } /** project a point from world coordinate to the image @@ -100,20 +96,20 @@ public: */ Point2 project(const Unit3& pw) const { const Unit3 pc = pose().rotation().unrotate(pw); // convert to camera frame - const Point2 pn = PinholeBase::Project(pc); - return calibration().uncalibrate(pn); + const Point2 pn = PinholeBase::Project(pc); // project to normalized coordinates + return calibration().uncalibrate(pn); // uncalibrate to pixel coordinates } - /** project a point (possibly at infinity) from world coordinate to the image - * @param pw is a point in world coordinates + /** Templated projection of a point (possibly at infinity) from world coordinate to the image + * @param pw is a 3D point or aUnit3 (point at infinity) in world coordinates * @param Dpose is the Jacobian w.r.t. pose3 * @param Dpoint is the Jacobian w.r.t. point3 * @param Dcal is the Jacobian w.r.t. calibration */ template - Point2 project(const POINT& pw, OptionalJacobian<2, 6> Dpose, - OptionalJacobian<2, FixedDimension::value> Dpoint = boost::none, - OptionalJacobian<2, DimK> Dcal = boost::none) const { + Point2 _project(const POINT& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, FixedDimension::value> Dpoint, + OptionalJacobian<2, DimK> Dcal) const { // project to normalized coordinates const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); @@ -132,6 +128,20 @@ public: return pi; } + /// project a 3D point from world coordinates into the image + Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 3> Dpoint = boost::none, + OptionalJacobian<2, DimK> Dcal = boost::none) const { + return _project(pw, Dpose, Dpoint, Dcal); + } + + /// project a point at infinity from world coordinates into the image + Point2 project(const Unit3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 2> Dpoint = boost::none, + OptionalJacobian<2, DimK> Dcal = boost::none) const { + return _project(pw, Dpose, Dpoint, Dcal); + } + /// backproject a 2-dimensional point to a 3-dimensional point at given depth Point3 backproject(const Point2& p, double depth) const { const Point2 pn = calibration().calibrate(p); @@ -318,15 +328,19 @@ public: return *K_; } - /** project a point (possibly at infinity) from world coordinate to the image, 2 derivatives only + /** project a point from world coordinate to the image, 2 derivatives only * @param pw is a point in world coordinates - * @param Dpose is the Jacobian w.r.t. the whole camera (realy only the pose) + * @param Dpose is the Jacobian w.r.t. the whole camera (really only the pose) * @param Dpoint is the Jacobian w.r.t. point3 - * TODO should use Unit3 */ - template - Point2 project2(const POINT& pw, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, FixedDimension::value> Dpoint = boost::none) const { + Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 3> Dpoint = boost::none) const { + return Base::project(pw, Dpose, Dpoint); + } + + /// project2 version for point at infinity + Point2 project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 2> Dpoint = boost::none) const { return Base::project(pw, Dpose, Dpoint); } From 51482ea358aa1c3a9e38a2adec7374955bd77abe Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Wed, 8 Apr 2015 14:21:40 -0400 Subject: [PATCH 151/173] Remove template parameter D, get from Base::Dim instead --- .../slam/SmartStereoProjectionFactor.h | 44 +++++++++---------- .../slam/SmartStereoProjectionPoseFactor.h | 4 +- 2 files changed, 24 insertions(+), 24 deletions(-) diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 197ee82d2..642e2350b 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -63,7 +63,7 @@ enum LinearizationMode { /** * SmartStereoProjectionFactor: triangulates point */ -template +template class SmartStereoProjectionFactor: public SmartFactorBase { protected: @@ -104,7 +104,7 @@ protected: // and the factor is disregarded if the error is large /// shorthand for this class - typedef SmartStereoProjectionFactor This; + typedef SmartStereoProjectionFactor This; enum { ZDim = 3 @@ -347,7 +347,7 @@ public: } /// linearize returns a Hessianfactor that is an approximation of error(p) - boost::shared_ptr > createHessianFactor( + boost::shared_ptr > createHessianFactor( const Cameras& cameras, const double lambda = 0.0) const { bool isDebug = false; @@ -374,10 +374,10 @@ public: if (isDebug) std::cout << "In linearize: exception" << std::endl; BOOST_FOREACH(Matrix& m, Gs) - m = zeros(D, D); + m = zeros(Base::Dim, Base::Dim); BOOST_FOREACH(Vector& v, gs) - v = zero(D); - return boost::make_shared >(this->keys_, Gs, gs, + v = zero(Base::Dim); + return boost::make_shared >(this->keys_, Gs, gs, 0.0); } @@ -407,7 +407,7 @@ public: << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" << std::endl; exit(1); - return boost::make_shared >(this->keys_, + return boost::make_shared >(this->keys_, this->state_->Gs, this->state_->gs, this->state_->f); } @@ -421,7 +421,7 @@ public: // Schur complement trick // Frank says: should be possible to do this more efficiently? // And we care, as in grouped factors this is called repeatedly - Matrix H(D * numKeys, D * numKeys); + Matrix H(Base::Dim * numKeys, Base::Dim * numKeys); Vector gs_vector; Matrix3 P = Cameras::PointCov(E, lambda); @@ -436,11 +436,11 @@ public: // Populate Gs and gs int GsCount2 = 0; for (DenseIndex i1 = 0; i1 < (DenseIndex) numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * D; - gs.at(i1) = gs_vector.segment(i1D); + DenseIndex i1D = i1 * Base::Dim; + gs.at(i1) = gs_vector.segment(i1D); for (DenseIndex i2 = 0; i2 < (DenseIndex) numKeys; i2++) { if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * D); + Gs.at(GsCount2) = H.block(i1D, i2 * Base::Dim); GsCount2++; } } @@ -452,29 +452,29 @@ public: this->state_->gs = gs; this->state_->f = f; } - return boost::make_shared >(this->keys_, Gs, gs, f); + return boost::make_shared >(this->keys_, Gs, gs, f); } // // create factor -// boost::shared_ptr > createImplicitSchurFactor( +// boost::shared_ptr > createImplicitSchurFactor( // const Cameras& cameras, double lambda) const { // if (triangulateForLinearize(cameras)) // return Base::createImplicitSchurFactor(cameras, point_, lambda); // else -// return boost::shared_ptr >(); +// return boost::shared_ptr >(); // } // // /// create factor -// boost::shared_ptr > createJacobianQFactor( +// boost::shared_ptr > createJacobianQFactor( // const Cameras& cameras, double lambda) const { // if (triangulateForLinearize(cameras)) // return Base::createJacobianQFactor(cameras, point_, lambda); // else -// return boost::make_shared< JacobianFactorQ >(this->keys_); +// return boost::make_shared< JacobianFactorQ >(this->keys_); // } // // /// Create a factor, takes values -// boost::shared_ptr > createJacobianQFactor( +// boost::shared_ptr > createJacobianQFactor( // const Values& values, double lambda) const { // Cameras cameras; // // TODO triangulate twice ?? @@ -482,7 +482,7 @@ public: // if (nonDegenerate) // return createJacobianQFactor(cameras, lambda); // else -// return boost::make_shared< JacobianFactorQ >(this->keys_); +// return boost::make_shared< JacobianFactorQ >(this->keys_); // } // /// different (faster) way to compute Jacobian factor @@ -491,7 +491,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared >(this->keys_); + return boost::make_shared >(this->keys_); } /// Returns true if nonDegenerate @@ -717,9 +717,9 @@ private: }; /// traits -template -struct traits > : public Testable< - SmartStereoProjectionFactor > { +template +struct traits > : public Testable< + SmartStereoProjectionFactor > { }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 8fe8bea69..2ac719056 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -39,7 +39,7 @@ namespace gtsam { * @addtogroup SLAM */ template -class SmartStereoProjectionPoseFactor: public SmartStereoProjectionFactor { +class SmartStereoProjectionPoseFactor: public SmartStereoProjectionFactor { protected: LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) @@ -51,7 +51,7 @@ public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for base class type - typedef SmartStereoProjectionFactor Base; + typedef SmartStereoProjectionFactor Base; /// shorthand for this class typedef SmartStereoProjectionPoseFactor This; From 762a7b74350cd6a6b91eaf451faa003716072bd9 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Wed, 8 Apr 2015 17:52:25 -0400 Subject: [PATCH 152/173] Remove selective relinearization and state --- .../slam/SmartStereoProjectionFactor.h | 108 ++---------------- .../slam/SmartStereoProjectionPoseFactor.h | 7 ++ .../testSmartStereoProjectionPoseFactor.cpp | 21 ++-- 3 files changed, 27 insertions(+), 109 deletions(-) diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 642e2350b..eb3e2f761 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -33,33 +33,6 @@ namespace gtsam { -/** - * Structure for storing some state memory, used to speed up optimization - * @addtogroup SLAM - */ -class SmartStereoProjectionFactorState { - -protected: - -public: - - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - SmartStereoProjectionFactorState() { - } - // Hessian representation (after Schur complement) - bool calculatedHessian; - Matrix H; - Vector gs_vector; - std::vector Gs; - std::vector gs; - double f; -}; - -enum LinearizationMode { - HESSIAN, JACOBIAN_SVD, JACOBIAN_Q -}; - /** * SmartStereoProjectionFactor: triangulates point */ @@ -84,14 +57,6 @@ protected: mutable bool degenerate_; mutable bool cheiralityException_; - // verbosity handling for Cheirality Exceptions - const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) - const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) - - boost::shared_ptr state_; - - /// shorthand for smart projection factor state variable - typedef boost::shared_ptr SmartFactorStatePtr; /// shorthand for base class type typedef SmartFactorBase Base; @@ -110,6 +75,12 @@ protected: ZDim = 3 }; ///< Dimension trait of measurement type + /// @name Parameters governing how triangulation result is treated + /// @{ + const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) + const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) + /// @} + public: /// shorthand for a smart pointer to a factor @@ -133,12 +104,11 @@ public: SmartStereoProjectionFactor(const double rankTol, const double linThreshold, const bool manageDegeneracy, const bool enableEPI, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1, SmartFactorStatePtr state = - SmartFactorStatePtr(new SmartStereoProjectionFactorState())) : + double dynamicOutlierRejectionThreshold = -1) : rankTolerance_(rankTol), retriangulationThreshold_(1e-5), manageDegeneracy_( manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( - false), verboseCheirality_(false), state_(state), landmarkDistanceThreshold_( + false), verboseCheirality_(false), landmarkDistanceThreshold_( landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( dynamicOutlierRejectionThreshold) { } @@ -199,40 +169,6 @@ public: return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation } - /// This function checks if the new linearization point_ is 'close' to the previous one used for linearization - bool decideIfLinearize(const Cameras& cameras) const { - // "selective linearization" - // The function evaluates how close are the old and the new poses, transformed in the ref frame of the first pose - // (we only care about the "rigidity" of the poses, not about their absolute pose) - - if (this->linearizationThreshold_ < 0) //by convention if linearizationThreshold is negative we always relinearize - return true; - - // if we do not have a previous linearization point_ or the new linearization point_ includes more poses - if (cameraPosesLinearization_.empty() - || (cameras.size() != cameraPosesLinearization_.size())) - return true; - - Pose3 firstCameraPose, firstCameraPoseOld; - for (size_t i = 0; i < cameras.size(); i++) { - - if (i == 0) { // we store the initial pose, this is useful for selective re-linearization - firstCameraPose = cameras[i].pose(); - firstCameraPoseOld = cameraPosesLinearization_[i]; - continue; - } - - // we compare the poses in the frame of the first pose - Pose3 localCameraPose = firstCameraPose.between(cameras[i].pose()); - Pose3 localCameraPoseOld = firstCameraPoseOld.between( - cameraPosesLinearization_[i]); - if (!localCameraPose.equals(localCameraPoseOld, - this->linearizationThreshold_)) - return true; // at least two "relative" poses are different, hence we re-linearize - } - return false; // if we arrive to this point_ all poses are the same and we don't need re-linearize - } - /// triangulateSafe size_t triangulateSafe(const Values& values) const { return triangulateSafe(this->cameras(values)); @@ -364,7 +300,7 @@ public: exit(1); } - this->triangulateSafe(cameras); + triangulateSafe(cameras); if (isDebug) std::cout << "point_ = " << point_ << std::endl; @@ -388,29 +324,10 @@ public: std::cout << "degenerate_ = true" << std::endl; } - bool doLinearize = this->decideIfLinearize(cameras); - - if (isDebug) - std::cout << "doLinearize = " << doLinearize << std::endl; - - if (this->linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize + if (this->linearizationThreshold_ >= 0) // if we apply selective relinearization and we need to relinearize for (size_t i = 0; i < cameras.size(); i++) this->cameraPosesLinearization_[i] = cameras[i].pose(); - if (!doLinearize) { // return the previous Hessian factor - std::cout << "=============================" << std::endl; - std::cout << "doLinearize " << doLinearize << std::endl; - std::cout << "this->linearizationThreshold_ " - << this->linearizationThreshold_ << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; - std::cout - << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" - << std::endl; - exit(1); - return boost::make_shared >(this->keys_, - this->state_->Gs, this->state_->gs, this->state_->f); - } - // ================================================================== std::vector Fblocks; Matrix F, E; @@ -447,11 +364,6 @@ public: } // ================================================================== double f = b.squaredNorm(); - if (this->linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables - this->state_->Gs = Gs; - this->state_->gs = gs; - this->state_->f = f; - } return boost::make_shared >(this->keys_, Gs, gs, f); } diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 2ac719056..a9cec0f57 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -40,6 +40,13 @@ namespace gtsam { */ template class SmartStereoProjectionPoseFactor: public SmartStereoProjectionFactor { + +public: + /// Linearization mode: what factor to linearize to + enum LinearizationMode { + HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD + }; + protected: LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 0112db915..258c8d0eb 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -64,7 +64,6 @@ static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); typedef SmartStereoProjectionPoseFactor SmartFactor; -typedef SmartStereoProjectionPoseFactor SmartFactorBundler; vector stereo_projectToMultipleCameras(const StereoCamera& cam1, const StereoCamera& cam2, const StereoCamera& cam3, Point3 landmark) { @@ -327,15 +326,15 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { cam2, cam3, landmark3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD)); smartFactor1->add(measurements_cam1, views, model, K); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD)); smartFactor2->add(measurements_cam2, views, model, K); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD)); + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD)); smartFactor3->add(measurements_cam3, views, model, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -395,17 +394,17 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { cam2, cam3, landmark3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor1->add(measurements_cam1, views, model, K); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor2->add(measurements_cam2, views, model, K); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor3->add(measurements_cam3, views, model, K); @@ -473,22 +472,22 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + StereoPoint2(10, 10, 1); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model, K); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model, K); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model, K); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(1, -1, false, false, JACOBIAN_SVD, + new SmartFactor(1, -1, false, false, SmartFactor::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model, K); From ea6f5e3fb933717dd57971e7d2304bf9ae1569ab Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Wed, 8 Apr 2015 21:36:11 -0400 Subject: [PATCH 153/173] Use TriangulationParameters --- .../slam/SmartStereoProjectionFactor.h | 45 +++++++++---------- 1 file changed, 20 insertions(+), 25 deletions(-) diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index eb3e2f761..2e3fdcbdb 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -40,15 +40,18 @@ template class SmartStereoProjectionFactor: public SmartFactorBase { protected: - // Some triangulation parameters - const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ + /// @name Caching triangulation + /// @{ + const TriangulationParameters parameters_; + // TODO: +// mutable TriangulationResult result_; ///< result from triangulateSafe + const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses + /// @} const bool manageDegeneracy_; ///< if set to true will use the rotation-only version for degenerate cases - const bool enableEPI_; ///< if set to true, will refine triangulation using LM - const double linearizationThreshold_; ///< threshold to decide whether to re-linearize mutable std::vector cameraPosesLinearization_; ///< current linearization poses @@ -61,13 +64,6 @@ protected: /// shorthand for base class type typedef SmartFactorBase Base; - double landmarkDistanceThreshold_; // if the landmark is triangulated at a - // distance larger than that the factor is considered degenerate - - double dynamicOutlierRejectionThreshold_; // if this is nonnegative the factor will check if the - // average reprojection error is smaller than this threshold after triangulation, - // and the factor is disregarded if the error is large - /// shorthand for this class typedef SmartStereoProjectionFactor This; @@ -101,16 +97,15 @@ public: * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations * @param body_P_sensor is the transform from body to sensor frame (default identity) */ - SmartStereoProjectionFactor(const double rankTol, const double linThreshold, - const bool manageDegeneracy, const bool enableEPI, - double landmarkDistanceThreshold = 1e10, + SmartStereoProjectionFactor(const double rankTolerance, + const double linThreshold, const bool manageDegeneracy, + const bool enableEPI, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : - rankTolerance_(rankTol), retriangulationThreshold_(1e-5), manageDegeneracy_( - manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( + parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, + dynamicOutlierRejectionThreshold), // + retriangulationThreshold_(1e-5), manageDegeneracy_(manageDegeneracy), linearizationThreshold_( linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( - false), verboseCheirality_(false), landmarkDistanceThreshold_( - landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( - dynamicOutlierRejectionThreshold) { + false), verboseCheirality_(false) { } /** Virtual destructor */ @@ -124,8 +119,8 @@ public: */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "SmartStereoProjectionFactor, z = \n"; - std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; + std::cout << s << "SmartStereoProjectionFactor\n"; + std::cout << "triangulationParameters:\n" << parameters_ << std::endl; std::cout << "degenerate_ = " << degenerate_ << std::endl; std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; std::cout << "linearizationThreshold_ = " << linearizationThreshold_ @@ -206,7 +201,7 @@ public: mono_cameras.push_back(PinholeCamera(pose, K)); } point_ = triangulatePoint3(mono_cameras, mono_measurements, - rankTolerance_, enableEPI_); + parameters_.rankTolerance, parameters_.enableEPI); // // // End temporary hack @@ -223,7 +218,7 @@ public: BOOST_FOREACH(const Camera& camera, cameras) { Point3 cameraTranslation = camera.pose().translation(); // we discard smart factors corresponding to points that are far away - if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { + if (cameraTranslation.distance(point_) > parameters_.landmarkDistanceThreshold) { degenerate_ = true; break; } @@ -238,8 +233,8 @@ public: } //std::cout << "totalReprojError error: " << totalReprojError << std::endl; // we discard smart factors that have large reprojection error - if (dynamicOutlierRejectionThreshold_ > 0 - && totalReprojError / m > dynamicOutlierRejectionThreshold_) + if (parameters_.dynamicOutlierRejectionThreshold > 0 + && totalReprojError / m > parameters_.dynamicOutlierRejectionThreshold) degenerate_ = true; } catch (TriangulationUnderconstrainedException&) { From 356d43bb9e5ff72ac4547af9c9518ac78335e230 Mon Sep 17 00:00:00 2001 From: Luca Date: Tue, 14 Apr 2015 12:36:36 -0400 Subject: [PATCH 154/173] added typedef to preserve compatibility with SmartProjectionCameraFactor --- gtsam/slam/SmartProjectionFactor.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 7c137ad5c..1ee3fdb0b 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -52,6 +52,7 @@ public: private: typedef SmartFactorBase Base; typedef SmartProjectionFactor This; + typedef SmartProjectionFactor SmartProjectionCameraFactor; protected: From 24128f15fc086b332dbaa6055b134ce52b1dd313 Mon Sep 17 00:00:00 2001 From: Frank Date: Tue, 12 May 2015 16:12:28 -0700 Subject: [PATCH 155/173] Some comments --- gtsam/slam/SmartProjectionFactor.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 1ee3fdb0b..aad1a27f6 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -205,7 +205,7 @@ public: triangulateSafe(cameras); if (degeneracyMode_ == ZERO_ON_DEGENERACY && !result_) { - // put in "empty" Hessian + // failed: return"empty" Hessian BOOST_FOREACH(Matrix& m, Gs) m = zeros(Base::Dim, Base::Dim); BOOST_FOREACH(Vector& v, gs) @@ -237,6 +237,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda); else + // failed: return empty return boost::shared_ptr >(); } @@ -246,6 +247,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianQFactor(cameras, *result_, lambda); else + // failed: return empty return boost::make_shared >(this->keys_); } @@ -261,6 +263,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, *result_, lambda); else + // failed: return empty return boost::make_shared >(this->keys_); } From 391386a6540e199f6db5172ebb50795e3a43cccf Mon Sep 17 00:00:00 2001 From: Luca Date: Thu, 18 Jun 2015 16:00:54 -0400 Subject: [PATCH 156/173] revived SmartProjectionPoseFactor. Compiles now, going to fix unit tests now --- .cproject | 120 +++---------- gtsam/slam/SmartProjectionFactor.h | 20 +-- gtsam/slam/SmartProjectionPoseFactor.h | 160 ++++++++++++++++++ gtsam/slam/tests/smartFactorScenarios.h | 5 +- .../tests/testSmartProjectionPoseFactor.cpp | 91 +++++----- 5 files changed, 243 insertions(+), 153 deletions(-) create mode 100644 gtsam/slam/SmartProjectionPoseFactor.h diff --git a/.cproject b/.cproject index 86952742b..1134896ad 100644 --- a/.cproject +++ b/.cproject @@ -5,13 +5,13 @@ - - + + @@ -60,13 +60,13 @@ - - + + @@ -116,13 +116,13 @@ - - + + @@ -819,10 +819,18 @@ false true - + make - -j4 - SmartStereoProjectionFactorExample.run + -j5 + SmartProjectionFactorExample_kitti_nonbatch.run + true + true + true + + + make + -j5 + SmartProjectionFactorExample_kitti.run true true true @@ -835,14 +843,6 @@ true true - - make - -j4 - SmartProjectionFactorExample.run - true - true - true - make -j2 @@ -1035,30 +1035,6 @@ true true - - make - -j4 - testCameraSet.run - true - true - true - - - make - -j4 - testTriangulation.run - true - true - true - - - make - -j4 - testPinholeSet.run - true - true - true - make -j2 @@ -1147,6 +1123,14 @@ true true + + make + -j5 + testSmartProjectionFactor.run + true + true + true + make -j5 @@ -1546,10 +1530,10 @@ true true - + make - -j4 - testRegularImplicitSchurFactor.run + -j5 + testImplicitSchurFactor.run true true true @@ -1578,30 +1562,6 @@ true true - - make - -j4 - testSmartProjectionCameraFactor.run - true - true - true - - - make - -j4 - testSmartFactorBase.run - true - true - true - - - make - -j4 - testTriangulationFactor.run - true - true - true - make -j3 @@ -2503,14 +2463,6 @@ true true - - make - -j4 - SFMExample_SmartFactorPCG.run - true - true - true - make -j2 @@ -3103,22 +3055,6 @@ true true - - make - -j4 - testRegularHessianFactor.run - true - true - true - - - make - -j4 - testRegularJacobianFactor.run - true - true - true - make -j5 diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index aad1a27f6..c7b2962e4 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -31,6 +31,16 @@ namespace gtsam { +/// Linearization mode: what factor to linearize to +enum LinearizationMode { + HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD +}; + +/// How to manage degeneracy +enum DegeneracyMode { + IGNORE_DEGENERACY, ZERO_ON_DEGENERACY, HANDLE_INFINITY +}; + /** * SmartProjectionFactor: triangulates point and keeps an estimate of it around. */ @@ -39,16 +49,6 @@ class SmartProjectionFactor: public SmartFactorBase { public: - /// Linearization mode: what factor to linearize to - enum LinearizationMode { - HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD - }; - - /// How to manage degeneracy - enum DegeneracyMode { - IGNORE_DEGENERACY, ZERO_ON_DEGENERACY, HANDLE_INFINITY - }; - private: typedef SmartFactorBase Base; typedef SmartProjectionFactor This; diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h new file mode 100644 index 000000000..7a5137bfc --- /dev/null +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -0,0 +1,160 @@ +/* ---------------------------------------------------------------------------- + + * 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 SmartProjectionPoseFactor.h + * @brief Produces an Hessian factors on POSES from monocular measurements of a single landmark + * @author Luca Carlone + * @author Chris Beall + * @author Zsolt Kira + */ + +#pragma once + +#include + +namespace gtsam { +/** + * + * @addtogroup SLAM + * + * If you are using the factor, please cite: + * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally + * independent sets in factor graphs: a unifying perspective based on smart factors, + * Int. Conf. on Robotics and Automation (ICRA), 2014. + * + */ + +/** + * The calibration is known here. The factor only constraints poses (variable dimension is 6) + * @addtogroup SLAM + */ +template +class SmartProjectionPoseFactor: public SmartProjectionFactor< + PinholePose > { + +private: + typedef PinholePose Camera; + typedef SmartProjectionFactor Base; + typedef SmartProjectionPoseFactor This; + +protected: + + boost::optional body_P_sensor_; ///< Pose of the camera in the body frame + std::vector > sharedKs_; ///< shared pointer to calibration object (one for each camera) + +public: + + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** + * Constructor + * @param rankTol tolerance used to check if point triangulation is degenerate + * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) + * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, + * otherwise the factor is simply neglected (this functionality is deprecated) + * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations + * @param body_P_sensor is the transform from sensor to body frame (default identity) + */ + SmartProjectionPoseFactor(const double rankTol = 1, + const double linThreshold = -1, const DegeneracyMode manageDegeneracy = IGNORE_DEGENERACY, + const bool enableEPI = false, boost::optional body_P_sensor = boost::none, + LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, + double dynamicOutlierRejectionThreshold = -1) : + Base(linearizeTo, rankTol, manageDegeneracy, enableEPI, + landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), body_P_sensor_(body_P_sensor) {} + + /** Virtual destructor */ + virtual ~SmartProjectionPoseFactor() {} + + /** + * print + * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols + */ + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const { + std::cout << s << "SmartProjectionPoseFactor, z = \n "; + if(body_P_sensor_) + body_P_sensor_->print("body_P_sensor_:\n"); + Base::print("", keyFormatter); + } + + /// equals + virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + const This *e = dynamic_cast(&p); + return e && Base::equals(p, tol); + } + + /** + * Linearize to Gaussian Factor + * @param values Values structure which must contain camera poses for this factor + * @return + */ + virtual boost::shared_ptr linearize( + const Values& values) const { + // depending on flag set on construction we may linearize to different linear factors +// switch(linearizeTo_){ +// case JACOBIAN_SVD : +// return this->createJacobianSVDFactor(Base::cameras(values), 0.0); +// break; +// case JACOBIAN_Q : +// return this->createJacobianQFactor(Base::cameras(values), 0.0); +// break; +// default: + return this->createHessianFactor(Base::cameras(values)); +// break; +// } + } + + /** + * error calculates the error of the factor. + */ + virtual double error(const Values& values) const { + if (this->active(values)) { + return this->totalReprojectionError(Base::cameras(values)); + } else { // else of active flag + return 0.0; + } + } + + /** return calibration shared pointers */ + inline const std::vector > calibration() const { + return sharedKs_; + } + + Pose3 body_P_sensor() const{ + if(body_P_sensor_) + return *body_P_sensor_; + else + return Pose3(); // if unspecified, the transformation is the identity + } + +private: + + /// Serialization function + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar & BOOST_SERIALIZATION_NVP(sharedKs_); + } + +}; // end of class declaration + +/// traits +template +struct traits > : public Testable< + SmartProjectionPoseFactor > { +}; + +} // \ namespace gtsam diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index c3598e4c1..e821f9e40 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -17,6 +17,7 @@ */ #pragma once +#include #include #include #include @@ -66,7 +67,7 @@ typedef GeneralSFMFactor SFMFactor; // default Cal3_S2 poses namespace vanillaPose { typedef PinholePose Camera; -typedef SmartProjectionFactor SmartFactor; +typedef SmartProjectionPoseFactor SmartFactor; static Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); Camera level_camera(level_pose, sharedK); Camera level_camera_right(pose_right, sharedK); @@ -108,7 +109,7 @@ typedef GeneralSFMFactor SFMFactor; // Cal3Bundler poses namespace bundlerPose { typedef PinholePose Camera; -typedef SmartProjectionFactor SmartFactor; +typedef SmartProjectionPoseFactor SmartFactor; static boost::shared_ptr sharedBundlerK( new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); Camera level_camera(level_pose, sharedBundlerK); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 1e21a3afd..790e85dfb 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -59,7 +59,7 @@ TEST( SmartProjectionPoseFactor, Constructor) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor2) { using namespace vanillaPose; - SmartFactor factor1(SmartFactor::HESSIAN, rankTol); + SmartFactor factor1(gtsam::HESSIAN, rankTol); } /* ************************************************************************* */ @@ -72,7 +72,7 @@ TEST( SmartProjectionPoseFactor, Constructor3) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { using namespace vanillaPose; - SmartFactor factor1(SmartFactor::HESSIAN, rankTol); + SmartFactor factor1(gtsam::HESSIAN, rankTol); factor1.add(measurement1, x1, model); } @@ -495,15 +495,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD)); + new SmartFactor(gtsam::JACOBIAN_SVD)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD)); + new SmartFactor(gtsam::JACOBIAN_SVD)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD)); + new SmartFactor(gtsam::JACOBIAN_SVD)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -549,21 +549,18 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, - SmartFactor::IGNORE_DEGENERACY, false, - excludeLandmarksFutherThanDist)); + new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, - SmartFactor::IGNORE_DEGENERACY, false, - excludeLandmarksFutherThanDist)); + new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, - SmartFactor::IGNORE_DEGENERACY, false, - excludeLandmarksFutherThanDist)); + new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -617,27 +614,23 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, - SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, - dynamicOutlierRejectionThreshold)); + new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, - SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, - dynamicOutlierRejectionThreshold)); + new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, - SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, - dynamicOutlierRejectionThreshold)); + new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(SmartFactor::JACOBIAN_SVD, 1, - SmartFactor::IGNORE_DEGENERACY, false, excludeLandmarksFutherThanDist, - dynamicOutlierRejectionThreshold)); + new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -680,15 +673,15 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::JACOBIAN_Q)); + new SmartFactor(gtsam::JACOBIAN_Q)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::JACOBIAN_Q)); + new SmartFactor(gtsam::JACOBIAN_Q)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::JACOBIAN_Q)); + new SmartFactor(gtsam::JACOBIAN_Q)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -799,15 +792,15 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol)); + new SmartFactor(gtsam::HESSIAN, rankTol)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol)); + new SmartFactor(gtsam::HESSIAN, rankTol)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::HESSIAN, rankTol)); + new SmartFactor(gtsam::HESSIAN, rankTol)); smartFactor3->add(measurements_cam3, views, model); NonlinearFactorGraph graph; @@ -880,13 +873,13 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::HANDLE_INFINITY)); + new SmartFactor(gtsam::HESSIAN, rankTol, + gtsam::HANDLE_INFINITY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::HANDLE_INFINITY)); + new SmartFactor(gtsam::HESSIAN, rankTol, + gtsam::HANDLE_INFINITY)); smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -961,18 +954,18 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + new SmartFactor(gtsam::HESSIAN, rankTol, + gtsam::ZERO_ON_DEGENERACY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + new SmartFactor(gtsam::HESSIAN, rankTol, + gtsam::ZERO_ON_DEGENERACY)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + new SmartFactor(gtsam::HESSIAN, rankTol, + gtsam::ZERO_ON_DEGENERACY)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1168,7 +1161,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { using namespace bundlerPose; - SmartFactor factor(SmartFactor::HESSIAN, rankTol); + SmartFactor factor(gtsam::HESSIAN, rankTol); factor.add(measurement1, x1, model); } @@ -1262,18 +1255,18 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + new SmartFactor(rankTol, -1.0, gtsam::ZERO_ON_DEGENERACY, + false, Pose3(), gtsam::HESSIAN)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + new SmartFactor(rankTol, -1, gtsam::ZERO_ON_DEGENERACY, + false, Pose3(), gtsam::HESSIAN)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(SmartFactor::HESSIAN, rankTol, - SmartFactor::ZERO_ON_DEGENERACY)); + new SmartFactor(rankTol, -1, gtsam::ZERO_ON_DEGENERACY, + false, Pose3(), gtsam::HESSIAN)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); From 66083f5e18d896f8212555aeb951f2261955f427 Mon Sep 17 00:00:00 2001 From: Luca Date: Thu, 18 Jun 2015 16:33:17 -0400 Subject: [PATCH 157/173] included calibration in constructor SmartProjectionPoseFactor --- gtsam/slam/SmartProjectionPoseFactor.h | 14 +- .../tests/testSmartProjectionPoseFactor.cpp | 177 +++++++++++++----- 2 files changed, 141 insertions(+), 50 deletions(-) diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 7a5137bfc..e86f8e555 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -48,8 +48,8 @@ private: protected: + boost::shared_ptr K_; ///< calibration object (one for all cameras) boost::optional body_P_sensor_; ///< Pose of the camera in the body frame - std::vector > sharedKs_; ///< shared pointer to calibration object (one for each camera) public: @@ -65,13 +65,13 @@ public: * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations * @param body_P_sensor is the transform from sensor to body frame (default identity) */ - SmartProjectionPoseFactor(const double rankTol = 1, + SmartProjectionPoseFactor(const boost::shared_ptr K, const double rankTol = 1, const double linThreshold = -1, const DegeneracyMode manageDegeneracy = IGNORE_DEGENERACY, const bool enableEPI = false, boost::optional body_P_sensor = boost::none, LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : - Base(linearizeTo, rankTol, manageDegeneracy, enableEPI, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), body_P_sensor_(body_P_sensor) {} + Base(linearizeTo, rankTol, manageDegeneracy, enableEPI, landmarkDistanceThreshold, + dynamicOutlierRejectionThreshold), K_(K), body_P_sensor_(body_P_sensor) {} /** Virtual destructor */ virtual ~SmartProjectionPoseFactor() {} @@ -128,8 +128,8 @@ public: } /** return calibration shared pointers */ - inline const std::vector > calibration() const { - return sharedKs_; + inline const boost::shared_ptr calibration() const { + return K_; } Pose3 body_P_sensor() const{ @@ -146,7 +146,7 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(sharedKs_); + ar & BOOST_SERIALIZATION_NVP(K_); } }; // end of class declaration diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 790e85dfb..14e15f6c9 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -53,36 +53,36 @@ LevenbergMarquardtParams params; /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor) { using namespace vanillaPose; - SmartFactor::shared_ptr factor1(new SmartFactor()); + SmartFactor::shared_ptr factor1(new SmartFactor(sharedK)); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor2) { using namespace vanillaPose; - SmartFactor factor1(gtsam::HESSIAN, rankTol); + SmartFactor factor1(sharedK, rankTol); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor3) { using namespace vanillaPose; - SmartFactor::shared_ptr factor1(new SmartFactor()); + SmartFactor::shared_ptr factor1(new SmartFactor(sharedK)); factor1->add(measurement1, x1, model); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { using namespace vanillaPose; - SmartFactor factor1(gtsam::HESSIAN, rankTol); + SmartFactor factor1(sharedK, rankTol); factor1.add(measurement1, x1, model); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Equals ) { using namespace vanillaPose; - SmartFactor::shared_ptr factor1(new SmartFactor()); + SmartFactor::shared_ptr factor1(new SmartFactor(sharedK)); factor1->add(measurement1, x1, model); - SmartFactor::shared_ptr factor2(new SmartFactor()); + SmartFactor::shared_ptr factor2(new SmartFactor(sharedK)); factor2->add(measurement1, x1, model); CHECK(assert_equal(*factor1, *factor2)); @@ -97,7 +97,7 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { Point2 level_uv = level_camera.project(landmark1); Point2 level_uv_right = level_camera_right.project(landmark1); - SmartFactor factor; + SmartFactor factor(sharedK); factor.add(level_uv, x1, model); factor.add(level_uv_right, x2, model); @@ -162,13 +162,13 @@ TEST( SmartProjectionPoseFactor, noisy ) { Point3(0.5, 0.1, 0.3)); values.insert(x2, Camera(pose_right.compose(noise_pose), sharedK)); - SmartFactor::shared_ptr factor(new SmartFactor()); + SmartFactor::shared_ptr factor(new SmartFactor((sharedK))); factor->add(level_uv, x1, model); factor->add(level_uv_right, x2, model); double actualError1 = factor->error(values); - SmartFactor::shared_ptr factor2(new SmartFactor()); + SmartFactor::shared_ptr factor2(new SmartFactor((sharedK))); vector measurements; measurements.push_back(level_uv); measurements.push_back(level_uv_right); @@ -186,6 +186,96 @@ TEST( SmartProjectionPoseFactor, noisy ) { DOUBLES_EQUAL(actualError1, actualError2, 1e-7); } +/* *************************************************************************/ +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); + + // 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(); // + + // 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()); + + // 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); + + vector 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 + std::vector views; + views.push_back(x1); + views.push_back(x2); + views.push_back(x3); + + bool enableEPI = false; + + SmartProjectionPoseFactor smartFactor1(K, 1.0, -1.0, gtsam::IGNORE_DEGENERACY, enableEPI, sensor_to_body); + smartFactor1.add(measurements_cam1, views, model); + + SmartProjectionPoseFactor smartFactor2(K, 1.0, -1.0, gtsam::IGNORE_DEGENERACY, enableEPI, sensor_to_body); + smartFactor2.add(measurements_cam2, views, model); + + SmartProjectionPoseFactor smartFactor3(K, 1.0, -1.0, gtsam::IGNORE_DEGENERACY, enableEPI, sensor_to_body); + smartFactor3.add(measurements_cam3, views, model); + + 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); + graph.push_back(PriorFactor(x1, bodyPose1, noisePrior)); + graph.push_back(PriorFactor(x2, bodyPose2, noisePrior)); + + // Check errors at ground truth poses + Values gtValues; + gtValues.insert(x1, bodyPose1); + gtValues.insert(x2, bodyPose2); + gtValues.insert(x3, bodyPose3); + 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)); + 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); + + LevenbergMarquardtParams params; + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + + // result.print("results of 3 camera, 3 landmark optimization \n"); + // result.at(x3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(bodyPose3,result.at(x3))); +} + /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { @@ -277,7 +367,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { views.push_back(x1); views.push_back(x2); - SmartFactor::shared_ptr smartFactor1 = boost::make_shared(); + SmartFactor::shared_ptr smartFactor1 = boost::make_shared(sharedK); smartFactor1->add(measurements_cam1, views, model); SmartFactor::Cameras cameras; @@ -435,13 +525,13 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(sharedK)); smartFactor1->add(measurements_cam1, views, model); - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + SmartFactor::shared_ptr smartFactor2(new SmartFactor(sharedK)); smartFactor2->add(measurements_cam2, views, model); - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + SmartFactor::shared_ptr smartFactor3(new SmartFactor(sharedK)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -495,15 +585,15 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(gtsam::JACOBIAN_SVD)); + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(gtsam::JACOBIAN_SVD)); + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(gtsam::JACOBIAN_SVD)); + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -549,17 +639,17 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); smartFactor3->add(measurements_cam3, views, model); @@ -614,22 +704,22 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor3->add(measurements_cam3, views, model); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); smartFactor4->add(measurements_cam4, views, model); @@ -673,15 +763,19 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(gtsam::JACOBIAN_Q)); + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, + false, Pose3(), gtsam::JACOBIAN_Q)); + smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(gtsam::JACOBIAN_Q)); + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, + false, Pose3(), gtsam::JACOBIAN_Q)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(gtsam::JACOBIAN_Q)); + new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, + false, Pose3(), gtsam::JACOBIAN_Q)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -792,15 +886,15 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(gtsam::HESSIAN, rankTol)); + new SmartFactor(sharedK, rankTol)); // HESSIAN, by default smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(gtsam::HESSIAN, rankTol)); + new SmartFactor(sharedK, rankTol)); // HESSIAN, by default smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(gtsam::HESSIAN, rankTol)); + new SmartFactor(sharedK, rankTol)); // HESSIAN, by default smartFactor3->add(measurements_cam3, views, model); NonlinearFactorGraph graph; @@ -954,18 +1048,15 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(gtsam::HESSIAN, rankTol, - gtsam::ZERO_ON_DEGENERACY)); + new SmartFactor(sharedK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(gtsam::HESSIAN, rankTol, - gtsam::ZERO_ON_DEGENERACY)); + new SmartFactor(sharedK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(gtsam::HESSIAN, rankTol, - gtsam::ZERO_ON_DEGENERACY)); + new SmartFactor(sharedK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1062,7 +1153,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); + SmartFactor::shared_ptr smartFactorInstance(new SmartFactor(sharedK)); smartFactorInstance->add(measurements_cam1, views, model); Values values; @@ -1161,7 +1252,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { using namespace bundlerPose; - SmartFactor factor(gtsam::HESSIAN, rankTol); + SmartFactor factor(sharedBundlerK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY, false, Pose3(), gtsam::HESSIAN); factor.add(measurement1, x1, model); } @@ -1185,13 +1276,13 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { views.push_back(x2); views.push_back(x3); - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(sharedBundlerK)); smartFactor1->add(measurements_cam1, views, model); - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + SmartFactor::shared_ptr smartFactor2(new SmartFactor(sharedBundlerK)); smartFactor2->add(measurements_cam2, views, model); - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + SmartFactor::shared_ptr smartFactor3(new SmartFactor(sharedBundlerK)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1255,17 +1346,17 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { double rankTol = 10; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(rankTol, -1.0, gtsam::ZERO_ON_DEGENERACY, + new SmartFactor(sharedBundlerK, rankTol, -1.0, gtsam::ZERO_ON_DEGENERACY, false, Pose3(), gtsam::HESSIAN)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(rankTol, -1, gtsam::ZERO_ON_DEGENERACY, + new SmartFactor(sharedBundlerK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY, false, Pose3(), gtsam::HESSIAN)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(rankTol, -1, gtsam::ZERO_ON_DEGENERACY, + new SmartFactor(sharedBundlerK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY, false, Pose3(), gtsam::HESSIAN)); smartFactor3->add(measurements_cam3, views, model); From 756d1d29b7bce6d8ffc89d80806d7d133375e4af Mon Sep 17 00:00:00 2001 From: Luca Date: Thu, 18 Jun 2015 17:23:39 -0400 Subject: [PATCH 158/173] fixing key unit tests - still failures in the optimization --- gtsam/slam/SmartProjectionFactor.h | 27 ++++++++-- gtsam/slam/SmartProjectionPoseFactor.h | 53 ++++++++++++++----- gtsam/slam/tests/smartFactorScenarios.h | 2 +- .../tests/testSmartProjectionPoseFactor.cpp | 30 +++++------ 4 files changed, 78 insertions(+), 34 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index c7b2962e4..b5b325bfe 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -290,10 +290,9 @@ public: * @param values Values structure which must contain camera poses for this factor * @return a Gaussian factor */ - boost::shared_ptr linearizeDamped(const Values& values, + boost::shared_ptr linearizeDamped(const Cameras& cameras, const double lambda = 0.0) const { // depending on flag set on construction we may linearize to different linear factors - Cameras cameras = this->cameras(values); switch (linearizationMode_) { case HESSIAN: return createHessianFactor(cameras, lambda); @@ -308,6 +307,18 @@ public: } } + /** + * Linearize to Gaussian Factor + * @param values Values structure which must contain camera poses for this factor + * @return a Gaussian factor + */ + boost::shared_ptr linearizeDamped(const Values& values, + const double lambda = 0.0) const { + // depending on flag set on construction we may linearize to different linear factors + Cameras cameras = this->cameras(values); + return linearizeDamped(cameras, lambda); + } + /// linearize virtual boost::shared_ptr linearize( const Values& values) const { @@ -318,14 +329,22 @@ public: * Triangulate and compute derivative of error with respect to point * @return whether triangulation worked */ - bool triangulateAndComputeE(Matrix& E, const Values& values) const { - Cameras cameras = this->cameras(values); + bool triangulateAndComputeE(Matrix& E, const Cameras& cameras) const { bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) cameras.project2(*result_, boost::none, E); return nonDegenerate; } + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Values& values) const { + Cameras cameras = this->cameras(values); + return triangulateAndComputeE(E, cameras); + } + /// Compute F, E only (called below in both vanilla and SVD versions) /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index e86f8e555..275056735 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -98,22 +98,19 @@ public: /** * Linearize to Gaussian Factor * @param values Values structure which must contain camera poses for this factor - * @return + * @return a Gaussian factor */ + boost::shared_ptr linearizeDamped(const Values& values, + const double lambda = 0.0) const { + // depending on flag set on construction we may linearize to different linear factors + typename Base::Cameras cameras = this->cameras(values); + return Base::linearizeDamped(cameras, lambda); + } + + /// linearize virtual boost::shared_ptr linearize( const Values& values) const { - // depending on flag set on construction we may linearize to different linear factors -// switch(linearizeTo_){ -// case JACOBIAN_SVD : -// return this->createJacobianSVDFactor(Base::cameras(values), 0.0); -// break; -// case JACOBIAN_Q : -// return this->createJacobianQFactor(Base::cameras(values), 0.0); -// break; -// default: - return this->createHessianFactor(Base::cameras(values)); -// break; -// } + return linearizeDamped(values); } /** @@ -121,7 +118,7 @@ public: */ virtual double error(const Values& values) const { if (this->active(values)) { - return this->totalReprojectionError(Base::cameras(values)); + return this->totalReprojectionError(cameras(values)); } else { // else of active flag return 0.0; } @@ -139,6 +136,34 @@ public: return Pose3(); // if unspecified, the transformation is the identity } + /** + * Collect all cameras involved in this factor + * @param values Values structure which must contain camera poses corresponding + * to keys involved in this factor + * @return vector of Values + */ + typename Base::Cameras cameras(const Values& values) const { + typename Base::Cameras cameras; + BOOST_FOREACH(const Key& k, this->keys_) { + Pose3 pose = values.at(k); + if(body_P_sensor_) + pose = pose.compose(*(body_P_sensor_)); + + Camera camera(pose, K_); + cameras.push_back(camera); + } + return cameras; + } + + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Values& values) const { + typename Base::Cameras cameras = this->cameras(values); + return Base::triangulateAndComputeE(E, cameras); + } + private: /// Serialization function diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index e821f9e40..e566146d0 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -80,7 +80,7 @@ Camera cam3(pose_above, sharedK); // default Cal3_S2 poses namespace vanillaPose2 { typedef PinholePose Camera; -typedef SmartProjectionFactor SmartFactor; +typedef SmartProjectionPoseFactor SmartFactor; static Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); Camera level_camera(level_pose, sharedK2); Camera level_camera_right(pose_right, sharedK2); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 14e15f6c9..a540ccb52 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -89,7 +89,7 @@ TEST( SmartProjectionPoseFactor, Equals ) { } /* *************************************************************************/ -TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { +TEST( SmartProjectionPoseFactor, noiseless ) { using namespace vanillaPose; @@ -101,9 +101,9 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { factor.add(level_uv, x1, model); factor.add(level_uv_right, x2, model); - Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + Values values; // it's a pose factor, hence these are poses + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); double actualError = factor.error(values); double expectedError = 0.0; @@ -157,10 +157,10 @@ TEST( SmartProjectionPoseFactor, noisy ) { Point2 level_uv_right = level_camera_right.project(landmark1); Values values; - values.insert(x1, cam1); + values.insert(x1, cam1.pose()); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); - values.insert(x2, Camera(pose_right.compose(noise_pose), sharedK)); + values.insert(x2, pose_right.compose(noise_pose)); SmartFactor::shared_ptr factor(new SmartFactor((sharedK))); factor->add(level_uv, x1, model); @@ -276,6 +276,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ EXPECT(assert_equal(bodyPose3,result.at(x3))); } +#if 0 /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { @@ -292,13 +293,13 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { views.push_back(x2); views.push_back(x3); - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(sharedK2)); smartFactor1->add(measurements_cam1, views, model); - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + SmartFactor::shared_ptr smartFactor2(new SmartFactor(sharedK2)); smartFactor2->add(measurements_cam2, views, model); - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + SmartFactor::shared_ptr smartFactor3(new SmartFactor(sharedK2)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -967,13 +968,11 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac double rankTol = 50; SmartFactor::shared_ptr smartFactor1( - new SmartFactor(gtsam::HESSIAN, rankTol, - gtsam::HANDLE_INFINITY)); + new SmartFactor(sharedK2, rankTol, -1.0, gtsam::HANDLE_INFINITY)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(gtsam::HESSIAN, rankTol, - gtsam::HANDLE_INFINITY)); + new SmartFactor(sharedK2, rankTol, -1.0, gtsam::HANDLE_INFINITY)); smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1121,7 +1120,7 @@ TEST( SmartProjectionPoseFactor, Hessian ) { measurements_cam1.push_back(cam1_uv1); measurements_cam1.push_back(cam2_uv1); - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(sharedK2)); smartFactor1->add(measurements_cam1, views, model); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), @@ -1210,7 +1209,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { vector measurements_cam1; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - SmartFactor::shared_ptr smartFactor(new SmartFactor()); + SmartFactor::shared_ptr smartFactor(new SmartFactor(sharedK2)); smartFactor->add(measurements_cam1, views, model); Values values; @@ -1405,6 +1404,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3).pose())); } +#endif /* ************************************************************************* */ int main() { From 100016e3af9377ca4b0dbff2c587295e175bc2a3 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 10:39:59 -0400 Subject: [PATCH 159/173] put sensor_T_body in SmartProjectionFactor --- gtsam/slam/SmartProjectionFactor.h | 19 +++++++++++++++++-- gtsam/slam/SmartProjectionPoseFactor.h | 16 +++------------- 2 files changed, 20 insertions(+), 15 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index b5b325bfe..92c9a7660 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -74,6 +74,10 @@ protected: const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) /// @} + /// @name Pose of the camera in the body frame + const boost::optional body_P_sensor_; ///< Pose of the camera in the body frame + /// @} + public: /// shorthand for a smart pointer to a factor @@ -94,14 +98,16 @@ public: double rankTolerance = 1, DegeneracyMode degeneracyMode = IGNORE_DEGENERACY, bool enableEPI = false, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1) : + double dynamicOutlierRejectionThreshold = -1, + boost::optional body_P_sensor = boost::none) : linearizationMode_(linearizationMode), // degeneracyMode_(degeneracyMode), // parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), // result_(TriangulationResult::Degenerate()), // retriangulationThreshold_(1e-5), // - throwCheirality_(false), verboseCheirality_(false) { + throwCheirality_(false), verboseCheirality_(false), + body_P_sensor_(body_P_sensor){ } /** Virtual destructor */ @@ -119,6 +125,8 @@ public: std::cout << "linearizationMode:\n" << linearizationMode_ << std::endl; std::cout << "triangulationParameters:\n" << parameters_ << std::endl; std::cout << "result:\n" << result_ << std::endl; + if(body_P_sensor_) + body_P_sensor_->print("body_P_sensor_:\n"); Base::print("", keyFormatter); } @@ -468,6 +476,13 @@ public: return throwCheirality_; } + Pose3 body_P_sensor() const{ + if(body_P_sensor_) + return *body_P_sensor_; + else + return Pose3(); // if unspecified, the transformation is the identity + } + private: /// Serialization function diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 275056735..9a47bd34f 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -49,7 +49,6 @@ private: protected: boost::shared_ptr K_; ///< calibration object (one for all cameras) - boost::optional body_P_sensor_; ///< Pose of the camera in the body frame public: @@ -71,7 +70,7 @@ public: LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1) : Base(linearizeTo, rankTol, manageDegeneracy, enableEPI, landmarkDistanceThreshold, - dynamicOutlierRejectionThreshold), K_(K), body_P_sensor_(body_P_sensor) {} + dynamicOutlierRejectionThreshold, body_P_sensor), K_(K) {} /** Virtual destructor */ virtual ~SmartProjectionPoseFactor() {} @@ -84,8 +83,6 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionPoseFactor, z = \n "; - if(body_P_sensor_) - body_P_sensor_->print("body_P_sensor_:\n"); Base::print("", keyFormatter); } @@ -129,13 +126,6 @@ public: return K_; } - Pose3 body_P_sensor() const{ - if(body_P_sensor_) - return *body_P_sensor_; - else - return Pose3(); // if unspecified, the transformation is the identity - } - /** * Collect all cameras involved in this factor * @param values Values structure which must contain camera poses corresponding @@ -146,8 +136,8 @@ public: typename Base::Cameras cameras; BOOST_FOREACH(const Key& k, this->keys_) { Pose3 pose = values.at(k); - if(body_P_sensor_) - pose = pose.compose(*(body_P_sensor_)); + if(Base::body_P_sensor_) + pose = pose.compose(*(Base::body_P_sensor_)); Camera camera(pose, K_); cameras.push_back(camera); From fb7bc12c84c939ed07b68dceb2ab73bdf24cd1ac Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 11:42:51 -0400 Subject: [PATCH 160/173] most unit tests fixed - 2 to go, now sensor_T_body is in the base class, probably not the best choice --- gtsam/slam/SmartFactorBase.h | 30 ++- gtsam/slam/SmartProjectionFactor.h | 18 +- .../tests/testSmartProjectionPoseFactor.cpp | 220 ++++++++---------- 3 files changed, 131 insertions(+), 137 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index e651244af..870f4d5db 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -58,7 +58,6 @@ private: SharedIsotropic noiseModel_; protected: - /** * 2D measurement and noise model for each of the m views * We keep a copy of measurements for I/O and computing the error. @@ -66,6 +65,10 @@ protected: */ std::vector measured_; + /// @name Pose of the camera in the body frame + const boost::optional body_P_sensor_; ///< Pose of the camera in the body frame + /// @} + static const int Dim = traits::dimension; ///< Camera dimension static const int ZDim = traits::dimension; ///< Measurement dimension @@ -105,6 +108,10 @@ public: /// We use the new CameraSte data structure to refer to a set of cameras typedef CameraSet Cameras; + /// Constructor + SmartFactorBase(boost::optional body_P_sensor = boost::none) : + body_P_sensor_(body_P_sensor){} + /// Virtual destructor, subclasses from NonlinearFactor virtual ~SmartFactorBase() { } @@ -189,6 +196,8 @@ public: std::cout << "measurement, p = " << measured_[k] << "\t"; noiseModel_->print("noise model = "); } + if(body_P_sensor_) + body_P_sensor_->print("body_P_sensor_:\n"); print("", keyFormatter); } @@ -210,7 +219,16 @@ public: Vector unwhitenedError(const Cameras& cameras, const POINT& point, boost::optional Fs = boost::none, // boost::optional E = boost::none) const { - return cameras.reprojectionError(point, measured_, Fs, E); + Vector ue = cameras.reprojectionError(point, measured_, Fs, E); + if(body_P_sensor_){ + for(size_t i=0; i < Fs->size(); i++){ + Pose3 w_Pose_body = (cameras[i].pose()).compose(body_P_sensor_->inverse()); + Matrix J(6, 6); + Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); + Fs->at(i) = Fs->at(i) * J; + } + } + return ue; } /** @@ -375,6 +393,14 @@ public: F.block(ZDim * i, Dim * i) = Fblocks.at(i); } + + Pose3 body_P_sensor() const{ + if(body_P_sensor_) + return *body_P_sensor_; + else + return Pose3(); // if unspecified, the transformation is the identity + } + private: /// Serialization function diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 92c9a7660..9cb9855c8 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -74,10 +74,6 @@ protected: const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) /// @} - /// @name Pose of the camera in the body frame - const boost::optional body_P_sensor_; ///< Pose of the camera in the body frame - /// @} - public: /// shorthand for a smart pointer to a factor @@ -100,15 +96,14 @@ public: double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1, boost::optional body_P_sensor = boost::none) : + Base(body_P_sensor), linearizationMode_(linearizationMode), // degeneracyMode_(degeneracyMode), // parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), // result_(TriangulationResult::Degenerate()), // retriangulationThreshold_(1e-5), // - throwCheirality_(false), verboseCheirality_(false), - body_P_sensor_(body_P_sensor){ - } + throwCheirality_(false), verboseCheirality_(false) {} /** Virtual destructor */ virtual ~SmartProjectionFactor() { @@ -125,8 +120,6 @@ public: std::cout << "linearizationMode:\n" << linearizationMode_ << std::endl; std::cout << "triangulationParameters:\n" << parameters_ << std::endl; std::cout << "result:\n" << result_ << std::endl; - if(body_P_sensor_) - body_P_sensor_->print("body_P_sensor_:\n"); Base::print("", keyFormatter); } @@ -476,13 +469,6 @@ public: return throwCheirality_; } - Pose3 body_P_sensor() const{ - if(body_P_sensor_) - return *body_P_sensor_; - else - return Pose3(); // if unspecified, the transformation is the identity - } - private: /// Serialization function diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index a540ccb52..ffd8008ec 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -270,13 +270,9 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - // result.at(x3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(bodyPose3,result.at(x3))); } -#if 0 /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { @@ -308,39 +304,34 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); Values groundTruth; - groundTruth.insert(x1, cam1); - groundTruth.insert(x2, cam2); - groundTruth.insert(x3, cam3); + groundTruth.insert(x1, cam1.pose()); + groundTruth.insert(x2, cam2.pose()); + groundTruth.insert(x3, cam3.pose()); DOUBLES_EQUAL(0, graph.error(groundTruth), 1e-9); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose, sharedK2)); + values.insert(x3, pose_above * noise_pose); EXPECT( assert_equal( Pose3( Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), - Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); + Point3(0.1, -0.1, 1.9)), values.at(x3))); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - -// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); -// VectorValues delta = GFG->optimize(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ @@ -541,31 +532,29 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose, sharedK)); + values.insert(x3, pose_above * noise_pose); EXPECT( assert_equal( Pose3( Rot3(1.11022302e-16, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), Point3(0.1, -0.1, 1.9)), - values.at(x3).pose())); + values.at(x3))); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-7)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); } /* *************************************************************************/ @@ -603,21 +592,21 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); - values.insert(x3, Camera(pose_above * noise_pose, sharedK)); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, pose_above * noise_pose); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ @@ -660,22 +649,22 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); - values.insert(x3, Camera(pose_above * noise_pose, sharedK)); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, pose_above * noise_pose); // All factors are disabled and pose should remain where it is Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(values.at(x3), result.at(x3))); + EXPECT(assert_equal(values.at(x3), result.at(x3))); } /* *************************************************************************/ @@ -731,19 +720,19 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(smartFactor4); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); - values.insert(x3, cam3); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, cam3.pose()); // All factors are disabled and pose should remain where it is Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(cam3, result.at(x3))); + EXPECT(assert_equal(cam3.pose(), result.at(x3))); } /* *************************************************************************/ @@ -766,7 +755,6 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { SmartFactor::shared_ptr smartFactor1( new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_Q)); - smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( @@ -785,20 +773,20 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); - values.insert(x3, Camera(pose_above * noise_pose, sharedK)); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, pose_above * noise_pose); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT(assert_equal(pose_above, result.at(x3).pose(), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ @@ -907,10 +895,10 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose3 * noise_pose, sharedK)); + values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( Pose3( @@ -918,7 +906,7 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { -0.130426831, -0.0115837907, 0.130819108, -0.98278564, -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), - values.at(x3).pose())); + values.at(x3))); boost::shared_ptr factor1 = smartFactor1->linearize(values); boost::shared_ptr factor2 = smartFactor2->linearize(values); @@ -938,14 +926,13 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { + factor2->augmentedInformation() + factor3->augmentedInformation(); // Check Information vector - // cout << AugInformationMatrix.size() << endl; Vector InfoVector = AugInformationMatrix.block(0, 18, 18, 1); // 18x18 Hessian + information vector // Check Hessian EXPECT(assert_equal(InfoVector, GaussianGraph->hessian().second, 1e-8)); } -/* *************************************************************************/ +/* ************************************************************************* TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ) { using namespace vanillaPose2; @@ -976,26 +963,25 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, - 0.10); + const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); Point3 positionPrior = Point3(0, 0, 1); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back( - PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( - PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, Camera(pose2 * noise_pose, sharedK2)); + values.insert(x1, cam1.pose()); + values.insert(x2, pose2 * noise_pose); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose3 * noise_pose * noise_pose, sharedK2)); + values.insert(x3, pose3 * noise_pose * noise_pose); EXPECT( assert_equal( Pose3( @@ -1003,7 +989,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac -0.572308662, -0.324093872, 0.639358349, -0.521617766, -0.564921063), Point3(0.145118171, -0.252907438, 0.819956033)), - values.at(x3).pose())); + values.at(x3))); Values result; params.verbosityLM = LevenbergMarquardtParams::SUMMARY; @@ -1017,10 +1003,10 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac -0.572308662, -0.324093872, 0.639358349, -0.521617766, -0.564921063), Point3(0.145118171, -0.252907438, 0.819956033)), - result.at(x3).pose())); + result.at(x3))); } -/* *************************************************************************/ +/* ************************************************************************* TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) { using namespace vanillaPose; @@ -1067,20 +1053,20 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back( - PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( - PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose3 * noise_pose, sharedK)); + values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( Pose3( @@ -1088,7 +1074,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) -0.130426831, -0.0115837907, 0.130819108, -0.98278564, -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), - values.at(x3).pose())); + values.at(x3))); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); @@ -1101,7 +1087,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) -0.130426831, -0.0115837907, 0.130819108, -0.98278564, -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), - result.at(x3).pose())); + result.at(x3))); } /* *************************************************************************/ @@ -1126,8 +1112,8 @@ TEST( SmartProjectionPoseFactor, Hessian ) { Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); boost::shared_ptr factor = smartFactor1->linearize(values); @@ -1156,9 +1142,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { smartFactorInstance->add(measurements_cam1, views, model); Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); - values.insert(x3, cam3); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, cam3.pose()); boost::shared_ptr factor = smartFactorInstance->linearize( values); @@ -1166,9 +1152,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, Camera(poseDrift.compose(level_pose), sharedK)); - rotValues.insert(x2, Camera(poseDrift.compose(pose_right), sharedK)); - rotValues.insert(x3, Camera(poseDrift.compose(pose_above), sharedK)); + rotValues.insert(x1, poseDrift.compose(level_pose)); + rotValues.insert(x2, poseDrift.compose(pose_right)); + rotValues.insert(x3, poseDrift.compose(pose_above)); boost::shared_ptr factorRot = smartFactorInstance->linearize( rotValues); @@ -1180,16 +1166,15 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, Camera(poseDrift2.compose(level_pose), sharedK)); - tranValues.insert(x2, Camera(poseDrift2.compose(pose_right), sharedK)); - tranValues.insert(x3, Camera(poseDrift2.compose(pose_above), sharedK)); + tranValues.insert(x1, poseDrift2.compose(level_pose)); + tranValues.insert(x2, poseDrift2.compose(pose_right)); + tranValues.insert(x3, poseDrift2.compose(pose_above)); boost::shared_ptr factorRotTran = smartFactorInstance->linearize(tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT( - assert_equal(factor->information(), factorRotTran->information(), 1e-7)); + EXPECT(assert_equal(factor->information(), factorRotTran->information(), 1e-7)); } /* *************************************************************************/ @@ -1213,18 +1198,18 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { smartFactor->add(measurements_cam1, views, model); Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); - values.insert(x3, cam3); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, cam3.pose()); boost::shared_ptr factor = smartFactor->linearize(values); Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, Camera(poseDrift.compose(level_pose), sharedK2)); - rotValues.insert(x2, Camera(poseDrift.compose(level_pose), sharedK2)); - rotValues.insert(x3, Camera(poseDrift.compose(level_pose), sharedK2)); + rotValues.insert(x1, poseDrift.compose(level_pose)); + rotValues.insert(x2, poseDrift.compose(level_pose)); + rotValues.insert(x3, poseDrift.compose(level_pose)); boost::shared_ptr factorRot = // smartFactor->linearize(rotValues); @@ -1236,16 +1221,15 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, Camera(poseDrift2.compose(level_pose), sharedK2)); - tranValues.insert(x2, Camera(poseDrift2.compose(level_pose), sharedK2)); - tranValues.insert(x3, Camera(poseDrift2.compose(level_pose), sharedK2)); + tranValues.insert(x1, poseDrift2.compose(level_pose)); + tranValues.insert(x2, poseDrift2.compose(level_pose)); + tranValues.insert(x3, poseDrift2.compose(level_pose)); boost::shared_ptr factorRotTran = smartFactor->linearize( tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT( - assert_equal(factor->information(), factorRotTran->information(), 1e-7)); + EXPECT(assert_equal(factor->information(), factorRotTran->information(), 1e-7)); } /* ************************************************************************* */ @@ -1290,29 +1274,28 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); - graph.push_back(PriorFactor(x2, cam2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose_above * noise_pose, sharedBundlerK)); + values.insert(x3, pose_above * noise_pose); EXPECT( assert_equal( Pose3( Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), - Point3(0.1, -0.1, 1.9)), values.at(x3).pose())); + Point3(0.1, -0.1, 1.9)), values.at(x3))); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - - EXPECT(assert_equal(cam3, result.at(x3), 1e-6)); + EXPECT(assert_equal(cam3.pose(), result.at(x3), 1e-6)); } /* *************************************************************************/ @@ -1368,20 +1351,20 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, cam1, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back( - PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( - PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, cam1); - values.insert(x2, cam2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, Camera(pose3 * noise_pose, sharedBundlerK)); + values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( Pose3( @@ -1389,7 +1372,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { -0.130426831, -0.0115837907, 0.130819108, -0.98278564, -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), - values.at(x3).pose())); + values.at(x3))); Values result; LevenbergMarquardtOptimizer optimizer(graph, values, params); @@ -1402,9 +1385,8 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { -0.130426831, -0.0115837907, 0.130819108, -0.98278564, -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), - values.at(x3).pose())); + values.at(x3))); } -#endif /* ************************************************************************* */ int main() { From 78c8160dc526e4f461fe05cef22d8413c86050e5 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 12:06:45 -0400 Subject: [PATCH 161/173] all tests pass and it compiles (yuppii!), but if I make check I get errors with isManifold and something that seems unrelated to smart factors. going to merge with develop --- .../tests/testSmartProjectionPoseFactor.cpp | 51 +++++-------------- .../examples/SmartProjectionFactorExample.cpp | 12 ++--- 2 files changed, 20 insertions(+), 43 deletions(-) diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index ffd8008ec..5f6c2fee3 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -932,7 +932,7 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { EXPECT(assert_equal(InfoVector, GaussianGraph->hessian().second, 1e-8)); } -/* ************************************************************************* +/* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ) { using namespace vanillaPose2; @@ -941,13 +941,13 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac views.push_back(x2); views.push_back(x3); - // Two different cameras + // Two different cameras, at the same position, but different rotations Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3()); Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3()); Camera cam2(pose2, sharedK2); Camera cam3(pose3, sharedK2); - vector measurements_cam1, measurements_cam2, measurements_cam3; + vector measurements_cam1, measurements_cam2; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -975,38 +975,20 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac graph.push_back( PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); values.insert(x2, pose2 * noise_pose); - // initialize third pose with some noise, we expect it to move back to original pose_above - values.insert(x3, pose3 * noise_pose * noise_pose); - EXPECT( - assert_equal( - Pose3( - Rot3(0.154256096, -0.632754061, 0.75883289, -0.753276814, - -0.572308662, -0.324093872, 0.639358349, -0.521617766, - -0.564921063), - Point3(0.145118171, -0.252907438, 0.819956033)), - values.at(x3))); + values.insert(x3, pose3 * noise_pose); - Values result; - params.verbosityLM = LevenbergMarquardtParams::SUMMARY; + // params.verbosityLM = LevenbergMarquardtParams::SUMMARY; LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - - EXPECT( - assert_equal( - Pose3( - Rot3(0.154256096, -0.632754061, 0.75883289, -0.753276814, - -0.572308662, -0.324093872, 0.639358349, -0.521617766, - -0.564921063), - Point3(0.145118171, -0.252907438, 0.819956033)), - result.at(x3))); + Values result = optimizer.optimize(); + EXPECT(assert_equal(pose3, result.at(x3))); } -/* ************************************************************************* +/* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) { using namespace vanillaPose; @@ -1016,7 +998,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) views.push_back(x2); views.push_back(x3); - // Two different cameras + // 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)); Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); @@ -1065,7 +1047,6 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) Values values; values.insert(x1, cam1.pose()); values.insert(x2, cam2.pose()); - // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( @@ -1080,14 +1061,10 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) LevenbergMarquardtOptimizer optimizer(graph, values, params); result = optimizer.optimize(); - EXPECT( - assert_equal( - Pose3( - Rot3(0.00563056869, -0.130848107, 0.991386438, -0.991390265, - -0.130426831, -0.0115837907, 0.130819108, -0.98278564, - -0.130455917), - Point3(0.0897734171, -0.110201006, 0.901022872)), - result.at(x3))); + // Since we do not do anything on degenerate instances (ZERO_ON_DEGENERACY) + // rotation remains the same as the initial guess, but position is fixed by PoseTranslationPrior + EXPECT(assert_equal(Pose3(values.at(x3).rotation(), + Point3(0,0,1)), result.at(x3))); } /* *************************************************************************/ diff --git a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp index 9e8523ebb..e00dcee57 100644 --- a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp @@ -73,7 +73,7 @@ int main(int argc, char** argv){ while (pose_file >> i) { for (int i = 0; i < 16; i++) pose_file >> m.data()[i]; - initial_estimate.insert(i, Camera(Pose3(m),K)); + initial_estimate.insert(i, Pose3(m)); } // landmark keys @@ -87,24 +87,24 @@ int main(int argc, char** argv){ //read stereo measurements and construct smart factors - SmartFactor::shared_ptr factor(new SmartFactor()); + SmartFactor::shared_ptr factor(new SmartFactor(K)); size_t current_l = 3; // hardcoded landmark ID from first measurement while (factor_file >> i >> l >> uL >> uR >> v >> X >> Y >> Z) { if(current_l != l) { graph.push_back(factor); - factor = SmartFactor::shared_ptr(new SmartFactor()); + factor = SmartFactor::shared_ptr(new SmartFactor(K)); current_l = l; } factor->add(Point2(uL,v), i, model); } - Camera firstCamera = initial_estimate.at(1); + Pose3 firstPose = initial_estimate.at(1); //constrain the first pose such that it cannot change from its original value during optimization // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky // QR is much slower than Cholesky, but numerically more stable - graph.push_back(NonlinearEquality(1,firstCamera)); + graph.push_back(NonlinearEquality(1,firstPose)); LevenbergMarquardtParams params; params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; @@ -116,7 +116,7 @@ int main(int argc, char** argv){ Values result = optimizer.optimize(); cout << "Final result sample:" << endl; - Values pose_values = result.filter(); + Values pose_values = result.filter(); pose_values.print("Final camera poses:\n"); return 0; From 917e7c177d4a6b82445ac777b1418404331e2fed Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 13:10:34 -0400 Subject: [PATCH 162/173] fixed examples --- examples/SFMExample_SmartFactor.cpp | 2 +- examples/SFMExample_SmartFactorPCG.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/SFMExample_SmartFactor.cpp b/examples/SFMExample_SmartFactor.cpp index cd6024e6c..97d646552 100644 --- a/examples/SFMExample_SmartFactor.cpp +++ b/examples/SFMExample_SmartFactor.cpp @@ -58,7 +58,7 @@ int main(int argc, char* argv[]) { for (size_t j = 0; j < points.size(); ++j) { // every landmark represent a single landmark, we use shared pointer to init the factor, and then insert measurements. - SmartFactor::shared_ptr smartfactor(new SmartFactor()); + SmartFactor::shared_ptr smartfactor(new SmartFactor(K)); for (size_t i = 0; i < poses.size(); ++i) { diff --git a/examples/SFMExample_SmartFactorPCG.cpp b/examples/SFMExample_SmartFactorPCG.cpp index 27ef7b9cc..c1b18a946 100644 --- a/examples/SFMExample_SmartFactorPCG.cpp +++ b/examples/SFMExample_SmartFactorPCG.cpp @@ -54,7 +54,7 @@ int main(int argc, char* argv[]) { for (size_t j = 0; j < points.size(); ++j) { // every landmark represent a single landmark, we use shared pointer to init the factor, and then insert measurements. - SmartFactor::shared_ptr smartfactor(new SmartFactor()); + SmartFactor::shared_ptr smartfactor(new SmartFactor(K)); for (size_t i = 0; i < poses.size(); ++i) { From f1e5c61762f8346bf5a17644202bae91669f35a7 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 13:10:42 -0400 Subject: [PATCH 163/173] adding parameter structure --- gtsam/slam/SmartProjectionFactor.h | 115 +++++++++++++++++++---------- 1 file changed, 77 insertions(+), 38 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 9cb9855c8..9c206bdd5 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -41,6 +41,65 @@ enum DegeneracyMode { IGNORE_DEGENERACY, ZERO_ON_DEGENERACY, HANDLE_INFINITY }; +/* + * Parameters for the smart projection factors + */ +class GTSAM_EXPORT SmartProjectionFactorParams { + +public: + + const LinearizationMode linearizationMode; ///< How to linearize the factor + const DegeneracyMode degeneracyMode; ///< How to linearize the factor + + /// @name Parameters governing the triangulation + /// @{ + const TriangulationParameters triangulationParameters; + const double retriangulationThreshold; ///< threshold to decide whether to re-triangulate + /// @} + + /// @name Parameters governing how triangulation result is treated + /// @{ + const bool throwCheirality; ///< If true, re-throws Cheirality exceptions (default: false) + const bool verboseCheirality; ///< If true, prints text for Cheirality exceptions (default: false) + /// @} + + // Constructor + SmartProjectionFactorParams(LinearizationMode linMode = HESSIAN, + DegeneracyMode degMode = IGNORE_DEGENERACY, double rankTol = 1, + bool enableEPI = false, double landmarkDistanceThreshold = 1e10, + double dynamicOutlierRejectionThreshold = -1): + linearizationMode(linMode), degeneracyMode(degMode), + triangulationParameters(rankTol, enableEPI, + landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), + retriangulationThreshold(1e-5), + throwCheirality(false), verboseCheirality(false) {} + + virtual ~SmartProjectionFactorParams() {} + + void print(const std::string& str) const { + std::cout << " linearizationMode: " << linearizationMode << "\n"; + std::cout << " degeneracyMode: " << degeneracyMode << "\n"; + std::cout << " rankTolerance: " << triangulationParameters.rankTolerance << "\n"; + std::cout << " enableEPI: " << triangulationParameters.enableEPI << "\n"; + std::cout << " landmarkDistanceThreshold: " << triangulationParameters.landmarkDistanceThreshold << "\n"; + std::cout << " OutlierRejectionThreshold: " << triangulationParameters.dynamicOutlierRejectionThreshold << "\n"; + std::cout.flush(); + } + + inline LinearizationMode getLinearizationMode() const { + return linearizationMode; + } + /** return cheirality verbosity */ + inline bool getVerboseCheirality() const { + return verboseCheirality; + } + /** return flag for throwing cheirality exceptions */ + inline bool getThrowCheirality() const { + return throwCheirality; + } + +}; + /** * SmartProjectionFactor: triangulates point and keeps an estimate of it around. */ @@ -56,24 +115,17 @@ private: protected: - LinearizationMode linearizationMode_; ///< How to linearize the factor - DegeneracyMode degeneracyMode_; ///< How to linearize the factor + /// @name Parameters + /// @{ + const SmartProjectionFactorParams params_; + /// @} /// @name Caching triangulation /// @{ - const TriangulationParameters parameters_; mutable TriangulationResult result_; ///< result from triangulateSafe - - const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses /// @} - /// @name Parameters governing how triangulation result is treated - /// @{ - const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) - const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) - /// @} - public: /// shorthand for a smart pointer to a factor @@ -97,13 +149,10 @@ public: double dynamicOutlierRejectionThreshold = -1, boost::optional body_P_sensor = boost::none) : Base(body_P_sensor), - linearizationMode_(linearizationMode), // - degeneracyMode_(degeneracyMode), // - parameters_(rankTolerance, enableEPI, landmarkDistanceThreshold, - dynamicOutlierRejectionThreshold), // - result_(TriangulationResult::Degenerate()), // - retriangulationThreshold_(1e-5), // - throwCheirality_(false), verboseCheirality_(false) {} + params_(linearizationMode, degeneracyMode, + rankTolerance, enableEPI, landmarkDistanceThreshold, + dynamicOutlierRejectionThreshold), // + result_(TriangulationResult::Degenerate()) {} /** Virtual destructor */ virtual ~SmartProjectionFactor() { @@ -117,8 +166,8 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionFactor\n"; - std::cout << "linearizationMode:\n" << linearizationMode_ << std::endl; - std::cout << "triangulationParameters:\n" << parameters_ << std::endl; + std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl; + std::cout << "triangulationParameters:\n" << params_.triangulationParameters << std::endl; std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); } @@ -126,7 +175,7 @@ public: /// equals virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { const This *e = dynamic_cast(&p); - return e && linearizationMode_ == e->linearizationMode_ + return e && params_.linearizationMode == e->params_.linearizationMode && Base::equals(p, tol); } @@ -148,7 +197,7 @@ public: if (!retriangulate) { for (size_t i = 0; i < cameras.size(); i++) { if (!cameras[i].pose().equals(cameraPosesTriangulation_[i], - retriangulationThreshold_)) { + params_.retriangulationThreshold)) { retriangulate = true; // at least two poses are different, hence we retriangulate break; } @@ -175,7 +224,7 @@ public: bool retriangulate = decideIfTriangulate(cameras); if (retriangulate) - result_ = gtsam::triangulateSafe(cameras, this->measured_, parameters_); + result_ = gtsam::triangulateSafe(cameras, this->measured_, params_.triangulationParameters); return result_; } @@ -205,7 +254,7 @@ public: triangulateSafe(cameras); - if (degeneracyMode_ == ZERO_ON_DEGENERACY && !result_) { + if (params_.degeneracyMode == ZERO_ON_DEGENERACY && !result_) { // failed: return"empty" Hessian BOOST_FOREACH(Matrix& m, Gs) m = zeros(Base::Dim, Base::Dim); @@ -294,7 +343,7 @@ public: boost::shared_ptr linearizeDamped(const Cameras& cameras, const double lambda = 0.0) const { // depending on flag set on construction we may linearize to different linear factors - switch (linearizationMode_) { + switch (params_.linearizationMode) { case HESSIAN: return createHessianFactor(cameras, lambda); case IMPLICIT_SCHUR: @@ -414,7 +463,7 @@ public: if (result_) // All good, just use version in base class return Base::totalReprojectionError(cameras, *result_); - else if (degeneracyMode_ == HANDLE_INFINITY) { + else if (params_.degeneracyMode == HANDLE_INFINITY) { // Otherwise, manage the exceptions with rotation-only factors const Point2& z0 = this->measured_.at(0); Unit3 backprojected = cameras.front().backprojectPointAtInfinity(z0); @@ -459,16 +508,6 @@ public: return result_.behindCamera(); } - /** return cheirality verbosity */ - inline bool verboseCheirality() const { - return verboseCheirality_; - } - - /** return flag for throwing cheirality exceptions */ - inline bool throwCheirality() const { - return throwCheirality_; - } - private: /// Serialization function @@ -476,8 +515,8 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(throwCheirality_); - ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); + ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality); + ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality); } } ; From dcce21639f7d1e28e98884689fc6f0ed558b4e66 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 14:59:33 -0400 Subject: [PATCH 164/173] included new constructors (still commented out) --- gtsam/slam/SmartProjectionFactor.h | 19 +++++++++++++++---- gtsam/slam/SmartProjectionPoseFactor.h | 11 +++++++++++ 2 files changed, 26 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 9c206bdd5..7ac2a03be 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -44,7 +44,7 @@ enum DegeneracyMode { /* * Parameters for the smart projection factors */ -class GTSAM_EXPORT SmartProjectionFactorParams { +class GTSAM_EXPORT SmartProjectionParams { public: @@ -64,7 +64,7 @@ public: /// @} // Constructor - SmartProjectionFactorParams(LinearizationMode linMode = HESSIAN, + SmartProjectionParams(LinearizationMode linMode = HESSIAN, DegeneracyMode degMode = IGNORE_DEGENERACY, double rankTol = 1, bool enableEPI = false, double landmarkDistanceThreshold = 1e10, double dynamicOutlierRejectionThreshold = -1): @@ -74,7 +74,7 @@ public: retriangulationThreshold(1e-5), throwCheirality(false), verboseCheirality(false) {} - virtual ~SmartProjectionFactorParams() {} + virtual ~SmartProjectionParams() {} void print(const std::string& str) const { std::cout << " linearizationMode: " << linearizationMode << "\n"; @@ -117,7 +117,7 @@ protected: /// @name Parameters /// @{ - const SmartProjectionFactorParams params_; + const SmartProjectionParams params_; /// @} /// @name Caching triangulation @@ -154,6 +154,17 @@ public: dynamicOutlierRejectionThreshold), // result_(TriangulationResult::Degenerate()) {} + /** + * Constructor + * @param body_P_sensor pose of the camera in the body frame + * @param params internal parameters of the smart factors + */ +// SmartProjectionFactor(const boost::optional body_P_sensor = boost::none, +// const SmartProjectionParams params = SmartProjectionParams()) : +// Base(body_P_sensor), +// params_(params), // +// result_(TriangulationResult::Degenerate()) {} + /** Virtual destructor */ virtual ~SmartProjectionFactor() { } diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 9a47bd34f..fbd9e1ca6 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -72,6 +72,17 @@ public: Base(linearizeTo, rankTol, manageDegeneracy, enableEPI, landmarkDistanceThreshold, dynamicOutlierRejectionThreshold, body_P_sensor), K_(K) {} + /** + * Constructor + * @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 + */ +// SmartProjectionPoseFactor(const boost::shared_ptr K, +// const boost::optional body_P_sensor = boost::none, +// const SmartProjectionParams params = SmartProjectionParams()) : +// Base(body_P_sensor, params), K_(K) {} + /** Virtual destructor */ virtual ~SmartProjectionPoseFactor() {} From 2d9fddbcaa5687c0e1e4469b6f5a49b9dc683c14 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 15:33:18 -0400 Subject: [PATCH 165/173] made cameras virtual and simplified pose factor (with Frank) --- gtsam/slam/SmartFactorBase.h | 6 +++--- gtsam/slam/SmartProjectionPoseFactor.h | 27 -------------------------- 2 files changed, 3 insertions(+), 30 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 870f4d5db..ba38a65d9 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -142,7 +142,7 @@ public: } /** - * Add a bunch of measurements and uses the same noise model for all of them + * Add a bunch of measurements and use the same noise model for all of them */ void add(std::vector& measurements, std::vector& cameraKeys, const SharedNoiseModel& noise) { @@ -177,7 +177,7 @@ public: } /// Collect all cameras: important that in key order - Cameras cameras(const Values& values) const { + virtual Cameras cameras(const Values& values) const { Cameras cameras; BOOST_FOREACH(const Key& k, this->keys_) cameras.push_back(values.at(k)); @@ -214,7 +214,7 @@ public: return e && Base::equals(p, tol) && areMeasurementsEqual; } - ///Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives + /// 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, // diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index fbd9e1ca6..e089e6f4f 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -103,24 +103,6 @@ public: return e && Base::equals(p, tol); } - /** - * Linearize to Gaussian Factor - * @param values Values structure which must contain camera poses for this factor - * @return a Gaussian factor - */ - boost::shared_ptr linearizeDamped(const Values& values, - const double lambda = 0.0) const { - // depending on flag set on construction we may linearize to different linear factors - typename Base::Cameras cameras = this->cameras(values); - return Base::linearizeDamped(cameras, lambda); - } - - /// linearize - virtual boost::shared_ptr linearize( - const Values& values) const { - return linearizeDamped(values); - } - /** * error calculates the error of the factor. */ @@ -156,15 +138,6 @@ public: return cameras; } - /** - * Triangulate and compute derivative of error with respect to point - * @return whether triangulation worked - */ - bool triangulateAndComputeE(Matrix& E, const Values& values) const { - typename Base::Cameras cameras = this->cameras(values); - return Base::triangulateAndComputeE(E, cameras); - } - private: /// Serialization function From cd6c5ca0bd32a18899efd0510cd12303790c1180 Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 19 Jun 2015 18:09:39 -0400 Subject: [PATCH 166/173] using parameters in smart projection factors constructors.. breaking the API, but now is way more elegant --- .cproject | 3534 ++++++++--------- gtsam/geometry/triangulation.h | 8 +- gtsam/slam/SmartProjectionFactor.h | 71 +- gtsam/slam/SmartProjectionPoseFactor.h | 25 +- gtsam/slam/tests/smartFactorScenarios.h | 1 + .../tests/testSmartProjectionCameraFactor.cpp | 81 +- .../tests/testSmartProjectionPoseFactor.cpp | 152 +- 7 files changed, 1945 insertions(+), 1927 deletions(-) diff --git a/.cproject b/.cproject index fa20e5794..2051b74fb 100644 --- a/.cproject +++ b/.cproject @@ -1,17 +1,19 @@ - + + + + + - - @@ -60,13 +62,13 @@ + + - - @@ -116,13 +118,13 @@ + + - - @@ -484,341 +486,6 @@ - - make - -j5 - testCombinedImuFactor.run - true - true - true - - - make - -j5 - testImuFactor.run - true - true - true - - - make - -j5 - testAHRSFactor.run - true - true - true - - - make - -j8 - testAttitudeFactor.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - testNonlinearConstraint.run - true - true - true - - - make - -j2 - testLieConfig.run - true - true - true - - - make - -j2 - testConstraintOptimizer.run - true - true - true - - - make - -j2 - testGaussianFactor.run - true - true - true - - - make - -j4 - testImuFactor.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testBTree.run - true - true - true - - - make - -j2 - testDSF.run - true - true - true - - - make - -j2 - testDSFVector.run - true - true - true - - - make - -j2 - testMatrix.run - true - true - true - - - make - -j2 - testSPQRUtil.run - true - true - true - - - make - -j2 - testVector.run - true - true - true - - - make - -j2 - timeMatrix.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - wrap - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - install - true - true - true - - - make - -j2 - all - true - true - true - - - cmake - .. - true - false - true - - - make - -j2 - check - true - true - true - - - make - -j2 - tests/testLieConfig.run - true - true - true - - - make - -j4 - testSimilarity3.run - true - true - true - - - make - -j5 - testInvDepthCamera3.run - true - true - true - - - make - -j5 - testTriangulation.run - true - true - true - - - make - -j4 - testEvent.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - all - true - false - true - - - make - -j5 - check - true - false - true - make -j5 @@ -867,183 +534,39 @@ true true - - make - -j5 - testCal3Bundler.run - true - true - true - - - make - -j5 - testCal3DS2.run - true - true - true - - - make - -j5 - testCalibratedCamera.run - true - true - true - - - make - -j5 - testEssentialMatrix.run - true - true - true - - - make - -j1 VERBOSE=1 - testHomography2.run - true - false - true - - - make - -j5 - testPinholeCamera.run - true - true - true - - - make - -j5 - testPoint2.run - true - true - true - - - make - -j5 - testPoint3.run - true - true - true - - - make - -j5 - testPose2.run - true - true - true - - - make - -j5 - testPose3.run - true - true - true - - - make - -j5 - testRot3M.run - true - true - true - - - make - -j5 - testSphere2.run - true - true - true - - - make - -j5 - testStereoCamera.run - true - true - true - - - make - -j5 - testCal3Unified.run - true - true - true - - - make - -j5 - testRot2.run - true - true - true - - - make - -j5 - testRot3Q.run - true - true - true - - - make - -j5 - testRot3.run - true - true - true - - + make -j4 - testSO3.run + testSimilarity3.run true true true - + + make + -j5 + testInvDepthCamera3.run + true + true + true + + + make + -j5 + testTriangulation.run + true + true + true + + make -j4 - testQuaternion.run + testEvent.run true true true - - make - -j4 - testOrientedPlane3.run - true - true - true - - - make - -j4 - testPinholePose.run - true - true - true - - - make - -j4 - testCyclic.run - true - true - true - - + make -j2 all @@ -1051,7 +574,7 @@ true true - + make -j2 clean @@ -1059,23 +582,137 @@ true true - + + make + -k + check + true + false + true + + + make + tests/testBayesTree.run + true + false + true + + + make + testBinaryBayesNet.run + true + false + true + + make -j2 - clean all + testFactorGraph.run true true true - + make -j2 - install + testISAM.run true true true - + + make + -j2 + testJunctionTree.run + true + true + true + + + make + -j2 + testKey.run + true + true + true + + + make + -j2 + testOrdering.run + true + true + true + + + make + testSymbolicBayesNet.run + true + false + true + + + make + tests/testSymbolicFactor.run + true + false + true + + + make + testSymbolicFactorGraph.run + true + false + true + + + make + -j2 + timeSymbolMaps.run + true + true + true + + + make + tests/testBayesTree + true + false + true + + + make + -j2 + tests/testPose2.run + true + true + true + + + make + -j2 + tests/testPose3.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + check + true + true + true + + make -j2 clean @@ -1227,143 +864,154 @@ true true - + make - -j2 - all + -j5 + testGaussianFactorGraphUnordered.run true true true - + make - -j2 - check + -j5 + testGaussianBayesNetUnordered.run true true true - + make - -j2 + -j5 + testGaussianConditional.run + true + true + true + + + make + -j5 + testGaussianDensity.run + true + true + true + + + make + -j5 + testGaussianJunctionTree.run + true + true + true + + + make + -j5 + testHessianFactor.run + true + true + true + + + make + -j5 + testJacobianFactor.run + true + true + true + + + make + -j5 + testKalmanFilter.run + true + true + true + + + make + -j5 + testNoiseModel.run + true + true + true + + + make + -j5 + testSampler.run + true + true + true + + + make + -j5 + testSerializationLinear.run + true + true + true + + + make + -j5 + testVectorValues.run + true + true + true + + + make + -j5 + testGaussianBayesTree.run + true + true + true + + + make + -j5 + testCombinedImuFactor.run + true + true + true + + + make + -j5 + testImuFactor.run + true + true + true + + + make + -j5 + testAHRSFactor.run + true + true + true + + + make + -j8 + testAttitudeFactor.run + true + true + true + + + make + -j5 clean true true true - + make - -j2 - testPlanarSLAM.run - true - true - true - - - make - -j2 - testPose2Config.run - true - true - true - - - make - -j2 - testPose2Factor.run - true - true - true - - - make - -j2 - testPose2Prior.run - true - true - true - - - make - -j2 - testPose2SLAM.run - true - true - true - - - make - -j2 - testPose3Config.run - true - true - true - - - make - -j2 - testPose3SLAM.run - true - true - true - - - make - testSimulated2DOriented.run - true - false - true - - - make - -j2 - testVSLAMConfig.run - true - true - true - - - make - -j2 - testVSLAMFactor.run - true - true - true - - - make - -j2 - testVSLAMGraph.run - true - true - true - - - make - -j2 - testPose3Factor.run - true - true - true - - - make - testSimulated2D.run - true - false - true - - - make - testSimulated3D.run - true - false - true - - - make - -j2 - tests/testGaussianISAM2 + -j5 + all true true true @@ -1458,112 +1106,479 @@ make - testErrors.run true false true - + make - -j5 - testAntiFactor.run + -j2 + check true true true - + make - -j5 - testPriorFactor.run + -j2 + tests/testGaussianJunctionTree.run true true true - + make - -j5 - testDataset.run + -j2 + tests/testGaussianFactor.run true true true - + make - -j5 - testEssentialMatrixFactor.run + -j2 + tests/testGaussianConditional.run true true true - + make - -j5 - testGeneralSFMFactor_Cal3Bundler.run + -j2 + tests/timeSLAMlike.run true true true - + make - -j5 - testGeneralSFMFactor.run + -j2 + check true true true - + make - -j5 - testProjectionFactor.run + -j2 + clean true true true - + make - -j5 - testRotateFactor.run + -j2 + testBTree.run true true true - + make - -j5 - testPoseRotationPrior.run + -j2 + testDSF.run true true true - + make - -j5 - testImplicitSchurFactor.run + -j2 + testDSFVector.run true true true - + + make + -j2 + testMatrix.run + true + true + true + + + make + -j2 + testSPQRUtil.run + true + true + true + + + make + -j2 + testVector.run + true + true + true + + + make + -j2 + timeMatrix.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + testClusterTree.run + true + true + true + + + make + -j2 + testJunctionTree.run + true + true + true + + + make + -j2 + tests/testEliminationTree.run + true + true + true + + + make + -j2 + tests/testSymbolicFactor.run + true + true + true + + + make + -j2 + tests/testVariableSlots.run + true + true + true + + + make + -j2 + tests/testConditional.run + true + true + true + + + make + -j2 + tests/testSymbolicFactorGraph.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + testNonlinearConstraint.run + true + true + true + + + make + -j2 + testLieConfig.run + true + true + true + + + make + -j2 + testConstraintOptimizer.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPlanarSLAM.run + true + true + true + + + make + -j2 + testPose2Config.run + true + true + true + + + make + -j2 + testPose2Factor.run + true + true + true + + + make + -j2 + testPose2Prior.run + true + true + true + + + make + -j2 + testPose2SLAM.run + true + true + true + + + make + -j2 + testPose3Config.run + true + true + true + + + make + -j2 + testPose3SLAM.run + true + true + true + + + make + + testSimulated2DOriented.run + true + false + true + + + make + -j2 + testVSLAMConfig.run + true + true + true + + + make + -j2 + testVSLAMFactor.run + true + true + true + + + make + -j2 + testVSLAMGraph.run + true + true + true + + + make + -j2 + testPose3Factor.run + true + true + true + + + make + + testSimulated2D.run + true + false + true + + + make + + testSimulated3D.run + true + false + true + + + make + -j2 + tests/testGaussianISAM2 + true + true + true + + + make + -j5 + testBTree.run + true + true + true + + + make + -j5 + testDSF.run + true + true + true + + + make + -j5 + testDSFMap.run + true + true + true + + + make + -j5 + testDSFVector.run + true + true + true + + + make + -j5 + testFixedVector.run + true + true + true + + + make + -j5 + testEliminationTree.run + true + true + true + + + make + -j5 + testInference.run + true + true + true + + + make + -j5 + testKey.run + true + true + true + + + make + -j1 + testSymbolicBayesTree.run + true + false + true + + + make + -j1 + testSymbolicSequentialSolver.run + true + false + true + + make -j4 - testRangeFactor.run + testLabeledSymbol.run true true true - + make - -j4 - testOrientedPlane3Factor.run + -j2 + check true true true - + make - -j4 - testSmartProjectionPoseFactor.run + -j2 + tests/testLieConfig.run true true true @@ -1769,7 +1784,6 @@ cpack - -G DEB true false @@ -1777,7 +1791,6 @@ cpack - -G RPM true false @@ -1785,7 +1798,6 @@ cpack - -G TGZ true false @@ -1793,7 +1805,6 @@ cpack - --config CPackSourceConfig.cmake true false @@ -1975,7 +1986,7 @@ false true - + make -j2 check @@ -1983,54 +1994,38 @@ true true - + make - tests/testGaussianISAM2 + -j2 + clean + true + true + true + + + make + -j2 + install + true + true + true + + + make + -j2 + all + true + true + true + + + cmake + .. true false true - - make - -j2 - check - true - true - true - - - make - -j2 - tests/testGaussianJunctionTree.run - true - true - true - - - make - -j2 - tests/testGaussianFactor.run - true - true - true - - - make - -j2 - tests/testGaussianConditional.run - true - true - true - - - make - -j2 - tests/timeSLAMlike.run - true - true - true - - + make -j2 testGaussianFactor.run @@ -2038,10 +2033,442 @@ true true - + make -j5 - testParticleFactor.run + testCal3Bundler.run + true + true + true + + + make + -j5 + testCal3DS2.run + true + true + true + + + make + -j5 + testCalibratedCamera.run + true + true + true + + + make + -j5 + testEssentialMatrix.run + true + true + true + + + make + -j1 VERBOSE=1 + testHomography2.run + true + false + true + + + make + -j5 + testPinholeCamera.run + true + true + true + + + make + -j5 + testPoint2.run + true + true + true + + + make + -j5 + testPoint3.run + true + true + true + + + make + -j5 + testPose2.run + true + true + true + + + make + -j5 + testPose3.run + true + true + true + + + make + -j5 + testRot3M.run + true + true + true + + + make + -j5 + testSphere2.run + true + true + true + + + make + -j5 + testStereoCamera.run + true + true + true + + + make + -j5 + testCal3Unified.run + true + true + true + + + make + -j5 + testRot2.run + true + true + true + + + make + -j5 + testRot3Q.run + true + true + true + + + make + -j5 + testRot3.run + true + true + true + + + make + -j4 + testSO3.run + true + true + true + + + make + -j4 + testQuaternion.run + true + true + true + + + make + -j4 + testOrientedPlane3.run + true + true + true + + + make + -j4 + testPinholePose.run + true + true + true + + + make + -j4 + testCyclic.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + all + true + false + true + + + make + -j5 + check + true + false + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + clean all + true + true + true + + + make + -j1 + testDiscreteBayesTree.run + true + false + true + + + make + -j5 + testDiscreteConditional.run + true + true + true + + + make + -j5 + testDiscreteFactor.run + true + true + true + + + make + -j5 + testDiscreteFactorGraph.run + true + true + true + + + make + -j5 + testDiscreteMarginals.run + true + true + true + + + make + -j5 + testIMUSystem.run + true + true + true + + + make + -j5 + testPoseRTV.run + true + true + true + + + make + -j5 + testVelocityConstraint.run + true + true + true + + + make + -j5 + testVelocityConstraint3.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + timeCalibratedCamera.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + testWrap.run + true + true + true + + + make + -j5 + testSpirit.run + true + true + true + + + make + -j5 + check.wrap + true + true + true + + + make + -j5 + testMethod.run + true + true + true + + + make + -j5 + testClass.run + true + true + true + + + make + -j4 + testType.run + true + true + true + + + make + -j4 + testArgument.run + true + true + true + + + make + -j4 + testReturnValue.run + true + true + true + + + make + -j4 + testTemplate.run + true + true + true + + + make + -j4 + testGlobalFunction.run true true true @@ -2094,7 +2521,332 @@ true true - + + make + -j2 + vSFMexample.run + true + true + true + + + make + -j5 + testMatrix.run + true + true + true + + + make + -j5 + testVector.run + true + true + true + + + make + -j5 + testNumericalDerivative.run + true + true + true + + + make + -j5 + testVerticalBlockMatrix.run + true + true + true + + + make + -j4 + testOptionalJacobian.run + true + true + true + + + make + -j4 + testGroup.run + true + true + true + + + make + -j2 + testVSLAMGraph + true + true + true + + + make + -j5 + check.tests + true + true + true + + + make + -j2 + timeGaussianFactorGraph.run + true + true + true + + + make + -j5 + testMarginals.run + true + true + true + + + make + -j5 + testGaussianISAM2.run + true + true + true + + + make + -j5 + testSymbolicFactorGraphB.run + true + true + true + + + make + -j2 + timeSequentialOnDataset.run + true + true + true + + + make + -j5 + testGradientDescentOptimizer.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + testNonlinearOptimizer.run + true + true + true + + + make + -j2 + testGaussianBayesNet.run + true + true + true + + + make + -j2 + testNonlinearISAM.run + true + true + true + + + make + -j2 + testNonlinearEquality.run + true + true + true + + + make + -j2 + testExtendedKalmanFilter.run + true + true + true + + + make + -j5 + timing.tests + true + true + true + + + make + -j5 + testNonlinearFactor.run + true + true + true + + + make + -j5 + clean + true + true + true + + + make + -j5 + testGaussianJunctionTreeB.run + true + true + true + + + make + testGraph.run + true + false + true + + + make + testJunctionTree.run + true + false + true + + + make + testSymbolicBayesNetB.run + true + false + true + + + make + -j5 + testGaussianISAM.run + true + true + true + + + make + -j5 + testDoglegOptimizer.run + true + true + true + + + make + -j5 + testNonlinearFactorGraph.run + true + true + true + + + make + -j5 + testIterative.run + true + true + true + + + make + -j5 + testSubgraphSolver.run + true + true + true + + + make + -j5 + testGaussianFactorGraphB.run + true + true + true + + + make + -j5 + testSummarization.run + true + true + true + + + make + -j5 + testManifold.run + true + true + true + + + make + -j4 + testLie.run + true + true + true + + + make + -j5 + testParticleFactor.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + install + true + true + true + + + make + -j2 + clean + true + true + true + + make -j2 all @@ -2102,7 +2854,7 @@ true true - + make -j2 clean @@ -2110,135 +2862,15 @@ true true - - make - -k - check - true - false - true - - - make - - tests/testBayesTree.run - true - false - true - - - make - - testBinaryBayesNet.run - true - false - true - - + make -j2 - testFactorGraph.run + all true true true - - make - -j2 - testISAM.run - true - true - true - - - make - -j2 - testJunctionTree.run - true - true - true - - - make - -j2 - testKey.run - true - true - true - - - make - -j2 - testOrdering.run - true - true - true - - - make - - testSymbolicBayesNet.run - true - false - true - - - make - - tests/testSymbolicFactor.run - true - false - true - - - make - - testSymbolicFactorGraph.run - true - false - true - - - make - -j2 - timeSymbolMaps.run - true - true - true - - - make - - tests/testBayesTree - true - false - true - - - make - -j2 - check - true - true - true - - - make - -j2 - timeCalibratedCamera.run - true - true - true - - - make - -j2 - timeRot3.run - true - true - true - - + make -j2 clean @@ -2246,18 +2878,114 @@ true true - + make - -j2 - tests/testPose2.run + -j5 + testAntiFactor.run true true true - + make - -j2 - tests/testPose3.run + -j5 + testPriorFactor.run + true + true + true + + + make + -j5 + testDataset.run + true + true + true + + + make + -j5 + testEssentialMatrixFactor.run + true + true + true + + + make + -j5 + testGeneralSFMFactor_Cal3Bundler.run + true + true + true + + + make + -j5 + testGeneralSFMFactor.run + true + true + true + + + make + -j5 + testProjectionFactor.run + true + true + true + + + make + -j5 + testRotateFactor.run + true + true + true + + + make + -j5 + testPoseRotationPrior.run + true + true + true + + + make + -j5 + testImplicitSchurFactor.run + true + true + true + + + make + -j4 + testRangeFactor.run + true + true + true + + + make + -j4 + testOrientedPlane3Factor.run + true + true + true + + + make + -j4 + testSmartProjectionPoseFactor.run + true + true + true + + + make + -j4 + testSmartProjectionCameraFactor.run true true true @@ -2462,6 +3190,190 @@ true true + + make + -j5 + testLago.run + true + true + true + + + make + -j5 + testLinearContainerFactor.run + true + true + true + + + make + -j5 + testOrdering.run + true + true + true + + + make + -j5 + testValues.run + true + true + true + + + make + -j5 + testWhiteNoiseFactor.run + true + true + true + + + make + -j4 + testExpression.run + true + true + true + + + make + -j4 + testAdaptAutoDiff.run + true + true + true + + + make + -j4 + testCallRecord.run + true + true + true + + + make + -j4 + testExpressionFactor.run + true + true + true + + + make + -j4 + testExecutionTrace.run + true + true + true + + + make + -j4 + testImuFactor.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + + tests/testGaussianISAM2 + true + false + true + + + make + -j5 + timeCalibratedCamera.run + true + true + true + + + make + -j5 + timePinholeCamera.run + true + true + true + + + make + -j5 + timeStereoCamera.run + true + true + true + + + make + -j5 + timeLago.run + true + true + true + + + make + -j5 + timePose3.run + true + true + true + + + make + -j4 + timeAdaptAutoDiff.run + true + true + true + + + make + -j4 + timeCameraExpression.run + true + true + true + + + make + -j4 + timeOneCameraExpression.run + true + true + true + + + make + -j4 + timeSFMExpressions.run + true + true + true + + + make + -j4 + timeIncremental.run + true + true + true + make -j2 @@ -2558,922 +3470,10 @@ true true - - make - -j1 - testDiscreteBayesTree.run - true - false - true - - - make - -j5 - testDiscreteConditional.run - true - true - true - - - make - -j5 - testDiscreteFactor.run - true - true - true - - - make - -j5 - testDiscreteFactorGraph.run - true - true - true - - - make - -j5 - testDiscreteMarginals.run - true - true - true - - - make - -j5 - testEliminationTree.run - true - true - true - - - make - -j5 - testInference.run - true - true - true - - - make - -j5 - testKey.run - true - true - true - - - make - -j1 - testSymbolicBayesTree.run - true - false - true - - - make - -j1 - testSymbolicSequentialSolver.run - true - false - true - - - make - -j4 - testLabeledSymbol.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - testClusterTree.run - true - true - true - - - make - -j2 - testJunctionTree.run - true - true - true - - - make - -j2 - tests/testEliminationTree.run - true - true - true - - - make - -j2 - tests/testSymbolicFactor.run - true - true - true - - - make - -j2 - tests/testVariableSlots.run - true - true - true - - - make - -j2 - tests/testConditional.run - true - true - true - - - make - -j2 - tests/testSymbolicFactorGraph.run - true - true - true - - - make - -j5 - testLago.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run - true - true - true - - - make - -j5 - testOrdering.run - true - true - true - - - make - -j5 - testValues.run - true - true - true - - - make - -j5 - testWhiteNoiseFactor.run - true - true - true - - - make - -j4 - testExpression.run - true - true - true - - - make - -j4 - testAdaptAutoDiff.run - true - true - true - - - make - -j4 - testCallRecord.run - true - true - true - - - make - -j4 - testExpressionFactor.run - true - true - true - - - make - -j4 - testExecutionTrace.run - true - true - true - - - make - -j5 - testIMUSystem.run - true - true - true - - - make - -j5 - testPoseRTV.run - true - true - true - - - make - -j5 - testVelocityConstraint.run - true - true - true - - - make - -j5 - testVelocityConstraint3.run - true - true - true - - - make - -j5 - timeCalibratedCamera.run - true - true - true - - - make - -j5 - timePinholeCamera.run - true - true - true - - - make - -j5 - timeStereoCamera.run - true - true - true - - - make - -j5 - timeLago.run - true - true - true - - - make - -j5 - timePose3.run - true - true - true - - - make - -j4 - timeAdaptAutoDiff.run - true - true - true - - - make - -j4 - timeCameraExpression.run - true - true - true - - - make - -j4 - timeOneCameraExpression.run - true - true - true - - - make - -j4 - timeSFMExpressions.run - true - true - true - - - make - -j4 - timeIncremental.run - true - true - true - - - make - -j5 - testBTree.run - true - true - true - - - make - -j5 - testDSF.run - true - true - true - - - make - -j5 - testDSFMap.run - true - true - true - - - make - -j5 - testDSFVector.run - true - true - true - - - make - -j5 - testFixedVector.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - testGaussianFactorGraphUnordered.run - true - true - true - - - make - -j5 - testGaussianBayesNetUnordered.run - true - true - true - - - make - -j5 - testGaussianConditional.run - true - true - true - - - make - -j5 - testGaussianDensity.run - true - true - true - - - make - -j5 - testGaussianJunctionTree.run - true - true - true - - - make - -j5 - testHessianFactor.run - true - true - true - - - make - -j5 - testJacobianFactor.run - true - true - true - - + make -j5 - testKalmanFilter.run - true - true - true - - - make - -j5 - testNoiseModel.run - true - true - true - - - make - -j5 - testSampler.run - true - true - true - - - make - -j5 - testSerializationLinear.run - true - true - true - - - make - -j5 - testVectorValues.run - true - true - true - - - make - -j5 - testGaussianBayesTree.run - true - true - true - - - make - -j5 - testWrap.run - true - true - true - - - make - -j5 - testSpirit.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - testMethod.run - true - true - true - - - make - -j5 - testClass.run - true - true - true - - - make - -j4 - testType.run - true - true - true - - - make - -j4 - testArgument.run - true - true - true - - - make - -j4 - testReturnValue.run - true - true - true - - - make - -j4 - testTemplate.run - true - true - true - - - make - -j4 - testGlobalFunction.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - testMatrix.run - true - true - true - - - make - -j5 - testVector.run - true - true - true - - - make - -j5 - testNumericalDerivative.run - true - true - true - - - make - -j5 - testVerticalBlockMatrix.run - true - true - true - - - make - -j4 - testOptionalJacobian.run - true - true - true - - - make - -j4 - testGroup.run - true - true - true - - - make - -j5 - check.tests - true - true - true - - - make - -j2 - timeGaussianFactorGraph.run - true - true - true - - - make - -j5 - testMarginals.run - true - true - true - - - make - -j5 - testGaussianISAM2.run - true - true - true - - - make - -j5 - testSymbolicFactorGraphB.run - true - true - true - - - make - -j2 - timeSequentialOnDataset.run - true - true - true - - - make - -j5 - testGradientDescentOptimizer.run - true - true - true - - - make - -j2 - testGaussianFactor.run - true - true - true - - - make - -j2 - testNonlinearOptimizer.run - true - true - true - - - make - -j2 - testGaussianBayesNet.run - true - true - true - - - make - -j2 - testNonlinearISAM.run - true - true - true - - - make - -j2 - testNonlinearEquality.run - true - true - true - - - make - -j2 - testExtendedKalmanFilter.run - true - true - true - - - make - -j5 - timing.tests - true - true - true - - - make - -j5 - testNonlinearFactor.run - true - true - true - - - make - -j5 - clean - true - true - true - - - make - -j5 - testGaussianJunctionTreeB.run - true - true - true - - - make - - testGraph.run - true - false - true - - - make - - testJunctionTree.run - true - false - true - - - make - - testSymbolicBayesNetB.run - true - false - true - - - make - -j5 - testGaussianISAM.run - true - true - true - - - make - -j5 - testDoglegOptimizer.run - true - true - true - - - make - -j5 - testNonlinearFactorGraph.run - true - true - true - - - make - -j5 - testIterative.run - true - true - true - - - make - -j5 - testSubgraphSolver.run - true - true - true - - - make - -j5 - testGaussianFactorGraphB.run - true - true - true - - - make - -j5 - testSummarization.run - true - true - true - - - make - -j5 - testManifold.run - true - true - true - - - make - -j4 - testLie.run - true - true - true - - - make - -j2 - vSFMexample.run - true - true - true - - - make - -j5 - clean - true - true - true - - - make - -j5 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - testVSLAMGraph + wrap true true true diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index adaa3dbaf..4ac634f03 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -320,21 +320,21 @@ Point3 triangulatePoint3( struct TriangulationParameters { - const double rankTolerance; ///< threshold to decide whether triangulation is result.degenerate - const bool enableEPI; ///< if set to true, will refine triangulation using LM + double rankTolerance; ///< threshold to decide whether triangulation is result.degenerate + bool enableEPI; ///< if set to true, will refine triangulation using LM /** * if the landmark is triangulated at distance larger than this, * result is flagged as degenerate. */ - const double landmarkDistanceThreshold; // + double landmarkDistanceThreshold; // /** * If this is nonnegative the we will check if the average reprojection error * is smaller than this threshold after triangulation, otherwise result is * flagged as degenerate. */ - const double dynamicOutlierRejectionThreshold; + double dynamicOutlierRejectionThreshold; /** * Constructor diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 7ac2a03be..3ad2d05a5 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -48,12 +48,12 @@ class GTSAM_EXPORT SmartProjectionParams { public: - const LinearizationMode linearizationMode; ///< How to linearize the factor - const DegeneracyMode degeneracyMode; ///< How to linearize the factor + LinearizationMode linearizationMode; ///< How to linearize the factor + DegeneracyMode degeneracyMode; ///< How to linearize the factor /// @name Parameters governing the triangulation /// @{ - const TriangulationParameters triangulationParameters; + mutable TriangulationParameters triangulationParameters; const double retriangulationThreshold; ///< threshold to decide whether to re-triangulate /// @} @@ -64,10 +64,10 @@ public: /// @} // Constructor - SmartProjectionParams(LinearizationMode linMode = HESSIAN, - DegeneracyMode degMode = IGNORE_DEGENERACY, double rankTol = 1, - bool enableEPI = false, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1): + SmartProjectionParams(const LinearizationMode linMode = HESSIAN, + const DegeneracyMode degMode = IGNORE_DEGENERACY, const double rankTol = 1, + const bool enableEPI = false, const double landmarkDistanceThreshold = 1e10, + const double dynamicOutlierRejectionThreshold = -1): linearizationMode(linMode), degeneracyMode(degMode), triangulationParameters(rankTol, enableEPI, landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), @@ -89,15 +89,36 @@ public: inline LinearizationMode getLinearizationMode() const { return linearizationMode; } - /** return cheirality verbosity */ + inline DegeneracyMode getDegeneracyMode() const { + return degeneracyMode; + } + inline TriangulationParameters getTriangulationParameters() const { + return triangulationParameters; + } inline bool getVerboseCheirality() const { return verboseCheirality; } - /** return flag for throwing cheirality exceptions */ inline bool getThrowCheirality() const { return throwCheirality; } - + inline void setLinearizationMode(LinearizationMode linMode) { + linearizationMode = linMode; + } + inline void setDegeneracyMode(DegeneracyMode degMode) { + degeneracyMode = degMode; + } + inline void setRankTolerance(double rankTol) { + triangulationParameters.rankTolerance = rankTol; + } + inline void setEnableEPI(bool enableEPI) { + triangulationParameters.enableEPI = enableEPI; + } + inline void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold) { + triangulationParameters.landmarkDistanceThreshold = landmarkDistanceThreshold; + } + inline void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold) { + triangulationParameters.dynamicOutlierRejectionThreshold = dynOutRejectionThreshold; + } }; /** @@ -134,36 +155,16 @@ public: /// shorthand for a set of cameras typedef CameraSet Cameras; - /** - * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - */ - SmartProjectionFactor(LinearizationMode linearizationMode = HESSIAN, - double rankTolerance = 1, DegeneracyMode degeneracyMode = - IGNORE_DEGENERACY, bool enableEPI = false, - double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1, - boost::optional body_P_sensor = boost::none) : - Base(body_P_sensor), - params_(linearizationMode, degeneracyMode, - rankTolerance, enableEPI, landmarkDistanceThreshold, - dynamicOutlierRejectionThreshold), // - result_(TriangulationResult::Degenerate()) {} - /** * Constructor * @param body_P_sensor pose of the camera in the body frame * @param params internal parameters of the smart factors */ -// SmartProjectionFactor(const boost::optional body_P_sensor = boost::none, -// const SmartProjectionParams params = SmartProjectionParams()) : -// Base(body_P_sensor), -// params_(params), // -// result_(TriangulationResult::Degenerate()) {} + SmartProjectionFactor(const boost::optional body_P_sensor = boost::none, + const SmartProjectionParams params = SmartProjectionParams()) : + Base(body_P_sensor), + params_(params), // + result_(TriangulationResult::Degenerate()) {} /** Virtual destructor */ virtual ~SmartProjectionFactor() { diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index b428d7b05..322c3790f 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -55,33 +55,16 @@ public: /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; - /** - * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected (this functionality is deprecated) - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from sensor to body frame (default identity) - */ - SmartProjectionPoseFactor(const boost::shared_ptr K, const double rankTol = 1, - const double linThreshold = -1, const DegeneracyMode manageDegeneracy = IGNORE_DEGENERACY, - const bool enableEPI = false, boost::optional body_P_sensor = boost::none, - LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1) : - Base(linearizeTo, rankTol, manageDegeneracy, enableEPI, landmarkDistanceThreshold, - dynamicOutlierRejectionThreshold, body_P_sensor), K_(K) {} - /** * Constructor * @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 */ -// SmartProjectionPoseFactor(const boost::shared_ptr K, -// const boost::optional body_P_sensor = boost::none, -// const SmartProjectionParams params = SmartProjectionParams()) : -// Base(body_P_sensor, params), K_(K) {} + SmartProjectionPoseFactor(const boost::shared_ptr K, + const boost::optional body_P_sensor = boost::none, + const SmartProjectionParams params = SmartProjectionParams()) : + Base(body_P_sensor, params), K_(K) {} /** Virtual destructor */ virtual ~SmartProjectionPoseFactor() {} diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index e566146d0..8e83ec503 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -61,6 +61,7 @@ Camera cam1(level_pose, K2); Camera cam2(pose_right, K2); Camera cam3(pose_above, K2); typedef GeneralSFMFactor SFMFactor; +SmartProjectionParams params; } /* ************************************************************************* */ diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 636e69b4b..533e16bec 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -30,8 +30,6 @@ using namespace boost::assign; static bool isDebugTest = false; -static double rankTol = 1.0; - // Convenience for named keys using symbol_shorthand::X; using symbol_shorthand::L; @@ -42,6 +40,8 @@ Key c1 = 1, c2 = 2, c3 = 3; static Point2 measurement1(323.0, 240.0); +static double rankTol = 1.0; + template PinholeCamera perturbCameraPoseAndCalibration( const PinholeCamera& camera) { @@ -78,7 +78,8 @@ TEST( SmartProjectionCameraFactor, Constructor) { /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor2) { using namespace vanilla; - SmartFactor factor1(gtsam::HESSIAN, rankTol); + params.setRankTolerance(rankTol); + SmartFactor factor1(boost::none, params); } /* ************************************************************************* */ @@ -91,7 +92,8 @@ TEST( SmartProjectionCameraFactor, Constructor3) { /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, Constructor4) { using namespace vanilla; - SmartFactor factor1(gtsam::HESSIAN, rankTol); + params.setRankTolerance(rankTol); + SmartFactor factor1(boost::none, params); factor1.add(measurement1, x1, unit2); } @@ -257,12 +259,12 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { EXPECT(assert_equal(expected, actual, 1)); // Optimize - LevenbergMarquardtParams params; + LevenbergMarquardtParams lmParams; if (isDebugTest) { - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - params.verbosity = NonlinearOptimizerParams::ERROR; + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + lmParams.verbosity = NonlinearOptimizerParams::ERROR; } - LevenbergMarquardtOptimizer optimizer(graph, initial, params); + LevenbergMarquardtOptimizer optimizer(graph, initial, lmParams); Values result = optimizer.optimize(); EXPECT(assert_equal(landmark1, *smartFactor1->point(), 1e-7)); @@ -338,14 +340,14 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { if (isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); - LevenbergMarquardtParams params; + LevenbergMarquardtParams lmParams; if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; + lmParams.verbosity = NonlinearOptimizerParams::ERROR; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); @@ -415,17 +417,17 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { if (isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); - LevenbergMarquardtParams params; - params.relativeErrorTol = 1e-8; - params.absoluteErrorTol = 0; - params.maxIterations = 20; + LevenbergMarquardtParams lmParams; + lmParams.relativeErrorTol = 1e-8; + lmParams.absoluteErrorTol = 0; + lmParams.maxIterations = 20; if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; + lmParams.verbosity = NonlinearOptimizerParams::ERROR; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); @@ -494,17 +496,17 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { if (isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); - LevenbergMarquardtParams params; - params.relativeErrorTol = 1e-8; - params.absoluteErrorTol = 0; - params.maxIterations = 20; + LevenbergMarquardtParams lmParams; + lmParams.relativeErrorTol = 1e-8; + lmParams.absoluteErrorTol = 0; + lmParams.maxIterations = 20; if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; + lmParams.verbosity = NonlinearOptimizerParams::ERROR; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); if (isDebugTest) @@ -570,17 +572,17 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { if (isDebugTest) values.at(c3).print("Smart: Pose3 before optimization: "); - LevenbergMarquardtParams params; - params.relativeErrorTol = 1e-8; - params.absoluteErrorTol = 0; - params.maxIterations = 20; + LevenbergMarquardtParams lmParams; + lmParams.relativeErrorTol = 1e-8; + lmParams.absoluteErrorTol = 0; + lmParams.maxIterations = 20; if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; + lmParams.verbosity = NonlinearOptimizerParams::ERROR; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); if (isDebugTest) @@ -805,9 +807,14 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { bool useEPI = false; // Hessian version + SmartProjectionParams params; + params.setRankTolerance(rankTol); + params.setLinearizationMode(gtsam::HESSIAN); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setEnableEPI(useEPI); + SmartFactor::shared_ptr explicitFactor( - new SmartFactor(gtsam::HESSIAN, rankTol, - gtsam::IGNORE_DEGENERACY, useEPI)); + new SmartFactor(boost::none, params)); explicitFactor->add(level_uv, c1, unit2); explicitFactor->add(level_uv_right, c2, unit2); @@ -817,9 +824,9 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { dynamic_cast(*gaussianHessianFactor); // Implicit Schur version + params.setLinearizationMode(gtsam::IMPLICIT_SCHUR); SmartFactor::shared_ptr implicitFactor( - new SmartFactor(gtsam::IMPLICIT_SCHUR, rankTol, - gtsam::IGNORE_DEGENERACY, useEPI)); + new SmartFactor(boost::none, params)); implicitFactor->add(level_uv, c1, unit2); implicitFactor->add(level_uv_right, c2, unit2); GaussianFactor::shared_ptr gaussianImplicitSchurFactor = diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 5f6c2fee3..72147ff35 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -46,7 +46,7 @@ static Symbol x3('X', 3); static Point2 measurement1(323.0, 240.0); -LevenbergMarquardtParams params; +LevenbergMarquardtParams lmParams; // Make more verbose like so (in tests): // params.verbosityLM = LevenbergMarquardtParams::SUMMARY; @@ -59,7 +59,9 @@ TEST( SmartProjectionPoseFactor, Constructor) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor2) { using namespace vanillaPose; - SmartFactor factor1(sharedK, rankTol); + SmartProjectionParams params; + params.setRankTolerance(rankTol); + SmartFactor factor1(sharedK, boost::none, params); } /* ************************************************************************* */ @@ -72,7 +74,9 @@ TEST( SmartProjectionPoseFactor, Constructor3) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { using namespace vanillaPose; - SmartFactor factor1(sharedK, rankTol); + SmartProjectionParams params; + params.setRankTolerance(rankTol); + SmartFactor factor1(sharedK, boost::none, params); factor1.add(measurement1, x1, model); } @@ -229,15 +233,18 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ views.push_back(x2); views.push_back(x3); - bool enableEPI = false; + SmartProjectionParams params; + params.setRankTolerance(1.0); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setEnableEPI(false); - SmartProjectionPoseFactor smartFactor1(K, 1.0, -1.0, gtsam::IGNORE_DEGENERACY, enableEPI, sensor_to_body); + SmartProjectionPoseFactor smartFactor1(K, sensor_to_body, params); smartFactor1.add(measurements_cam1, views, model); - SmartProjectionPoseFactor smartFactor2(K, 1.0, -1.0, gtsam::IGNORE_DEGENERACY, enableEPI, sensor_to_body); + SmartProjectionPoseFactor smartFactor2(K, sensor_to_body, params); smartFactor2.add(measurements_cam2, views, model); - SmartProjectionPoseFactor smartFactor3(K, 1.0, -1.0, gtsam::IGNORE_DEGENERACY, enableEPI, sensor_to_body); + SmartProjectionPoseFactor smartFactor3(K, sensor_to_body, params); smartFactor3.add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -266,9 +273,9 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ // initialize third pose with some noise, we expect it to move back to original pose3 values.insert(x3, bodyPose3*noise_pose); - LevenbergMarquardtParams params; + LevenbergMarquardtParams lmParams; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(bodyPose3,result.at(x3))); } @@ -329,7 +336,7 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { Point3(0.1, -0.1, 1.9)), values.at(x3))); Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } @@ -552,7 +559,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { values.at(x3))); Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); } @@ -574,16 +581,23 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + SmartProjectionParams params; + params.setRankTolerance(1.0); + params.setLinearizationMode(gtsam::JACOBIAN_SVD); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setEnableEPI(false); + SmartFactor factor1(sharedK, boost::none, params); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD)); + new SmartFactor(sharedK, boost::none, params)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD)); + new SmartFactor(sharedK, boost::none, params)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), gtsam::JACOBIAN_SVD)); + new SmartFactor(sharedK, boost::none, params)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -604,7 +618,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { values.insert(x3, pose_above * noise_pose); Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } @@ -628,19 +642,23 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + SmartProjectionParams params; + params.setRankTolerance(1.0); + params.setLinearizationMode(gtsam::JACOBIAN_SVD); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setLandmarkDistanceThreshold(excludeLandmarksFutherThanDist); + params.setEnableEPI(false); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), - gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + new SmartFactor(sharedK, boost::none, params)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), - gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + new SmartFactor(sharedK, boost::none, params)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), - gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + new SmartFactor(sharedK, boost::none, params)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -662,7 +680,7 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { // All factors are disabled and pose should remain where it is Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(values.at(x3), result.at(x3))); } @@ -693,24 +711,25 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier + SmartProjectionParams params; + params.setLinearizationMode(gtsam::JACOBIAN_SVD); + params.setLandmarkDistanceThreshold(excludeLandmarksFutherThanDist); + params.setDynamicOutlierRejectionThreshold(dynamicOutlierRejectionThreshold); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), - gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(sharedK, boost::none, params)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), - gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(sharedK, boost::none, params)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), - gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(sharedK, boost::none, params)); smartFactor3->add(measurements_cam3, views, model); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, false, Pose3(), - gtsam::JACOBIAN_SVD, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + new SmartFactor(sharedK, boost::none, params)); smartFactor4->add(measurements_cam4, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -730,7 +749,7 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { // All factors are disabled and pose should remain where it is Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(cam3.pose(), result.at(x3))); } @@ -752,19 +771,19 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + SmartProjectionParams params; + params.setLinearizationMode(gtsam::JACOBIAN_Q); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, - false, Pose3(), gtsam::JACOBIAN_Q)); + new SmartFactor(sharedK, boost::none, params)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, - false, Pose3(), gtsam::JACOBIAN_Q)); + new SmartFactor(sharedK, boost::none, params)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(sharedK, 1, -1, gtsam::IGNORE_DEGENERACY, - false, Pose3(), gtsam::JACOBIAN_Q)); + new SmartFactor(sharedK, boost::none, params)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -784,7 +803,7 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { values.insert(x3, pose_above * noise_pose); Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } @@ -840,7 +859,7 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { DOUBLES_EQUAL(48406055, graph.error(values), 1); - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); Values result = optimizer.optimize(); DOUBLES_EQUAL(0, graph.error(result), 1e-9); @@ -872,18 +891,19 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - double rankTol = 10; + SmartProjectionParams params; + params.setRankTolerance(10); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedK, rankTol)); // HESSIAN, by default + new SmartFactor(sharedK, boost::none, params)); // HESSIAN, by default smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedK, rankTol)); // HESSIAN, by default + new SmartFactor(sharedK, boost::none, params)); // HESSIAN, by default smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(sharedK, rankTol)); // HESSIAN, by default + new SmartFactor(sharedK, boost::none, params)); // HESSIAN, by default smartFactor3->add(measurements_cam3, views, model); NonlinearFactorGraph graph; @@ -953,13 +973,16 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - double rankTol = 50; + SmartProjectionParams params; + params.setRankTolerance(50); + params.setDegeneracyMode(gtsam::HANDLE_INFINITY); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedK2, rankTol, -1.0, gtsam::HANDLE_INFINITY)); + new SmartFactor(sharedK2, boost::none, params)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedK2, rankTol, -1.0, gtsam::HANDLE_INFINITY)); + new SmartFactor(sharedK2, boost::none, params)); smartFactor2->add(measurements_cam2, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -983,7 +1006,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac values.insert(x3, pose3 * noise_pose); // params.verbosityLM = LevenbergMarquardtParams::SUMMARY; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); Values result = optimizer.optimize(); EXPECT(assert_equal(pose3, result.at(x3))); } @@ -1012,18 +1035,20 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - double rankTol = 10; + SmartProjectionParams params; + params.setRankTolerance(10); + params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY)); + new SmartFactor(sharedK, boost::none, params)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY)); + new SmartFactor(sharedK, boost::none, params)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(sharedK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY)); + new SmartFactor(sharedK, boost::none, params)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1058,7 +1083,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) values.at(x3))); Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); // Since we do not do anything on degenerate instances (ZERO_ON_DEGENERACY) @@ -1212,7 +1237,9 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { using namespace bundlerPose; - SmartFactor factor(sharedBundlerK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY, false, Pose3(), gtsam::HESSIAN); + SmartProjectionParams params; + params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); + SmartFactor factor(sharedBundlerK, boost::none, params); factor.add(measurement1, x1, model); } @@ -1221,7 +1248,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { using namespace bundlerPose; - // three landmarks ~5 meters infront of camera + // three landmarks ~5 meters in front of camera Point3 landmark3(3, 0, 3.0); vector measurements_cam1, measurements_cam2, measurements_cam3; @@ -1270,7 +1297,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { Point3(0.1, -0.1, 1.9)), values.at(x3))); Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(cam3.pose(), result.at(x3), 1e-6)); } @@ -1302,21 +1329,20 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - double rankTol = 10; + SmartProjectionParams params; + params.setRankTolerance(10); + params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(sharedBundlerK, rankTol, -1.0, gtsam::ZERO_ON_DEGENERACY, - false, Pose3(), gtsam::HESSIAN)); + new SmartFactor(sharedBundlerK, boost::none, params)); smartFactor1->add(measurements_cam1, views, model); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(sharedBundlerK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY, - false, Pose3(), gtsam::HESSIAN)); + new SmartFactor(sharedBundlerK, boost::none, params)); smartFactor2->add(measurements_cam2, views, model); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(sharedBundlerK, rankTol, -1, gtsam::ZERO_ON_DEGENERACY, - false, Pose3(), gtsam::HESSIAN)); + new SmartFactor(sharedBundlerK, boost::none, params)); smartFactor3->add(measurements_cam3, views, model); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1352,7 +1378,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { values.at(x3))); Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT( From 51df837f74760fb0ec40f9a77561631e134b1e2d Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 20 Jun 2015 11:49:13 -0700 Subject: [PATCH 167/173] Fixed small c++ issues (const, reference) and formatted --- gtsam/slam/SmartProjectionFactor.h | 62 +++++++++++++++----------- gtsam/slam/SmartProjectionPoseFactor.h | 13 +++--- 2 files changed, 45 insertions(+), 30 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 3ad2d05a5..903be1e8d 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -64,25 +64,30 @@ public: /// @} // Constructor - SmartProjectionParams(const LinearizationMode linMode = HESSIAN, - const DegeneracyMode degMode = IGNORE_DEGENERACY, const double rankTol = 1, - const bool enableEPI = false, const double landmarkDistanceThreshold = 1e10, - const double dynamicOutlierRejectionThreshold = -1): - linearizationMode(linMode), degeneracyMode(degMode), - triangulationParameters(rankTol, enableEPI, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), - retriangulationThreshold(1e-5), - throwCheirality(false), verboseCheirality(false) {} + SmartProjectionParams(LinearizationMode linMode = HESSIAN, + DegeneracyMode degMode = IGNORE_DEGENERACY, double rankTol = 1, + bool enableEPI = false, double landmarkDistanceThreshold = 1e10, + double dynamicOutlierRejectionThreshold = -1) : + linearizationMode(linMode), degeneracyMode(degMode), triangulationParameters( + rankTol, enableEPI, landmarkDistanceThreshold, + dynamicOutlierRejectionThreshold), retriangulationThreshold(1e-5), throwCheirality( + false), verboseCheirality(false) { + } - virtual ~SmartProjectionParams() {} + virtual ~SmartProjectionParams() { + } void print(const std::string& str) const { std::cout << " linearizationMode: " << linearizationMode << "\n"; std::cout << " degeneracyMode: " << degeneracyMode << "\n"; - std::cout << " rankTolerance: " << triangulationParameters.rankTolerance << "\n"; - std::cout << " enableEPI: " << triangulationParameters.enableEPI << "\n"; - std::cout << " landmarkDistanceThreshold: " << triangulationParameters.landmarkDistanceThreshold << "\n"; - std::cout << " OutlierRejectionThreshold: " << triangulationParameters.dynamicOutlierRejectionThreshold << "\n"; + std::cout << " rankTolerance: " + << triangulationParameters.rankTolerance << "\n"; + std::cout << " enableEPI: " + << triangulationParameters.enableEPI << "\n"; + std::cout << " landmarkDistanceThreshold: " + << triangulationParameters.landmarkDistanceThreshold << "\n"; + std::cout << " OutlierRejectionThreshold: " + << triangulationParameters.dynamicOutlierRejectionThreshold << "\n"; std::cout.flush(); } @@ -114,10 +119,13 @@ public: triangulationParameters.enableEPI = enableEPI; } inline void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold) { - triangulationParameters.landmarkDistanceThreshold = landmarkDistanceThreshold; + triangulationParameters.landmarkDistanceThreshold = + landmarkDistanceThreshold; } - inline void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold) { - triangulationParameters.dynamicOutlierRejectionThreshold = dynOutRejectionThreshold; + inline void setDynamicOutlierRejectionThreshold( + bool dynOutRejectionThreshold) { + triangulationParameters.dynamicOutlierRejectionThreshold = + dynOutRejectionThreshold; } }; @@ -160,11 +168,12 @@ public: * @param body_P_sensor pose of the camera in the body frame * @param params internal parameters of the smart factors */ - SmartProjectionFactor(const boost::optional body_P_sensor = boost::none, - const SmartProjectionParams params = SmartProjectionParams()) : - Base(body_P_sensor), - params_(params), // - result_(TriangulationResult::Degenerate()) {} + SmartProjectionFactor( + const boost::optional body_P_sensor = boost::none, + const SmartProjectionParams& params = SmartProjectionParams()) : + Base(body_P_sensor), params_(params), // + result_(TriangulationResult::Degenerate()) { + } /** Virtual destructor */ virtual ~SmartProjectionFactor() { @@ -178,8 +187,10 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionFactor\n"; - std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl; - std::cout << "triangulationParameters:\n" << params_.triangulationParameters << std::endl; + std::cout << "linearizationMode:\n" << params_.linearizationMode + << std::endl; + std::cout << "triangulationParameters:\n" << params_.triangulationParameters + << std::endl; std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); } @@ -236,7 +247,8 @@ public: bool retriangulate = decideIfTriangulate(cameras); if (retriangulate) - result_ = gtsam::triangulateSafe(cameras, this->measured_, params_.triangulationParameters); + result_ = gtsam::triangulateSafe(cameras, this->measured_, + params_.triangulationParameters); return result_; } diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 322c3790f..93a4449f5 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -63,11 +63,13 @@ public: */ SmartProjectionPoseFactor(const boost::shared_ptr K, const boost::optional body_P_sensor = boost::none, - const SmartProjectionParams params = SmartProjectionParams()) : - Base(body_P_sensor, params), K_(K) {} + const SmartProjectionParams& params = SmartProjectionParams()) : + Base(body_P_sensor, params), K_(K) { + } /** Virtual destructor */ - virtual ~SmartProjectionPoseFactor() {} + virtual ~SmartProjectionPoseFactor() { + } /** * print @@ -112,7 +114,7 @@ public: typename Base::Cameras cameras; BOOST_FOREACH(const Key& k, this->keys_) { Pose3 pose = values.at(k); - if(Base::body_P_sensor_) + if (Base::body_P_sensor_) pose = pose.compose(*(Base::body_P_sensor_)); Camera camera(pose, K_); @@ -131,7 +133,8 @@ private: ar & BOOST_SERIALIZATION_NVP(K_); } -}; // end of class declaration +}; +// end of class declaration /// traits template From acf4629f8588a921d2b9c755d350aa26cccaab1d Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 20 Jun 2015 11:49:44 -0700 Subject: [PATCH 168/173] Fixed MATLAB wrapping of smart factor --- gtsam.h | 27 ++++++++++++++++++++------- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/gtsam.h b/gtsam.h index b9edfe14f..8f0bcf634 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2354,18 +2354,31 @@ virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { void serialize() const; }; +#include +class SmartProjectionParams { + SmartProjectionParams(); + // TODO(frank): make these work: + // void setLinearizationMode(LinearizationMode linMode); + // void setDegeneracyMode(DegeneracyMode degMode); + void setRankTolerance(double rankTol); + void setEnableEPI(bool enableEPI); + void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold); + void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold); +}; + #include template -virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { +virtual class SmartProjectionPoseFactor: gtsam::NonlinearFactor { - SmartProjectionPoseFactor(double rankTol, double linThreshold, - bool manageDegeneracy, bool enableEPI, const gtsam::Pose3& body_P_sensor); - - SmartProjectionPoseFactor(double rankTol); - SmartProjectionPoseFactor(); + SmartProjectionPoseFactor(const CALIBRATION* K); + SmartProjectionPoseFactor(const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor); + SmartProjectionPoseFactor(const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor, + const gtsam::SmartProjectionParams& params); void add(const gtsam::Point2& measured_i, size_t poseKey_i, - const gtsam::noiseModel::Base* noise_i, const CALIBRATION* K_i); + const gtsam::noiseModel::Base* noise_i); // enabling serialization functionality //void serialize() const; From 2ce252fdc0d7ba48bccc3c98ce17a7fd9b076aeb Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 20 Jun 2015 12:42:59 -0700 Subject: [PATCH 169/173] Got rid of inline --- gtsam/slam/SmartProjectionFactor.h | 29 ++++++++++++++--------------- 1 file changed, 14 insertions(+), 15 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 903be1e8d..26dba2f55 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -91,39 +91,38 @@ public: std::cout.flush(); } - inline LinearizationMode getLinearizationMode() const { + LinearizationMode getLinearizationMode() const { return linearizationMode; } - inline DegeneracyMode getDegeneracyMode() const { + DegeneracyMode getDegeneracyMode() const { return degeneracyMode; } - inline TriangulationParameters getTriangulationParameters() const { + TriangulationParameters getTriangulationParameters() const { return triangulationParameters; } - inline bool getVerboseCheirality() const { + bool getVerboseCheirality() const { return verboseCheirality; } - inline bool getThrowCheirality() const { + bool getThrowCheirality() const { return throwCheirality; } - inline void setLinearizationMode(LinearizationMode linMode) { + void setLinearizationMode(LinearizationMode linMode) { linearizationMode = linMode; } - inline void setDegeneracyMode(DegeneracyMode degMode) { + void setDegeneracyMode(DegeneracyMode degMode) { degeneracyMode = degMode; } - inline void setRankTolerance(double rankTol) { + void setRankTolerance(double rankTol) { triangulationParameters.rankTolerance = rankTol; } - inline void setEnableEPI(bool enableEPI) { + void setEnableEPI(bool enableEPI) { triangulationParameters.enableEPI = enableEPI; } - inline void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold) { + void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold) { triangulationParameters.landmarkDistanceThreshold = landmarkDistanceThreshold; } - inline void setDynamicOutlierRejectionThreshold( - bool dynOutRejectionThreshold) { + void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold) { triangulationParameters.dynamicOutlierRejectionThreshold = dynOutRejectionThreshold; } @@ -518,17 +517,17 @@ public: } /// Is result valid? - inline bool isValid() const { + bool isValid() const { return result_; } /** return the degenerate state */ - inline bool isDegenerate() const { + bool isDegenerate() const { return result_.degenerate(); } /** return the cheirality status flag */ - inline bool isPointBehindCamera() const { + bool isPointBehindCamera() const { return result_.behindCamera(); } From 1f8adc9381939434f7e304de54ed50c3663555a7 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 20 Jun 2015 13:09:39 -0700 Subject: [PATCH 170/173] Cleaned up parameters a bit --- gtsam/slam/SmartProjectionFactor.h | 42 ++++++++++++++---------------- 1 file changed, 19 insertions(+), 23 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 26dba2f55..7867200e6 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -53,7 +53,7 @@ public: /// @name Parameters governing the triangulation /// @{ - mutable TriangulationParameters triangulationParameters; + mutable TriangulationParameters triangulation; const double retriangulationThreshold; ///< threshold to decide whether to re-triangulate /// @} @@ -65,13 +65,11 @@ public: // Constructor SmartProjectionParams(LinearizationMode linMode = HESSIAN, - DegeneracyMode degMode = IGNORE_DEGENERACY, double rankTol = 1, - bool enableEPI = false, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1) : - linearizationMode(linMode), degeneracyMode(degMode), triangulationParameters( - rankTol, enableEPI, landmarkDistanceThreshold, - dynamicOutlierRejectionThreshold), retriangulationThreshold(1e-5), throwCheirality( - false), verboseCheirality(false) { + DegeneracyMode degMode = IGNORE_DEGENERACY, bool throwCheirality = false, + bool verboseCheirality = false) : + linearizationMode(linMode), degeneracyMode(degMode), retriangulationThreshold( + 1e-5), throwCheirality(throwCheirality), verboseCheirality( + verboseCheirality) { } virtual ~SmartProjectionParams() { @@ -80,14 +78,14 @@ public: void print(const std::string& str) const { std::cout << " linearizationMode: " << linearizationMode << "\n"; std::cout << " degeneracyMode: " << degeneracyMode << "\n"; - std::cout << " rankTolerance: " - << triangulationParameters.rankTolerance << "\n"; - std::cout << " enableEPI: " - << triangulationParameters.enableEPI << "\n"; + std::cout << " rankTolerance: " << triangulation.rankTolerance + << "\n"; + std::cout << " enableEPI: " << triangulation.enableEPI + << "\n"; std::cout << " landmarkDistanceThreshold: " - << triangulationParameters.landmarkDistanceThreshold << "\n"; + << triangulation.landmarkDistanceThreshold << "\n"; std::cout << " OutlierRejectionThreshold: " - << triangulationParameters.dynamicOutlierRejectionThreshold << "\n"; + << triangulation.dynamicOutlierRejectionThreshold << "\n"; std::cout.flush(); } @@ -98,7 +96,7 @@ public: return degeneracyMode; } TriangulationParameters getTriangulationParameters() const { - return triangulationParameters; + return triangulation; } bool getVerboseCheirality() const { return verboseCheirality; @@ -113,18 +111,16 @@ public: degeneracyMode = degMode; } void setRankTolerance(double rankTol) { - triangulationParameters.rankTolerance = rankTol; + triangulation.rankTolerance = rankTol; } void setEnableEPI(bool enableEPI) { - triangulationParameters.enableEPI = enableEPI; + triangulation.enableEPI = enableEPI; } void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold) { - triangulationParameters.landmarkDistanceThreshold = - landmarkDistanceThreshold; + triangulation.landmarkDistanceThreshold = landmarkDistanceThreshold; } void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold) { - triangulationParameters.dynamicOutlierRejectionThreshold = - dynOutRejectionThreshold; + triangulation.dynamicOutlierRejectionThreshold = dynOutRejectionThreshold; } }; @@ -188,7 +184,7 @@ public: std::cout << s << "SmartProjectionFactor\n"; std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl; - std::cout << "triangulationParameters:\n" << params_.triangulationParameters + std::cout << "triangulationParameters:\n" << params_.triangulation << std::endl; std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); @@ -247,7 +243,7 @@ public: bool retriangulate = decideIfTriangulate(cameras); if (retriangulate) result_ = gtsam::triangulateSafe(cameras, this->measured_, - params_.triangulationParameters); + params_.triangulation); return result_; } From 1f2e7892408ac03d38c5d667980340c333f8eeca Mon Sep 17 00:00:00 2001 From: dellaert Date: Sat, 20 Jun 2015 13:26:25 -0700 Subject: [PATCH 171/173] Fixed print --- gtsam/slam/SmartProjectionFactor.h | 14 +++----------- 1 file changed, 3 insertions(+), 11 deletions(-) diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 7867200e6..d6b549acb 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -76,17 +76,9 @@ public: } void print(const std::string& str) const { - std::cout << " linearizationMode: " << linearizationMode << "\n"; - std::cout << " degeneracyMode: " << degeneracyMode << "\n"; - std::cout << " rankTolerance: " << triangulation.rankTolerance - << "\n"; - std::cout << " enableEPI: " << triangulation.enableEPI - << "\n"; - std::cout << " landmarkDistanceThreshold: " - << triangulation.landmarkDistanceThreshold << "\n"; - std::cout << " OutlierRejectionThreshold: " - << triangulation.dynamicOutlierRejectionThreshold << "\n"; - std::cout.flush(); + std::cout << "linearizationMode: " << linearizationMode << "\n"; + std::cout << " degeneracyMode: " << degeneracyMode << "\n"; + std::cout << triangulation << std::endl; } LinearizationMode getLinearizationMode() const { From 3a264ecc8cdc8695c61221e9a8d45569cf2889bd Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 23 Jun 2015 09:30:59 -0400 Subject: [PATCH 172/173] .cproject from develop --- .cproject | 3438 ++++++++++++++++++++++++++--------------------------- 1 file changed, 1719 insertions(+), 1719 deletions(-) diff --git a/.cproject b/.cproject index 2051b74fb..ac9b166ec 100644 --- a/.cproject +++ b/.cproject @@ -1,7 +1,5 @@ - - - + @@ -486,6 +484,341 @@ + + make + -j5 + testCombinedImuFactor.run + true + true + true + + + make + -j5 + testImuFactor.run + true + true + true + + + make + -j5 + testAHRSFactor.run + true + true + true + + + make + -j8 + testAttitudeFactor.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + testNonlinearConstraint.run + true + true + true + + + make + -j2 + testLieConfig.run + true + true + true + + + make + -j2 + testConstraintOptimizer.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j4 + testImuFactor.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testBTree.run + true + true + true + + + make + -j2 + testDSF.run + true + true + true + + + make + -j2 + testDSFVector.run + true + true + true + + + make + -j2 + testMatrix.run + true + true + true + + + make + -j2 + testSPQRUtil.run + true + true + true + + + make + -j2 + testVector.run + true + true + true + + + make + -j2 + timeMatrix.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + wrap + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + install + true + true + true + + + make + -j2 + all + true + true + true + + + cmake + .. + true + false + true + + + make + -j2 + check + true + true + true + + + make + -j2 + tests/testLieConfig.run + true + true + true + + + make + -j4 + testSimilarity3.run + true + true + true + + + make + -j5 + testInvDepthCamera3.run + true + true + true + + + make + -j5 + testTriangulation.run + true + true + true + + + make + -j4 + testEvent.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + all + true + false + true + + + make + -j5 + check + true + false + true + make -j5 @@ -534,39 +867,183 @@ true true - - make - -j4 - testSimilarity3.run - true - true - true - - + make -j5 - testInvDepthCamera3.run + testCal3Bundler.run true true true - + make -j5 - testTriangulation.run + testCal3DS2.run true true true - + + make + -j5 + testCalibratedCamera.run + true + true + true + + + make + -j5 + testEssentialMatrix.run + true + true + true + + + make + -j1 VERBOSE=1 + testHomography2.run + true + false + true + + + make + -j5 + testPinholeCamera.run + true + true + true + + + make + -j5 + testPoint2.run + true + true + true + + + make + -j5 + testPoint3.run + true + true + true + + + make + -j5 + testPose2.run + true + true + true + + + make + -j5 + testPose3.run + true + true + true + + + make + -j5 + testRot3M.run + true + true + true + + + make + -j5 + testSphere2.run + true + true + true + + + make + -j5 + testStereoCamera.run + true + true + true + + + make + -j5 + testCal3Unified.run + true + true + true + + + make + -j5 + testRot2.run + true + true + true + + + make + -j5 + testRot3Q.run + true + true + true + + + make + -j5 + testRot3.run + true + true + true + + make -j4 - testEvent.run + testSO3.run true true true - + + make + -j4 + testQuaternion.run + true + true + true + + + make + -j4 + testOrientedPlane3.run + true + true + true + + + make + -j4 + testPinholePose.run + true + true + true + + + make + -j4 + testCyclic.run + true + true + true + + make -j2 all @@ -574,7 +1051,7 @@ true true - + make -j2 clean @@ -582,137 +1059,23 @@ true true - - make - -k - check - true - false - true - - - make - tests/testBayesTree.run - true - false - true - - - make - testBinaryBayesNet.run - true - false - true - - + make -j2 - testFactorGraph.run + clean all true true true - + make -j2 - testISAM.run + install true true true - - make - -j2 - testJunctionTree.run - true - true - true - - - make - -j2 - testKey.run - true - true - true - - - make - -j2 - testOrdering.run - true - true - true - - - make - testSymbolicBayesNet.run - true - false - true - - - make - tests/testSymbolicFactor.run - true - false - true - - - make - testSymbolicFactorGraph.run - true - false - true - - - make - -j2 - timeSymbolMaps.run - true - true - true - - - make - tests/testBayesTree - true - false - true - - - make - -j2 - tests/testPose2.run - true - true - true - - - make - -j2 - tests/testPose3.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - check - true - true - true - - + make -j2 clean @@ -864,154 +1227,143 @@ true true - + make - -j5 - testGaussianFactorGraphUnordered.run + -j2 + all true true true - + make - -j5 - testGaussianBayesNetUnordered.run + -j2 + check true true true - + make - -j5 - testGaussianConditional.run - true - true - true - - - make - -j5 - testGaussianDensity.run - true - true - true - - - make - -j5 - testGaussianJunctionTree.run - true - true - true - - - make - -j5 - testHessianFactor.run - true - true - true - - - make - -j5 - testJacobianFactor.run - true - true - true - - - make - -j5 - testKalmanFilter.run - true - true - true - - - make - -j5 - testNoiseModel.run - true - true - true - - - make - -j5 - testSampler.run - true - true - true - - - make - -j5 - testSerializationLinear.run - true - true - true - - - make - -j5 - testVectorValues.run - true - true - true - - - make - -j5 - testGaussianBayesTree.run - true - true - true - - - make - -j5 - testCombinedImuFactor.run - true - true - true - - - make - -j5 - testImuFactor.run - true - true - true - - - make - -j5 - testAHRSFactor.run - true - true - true - - - make - -j8 - testAttitudeFactor.run - true - true - true - - - make - -j5 + -j2 clean true true true - + make - -j5 - all + -j2 + testPlanarSLAM.run + true + true + true + + + make + -j2 + testPose2Config.run + true + true + true + + + make + -j2 + testPose2Factor.run + true + true + true + + + make + -j2 + testPose2Prior.run + true + true + true + + + make + -j2 + testPose2SLAM.run + true + true + true + + + make + -j2 + testPose3Config.run + true + true + true + + + make + -j2 + testPose3SLAM.run + true + true + true + + + make + testSimulated2DOriented.run + true + false + true + + + make + -j2 + testVSLAMConfig.run + true + true + true + + + make + -j2 + testVSLAMFactor.run + true + true + true + + + make + -j2 + testVSLAMGraph.run + true + true + true + + + make + -j2 + testPose3Factor.run + true + true + true + + + make + testSimulated2D.run + true + false + true + + + make + testSimulated3D.run + true + false + true + + + make + -j2 + tests/testGaussianISAM2 true true true @@ -1106,479 +1458,112 @@ make + testErrors.run true false true - - make - -j2 - check - true - true - true - - - make - -j2 - tests/testGaussianJunctionTree.run - true - true - true - - - make - -j2 - tests/testGaussianFactor.run - true - true - true - - - make - -j2 - tests/testGaussianConditional.run - true - true - true - - - make - -j2 - tests/timeSLAMlike.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testBTree.run - true - true - true - - - make - -j2 - testDSF.run - true - true - true - - - make - -j2 - testDSFVector.run - true - true - true - - - make - -j2 - testMatrix.run - true - true - true - - - make - -j2 - testSPQRUtil.run - true - true - true - - - make - -j2 - testVector.run - true - true - true - - - make - -j2 - timeMatrix.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - testClusterTree.run - true - true - true - - - make - -j2 - testJunctionTree.run - true - true - true - - - make - -j2 - tests/testEliminationTree.run - true - true - true - - - make - -j2 - tests/testSymbolicFactor.run - true - true - true - - - make - -j2 - tests/testVariableSlots.run - true - true - true - - - make - -j2 - tests/testConditional.run - true - true - true - - - make - -j2 - tests/testSymbolicFactorGraph.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - testNonlinearConstraint.run - true - true - true - - - make - -j2 - testLieConfig.run - true - true - true - - - make - -j2 - testConstraintOptimizer.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testPlanarSLAM.run - true - true - true - - - make - -j2 - testPose2Config.run - true - true - true - - - make - -j2 - testPose2Factor.run - true - true - true - - - make - -j2 - testPose2Prior.run - true - true - true - - - make - -j2 - testPose2SLAM.run - true - true - true - - - make - -j2 - testPose3Config.run - true - true - true - - - make - -j2 - testPose3SLAM.run - true - true - true - - - make - - testSimulated2DOriented.run - true - false - true - - - make - -j2 - testVSLAMConfig.run - true - true - true - - - make - -j2 - testVSLAMFactor.run - true - true - true - - - make - -j2 - testVSLAMGraph.run - true - true - true - - - make - -j2 - testPose3Factor.run - true - true - true - - - make - - testSimulated2D.run - true - false - true - - - make - - testSimulated3D.run - true - false - true - - - make - -j2 - tests/testGaussianISAM2 - true - true - true - - + make -j5 - testBTree.run + testAntiFactor.run true true true - + make -j5 - testDSF.run + testPriorFactor.run true true true - + make -j5 - testDSFMap.run + testDataset.run true true true - + make -j5 - testDSFVector.run + testEssentialMatrixFactor.run true true true - + make -j5 - testFixedVector.run + testGeneralSFMFactor_Cal3Bundler.run true true true - + make -j5 - testEliminationTree.run + testGeneralSFMFactor.run true true true - + make -j5 - testInference.run + testProjectionFactor.run true true true - + make -j5 - testKey.run + testRotateFactor.run true true true - + make - -j1 - testSymbolicBayesTree.run + -j5 + testPoseRotationPrior.run true - false + true true - + make - -j1 - testSymbolicSequentialSolver.run + -j5 + testImplicitSchurFactor.run true - false + true true - + make -j4 - testLabeledSymbol.run + testRangeFactor.run true true true - + make - -j2 - check + -j4 + testOrientedPlane3Factor.run true true true - + make - -j2 - tests/testLieConfig.run + -j4 + testSmartProjectionPoseFactor.run true true true @@ -1784,6 +1769,7 @@ cpack + -G DEB true false @@ -1791,6 +1777,7 @@ cpack + -G RPM true false @@ -1798,6 +1785,7 @@ cpack + -G TGZ true false @@ -1805,6 +1793,7 @@ cpack + --config CPackSourceConfig.cmake true false @@ -1986,7 +1975,7 @@ false true - + make -j2 check @@ -1994,38 +1983,54 @@ true true - + make - -j2 - clean - true - true - true - - - make - -j2 - install - true - true - true - - - make - -j2 - all - true - true - true - - - cmake - .. + tests/testGaussianISAM2 true false true - + + make + -j2 + check + true + true + true + + + make + -j2 + tests/testGaussianJunctionTree.run + true + true + true + + + make + -j2 + tests/testGaussianFactor.run + true + true + true + + + make + -j2 + tests/testGaussianConditional.run + true + true + true + + + make + -j2 + tests/timeSLAMlike.run + true + true + true + + make -j2 testGaussianFactor.run @@ -2033,442 +2038,10 @@ true true - + make -j5 - testCal3Bundler.run - true - true - true - - - make - -j5 - testCal3DS2.run - true - true - true - - - make - -j5 - testCalibratedCamera.run - true - true - true - - - make - -j5 - testEssentialMatrix.run - true - true - true - - - make - -j1 VERBOSE=1 - testHomography2.run - true - false - true - - - make - -j5 - testPinholeCamera.run - true - true - true - - - make - -j5 - testPoint2.run - true - true - true - - - make - -j5 - testPoint3.run - true - true - true - - - make - -j5 - testPose2.run - true - true - true - - - make - -j5 - testPose3.run - true - true - true - - - make - -j5 - testRot3M.run - true - true - true - - - make - -j5 - testSphere2.run - true - true - true - - - make - -j5 - testStereoCamera.run - true - true - true - - - make - -j5 - testCal3Unified.run - true - true - true - - - make - -j5 - testRot2.run - true - true - true - - - make - -j5 - testRot3Q.run - true - true - true - - - make - -j5 - testRot3.run - true - true - true - - - make - -j4 - testSO3.run - true - true - true - - - make - -j4 - testQuaternion.run - true - true - true - - - make - -j4 - testOrientedPlane3.run - true - true - true - - - make - -j4 - testPinholePose.run - true - true - true - - - make - -j4 - testCyclic.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - all - true - false - true - - - make - -j5 - check - true - false - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - clean all - true - true - true - - - make - -j1 - testDiscreteBayesTree.run - true - false - true - - - make - -j5 - testDiscreteConditional.run - true - true - true - - - make - -j5 - testDiscreteFactor.run - true - true - true - - - make - -j5 - testDiscreteFactorGraph.run - true - true - true - - - make - -j5 - testDiscreteMarginals.run - true - true - true - - - make - -j5 - testIMUSystem.run - true - true - true - - - make - -j5 - testPoseRTV.run - true - true - true - - - make - -j5 - testVelocityConstraint.run - true - true - true - - - make - -j5 - testVelocityConstraint3.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - timeCalibratedCamera.run - true - true - true - - - make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - testWrap.run - true - true - true - - - make - -j5 - testSpirit.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - testMethod.run - true - true - true - - - make - -j5 - testClass.run - true - true - true - - - make - -j4 - testType.run - true - true - true - - - make - -j4 - testArgument.run - true - true - true - - - make - -j4 - testReturnValue.run - true - true - true - - - make - -j4 - testTemplate.run - true - true - true - - - make - -j4 - testGlobalFunction.run + testParticleFactor.run true true true @@ -2521,324 +2094,151 @@ true true - + make -j2 - vSFMexample.run + all true true true - - make - -j5 - testMatrix.run - true - true - true - - - make - -j5 - testVector.run - true - true - true - - - make - -j5 - testNumericalDerivative.run - true - true - true - - - make - -j5 - testVerticalBlockMatrix.run - true - true - true - - - make - -j4 - testOptionalJacobian.run - true - true - true - - - make - -j4 - testGroup.run - true - true - true - - + make -j2 - testVSLAMGraph - true - true - true - - - make - -j5 - check.tests - true - true - true - - - make - -j2 - timeGaussianFactorGraph.run - true - true - true - - - make - -j5 - testMarginals.run - true - true - true - - - make - -j5 - testGaussianISAM2.run - true - true - true - - - make - -j5 - testSymbolicFactorGraphB.run - true - true - true - - - make - -j2 - timeSequentialOnDataset.run - true - true - true - - - make - -j5 - testGradientDescentOptimizer.run - true - true - true - - - make - -j2 - testGaussianFactor.run - true - true - true - - - make - -j2 - testNonlinearOptimizer.run - true - true - true - - - make - -j2 - testGaussianBayesNet.run - true - true - true - - - make - -j2 - testNonlinearISAM.run - true - true - true - - - make - -j2 - testNonlinearEquality.run - true - true - true - - - make - -j2 - testExtendedKalmanFilter.run - true - true - true - - - make - -j5 - timing.tests - true - true - true - - - make - -j5 - testNonlinearFactor.run - true - true - true - - - make - -j5 clean true true true - + make - -j5 - testGaussianJunctionTreeB.run - true - true - true - - - make - testGraph.run + -k + check true false true - + make + + tests/testBayesTree.run + true + false + true + + + make + + testBinaryBayesNet.run + true + false + true + + + make + -j2 + testFactorGraph.run + true + true + true + + + make + -j2 + testISAM.run + true + true + true + + + make + -j2 testJunctionTree.run true - false + true true - + make - testSymbolicBayesNetB.run + -j2 + testKey.run + true + true + true + + + make + -j2 + testOrdering.run + true + true + true + + + make + + testSymbolicBayesNet.run true false true - + make - -j5 - testGaussianISAM.run + + tests/testSymbolicFactor.run true - true + false true - + make - -j5 - testDoglegOptimizer.run + + testSymbolicFactorGraph.run true - true + false true - - make - -j5 - testNonlinearFactorGraph.run - true - true - true - - - make - -j5 - testIterative.run - true - true - true - - - make - -j5 - testSubgraphSolver.run - true - true - true - - - make - -j5 - testGaussianFactorGraphB.run - true - true - true - - - make - -j5 - testSummarization.run - true - true - true - - - make - -j5 - testManifold.run - true - true - true - - - make - -j4 - testLie.run - true - true - true - - - make - -j5 - testParticleFactor.run - true - true - true - - + make -j2 - testGaussianFactor.run + timeSymbolMaps.run true true true - + + make + + tests/testBayesTree + true + false + true + + make -j2 - install + check true true true - + + make + -j2 + timeCalibratedCamera.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + make -j2 clean @@ -2846,146 +2246,18 @@ true true - + make -j2 - all + tests/testPose2.run true true true - + make -j2 - clean - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - testAntiFactor.run - true - true - true - - - make - -j5 - testPriorFactor.run - true - true - true - - - make - -j5 - testDataset.run - true - true - true - - - make - -j5 - testEssentialMatrixFactor.run - true - true - true - - - make - -j5 - testGeneralSFMFactor_Cal3Bundler.run - true - true - true - - - make - -j5 - testGeneralSFMFactor.run - true - true - true - - - make - -j5 - testProjectionFactor.run - true - true - true - - - make - -j5 - testRotateFactor.run - true - true - true - - - make - -j5 - testPoseRotationPrior.run - true - true - true - - - make - -j5 - testImplicitSchurFactor.run - true - true - true - - - make - -j4 - testRangeFactor.run - true - true - true - - - make - -j4 - testOrientedPlane3Factor.run - true - true - true - - - make - -j4 - testSmartProjectionPoseFactor.run - true - true - true - - - make - -j4 - testSmartProjectionCameraFactor.run + tests/testPose3.run true true true @@ -3190,190 +2462,6 @@ true true - - make - -j5 - testLago.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run - true - true - true - - - make - -j5 - testOrdering.run - true - true - true - - - make - -j5 - testValues.run - true - true - true - - - make - -j5 - testWhiteNoiseFactor.run - true - true - true - - - make - -j4 - testExpression.run - true - true - true - - - make - -j4 - testAdaptAutoDiff.run - true - true - true - - - make - -j4 - testCallRecord.run - true - true - true - - - make - -j4 - testExpressionFactor.run - true - true - true - - - make - -j4 - testExecutionTrace.run - true - true - true - - - make - -j4 - testImuFactor.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - - tests/testGaussianISAM2 - true - false - true - - - make - -j5 - timeCalibratedCamera.run - true - true - true - - - make - -j5 - timePinholeCamera.run - true - true - true - - - make - -j5 - timeStereoCamera.run - true - true - true - - - make - -j5 - timeLago.run - true - true - true - - - make - -j5 - timePose3.run - true - true - true - - - make - -j4 - timeAdaptAutoDiff.run - true - true - true - - - make - -j4 - timeCameraExpression.run - true - true - true - - - make - -j4 - timeOneCameraExpression.run - true - true - true - - - make - -j4 - timeSFMExpressions.run - true - true - true - - - make - -j4 - timeIncremental.run - true - true - true - make -j2 @@ -3470,10 +2558,922 @@ true true - + + make + -j1 + testDiscreteBayesTree.run + true + false + true + + make -j5 - wrap + testDiscreteConditional.run + true + true + true + + + make + -j5 + testDiscreteFactor.run + true + true + true + + + make + -j5 + testDiscreteFactorGraph.run + true + true + true + + + make + -j5 + testDiscreteMarginals.run + true + true + true + + + make + -j5 + testEliminationTree.run + true + true + true + + + make + -j5 + testInference.run + true + true + true + + + make + -j5 + testKey.run + true + true + true + + + make + -j1 + testSymbolicBayesTree.run + true + false + true + + + make + -j1 + testSymbolicSequentialSolver.run + true + false + true + + + make + -j4 + testLabeledSymbol.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + testClusterTree.run + true + true + true + + + make + -j2 + testJunctionTree.run + true + true + true + + + make + -j2 + tests/testEliminationTree.run + true + true + true + + + make + -j2 + tests/testSymbolicFactor.run + true + true + true + + + make + -j2 + tests/testVariableSlots.run + true + true + true + + + make + -j2 + tests/testConditional.run + true + true + true + + + make + -j2 + tests/testSymbolicFactorGraph.run + true + true + true + + + make + -j5 + testLago.run + true + true + true + + + make + -j5 + testLinearContainerFactor.run + true + true + true + + + make + -j5 + testOrdering.run + true + true + true + + + make + -j5 + testValues.run + true + true + true + + + make + -j5 + testWhiteNoiseFactor.run + true + true + true + + + make + -j4 + testExpression.run + true + true + true + + + make + -j4 + testAdaptAutoDiff.run + true + true + true + + + make + -j4 + testCallRecord.run + true + true + true + + + make + -j4 + testExpressionFactor.run + true + true + true + + + make + -j4 + testExecutionTrace.run + true + true + true + + + make + -j5 + testIMUSystem.run + true + true + true + + + make + -j5 + testPoseRTV.run + true + true + true + + + make + -j5 + testVelocityConstraint.run + true + true + true + + + make + -j5 + testVelocityConstraint3.run + true + true + true + + + make + -j5 + timeCalibratedCamera.run + true + true + true + + + make + -j5 + timePinholeCamera.run + true + true + true + + + make + -j5 + timeStereoCamera.run + true + true + true + + + make + -j5 + timeLago.run + true + true + true + + + make + -j5 + timePose3.run + true + true + true + + + make + -j4 + timeAdaptAutoDiff.run + true + true + true + + + make + -j4 + timeCameraExpression.run + true + true + true + + + make + -j4 + timeOneCameraExpression.run + true + true + true + + + make + -j4 + timeSFMExpressions.run + true + true + true + + + make + -j4 + timeIncremental.run + true + true + true + + + make + -j5 + testBTree.run + true + true + true + + + make + -j5 + testDSF.run + true + true + true + + + make + -j5 + testDSFMap.run + true + true + true + + + make + -j5 + testDSFVector.run + true + true + true + + + make + -j5 + testFixedVector.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + testGaussianFactorGraphUnordered.run + true + true + true + + + make + -j5 + testGaussianBayesNetUnordered.run + true + true + true + + + make + -j5 + testGaussianConditional.run + true + true + true + + + make + -j5 + testGaussianDensity.run + true + true + true + + + make + -j5 + testGaussianJunctionTree.run + true + true + true + + + make + -j5 + testHessianFactor.run + true + true + true + + + make + -j5 + testJacobianFactor.run + true + true + true + + + make + -j5 + testKalmanFilter.run + true + true + true + + + make + -j5 + testNoiseModel.run + true + true + true + + + make + -j5 + testSampler.run + true + true + true + + + make + -j5 + testSerializationLinear.run + true + true + true + + + make + -j5 + testVectorValues.run + true + true + true + + + make + -j5 + testGaussianBayesTree.run + true + true + true + + + make + -j5 + testWrap.run + true + true + true + + + make + -j5 + testSpirit.run + true + true + true + + + make + -j5 + check.wrap + true + true + true + + + make + -j5 + testMethod.run + true + true + true + + + make + -j5 + testClass.run + true + true + true + + + make + -j4 + testType.run + true + true + true + + + make + -j4 + testArgument.run + true + true + true + + + make + -j4 + testReturnValue.run + true + true + true + + + make + -j4 + testTemplate.run + true + true + true + + + make + -j4 + testGlobalFunction.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + testMatrix.run + true + true + true + + + make + -j5 + testVector.run + true + true + true + + + make + -j5 + testNumericalDerivative.run + true + true + true + + + make + -j5 + testVerticalBlockMatrix.run + true + true + true + + + make + -j4 + testOptionalJacobian.run + true + true + true + + + make + -j4 + testGroup.run + true + true + true + + + make + -j5 + check.tests + true + true + true + + + make + -j2 + timeGaussianFactorGraph.run + true + true + true + + + make + -j5 + testMarginals.run + true + true + true + + + make + -j5 + testGaussianISAM2.run + true + true + true + + + make + -j5 + testSymbolicFactorGraphB.run + true + true + true + + + make + -j2 + timeSequentialOnDataset.run + true + true + true + + + make + -j5 + testGradientDescentOptimizer.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + testNonlinearOptimizer.run + true + true + true + + + make + -j2 + testGaussianBayesNet.run + true + true + true + + + make + -j2 + testNonlinearISAM.run + true + true + true + + + make + -j2 + testNonlinearEquality.run + true + true + true + + + make + -j2 + testExtendedKalmanFilter.run + true + true + true + + + make + -j5 + timing.tests + true + true + true + + + make + -j5 + testNonlinearFactor.run + true + true + true + + + make + -j5 + clean + true + true + true + + + make + -j5 + testGaussianJunctionTreeB.run + true + true + true + + + make + + testGraph.run + true + false + true + + + make + + testJunctionTree.run + true + false + true + + + make + + testSymbolicBayesNetB.run + true + false + true + + + make + -j5 + testGaussianISAM.run + true + true + true + + + make + -j5 + testDoglegOptimizer.run + true + true + true + + + make + -j5 + testNonlinearFactorGraph.run + true + true + true + + + make + -j5 + testIterative.run + true + true + true + + + make + -j5 + testSubgraphSolver.run + true + true + true + + + make + -j5 + testGaussianFactorGraphB.run + true + true + true + + + make + -j5 + testSummarization.run + true + true + true + + + make + -j5 + testManifold.run + true + true + true + + + make + -j4 + testLie.run + true + true + true + + + make + -j2 + vSFMexample.run + true + true + true + + + make + -j5 + clean + true + true + true + + + make + -j5 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + testVSLAMGraph true true true From 16cbb97181efccba9abdf4d7735186d92f35219b Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 23 Jun 2015 22:41:08 -0700 Subject: [PATCH 173/173] Moved insert to cpp --- gtsam/linear/VectorValues.cpp | 12 ++++++++++++ gtsam/linear/VectorValues.h | 13 ++----------- 2 files changed, 14 insertions(+), 11 deletions(-) diff --git a/gtsam/linear/VectorValues.cpp b/gtsam/linear/VectorValues.cpp index 664fcf3b7..33c62cfb6 100644 --- a/gtsam/linear/VectorValues.cpp +++ b/gtsam/linear/VectorValues.cpp @@ -66,6 +66,18 @@ namespace gtsam { return result; } + /* ************************************************************************* */ + VectorValues::iterator VectorValues::insert(const std::pair& key_value) { + // Note that here we accept a pair with a reference to the Vector, but the Vector is copied as + // it is inserted into the values_ map. + std::pair result = values_.insert(key_value); + if(!result.second) + throw std::invalid_argument( + "Requested to insert variable '" + DefaultKeyFormatter(key_value.first) + + "' already in this VectorValues."); + return result.first; + } + /* ************************************************************************* */ void VectorValues::update(const VectorValues& values) { diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 968fc1adb..d04d9faac 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -181,23 +181,14 @@ namespace gtsam { * @param value The vector to be inserted. * @param j The index with which the value will be associated. */ iterator insert(Key j, const Vector& value) { - return insert(std::make_pair(j, value)); // Note only passing a reference to the Vector + return insert(std::make_pair(j, value)); } /** Insert a vector \c value with key \c j. Throws an invalid_argument exception if the key \c * j is already used. * @param value The vector to be inserted. * @param j The index with which the value will be associated. */ - iterator insert(const std::pair& key_value) { - // Note that here we accept a pair with a reference to the Vector, but the Vector is copied as - // it is inserted into the values_ map. - std::pair result = values_.insert(key_value); - if(!result.second) - throw std::invalid_argument( - "Requested to insert variable '" + DefaultKeyFormatter(key_value.first) - + "' already in this VectorValues."); - return result.first; - } + iterator insert(const std::pair& key_value); /** Insert all values from \c values. Throws an invalid_argument exception if any keys to be * inserted are already used. */