From 7a2af9999ae4f1a54d7af645411e0f6aff0ef1d8 Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Tue, 3 Jun 2014 11:21:11 -0400 Subject: [PATCH 01/57] Created stereo Smart factor classes, test class for SmartStereoProjectionPoseFactor --- gtsam/slam/SmartStereoProjectionFactor.h | 710 +++++++++ gtsam/slam/SmartStereoProjectionPoseFactor.h | 215 +++ .../testSmartStereoProjectionPoseFactor.cpp | 1318 +++++++++++++++++ 3 files changed, 2243 insertions(+) create mode 100644 gtsam/slam/SmartStereoProjectionFactor.h create mode 100644 gtsam/slam/SmartStereoProjectionPoseFactor.h create mode 100644 gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h new file mode 100644 index 000000000..4c8403a99 --- /dev/null +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -0,0 +1,710 @@ +/* ---------------------------------------------------------------------------- + + * 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 SmartStereoProjectionFactor.h + * @brief Base class to create smart factors on poses or cameras + * @author Luca Carlone + * @author Zsolt Kira + * @author Frank Dellaert + */ + +#pragma once + +#include "SmartFactorBase.h" + +#include +#include +#include +#include + +#include +#include +#include + +namespace gtsam { + +/** + * Structure for storing some state memory, used to speed up optimization + * @addtogroup SLAM + */ +class SmartStereoProjectionFactorState { + +protected: + +public: + + 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 + * TODO: why LANDMARK parameter? + */ +template +class SmartStereoProjectionFactor: public SmartFactorBase { +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 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 + + 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; + + /// 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; + +public: + + /// shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /// shorthand for a pinhole camera + typedef PinholeCamera Camera; + typedef std::vector 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 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, + 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_( + linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( + false), verboseCheirality_(false), state_(state), + landmarkDistanceThreshold_(landmarkDistanceThreshold), + dynamicOutlierRejectionThreshold_(dynamicOutlierRejectionThreshold) { + } + + /** Virtual destructor */ + virtual ~SmartStereoProjectionFactor() { + } + + /** + * 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 << "SmartStereoProjectionFactor, z = \n"; + std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; + std::cout << "degenerate_ = " << degenerate_ << std::endl; + std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; + Base::print("", keyFormatter); + } + + /// 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 + } + + /// 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)); + } + + /// 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->manageDegeneracy_ + && (this->cheiralityException_ || this->degenerate_))) { + if (isDebug) { + std::cout << "createImplicitSchurFactor: 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; + } + } + + /// linearize returns a Hessianfactor that is an approximation of error(p) + 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 < Key > js; + std::vector < Matrix > Gs(numKeys * (numKeys + 1) / 2); + std::vector < Vector > gs(numKeys); + + if (this->measured_.size() != cameras.size()) { + std::cout + << "SmartProjectionHessianFactor: this->measured_.size() inconsistent with input" + << std::endl; + exit(1); + } + + this->triangulateSafe(cameras); + + if (numKeys < 2 + || (!this->manageDegeneracy_ + && (this->cheiralityException_ || this->degenerate_))) { + // std::cout << "In linearize: exception" << std::endl; + BOOST_FOREACH(gtsam::Matrix& m, Gs) + m = zeros(D, D); + BOOST_FOREACH(Vector& v, gs) + v = zero(D); + return boost::make_shared >(this->keys_, 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; + } + + bool doLinearize = this->decideIfLinearize(cameras); + + if (this->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 + << "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; + Matrix3 PointCov; + Vector b; + double f = computeJacobians(F, E, PointCov, b, cameras, lambda); + + // 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); + Vector gs_vector; + + H.noalias() = F.transpose() * (F - (E * (PointCov * (E.transpose() * F)))); + gs_vector.noalias() = F.transpose() + * (b - (E * (PointCov * (E.transpose() * b)))); + if (isDebug) + std::cout << "gs_vector size " << gs_vector.size() << std::endl; + + // 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 < D > (i1D); + for (DenseIndex i2 = 0; i2 < (DenseIndex)numKeys; i2++) { + if (i2 >= i1) { + Gs.at(GsCount2) = H.block < D, D > (i1D, i2 * D); + GsCount2++; + } + } + } + // ================================================================== + 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); + } + + // create factor + boost::shared_ptr > createImplicitSchurFactor( + const Cameras& cameras, double lambda) const { + if (triangulateForLinearize(cameras)) + return Base::createImplicitSchurFactor(cameras, point_, lambda); + else + return boost::shared_ptr >(); + } + + /// create factor + 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_); + } + + /// Create a factor, takes values + boost::shared_ptr > createJacobianQFactor( + const Values& values, double lambda) const { + Cameras myCameras; + // TODO triangulate twice ?? + bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + if (nonDegenerate) + return createJacobianQFactor(myCameras, lambda); + else + return boost::make_shared< JacobianFactorQ >(this->keys_); + } + + /// different (faster) way to compute Jacobian factor + boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, + double lambda) const { + if (triangulateForLinearize(cameras)) + return Base::createJacobianSVDFactor(cameras, point_, lambda); + else + return boost::make_shared< JacobianFactorSVD >(this->keys_); + } + + /// Returns true if nonDegenerate + bool computeCamerasAndTriangulate(const Values& values, + Cameras& myCameras) 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); + + 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 << "SmartStereoProjectionFactor: this is not ready" << std::endl; + std::cout << "this->cheiralityException_ " << this->cheiralityException_ + << std::endl; + std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; + } + return true; + } + + /// Takes values + bool computeEP(Matrix& E, Matrix& PointCov, const Values& values) const { + Cameras myCameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + if (nonDegenerate) + computeEP(E, PointCov, myCameras); + return nonDegenerate; + } + + /// Assumes non-degenerate ! + void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras) const { + return Base::computeEP(E, PointCov, cameras, point_); + } + + /// Version that takes values, and creates the point + bool computeJacobians(std::vector& Fblocks, + Matrix& E, Matrix& PointCov, Vector& b, const Values& values) const { + Cameras myCameras; + bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + if (nonDegenerate) + computeJacobians(Fblocks, E, PointCov, b, myCameras, 0.0); + 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 { + + if (this->degenerate_) { + std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl; + std::cout << "point " << point_ << std::endl; + std::cout + << "SmartStereoProjectionFactor: Management of degeneracy is disabled - not ready to be used" + << std::endl; + if (D > 6) { + std::cout + << "Management of degeneracy is not yet ready when one also optimizes for the calibration " + << std::endl; + } + + int numKeys = this->keys_.size(); + E = zeros(2 * numKeys, 2); + b = zero(2 * numKeys); + 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) + - this->measured_.at(i)).vector(); + + this->noise_.at(i)->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; + subInsert(b, bi, 2 * i); + } + return f; + } else { + // nondegenerate: just return Base version + return Base::computeJacobians(Fblocks, E, b, cameras, point_); + } // 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 myCameras; + double good = computeCamerasAndTriangulate(values, myCameras); + if (good) + computeJacobiansSVD(Fblocks, Enull, b, myCameras); + 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, Matrix3& PointCov, Vector& b, + const Cameras& cameras, const double lambda) const { + return Base::computeJacobians(F, E, PointCov, b, cameras, point_, lambda); + } + + /// 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); + if (nonDegenerate) + return reprojectionError(myCameras); + else + return zero(myCameras.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->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; + 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; + 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->noise_.at(i)->distance(reprojectionError.vector()); + i += 1; + } + return overallError; + } else { + // Just use version in base class + return Base::totalReprojectionError(cameras, point_); + } + } + + /// Cameras are computed in derived class + virtual Cameras cameras(const Values& values) const = 0; + + /** 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 chirality 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_); + } +}; + +} // \ namespace gtsam diff --git a/gtsam/slam/SmartStereoProjectionPoseFactor.h b/gtsam/slam/SmartStereoProjectionPoseFactor.h new file mode 100644 index 000000000..06e82b2a7 --- /dev/null +++ b/gtsam/slam/SmartStereoProjectionPoseFactor.h @@ -0,0 +1,215 @@ +/* ---------------------------------------------------------------------------- + + * 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 SmartStereoProjectionPoseFactor.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 "SmartStereoProjectionFactor.h" + +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 SmartStereoProjectionPoseFactor: public SmartStereoProjectionFactor { +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) + +public: + + /// shorthand for base class type + typedef SmartStereoProjectionFactor Base; + + /// shorthand for this class + typedef SmartStereoProjectionPoseFactor 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 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, + double dynamicOutlierRejectionThreshold = -1) : + Base(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor, + landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_(linearizeTo) {} + + /** Virtual destructor */ + virtual ~SmartStereoProjectionPoseFactor() {} + + /** + * 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); + K_all_.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++) { + K_all_.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); + K_all_.push_back(K); + } + } + + /** + * 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 << "SmartStereoProjectionPoseFactor, z = \n "; + BOOST_FOREACH(const boost::shared_ptr& K, K_all_) + K->print("calibration = "); + 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 + virtual size_t dim() const { + return 6 * this->keys_.size(); + } + + /** + * 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); + typename Base::Camera camera(pose, *K_all_[i++]); + cameras.push_back(camera); + } + return cameras; + } + + /** + * 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(cameras(values), 0.0); + break; + case JACOBIAN_Q : + return this->createJacobianQFactor(cameras(values), 0.0); + break; + default: + return this->createHessianFactor(cameras(values)); + break; + } + } + + /** + * error calculates the error of the factor. + */ + virtual double error(const Values& values) const { + if (this->active(values)) { + return this->totalReprojectionError(cameras(values)); + } else { // else of active flag + return 0.0; + } + } + + /** return the calibration object */ + inline const std::vector > calibration() const { + return K_all_; + } + +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(K_all_); + } + +}; // end of class declaration + +} // \ namespace gtsam diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp new file mode 100644 index 000000000..c6192b1bd --- /dev/null +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -0,0 +1,1318 @@ +/* ---------------------------------------------------------------------------- + + * 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 TestSmartStereoProjectionPoseFactor.cpp + * @brief Unit tests for ProjectionFactor Class + * @author Chris Beall + * @author Luca Carlone + * @author Zsolt Kira + * @date Sept 2013 + */ + +#include "../SmartStereoProjectionPoseFactor.h" + +#include +#include +#include +#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 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, 1000, 2000)); + +static double rankTol = 1.0; +static double linThreshold = -1.0; +static bool manageDegeneracy = true; +// 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 +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 SmartStereoProjectionPoseFactor SmartFactor; +typedef SmartStereoProjectionPoseFactor SmartFactorBundler; + +void stereo_projectToMultipleCameras( + SimpleCamera cam1, SimpleCamera cam2, SimpleCamera 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( SmartStereoProjectionPoseFactor, Constructor) { + SmartFactor::shared_ptr factor1(new SmartFactor()); +} + +/* ************************************************************************* */ +//TEST( SmartStereoProjectionPoseFactor, Constructor2) { +// SmartFactor factor1(rankTol, linThreshold); +//} +// +///* ************************************************************************* */ +//TEST( SmartStereoProjectionPoseFactor, Constructor3) { +// SmartFactor::shared_ptr factor1(new SmartFactor()); +// factor1->add(measurement1, poseKey1, model, K); +//} +// +///* ************************************************************************* */ +//TEST( SmartStereoProjectionPoseFactor, Constructor4) { +// SmartFactor factor1(rankTol, linThreshold); +// 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()); +// factor1->add(measurement1, poseKey1, model, K); +// +// SmartFactor::shared_ptr factor2(new SmartFactor()); +// factor2->add(measurement1, poseKey1, model, K); +// +// CHECK(assert_equal(*factor1, *factor2)); +//} +// +///* *************************************************************************/ +//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), gtsam::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 level_uv = level_camera.project(landmark); +// Point2 level_uv_right = level_camera_right.project(landmark); +// +// Values values; +// values.insert(x1, level_pose); +// values.insert(x2, level_pose_right); +// +// SmartFactor factor1; +// factor1.add(level_uv, x1, model, K); +// factor1.add(level_uv_right, x2, model, K); +// +// double actualError = factor1.error(values); +// double expectedError = 0.0; +// EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7); +// +// SmartFactor::Cameras cameras = factor1.cameras(values); +// double actualError2 = factor1.totalReprojectionError(cameras); +// EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); +// +// // test vector of errors +// //Vector actual = factor1.unwhitenedError(values); +// //EXPECT(assert_equal(zero(4),actual,1e-8)); +//} +// +///* *************************************************************************/ +//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), gtsam::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); +// +// Values values; +// values.insert(x1, level_pose); +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); +// values.insert(x2, level_pose_right.compose(noise_pose)); +// +// SmartFactor::shared_ptr factor1(new SmartFactor()); +// factor1->add(level_uv, x1, model, K); +// factor1->add(level_uv_right, x2, model, K); +// +// double actualError1= factor1->error(values); +// +// SmartFactor::shared_ptr factor2(new SmartFactor()); +// vector measurements; +// measurements.push_back(level_uv); +// measurements.push_back(level_uv_right); +// +// std::vector< SharedNoiseModel > noises; +// noises.push_back(model); +// noises.push_back(model); +// +// std::vector< boost::shared_ptr > Ks; ///< shared pointer to calibration object (one for each camera) +// Ks.push_back(K); +// Ks.push_back(K); +// +// std::vector views; +// views.push_back(x1); +// views.push_back(x2); +// +// factor2->add(measurements, views, noises, Ks); +// +// double actualError2= factor2->error(values); +// +// DOUBLES_EQUAL(actualError1, actualError2, 1e-7); +//} +// +// +///* *************************************************************************/ +//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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K2); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K2); +// +// // 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); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// +// std::vector views; +// views.push_back(x1); +// views.push_back(x2); +// views.push_back(x3); +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); +// smartFactor1->add(measurements_cam1, views, model, K2); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor()); +// smartFactor2->add(measurements_cam2, views, model, K2); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor()); +// smartFactor3->add(measurements_cam3, views, model, K2); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); +// +// LevenbergMarquardtParams params; +// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; +// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; +// +// Values result; +// gttic_(SmartStereoProjectionPoseFactor); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +//// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); +//// VectorValues delta = GFG->optimize(); +// +// // 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_(); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, 3poses_iterative_smart_projection_factor ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// SimpleCamera cam3(pose3, *K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor()); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor()); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); +// +// LevenbergMarquardtParams params; +// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; +// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; +// +// Values result; +// gttic_(SmartStereoProjectionPoseFactor); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// EXPECT(assert_equal(pose3,result.at(x3))); +// if(isDebugTest) tictoc_print_(); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// SimpleCamera cam3(pose3, *K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// 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_SVD)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3*noise_pose); +// +// LevenbergMarquardtParams params; +// Values result; +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// EXPECT(assert_equal(pose3,result.at(x3))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, landmarkDistance ){ +// +// double excludeLandmarksFutherThanDist = 2; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// SimpleCamera cam3(pose3, *K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// 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_SVD, excludeLandmarksFutherThanDist)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// 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(); +// EXPECT(assert_equal(values.at(x3),result.at(x3))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ +// +// double excludeLandmarksFutherThanDist = 1e10; +// double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// SimpleCamera cam3(pose3, *K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// Point3 landmark4(5, -0.5, 1); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); +// 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, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, 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, +// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// SmartFactor::shared_ptr smartFactor4(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, +// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); +// smartFactor4->add(measurements_cam4, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(smartFactor4); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// 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(); +// EXPECT(assert_equal(pose3,result.at(x3))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, jacobianQ ){ +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// SimpleCamera cam3(pose3, *K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// 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)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3*noise_pose); +// +// LevenbergMarquardtParams params; +// Values result; +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// EXPECT(assert_equal(pose3,result.at(x3))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ +// // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K2); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K2); +// +// // 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); +// +// 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)); +// graph.push_back(ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); +// graph.push_back(ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); +// +// graph.push_back(ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); +// graph.push_back(ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); +// graph.push_back(ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); +// +// graph.push_back(ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); +// graph.push_back(ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); +// graph.push_back(ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3* noise_pose); +// values.insert(L(1), landmark1); +// values.insert(L(2), landmark2); +// values.insert(L(3), landmark3); +// 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))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, CheckHessian){ +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// SimpleCamera cam2(pose2, *K); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// SimpleCamera cam3(pose3, *K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// +// double rankTol = 10; +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); +// +// boost::shared_ptr hessianFactor1 = smartFactor1->linearize(values); +// boost::shared_ptr hessianFactor2 = smartFactor2->linearize(values); +// boost::shared_ptr hessianFactor3 = smartFactor3->linearize(values); +// +// Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); +// +// boost::shared_ptr GaussianGraph = graph.linearize(values); +// Matrix GraphInformation = GaussianGraph->hessian().first; +// +// // Check Hessian +// EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); +// +// Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + +// hessianFactor2->augmentedInformation() + hessianFactor3->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( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K2); +// +// // 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); +// +// // 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); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// +// double rankTol = 50; +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor1->add(measurements_cam1, views, model, K2); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor2->add(measurements_cam2, views, model, K2); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); +// Point3 positionPrior = gtsam::Point3(0,0,1); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); +// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2*noise_pose); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose*noise_pose); +// 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); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::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; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// SimpleCamera cam2(pose2, *K); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// SimpleCamera cam3(pose3, *K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// +// double rankTol = 10; +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); +// Point3 positionPrior = gtsam::Point3(0,0,1); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); +// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// 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); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::endl; +// // EXPECT(assert_equal(pose3,result.at(x3))); +// if(isDebugTest) tictoc_print_(); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, Hessian ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: Hessian **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K2); +// +// // 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); +// +// // 1. Project three landmarks into three cameras and triangulate +// Point2 cam1_uv1 = cam1.project(landmark1); +// Point2 cam2_uv1 = cam2.project(landmark1); +// vector measurements_cam1; +// measurements_cam1.push_back(cam1_uv1); +// measurements_cam1.push_back(cam2_uv1); +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); +// smartFactor1->add(measurements_cam1,views, model, K2); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// +// boost::shared_ptr hessianFactor = smartFactor1->linearize(values); +// if(isDebugTest) hessianFactor->print("Hessian factor \n"); +// +// // compute triangulation from linearization point +// // compute reprojection errors (sum squared) +// // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) +// // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] +//} +// +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// SimpleCamera cam2(pose2, *K); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// SimpleCamera cam3(pose3, *K); +// +// Point3 landmark1(5, 0.5, 1.2); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// +// SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); +// smartFactorInstance->add(measurements_cam1, views, model, K); +// +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3); +// +// boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); +// // hessianFactor->print("Hessian factor \n"); +// +// Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); +// +// Values rotValues; +// rotValues.insert(x1, poseDrift.compose(pose1)); +// rotValues.insert(x2, poseDrift.compose(pose2)); +// rotValues.insert(x3, poseDrift.compose(pose3)); +// +// boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); +// // hessianFactorRot->print("Hessian factor \n"); +// +// // Hessian is invariant to rotations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); +// +// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); +// +// Values tranValues; +// tranValues.insert(x1, poseDrift2.compose(pose1)); +// tranValues.insert(x2, poseDrift2.compose(pose2)); +// tranValues.insert(x3, poseDrift2.compose(pose3)); +// +// boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); +// +// // Hessian is invariant to rotations and translations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// SimpleCamera cam1(pose1, *K2); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0,0,0)); +// SimpleCamera cam2(pose2, *K2); +// +// // 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); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// +// SmartFactor::shared_ptr smartFactor(new SmartFactor()); +// smartFactor->add(measurements_cam1, views, model, K2); +// +// +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3); +// +// 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), gtsam::Point3(0,0,0)); +// +// Values rotValues; +// rotValues.insert(x1, poseDrift.compose(pose1)); +// rotValues.insert(x2, poseDrift.compose(pose2)); +// rotValues.insert(x3, poseDrift.compose(pose3)); +// +// boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); +// if(isDebugTest) hessianFactorRot->print("Hessian factor \n"); +// +// // Hessian is invariant to rotations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); +// +// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); +// +// Values tranValues; +// tranValues.insert(x1, poseDrift2.compose(pose1)); +// tranValues.insert(x2, poseDrift2.compose(pose2)); +// tranValues.insert(x3, poseDrift2.compose(pose3)); +// +// boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); +// +// // Hessian is invariant to rotations and translations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +//} +// +///* ************************************************************************* */ +//TEST( SmartStereoProjectionPoseFactor, ConstructorWithCal3Bundler) { +// SmartStereoProjectionPoseFactor factor1(rankTol, linThreshold); +// boost::shared_ptr Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); +// factor1.add(measurement1, poseKey1, model, Kbundler); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, Cal3Bundler ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: 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), gtsam::Point3(0,0,1)); +// PinholeCamera cam1(pose1, *Kbundler); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// PinholeCamera cam2(pose2, *Kbundler); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// PinholeCamera cam3(pose3, *Kbundler); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// Point2 cam1_uv1 = cam1.project(landmark1); +// Point2 cam2_uv1 = cam2.project(landmark1); +// Point2 cam3_uv1 = cam3.project(landmark1); +// measurements_cam1.push_back(cam1_uv1); +// measurements_cam1.push_back(cam2_uv1); +// measurements_cam1.push_back(cam3_uv1); +// +// Point2 cam1_uv2 = cam1.project(landmark2); +// Point2 cam2_uv2 = cam2.project(landmark2); +// Point2 cam3_uv2 = cam3.project(landmark2); +// measurements_cam2.push_back(cam1_uv2); +// measurements_cam2.push_back(cam2_uv2); +// measurements_cam2.push_back(cam3_uv2); +// +// Point2 cam1_uv3 = cam1.project(landmark3); +// Point2 cam2_uv3 = cam2.project(landmark3); +// Point2 cam3_uv3 = cam3.project(landmark3); +// measurements_cam3.push_back(cam1_uv3); +// measurements_cam3.push_back(cam2_uv3); +// measurements_cam3.push_back(cam3_uv3); +// +// std::vector views; +// views.push_back(x1); +// views.push_back(x2); +// views.push_back(x3); +// +// SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); +// smartFactor1->add(measurements_cam1, views, model, Kbundler); +// +// SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); +// smartFactor2->add(measurements_cam2, views, model, Kbundler); +// +// SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); +// smartFactor3->add(measurements_cam3, views, model, Kbundler); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); +// +// LevenbergMarquardtParams params; +// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; +// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; +// +// Values result; +// gttic_(SmartStereoProjectionPoseFactor); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// EXPECT(assert_equal(pose3,result.at(x3), 1e-6)); +// if(isDebugTest) tictoc_print_(); +// } +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, Cal3BundlerRotationOnly ){ +// +// std::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), gtsam::Point3(0,0,1)); +// PinholeCamera cam1(pose1, *Kbundler); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// PinholeCamera cam2(pose2, *Kbundler); +// +// // 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); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// Point2 cam1_uv1 = cam1.project(landmark1); +// Point2 cam2_uv1 = cam2.project(landmark1); +// Point2 cam3_uv1 = cam3.project(landmark1); +// measurements_cam1.push_back(cam1_uv1); +// measurements_cam1.push_back(cam2_uv1); +// measurements_cam1.push_back(cam3_uv1); +// +// Point2 cam1_uv2 = cam1.project(landmark2); +// Point2 cam2_uv2 = cam2.project(landmark2); +// Point2 cam3_uv2 = cam3.project(landmark2); +// measurements_cam2.push_back(cam1_uv2); +// measurements_cam2.push_back(cam2_uv2); +// measurements_cam2.push_back(cam3_uv2); +// +// Point2 cam1_uv3 = cam1.project(landmark3); +// Point2 cam2_uv3 = cam2.project(landmark3); +// Point2 cam3_uv3 = cam3.project(landmark3); +// measurements_cam3.push_back(cam1_uv3); +// measurements_cam3.push_back(cam2_uv3); +// measurements_cam3.push_back(cam3_uv3); +// +// double rankTol = 10; +// +// SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); +// smartFactor1->add(measurements_cam1, views, model, Kbundler); +// +// SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); +// smartFactor2->add(measurements_cam2, views, model, Kbundler); +// +// SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); +// smartFactor3->add(measurements_cam3, views, model, Kbundler); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); +// Point3 positionPrior = gtsam::Point3(0,0,1); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); +// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// 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); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::endl; +// // EXPECT(assert_equal(pose3,result.at(x3))); +// if(isDebugTest) tictoc_print_(); +//} +// +///* ************************************************************************* */ +//int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +///* ************************************************************************* */ + + From fb50e20c820f08f35f32b4cb9ae71fe577d0800a Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 3 Jun 2014 15:24:41 -0400 Subject: [PATCH 02/57] template on measurement so we can later have StereoPoint2 instead of Point2 --- gtsam/slam/SmartFactorBase.h | 199 ++++++++++++----------- gtsam/slam/SmartProjectionFactor.h | 4 +- gtsam/slam/SmartStereoProjectionFactor.h | 4 +- 3 files changed, 104 insertions(+), 103 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 1235fc6fb..29bb26437 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -36,31 +36,32 @@ namespace gtsam { /// Base class with no internal point, completely functional -template +template class SmartFactorBase: public NonlinearFactor { + protected: // Keep a copy of measurement and calibration for I/O - std::vector measured_; ///< 2D measurement for each of the m views + std::vector measured_; ///< 2D measurement for each of the m views std::vector noise_; ///< noise model used ///< (important that the order is the same as the keys that we use to create the factor) boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) /// 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 Matrix23; + typedef Eigen::Matrix Matrix23; typedef Eigen::Matrix VectorD; - typedef Eigen::Matrix Matrix2; + typedef Eigen::Matrix Matrix2; /// shorthand for base class type typedef NonlinearFactor Base; /// shorthand for this class - typedef SmartFactorBase This; + typedef SmartFactorBase This; public: @@ -89,7 +90,7 @@ public: * @param poseKey is the index corresponding to the camera observing the landmark * @param noise_i is the measurement noise */ - void add(const Point2& measured_i, const Key& poseKey_i, + void add(const Z& measured_i, const Key& poseKey_i, const SharedNoiseModel& noise_i) { this->measured_.push_back(measured_i); this->keys_.push_back(poseKey_i); @@ -100,7 +101,7 @@ public: * variant of the previous add: adds 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& poseKeys, std::vector& noises) { for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); @@ -113,7 +114,7 @@ public: * variant of the previous add: adds 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& poseKeys, const SharedNoiseModel& noise) { for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); @@ -127,16 +128,16 @@ public: * The noise is assumed to be the same for all measurements */ // **************************************************************************************************** - void add(const SfM_Track& trackToAdd, const SharedNoiseModel& noise) { - 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); - } - } +// void add(const SfM_Track& trackToAdd, const SharedNoiseModel& noise) { +// 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); +// } +// } /** return the measurements */ - const std::vector& measured() const { + const std::vector& measured() const { return measured_; } @@ -179,27 +180,27 @@ public: } // **************************************************************************************************** - /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionError(const Cameras& cameras, const Point3& point) const { - - Vector b = zero(2 * cameras.size()); - - size_t i = 0; - BOOST_FOREACH(const Camera& camera, cameras) { - const Point2& zi = this->measured_.at(i); - try { - Point2 e(camera.project(point) - zi); - b[2 * i] = e.x(); - b[2 * i + 1] = e.y(); - } catch (CheiralityException& e) { - std::cout << "Cheirality exception " << std::endl; - exit(EXIT_FAILURE); - } - i += 1; - } - - return b; - } +// /// Calculate vector of re-projection errors, before applying noise model +// Vector reprojectionError(const Cameras& cameras, const Point3& point) const { +// +// Vector b = zero(2 * cameras.size()); +// +// size_t i = 0; +// BOOST_FOREACH(const Camera& camera, cameras) { +// const Z& zi = this->measured_.at(i); +// try { +// Z e(camera.project(point) - zi); +// b[2 * i] = e.x(); +// b[2 * i + 1] = e.y(); +// } catch (CheiralityException& e) { +// std::cout << "Cheirality exception " << std::endl; +// exit(EXIT_FAILURE); +// } +// i += 1; +// } +// +// return b; +// } // **************************************************************************************************** /** @@ -216,9 +217,9 @@ public: size_t i = 0; BOOST_FOREACH(const Camera& camera, cameras) { - const Point2& zi = this->measured_.at(i); + const Z& zi = this->measured_.at(i); try { - Point2 reprojectionError(camera.project(point) - zi); + Z reprojectionError(camera.project(point) - zi); overallError += 0.5 * this->noise_.at(i)->distance(reprojectionError.vector()); } catch (CheiralityException&) { @@ -232,28 +233,28 @@ public: // **************************************************************************************************** /// Assumes non-degenerate ! - void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras, - const Point3& point) const { - - int numKeys = this->keys_.size(); - E = zeros(2 * numKeys, 3); - Vector b = zero(2 * numKeys); - - Matrix Ei(2, 3); - for (size_t i = 0; i < this->measured_.size(); i++) { - try { - cameras[i].project(point, boost::none, Ei); - } catch (CheiralityException& e) { - std::cout << "Cheirality exception " << std::endl; - exit(EXIT_FAILURE); - } - this->noise_.at(i)->WhitenSystem(Ei, b); - E.block<2, 3>(2 * i, 0) = Ei; - } - - // Matrix PointCov; - PointCov.noalias() = (E.transpose() * E).inverse(); - } +// void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras, +// const Point3& point) const { +// +// int numKeys = this->keys_.size(); +// E = zeros(2 * numKeys, 3); +// Vector b = zero(2 * numKeys); +// +// Matrix Ei(2, 3); +// for (size_t i = 0; i < this->measured_.size(); i++) { +// try { +// cameras[i].project(point, boost::none, Ei); +// } catch (CheiralityException& e) { +// std::cout << "Cheirality exception " << std::endl; +// exit(EXIT_FAILURE); +// } +// this->noise_.at(i)->WhitenSystem(Ei, b); +// E.block<2, 3>(2 * i, 0) = Ei; +// } +// +// // Matrix PointCov; +// PointCov.noalias() = (E.transpose() * E).inverse(); +// } // **************************************************************************************************** /// Compute F, E only (called below in both vanilla and SVD versions) @@ -262,11 +263,11 @@ public: Vector& b, const Cameras& cameras, const Point3& point) const { size_t numKeys = this->keys_.size(); - E = zeros(2 * numKeys, 3); - b = zero(2 * numKeys); + E = zeros(Z::Dim() * numKeys, 3); + b = zero(Z::Dim() * numKeys); double f = 0; - Matrix Fi(2, 6), Ei(2, 3), Hcali(2, D - 6), Hcam(2, D); + Matrix Fi(Z::Dim(), 6), Ei(Z::Dim(), 3), Hcali(Z::Dim(), D - 6), Hcam(Z::Dim(), D); for (size_t i = 0; i < this->measured_.size(); i++) { Vector bi; @@ -283,12 +284,12 @@ public: if (D == 6) { // optimize only camera pose Fblocks.push_back(KeyMatrix2D(this->keys_[i], Fi)); } else { - Hcam.block<2, 6>(0, 0) = Fi; // 2 x 6 block for the cameras - Hcam.block<2, D - 6>(0, 6) = Hcali; // 2 x nrCal block for the cameras + Hcam.block(0, 0) = Fi; // Z::Dim() x 6 block for the cameras + Hcam.block(0, 6) = Hcali; // Z::Dim() x nrCal block for the cameras Fblocks.push_back(KeyMatrix2D(this->keys_[i], Hcam)); } - E.block<2, 3>(2 * i, 0) = Ei; - subInsert(b, bi, 2 * i); + E.block(Z::dimension * i, 0) = Ei; + subInsert(b, bi, Z::Dim() * i); } return f; } @@ -329,10 +330,10 @@ public: std::vector Fblocks; double f = computeJacobians(Fblocks, E, PointCov, b, cameras, point, lambda); - F = zeros(2 * numKeys, D * numKeys); + F = zeros(Z::Dim() * numKeys, D * numKeys); for (size_t i = 0; i < this->keys_.size(); ++i) { - F.block<2, D>(2 * i, D * i) = Fblocks.at(i).second; // 2 x 6 block for the cameras + F.block(Z::Dim() * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras } return f; } @@ -351,9 +352,9 @@ public: // Do SVD on A Eigen::JacobiSVD svd(E, Eigen::ComputeFullU); Vector s = svd.singularValues(); - // Enull = zeros(2 * numKeys, 2 * numKeys - 3); + // Enull = zeros(Z::Dim() * numKeys, Z::Dim() * numKeys - 3); size_t numKeys = this->keys_.size(); - Enull = svd.matrixU().block(0, 3, 2 * numKeys, 2 * numKeys - 3); // last 2m-3 columns + Enull = svd.matrixU().block(0, 3, Z::Dim() * numKeys, Z::Dim() * numKeys - 3); // last Z::Dim()m-3 columns return f; } @@ -367,11 +368,11 @@ public: int numKeys = this->keys_.size(); std::vector Fblocks; double f = computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - F.resize(2 * numKeys, D * numKeys); + F.resize(Z::Dim() * numKeys, D * numKeys); F.setZero(); for (size_t i = 0; i < this->keys_.size(); ++i) - F.block<2, D>(2 * i, D * i) = Fblocks.at(i).second; // 2 x 6 block for the cameras + F.block(Z::Dim() * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras return f; } @@ -432,9 +433,9 @@ public: int numKeys = this->keys_.size(); /// Compute Full F ???? - Matrix F = zeros(2 * numKeys, D * numKeys); + Matrix F = zeros(Z::Dim() * numKeys, D * numKeys); for (size_t i = 0; i < this->keys_.size(); ++i) - F.block<2, D>(2 * i, D * i) = Fblocks.at(i).second; // 2 x 6 block for the cameras + F.block(Z::Dim() * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras Matrix H(D * numKeys, D * numKeys); Vector gs_vector; @@ -472,16 +473,16 @@ public: for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block<2, 3>(2 * i1, 0) * P; + const Matrix23 Ei1_P = E.block(Z::Dim() * i1, 0) * P; // D = (Dx2) * (2) // (augmentedHessian.matrix()).block (i1,numKeys+1) = Fi1.transpose() * b.segment < 2 > (2 * i1); // F' * b - augmentedHessian(i1, numKeys) = Fi1.transpose() * b.segment<2>(2 * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (Dx2) * (2x3) * (3*2m) * (2m x 1) + augmentedHessian(i1, numKeys) = Fi1.transpose() * b.segment(Z::Dim() * i1) // F' * b + - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZ::Dim()) * (Z::Dim()x3) * (3*Z::Dim()m) * (Z::Dim()m x 1) - // (DxD) = (Dx2) * ( (2xD) - (2x3) * (3x2) * (2xD) ) + // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xD) - (Z::Dim()x3) * (3xZ::Dim()) * (Z::Dim()xD) ) augmentedHessian(i1, i1) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block<2, 3>(2 * i1, 0).transpose() * Fi1); + * (Fi1 - Ei1_P * E.block(Z::Dim() * i1, 0).transpose() * Fi1); // upper triangular part of the hessian for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera @@ -489,7 +490,7 @@ public: // (DxD) = (Dx2) * ( (2x2) * (2xD) ) augmentedHessian(i1, i2) = -Fi1.transpose() - * (Ei1_P * E.block<2, 3>(2 * i2, 0).transpose() * Fi2); + * (Ei1_P * E.block(Z::Dim() * i2, 0).transpose() * Fi2); } } // end of for over cameras } @@ -516,16 +517,16 @@ public: // X X X X 14 const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block<2, 3>(2 * i1, 0) * P; + const Matrix23 Ei1_P = E.block(Z::Dim() * i1, 0) * P; { // for i1 = i2 // D = (Dx2) * (2) - gs.at(i1) = Fi1.transpose() * b.segment<2>(2 * i1) // F' * b - -Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (Dx2) * (2x3) * (3*2m) * (2m x 1) + gs.at(i1) = Fi1.transpose() * b.segment(Z::Dim() * i1) // F' * b + -Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZ::Dim()) * (Z::Dim()x3) * (3*Z::Dim()m) * (Z::Dim()m x 1) - // (DxD) = (Dx2) * ( (2xD) - (2x3) * (3x2) * (2xD) ) + // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xD) - (Z::Dim()x3) * (3xZ::Dim()) * (Z::Dim()xD) ) Gs.at(GsIndex) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block<2, 3>(2 * i1, 0).transpose() * Fi1); + * (Fi1 - Ei1_P * E.block(Z::Dim() * i1, 0).transpose() * Fi1); GsIndex++; } // upper triangular part of the hessian @@ -534,7 +535,7 @@ public: // (DxD) = (Dx2) * ( (2x2) * (2xD) ) Gs.at(GsIndex) = -Fi1.transpose() - * (Ei1_P * E.block<2, 3>(2 * i2, 0).transpose() * Fi2); + * (Ei1_P * E.block(Z::Dim() * i2, 0).transpose() * Fi2); GsIndex++; } } // end of for over cameras @@ -582,9 +583,9 @@ public: for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera in the current factor const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block<2, 3>(2 * i1, 0) * P; + const Matrix23 Ei1_P = E.block(Z::Dim() * i1, 0) * P; - // D = (Dx2) * (2) + // D = (DxZ::Dim()) * (Z::Dim()) // 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]; @@ -594,15 +595,15 @@ public: // vectorBlock = augmentedHessian(aug_i1, aug_numKeys).knownOffDiagonal(); // add contribution of current factor augmentedHessian(aug_i1, aug_numKeys) = augmentedHessian(aug_i1, aug_numKeys).knownOffDiagonal() - + Fi1.transpose() * b.segment<2>(2 * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (Dx2) * (2x3) * (3*2m) * (2m x 1) + + Fi1.transpose() * b.segment(Z::Dim() * i1) // F' * b + - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZ::Dim()) * (Z::Dim()x3) * (3*Z::Dim()m) * (Z::Dim()m x 1) - // (DxD) = (Dx2) * ( (2xD) - (2x3) * (3x2) * (2xD) ) + // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xD) - (Z::Dim()x3) * (3xZ::Dim()) * (Z::Dim()xD) ) // main block diagonal - store previous block matrixBlock = augmentedHessian(aug_i1, aug_i1); // add contribution of current factor augmentedHessian(aug_i1, aug_i1) = matrixBlock + - ( Fi1.transpose() * (Fi1 - Ei1_P * E.block<2, 3>(2 * i1, 0).transpose() * Fi1) ); + ( Fi1.transpose() * (Fi1 - Ei1_P * E.block(Z::Dim() * i1, 0).transpose() * Fi1) ); // upper triangular part of the hessian for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera @@ -611,12 +612,12 @@ public: //Key cameraKey_i2 = this->keys_[i2]; DenseIndex aug_i2 = KeySlotMap[this->keys_[i2]]; - // (DxD) = (Dx2) * ( (2x2) * (2xD) ) + // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xZ::Dim()) * (Z::Dim()xD) ) // off diagonal block - store previous block // matrixBlock = augmentedHessian(aug_i1, aug_i2).knownOffDiagonal(); // add contribution of current factor augmentedHessian(aug_i1, aug_i2) = augmentedHessian(aug_i1, aug_i2).knownOffDiagonal() - - Fi1.transpose() * (Ei1_P * E.block<2, 3>(2 * i2, 0).transpose() * Fi2); + - Fi1.transpose() * (Ei1_P * E.block(Z::Dim() * i2, 0).transpose() * Fi2); } } // end of for over cameras @@ -654,7 +655,7 @@ public: size_t numKeys = this->keys_.size(); std::vector < KeyMatrix2D > Fblocks; Vector b; - Matrix Enull(2*numKeys, 2*numKeys-3); + Matrix Enull(Z::Dim()*numKeys, Z::Dim()*numKeys-3); computeJacobiansSVD(Fblocks, Enull, b, cameras, point, lambda); return boost::make_shared< JacobianFactorSVD<6> >(Fblocks, Enull, b); } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 043528fea..b94b7239f 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -62,7 +62,7 @@ enum LinearizationMode { * TODO: why LANDMARK parameter? */ template -class SmartProjectionFactor: public SmartFactorBase { +class SmartProjectionFactor: public SmartFactorBase { protected: // Some triangulation parameters @@ -92,7 +92,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 diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 4c8403a99..cd9052f14 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -62,7 +62,7 @@ enum LinearizationMode { * TODO: why LANDMARK parameter? */ template -class SmartStereoProjectionFactor: public SmartFactorBase { +class SmartStereoProjectionFactor: public SmartFactorBase { protected: // Some triangulation parameters @@ -92,7 +92,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 From c583564098b7a7bd0802fdf989f753336e82b1eb Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 3 Jun 2014 15:24:50 -0400 Subject: [PATCH 03/57] uncomment test main --- gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index c6192b1bd..e31693f46 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -1310,9 +1310,9 @@ TEST( SmartStereoProjectionPoseFactor, Constructor) { // // EXPECT(assert_equal(pose3,result.at(x3))); // if(isDebugTest) tictoc_print_(); //} -// -///* ************************************************************************* */ -//int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -///* ************************************************************************* */ + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ From 6d33b3c24e880cb7c4f384a6cfc1b33f175b9031 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 3 Jun 2014 16:13:50 -0400 Subject: [PATCH 04/57] template base class on Camera instead of Calibration --- gtsam/slam/SmartFactorBase.h | 9 ++++----- gtsam/slam/SmartProjectionFactor.h | 4 ++-- gtsam/slam/SmartStereoProjectionFactor.h | 4 ++-- 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 29bb26437..7c5abca53 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -36,7 +36,7 @@ namespace gtsam { /// Base class with no internal point, completely functional -template +template class SmartFactorBase: public NonlinearFactor { protected: @@ -61,7 +61,7 @@ protected: typedef NonlinearFactor Base; /// shorthand for this class - typedef SmartFactorBase This; + typedef SmartFactorBase This; public: @@ -69,8 +69,7 @@ public: typedef boost::shared_ptr shared_ptr; /// shorthand for a pinhole camera - typedef PinholeCamera Camera; - typedef std::vector Cameras; + typedef std::vector Cameras; /** * Constructor @@ -216,7 +215,7 @@ public: double overallError = 0; size_t i = 0; - BOOST_FOREACH(const Camera& camera, cameras) { + BOOST_FOREACH(const CAMERA& camera, cameras) { const Z& zi = this->measured_.at(i); try { Z reprojectionError(camera.project(point) - zi); diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index b94b7239f..04112e239 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -62,7 +62,7 @@ enum LinearizationMode { * TODO: why LANDMARK parameter? */ template -class SmartProjectionFactor: public SmartFactorBase { +class SmartProjectionFactor: public SmartFactorBase, D> { protected: // Some triangulation parameters @@ -92,7 +92,7 @@ protected: typedef boost::shared_ptr SmartFactorStatePtr; /// shorthand for base class type - typedef SmartFactorBase Base; + typedef SmartFactorBase, D> Base; double landmarkDistanceThreshold_; // if the landmark is triangulated at a // distance larger than that the factor is considered degenerate diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index cd9052f14..56e5fdbf1 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -62,7 +62,7 @@ enum LinearizationMode { * TODO: why LANDMARK parameter? */ template -class SmartStereoProjectionFactor: public SmartFactorBase { +class SmartStereoProjectionFactor: public SmartFactorBase, D> { protected: // Some triangulation parameters @@ -92,7 +92,7 @@ protected: typedef boost::shared_ptr SmartFactorStatePtr; /// shorthand for base class type - typedef SmartFactorBase Base; + typedef SmartFactorBase, D> Base; double landmarkDistanceThreshold_; // if the landmark is triangulated at a // distance larger than that the factor is considered degenerate From 49ae04dc473a391cbf3df30487ec23d487a486ef Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 3 Jun 2014 16:51:03 -0400 Subject: [PATCH 05/57] start commenting out some unused code --- gtsam/slam/SmartFactorBase.h | 3 +- gtsam/slam/SmartStereoProjectionFactor.h | 146 +++++++++---------- gtsam/slam/SmartStereoProjectionPoseFactor.h | 12 +- 3 files changed, 80 insertions(+), 81 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 7c5abca53..69f92e402 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -25,10 +25,9 @@ #include "RegularHessianFactor.h" #include -#include +#include // for Cheirality exception #include #include -#include #include #include diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 56e5fdbf1..f93fb468b 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -408,44 +408,44 @@ public: return boost::make_shared >(this->keys_, Gs, gs, f); } - // create factor - boost::shared_ptr > createImplicitSchurFactor( - const Cameras& cameras, double lambda) const { - if (triangulateForLinearize(cameras)) - return Base::createImplicitSchurFactor(cameras, point_, lambda); - else - return boost::shared_ptr >(); - } - - /// create factor - 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_); - } - - /// Create a factor, takes values - boost::shared_ptr > createJacobianQFactor( - const Values& values, double lambda) const { - Cameras myCameras; - // TODO triangulate twice ?? - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); - if (nonDegenerate) - return createJacobianQFactor(myCameras, lambda); - else - return boost::make_shared< JacobianFactorQ >(this->keys_); - } - - /// different (faster) way to compute Jacobian factor - boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, - double lambda) const { - if (triangulateForLinearize(cameras)) - return Base::createJacobianSVDFactor(cameras, point_, lambda); - else - return boost::make_shared< JacobianFactorSVD >(this->keys_); - } +// // create factor +// boost::shared_ptr > createImplicitSchurFactor( +// const Cameras& cameras, double lambda) const { +// if (triangulateForLinearize(cameras)) +// return Base::createImplicitSchurFactor(cameras, point_, lambda); +// else +// return boost::shared_ptr >(); +// } +// +// /// create factor +// 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_); +// } +// +// /// Create a factor, takes values +// boost::shared_ptr > createJacobianQFactor( +// const Values& values, double lambda) const { +// Cameras myCameras; +// // TODO triangulate twice ?? +// bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); +// if (nonDegenerate) +// return createJacobianQFactor(myCameras, lambda); +// else +// return boost::make_shared< JacobianFactorQ >(this->keys_); +// } +// +// /// different (faster) way to compute Jacobian factor +// boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, +// double lambda) const { +// if (triangulateForLinearize(cameras)) +// return Base::createJacobianSVDFactor(cameras, point_, lambda); +// else +// return boost::make_shared< JacobianFactorSVD >(this->keys_); +// } /// Returns true if nonDegenerate bool computeCamerasAndTriangulate(const Values& values, @@ -546,41 +546,41 @@ 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 myCameras; - double good = computeCamerasAndTriangulate(values, myCameras); - if (good) - computeJacobiansSVD(Fblocks, Enull, b, myCameras); - 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_); - } +// /// 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 myCameras; +// double good = computeCamerasAndTriangulate(values, myCameras); +// if (good) +// computeJacobiansSVD(Fblocks, Enull, b, myCameras); +// 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, Matrix3& PointCov, Vector& b, diff --git a/gtsam/slam/SmartStereoProjectionPoseFactor.h b/gtsam/slam/SmartStereoProjectionPoseFactor.h index 06e82b2a7..4077071d9 100644 --- a/gtsam/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam/slam/SmartStereoProjectionPoseFactor.h @@ -172,12 +172,12 @@ public: 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(cameras(values), 0.0); - break; - case JACOBIAN_Q : - return this->createJacobianQFactor(cameras(values), 0.0); - break; +// case JACOBIAN_SVD : +// return this->createJacobianSVDFactor(cameras(values), 0.0); +// break; +// case JACOBIAN_Q : +// return this->createJacobianQFactor(cameras(values), 0.0); +// break; default: return this->createHessianFactor(cameras(values)); break; From 5f56d70000e4192cad99334c77484465f712bac2 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 3 Jun 2014 17:11:01 -0400 Subject: [PATCH 06/57] comment out things that wouldn't work with conversion to Stereo --- gtsam/slam/SmartStereoProjectionFactor.h | 44 ++++++++++++++---------- 1 file changed, 25 insertions(+), 19 deletions(-) diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index f93fb468b..9bfe72eae 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -23,6 +23,7 @@ #include #include +#include #include #include @@ -110,7 +111,10 @@ public: typedef boost::shared_ptr shared_ptr; /// shorthand for a pinhole camera + // TODO: Switch to stereoCamera: typedef PinholeCamera Camera; +// typedef StereoCamera Camera; + typedef std::vector Cameras; /** @@ -243,8 +247,10 @@ public: // We triangulate the 3D position of the landmark try { // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - point_ = triangulatePoint3(cameras, this->measured_, - rankTolerance_, enableEPI_); + + //TODO: Chris will replace this with something else for stereo +// point_ = triangulatePoint3(cameras, this->measured_, +// rankTolerance_, enableEPI_); degenerate_ = false; cheiralityException_ = false; @@ -639,23 +645,23 @@ public: } 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; - 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->noise_.at(i)->distance(reprojectionError.vector()); - i += 1; - } - return overallError; + 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; +// 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->noise_.at(i)->distance(reprojectionError.vector()); +// i += 1; +// } +// return overallError; } else { // Just use version in base class return Base::totalReprojectionError(cameras, point_); From c13569df4c659e5c27f9b819e5a93f4790f7c9ea Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Thu, 5 Jun 2014 09:25:06 -0400 Subject: [PATCH 07/57] Converted stereo factors to use stereo points and cameras; added operator<< to StereoPoint2 (STILL CAUSES LNK ERROR) --- gtsam/geometry/Cal3_S2Stereo.h | 5 +++++ gtsam/geometry/StereoPoint2.cpp | 5 +++++ gtsam/geometry/StereoPoint2.h | 2 ++ gtsam/slam/SmartFactorBase.h | 1 + gtsam/slam/SmartStereoProjectionFactor.h | 14 +++++++------- gtsam/slam/SmartStereoProjectionPoseFactor.h | 8 ++++---- .../testSmartStereoProjectionPoseFactor.cpp | 19 ++++++++++--------- 7 files changed, 34 insertions(+), 20 deletions(-) diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index 811264967..b47153547 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -52,6 +52,11 @@ namespace gtsam { /// constructor from vector Cal3_S2Stereo(const Vector &d): K_(d(0), d(1), d(2), d(3), d(4)), b_(d(5)){} + /// easy constructor; field-of-view in degrees, assumes zero skew + Cal3_S2Stereo(double fov, int w, int h, double b) : + K_(fov, w, h), b_(b) { + } + /// @} /// @name Testable /// @{ diff --git a/gtsam/geometry/StereoPoint2.cpp b/gtsam/geometry/StereoPoint2.cpp index f599a2dea..4aaa513f5 100644 --- a/gtsam/geometry/StereoPoint2.cpp +++ b/gtsam/geometry/StereoPoint2.cpp @@ -26,3 +26,8 @@ void StereoPoint2::print(const string& s) const { cout << s << "(" << uL_ << ", " << uR_ << ", " << v_ << ")" << endl; } /* ************************************************************************* */ + +ostream &operator<<(ostream &os, const StereoPoint2& p) { + os << '(' << p.uL() << ", " << p.uR() << p.v() << ')'; + return os; +} diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 8ce2e49bf..8e420fc16 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -88,6 +88,8 @@ namespace gtsam { StereoPoint2 operator-(const StereoPoint2& b) const { return StereoPoint2(uL_ - b.uL_, uR_ - b.uR_, v_ - b.v_); } + + GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const StereoPoint2& p); /// @} /// @name Manifold diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 69f92e402..eab7810db 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -26,6 +26,7 @@ #include #include // for Cheirality exception +#include #include #include diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 9bfe72eae..9fa1a2b27 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -63,7 +63,7 @@ enum LinearizationMode { * TODO: why LANDMARK parameter? */ template -class SmartStereoProjectionFactor: public SmartFactorBase, D> { +class SmartStereoProjectionFactor: public SmartFactorBase { protected: // Some triangulation parameters @@ -93,7 +93,7 @@ protected: typedef boost::shared_ptr SmartFactorStatePtr; /// shorthand for base class type - typedef SmartFactorBase, D> Base; + typedef SmartFactorBase Base; double landmarkDistanceThreshold_; // if the landmark is triangulated at a // distance larger than that the factor is considered degenerate @@ -112,7 +112,7 @@ public: /// shorthand for a pinhole camera // TODO: Switch to stereoCamera: - typedef PinholeCamera Camera; + typedef StereoCamera Camera; // typedef StereoCamera Camera; typedef std::vector Cameras; @@ -264,9 +264,9 @@ public: degenerate_ = true; break; } - const Point2& zi = this->measured_.at(i); + const StereoPoint2& zi = this->measured_.at(i); try { - Point2 reprojectionError(camera.project(point_) - zi); + StereoPoint2 reprojectionError(camera.project(point_) - zi); totalReprojError += reprojectionError.vector().norm(); } catch (CheiralityException) { cheiralityException_ = true; @@ -652,10 +652,10 @@ public: // size_t i = 0; // double overallError = 0; // BOOST_FOREACH(const Camera& camera, cameras) { -// const Point2& zi = this->measured_.at(i); +// const StereoPoint2& zi = this->measured_.at(i); // if (i == 0) // first pose // this->point_ = camera.backprojectPointAtInfinity(zi); // 3D parametrization of point at infinity -// Point2 reprojectionError( +// StereoPoint2 reprojectionError( // camera.projectPointAtInfinity(this->point_) - zi); // overallError += 0.5 // * this->noise_.at(i)->distance(reprojectionError.vector()); diff --git a/gtsam/slam/SmartStereoProjectionPoseFactor.h b/gtsam/slam/SmartStereoProjectionPoseFactor.h index 4077071d9..b6fad38fa 100644 --- a/gtsam/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam/slam/SmartStereoProjectionPoseFactor.h @@ -83,7 +83,7 @@ public: * @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, + void add(const StereoPoint2 measured_i, const Key poseKey_i, const SharedNoiseModel noise_i, const boost::shared_ptr K_i) { Base::add(measured_i, poseKey_i, noise_i); @@ -97,7 +97,7 @@ public: * @param noises vector of measurement noises * @param Ks vector of calibration objects */ - void add(std::vector measurements, std::vector poseKeys, + void add(std::vector measurements, std::vector poseKeys, std::vector noises, std::vector > Ks) { Base::add(measurements, poseKeys, noises); @@ -113,7 +113,7 @@ public: * @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, + 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); @@ -157,7 +157,7 @@ public: size_t i=0; BOOST_FOREACH(const Key& k, this->keys_) { Pose3 pose = values.at(k); - typename Base::Camera camera(pose, *K_all_[i++]); + typename Base::Camera camera(pose, K_all_[i++]); cameras.push_back(camera); } return cameras; diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index e31693f46..5952dd9bb 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -36,9 +36,10 @@ static bool isDebugTest = false; // make a realistic calibration matrix static double fov = 60; // degrees static size_t w=640,h=480; +static double b = 1; -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 Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fov,w,h,b)); +static Cal3_S2Stereo::shared_ptr K2(new Cal3_S2Stereo(1500, 1200, 0, 640, 480,b)); static boost::shared_ptr Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); static double rankTol = 1.0; @@ -57,19 +58,19 @@ static Symbol x2('X', 2); static Symbol x3('X', 3); static Key poseKey1(x1); -static Point2 measurement1(323.0, 240.0); +static StereoPoint2 measurement1(323.0, 300.0, 240.0); //potentially use more reasonable measurement value? 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 SmartFactor; typedef SmartStereoProjectionPoseFactor SmartFactorBundler; void stereo_projectToMultipleCameras( - SimpleCamera cam1, SimpleCamera cam2, SimpleCamera cam3, Point3 landmark, - vector& measurements_cam){ + StereoCamera cam1, StereoCamera cam2, StereoCamera cam3, Point3 landmark, + vector& measurements_cam){ - Point2 cam1_uv1 = cam1.project(landmark); - Point2 cam2_uv1 = cam2.project(landmark); - Point2 cam3_uv1 = cam3.project(landmark); + StereoPoint2 cam1_uv1 = cam1.project(landmark); + StereoPoint2 cam2_uv1 = cam2.project(landmark); + StereoPoint2 cam3_uv1 = cam3.project(landmark); measurements_cam.push_back(cam1_uv1); measurements_cam.push_back(cam2_uv1); measurements_cam.push_back(cam3_uv1); From a343c947b4418914613c3f579e0311088cb0f0a4 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 5 Jun 2014 10:59:06 -0400 Subject: [PATCH 08/57] fix linker error, namespace issue --- gtsam/geometry/StereoPoint2.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/StereoPoint2.cpp b/gtsam/geometry/StereoPoint2.cpp index 4aaa513f5..cd6f09507 100644 --- a/gtsam/geometry/StereoPoint2.cpp +++ b/gtsam/geometry/StereoPoint2.cpp @@ -19,15 +19,18 @@ #include using namespace std; -using namespace gtsam; + +namespace gtsam { /* ************************************************************************* */ void StereoPoint2::print(const string& s) const { cout << s << "(" << uL_ << ", " << uR_ << ", " << v_ << ")" << endl; } -/* ************************************************************************* */ +/* ************************************************************************* */ ostream &operator<<(ostream &os, const StereoPoint2& p) { - os << '(' << p.uL() << ", " << p.uR() << p.v() << ')'; + os << '(' << p.uL() << ", " << p.uR() << ", " << p.v() << ')'; return os; } + +} // namespace gtsam From 2120c7bcb911584c9c387347f28cb27cc772c75e Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 5 Jun 2014 11:00:38 -0400 Subject: [PATCH 09/57] Move friend to conventional place because it doesn't belong in "Group" --- gtsam/geometry/StereoPoint2.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 8e420fc16..186afae55 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -89,8 +89,6 @@ namespace gtsam { return StereoPoint2(uL_ - b.uL_, uR_ - b.uR_, v_ - b.v_); } - GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const StereoPoint2& p); - /// @} /// @name Manifold /// @{ @@ -154,6 +152,9 @@ namespace gtsam { return Point2(uR_, v_); } + /// Streaming + GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const StereoPoint2& p); + private: /// @} From f84817e572774b126dbd941659ff6c0155c89570 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 5 Jun 2014 11:01:23 -0400 Subject: [PATCH 10/57] comment out degenerate part and throw --- gtsam/slam/SmartStereoProjectionFactor.h | 66 ++++++++++++------------ 1 file changed, 33 insertions(+), 33 deletions(-) diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 9fa1a2b27..0d0d2bc0f 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -512,40 +512,40 @@ public: /// 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 { - if (this->degenerate_) { - std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl; - std::cout << "point " << point_ << std::endl; - std::cout - << "SmartStereoProjectionFactor: Management of degeneracy is disabled - not ready to be used" - << std::endl; - if (D > 6) { - std::cout - << "Management of degeneracy is not yet ready when one also optimizes for the calibration " - << std::endl; - } - - int numKeys = this->keys_.size(); - E = zeros(2 * numKeys, 2); - b = zero(2 * numKeys); - 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) - - this->measured_.at(i)).vector(); - - this->noise_.at(i)->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; - subInsert(b, bi, 2 * i); - } - return f; + throw("FIXME: computeJacobians degenerate case commented out!"); +// std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl; +// std::cout << "point " << point_ << std::endl; +// std::cout +// << "SmartStereoProjectionFactor: Management of degeneracy is disabled - not ready to be used" +// << std::endl; +// if (D > 6) { +// std::cout +// << "Management of degeneracy is not yet ready when one also optimizes for the calibration " +// << std::endl; +// } +// +// int numKeys = this->keys_.size(); +// E = zeros(2 * numKeys, 2); +// b = zero(2 * numKeys); +// 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) +// - this->measured_.at(i)).vector(); +// +// this->noise_.at(i)->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; +// subInsert(b, bi, 2 * i); +// } +// return f; } else { // nondegenerate: just return Base version return Base::computeJacobians(Fblocks, E, b, cameras, point_); From e376ad8cecc7cb5881720b4cdb0b408ca3edda2d Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Mon, 9 Jun 2014 00:20:59 -0400 Subject: [PATCH 11/57] Completed SmartStereoProjectionPoseFactor unit tests --- .../testSmartStereoProjectionPoseFactor.cpp | 2115 +++++++++-------- 1 file changed, 1058 insertions(+), 1057 deletions(-) diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 5952dd9bb..5cdb4ff04 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include #include @@ -82,1084 +83,1084 @@ TEST( SmartStereoProjectionPoseFactor, Constructor) { } /* ************************************************************************* */ -//TEST( SmartStereoProjectionPoseFactor, Constructor2) { -// SmartFactor factor1(rankTol, linThreshold); -//} -// +TEST( SmartStereoProjectionPoseFactor, Constructor2) { + SmartFactor factor1(rankTol, linThreshold); +} + ///* ************************************************************************* */ -//TEST( SmartStereoProjectionPoseFactor, Constructor3) { -// SmartFactor::shared_ptr factor1(new SmartFactor()); -// factor1->add(measurement1, poseKey1, model, K); -//} -// +TEST( SmartStereoProjectionPoseFactor, Constructor3) { + SmartFactor::shared_ptr factor1(new SmartFactor()); + factor1->add(measurement1, poseKey1, model, K); +} + ///* ************************************************************************* */ -//TEST( SmartStereoProjectionPoseFactor, Constructor4) { -// SmartFactor factor1(rankTol, linThreshold); -// factor1.add(measurement1, poseKey1, model, K); -//} -// +TEST( SmartStereoProjectionPoseFactor, Constructor4) { + SmartFactor factor1(rankTol, linThreshold); + 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()); -// factor1->add(measurement1, poseKey1, model, K); -// -// SmartFactor::shared_ptr factor2(new SmartFactor()); -// factor2->add(measurement1, poseKey1, model, K); -// -// CHECK(assert_equal(*factor1, *factor2)); -//} -// -///* *************************************************************************/ -//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), gtsam::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 level_uv = level_camera.project(landmark); -// Point2 level_uv_right = level_camera_right.project(landmark); -// -// Values values; -// values.insert(x1, level_pose); -// values.insert(x2, level_pose_right); -// -// SmartFactor factor1; -// factor1.add(level_uv, x1, model, K); -// factor1.add(level_uv_right, x2, model, K); -// -// double actualError = factor1.error(values); -// double expectedError = 0.0; -// EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7); -// -// SmartFactor::Cameras cameras = factor1.cameras(values); -// double actualError2 = factor1.totalReprojectionError(cameras); -// EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); -// -// // test vector of errors -// //Vector actual = factor1.unwhitenedError(values); -// //EXPECT(assert_equal(zero(4),actual,1e-8)); -//} -// -///* *************************************************************************/ -//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), gtsam::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); -// -// Values values; -// values.insert(x1, level_pose); -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); -// values.insert(x2, level_pose_right.compose(noise_pose)); -// -// SmartFactor::shared_ptr factor1(new SmartFactor()); -// factor1->add(level_uv, x1, model, K); -// factor1->add(level_uv_right, x2, model, K); -// -// double actualError1= factor1->error(values); -// -// SmartFactor::shared_ptr factor2(new SmartFactor()); -// vector measurements; -// measurements.push_back(level_uv); -// measurements.push_back(level_uv_right); -// -// std::vector< SharedNoiseModel > noises; -// noises.push_back(model); -// noises.push_back(model); -// -// std::vector< boost::shared_ptr > Ks; ///< shared pointer to calibration object (one for each camera) -// Ks.push_back(K); -// Ks.push_back(K); -// -// std::vector views; -// views.push_back(x1); -// views.push_back(x2); -// -// factor2->add(measurements, views, noises, Ks); -// -// double actualError2= factor2->error(values); -// -// DOUBLES_EQUAL(actualError1, actualError2, 1e-7); -//} -// -// -///* *************************************************************************/ -//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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K2); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K2); -// -// // 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); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); -// -// std::vector views; -// views.push_back(x1); -// views.push_back(x2); -// views.push_back(x3); -// -// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); -// smartFactor1->add(measurements_cam1, views, model, K2); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor()); -// smartFactor2->add(measurements_cam2, views, model, K2); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor()); -// smartFactor3->add(measurements_cam3, views, model, K2); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; -// -// Values result; -// gttic_(SmartStereoProjectionPoseFactor); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// gttoc_(SmartStereoProjectionPoseFactor); -// tictoc_finishedIteration_(); -// -//// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); -//// VectorValues delta = GFG->optimize(); -// -// // 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_(); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, 3poses_iterative_smart_projection_factor ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// SimpleCamera cam3(pose3, *K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); -// -// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor()); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor()); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; -// -// Values result; -// gttic_(SmartStereoProjectionPoseFactor); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// gttoc_(SmartStereoProjectionPoseFactor); -// tictoc_finishedIteration_(); -// -// // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// EXPECT(assert_equal(pose3,result.at(x3))); -// if(isDebugTest) tictoc_print_(); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K); -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// SimpleCamera cam3(pose3, *K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// 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_SVD)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3*noise_pose); -// -// LevenbergMarquardtParams params; -// Values result; -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// EXPECT(assert_equal(pose3,result.at(x3))); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, landmarkDistance ){ -// -// double excludeLandmarksFutherThanDist = 2; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K); -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// SimpleCamera cam3(pose3, *K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// 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_SVD, excludeLandmarksFutherThanDist)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// 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(); -// EXPECT(assert_equal(values.at(x3),result.at(x3))); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ -// -// double excludeLandmarksFutherThanDist = 1e10; -// double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K); -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// SimpleCamera cam3(pose3, *K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// Point3 landmark4(5, -0.5, 1); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); -// 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, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, 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, -// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// SmartFactor::shared_ptr smartFactor4(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, -// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); -// smartFactor4->add(measurements_cam4, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(smartFactor4); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// 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(); -// EXPECT(assert_equal(pose3,result.at(x3))); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, jacobianQ ){ -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K); -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// SimpleCamera cam3(pose3, *K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// 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)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3*noise_pose); -// -// LevenbergMarquardtParams params; -// Values result; -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// EXPECT(assert_equal(pose3,result.at(x3))); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ -// // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K2); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K2); -// -// // 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); -// -// 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)); -// graph.push_back(ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); -// graph.push_back(ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); -// -// graph.push_back(ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); -// graph.push_back(ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); -// graph.push_back(ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); -// -// graph.push_back(ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); -// graph.push_back(ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); -// graph.push_back(ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3* noise_pose); -// values.insert(L(1), landmark1); -// values.insert(L(2), landmark2); -// values.insert(L(3), landmark3); -// 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))); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, CheckHessian){ -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); -// SimpleCamera cam2(pose2, *K); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); -// SimpleCamera cam3(pose3, *K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); -// -// double rankTol = 10; -// -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// boost::shared_ptr hessianFactor1 = smartFactor1->linearize(values); -// boost::shared_ptr hessianFactor2 = smartFactor2->linearize(values); -// boost::shared_ptr hessianFactor3 = smartFactor3->linearize(values); -// -// Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); -// -// boost::shared_ptr GaussianGraph = graph.linearize(values); -// Matrix GraphInformation = GaussianGraph->hessian().first; -// -// // Check Hessian -// EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); -// -// Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + -// hessianFactor2->augmentedInformation() + hessianFactor3->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( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K2); -// -// // 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); -// -// // 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); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// -// double rankTol = 50; -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); -// smartFactor1->add(measurements_cam1, views, model, K2); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); -// smartFactor2->add(measurements_cam2, views, model, K2); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); -// Point3 positionPrior = gtsam::Point3(0,0,1); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); -// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); -// -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2*noise_pose); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose*noise_pose); -// 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); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// gttoc_(SmartStereoProjectionPoseFactor); -// tictoc_finishedIteration_(); -// -// // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::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; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); -// SimpleCamera cam2(pose2, *K); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); -// SimpleCamera cam3(pose3, *K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); -// -// double rankTol = 10; -// -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); -// Point3 positionPrior = gtsam::Point3(0,0,1); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); -// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose); -// 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); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// gttoc_(SmartStereoProjectionPoseFactor); -// tictoc_finishedIteration_(); -// -// // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::endl; -// // EXPECT(assert_equal(pose3,result.at(x3))); -// if(isDebugTest) tictoc_print_(); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, Hessian ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: Hessian **********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K2); -// -// // 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); -// -// // 1. Project three landmarks into three cameras and triangulate -// Point2 cam1_uv1 = cam1.project(landmark1); -// Point2 cam2_uv1 = cam2.project(landmark1); -// vector measurements_cam1; -// measurements_cam1.push_back(cam1_uv1); -// measurements_cam1.push_back(cam2_uv1); -// -// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); -// smartFactor1->add(measurements_cam1,views, model, K2); -// -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// -// boost::shared_ptr hessianFactor = smartFactor1->linearize(values); -// if(isDebugTest) hessianFactor->print("Hessian factor \n"); -// -// // compute triangulation from linearization point -// // compute reprojection errors (sum squared) -// // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) -// // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] -//} -// -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// SimpleCamera cam2(pose2, *K); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// SimpleCamera cam3(pose3, *K); -// -// Point3 landmark1(5, 0.5, 1.2); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// -// SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); -// smartFactorInstance->add(measurements_cam1, views, model, K); -// -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3); -// -// boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); -// // hessianFactor->print("Hessian factor \n"); -// -// Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); -// -// Values rotValues; -// rotValues.insert(x1, poseDrift.compose(pose1)); -// rotValues.insert(x2, poseDrift.compose(pose2)); -// rotValues.insert(x3, poseDrift.compose(pose3)); -// -// boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); -// // hessianFactorRot->print("Hessian factor \n"); -// -// // Hessian is invariant to rotations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); -// -// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); -// -// Values tranValues; -// tranValues.insert(x1, poseDrift2.compose(pose1)); -// tranValues.insert(x2, poseDrift2.compose(pose2)); -// tranValues.insert(x3, poseDrift2.compose(pose3)); -// -// boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); -// -// // Hessian is invariant to rotations and translations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// SimpleCamera cam1(pose1, *K2); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0,0,0)); -// SimpleCamera cam2(pose2, *K2); -// -// // 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); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// -// SmartFactor::shared_ptr smartFactor(new SmartFactor()); -// smartFactor->add(measurements_cam1, views, model, K2); -// -// -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3); -// -// 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), gtsam::Point3(0,0,0)); -// -// Values rotValues; -// rotValues.insert(x1, poseDrift.compose(pose1)); -// rotValues.insert(x2, poseDrift.compose(pose2)); -// rotValues.insert(x3, poseDrift.compose(pose3)); -// -// boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); -// if(isDebugTest) hessianFactorRot->print("Hessian factor \n"); -// -// // Hessian is invariant to rotations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); -// -// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); -// -// Values tranValues; -// tranValues.insert(x1, poseDrift2.compose(pose1)); -// tranValues.insert(x2, poseDrift2.compose(pose2)); -// tranValues.insert(x3, poseDrift2.compose(pose3)); -// -// boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); -// -// // Hessian is invariant to rotations and translations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -//} -// +TEST( 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()); + factor1->add(measurement1, poseKey1, model, K); + + SmartFactor::shared_ptr factor2(new SmartFactor()); + factor2->add(measurement1, poseKey1, model, K); + + CHECK(assert_equal(*factor1, *factor2)); +} + +/* *************************************************************************/ +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), gtsam::Point3(0,0,1)); + StereoCamera 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)); + StereoCamera 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 + StereoPoint2 level_uv = level_camera.project(landmark); + StereoPoint2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(x1, level_pose); + values.insert(x2, level_pose_right); + + SmartFactor factor1; + factor1.add(level_uv, x1, model, K); + factor1.add(level_uv_right, x2, model, K); + + double actualError = factor1.error(values); + double expectedError = 0.0; + EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7); + + SmartFactor::Cameras cameras = factor1.cameras(values); + double actualError2 = factor1.totalReprojectionError(cameras); + EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); + + // test vector of errors + //Vector actual = factor1.unwhitenedError(values); + //EXPECT(assert_equal(zero(4),actual,1e-8)); +} + +/* *************************************************************************/ +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), gtsam::Point3(0,0,1)); + StereoCamera 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)); + StereoCamera 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 + StereoPoint2 pixelError(0.2,0.2,0); + StereoPoint2 level_uv = level_camera.project(landmark) + pixelError; + StereoPoint2 level_uv_right = level_camera_right.project(landmark); + + Values values; + values.insert(x1, level_pose); + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); + values.insert(x2, level_pose_right.compose(noise_pose)); + + SmartFactor::shared_ptr factor1(new SmartFactor()); + factor1->add(level_uv, x1, model, K); + factor1->add(level_uv_right, x2, model, K); + + double actualError1= factor1->error(values); + + SmartFactor::shared_ptr factor2(new SmartFactor()); + vector measurements; + measurements.push_back(level_uv); + measurements.push_back(level_uv_right); + + std::vector< SharedNoiseModel > noises; + noises.push_back(model); + noises.push_back(model); + + std::vector< boost::shared_ptr > Ks; ///< shared pointer to calibration object (one for each camera) + Ks.push_back(K); + Ks.push_back(K); + + std::vector views; + views.push_back(x1); + views.push_back(x2); + + factor2->add(measurements, views, noises, Ks); + + double actualError2= factor2->error(values); + + DOUBLES_EQUAL(actualError1, actualError2, 1e-7); +} + + +/* *************************************************************************/ +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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K2); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K2); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera 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 + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + std::vector views; + views.push_back(x1); + views.push_back(x2); + views.push_back(x3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + smartFactor1->add(measurements_cam1, views, model, K2); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + smartFactor2->add(measurements_cam2, views, model, K2); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + smartFactor3->add(measurements_cam3, views, model, K2); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, pose3*noise_pose); + if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams params; + if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + gttic_(SmartStereoProjectionPoseFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartStereoProjectionPoseFactor); + tictoc_finishedIteration_(); + +// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); +// VectorValues delta = GFG->optimize(); + + // 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_(); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, 3poses_iterative_smart_projection_factor ){ + // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera cam3(pose3, K); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + Point3 landmark3(3, 0, 3.0); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor()); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor()); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, pose3*noise_pose); + if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams params; + if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + gttic_(SmartStereoProjectionPoseFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartStereoProjectionPoseFactor); + tictoc_finishedIteration_(); + + // result.print("results of 3 camera, 3 landmark optimization \n"); + if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(pose3,result.at(x3))); + if(isDebugTest) tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera cam3(pose3, K); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + Point3 landmark3(3, 0, 3.0); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + 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_SVD)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3*noise_pose); + + LevenbergMarquardtParams params; + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + EXPECT(assert_equal(pose3,result.at(x3))); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, landmarkDistance ){ + + double excludeLandmarksFutherThanDist = 2; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera cam3(pose3, K); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + Point3 landmark3(3, 0, 3.0); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + 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_SVD, excludeLandmarksFutherThanDist)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + 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(); + EXPECT(assert_equal(values.at(x3),result.at(x3))); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ + + double excludeLandmarksFutherThanDist = 1e10; + double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera 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); + Point3 landmark4(5, -0.5, 1); + + vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); + 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, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, 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, + excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + smartFactor3->add(measurements_cam3, views, model, K); + + SmartFactor::shared_ptr smartFactor4(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + smartFactor4->add(measurements_cam4, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(smartFactor4); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + 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(); + EXPECT(assert_equal(pose3,result.at(x3))); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, jacobianQ ){ + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera cam3(pose3, K); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + Point3 landmark3(3, 0, 3.0); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + 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)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3*noise_pose); + + LevenbergMarquardtParams params; + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + EXPECT(assert_equal(pose3,result.at(x3))); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ + // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K2); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K2); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera 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); + + typedef GenericStereoFactor ProjectionFactor; + NonlinearFactorGraph graph; + + // 1. Project three landmarks into three cameras and triangulate + graph.push_back(ProjectionFactor(cam1.project(landmark1), model, x1, L(1), K2)); + graph.push_back(ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); + graph.push_back(ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); + + graph.push_back(ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); + graph.push_back(ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); + graph.push_back(ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); + + graph.push_back(ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); + graph.push_back(ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); + graph.push_back(ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3* noise_pose); + values.insert(L(1), landmark1); + values.insert(L(2), landmark2); + values.insert(L(3), landmark3); + 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))); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, CheckHessian){ + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); + StereoCamera cam2(pose2, K); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); + StereoCamera cam3(pose3, K); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + Point3 landmark3(3, 0, 3.0); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + double rankTol = 10; + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); + smartFactor3->add(measurements_cam3, views, model, K); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, pose3*noise_pose); + if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); + + boost::shared_ptr hessianFactor1 = smartFactor1->linearize(values); + boost::shared_ptr hessianFactor2 = smartFactor2->linearize(values); + boost::shared_ptr hessianFactor3 = smartFactor3->linearize(values); + + Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); + + boost::shared_ptr GaussianGraph = graph.linearize(values); + Matrix GraphInformation = GaussianGraph->hessian().first; + + // Check Hessian + EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); + + Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + + hessianFactor2->augmentedInformation() + hessianFactor3->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( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ + // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K2); + + // 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)); + StereoCamera cam2(pose2, K2); + + // 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)); + StereoCamera cam3(pose3, K2); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + + double rankTol = 50; + SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + smartFactor1->add(measurements_cam1, views, model, K2); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + smartFactor2->add(measurements_cam2, views, model, K2); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); + Point3 positionPrior = gtsam::Point3(0,0,1); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2*noise_pose); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, pose3*noise_pose*noise_pose); + 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); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartStereoProjectionPoseFactor); + tictoc_finishedIteration_(); + + // result.print("results of 3 camera, 3 landmark optimization \n"); + if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); + std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::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; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); + StereoCamera cam2(pose2, K); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); + StereoCamera cam3(pose3, K); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + Point3 landmark2(5, -0.5, 1.2); + Point3 landmark3(3, 0, 3.0); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + // 1. Project three landmarks into three cameras and triangulate + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + double rankTol = 10; + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); + Point3 positionPrior = gtsam::Point3(0,0,1); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); + graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, pose3*noise_pose); + 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); + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + gttoc_(SmartStereoProjectionPoseFactor); + tictoc_finishedIteration_(); + + // result.print("results of 3 camera, 3 landmark optimization \n"); + if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); + std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::endl; + // EXPECT(assert_equal(pose3,result.at(x3))); + if(isDebugTest) tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, Hessian ){ + // cout << " ************************ SmartStereoProjectionPoseFactor: Hessian **********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K2); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K2); + + // three landmarks ~5 meters infront of camera + Point3 landmark1(5, 0.5, 1.2); + + // 1. Project three landmarks into three cameras and triangulate + StereoPoint2 cam1_uv1 = cam1.project(landmark1); + StereoPoint2 cam2_uv1 = cam2.project(landmark1); + vector measurements_cam1; + measurements_cam1.push_back(cam1_uv1); + measurements_cam1.push_back(cam2_uv1); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor()); + smartFactor1->add(measurements_cam1,views, model, K2); + + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + + boost::shared_ptr hessianFactor = smartFactor1->linearize(values); + if(isDebugTest) hessianFactor->print("Hessian factor \n"); + + // compute triangulation from linearization point + // compute reprojection errors (sum squared) + // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) + // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] +} + + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ){ + // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera cam3(pose3, K); + + Point3 landmark1(5, 0.5, 1.2); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + + SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); + smartFactorInstance->add(measurements_cam1, views, model, K); + + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3); + + boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); + // hessianFactor->print("Hessian factor \n"); + + Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); + + Values rotValues; + rotValues.insert(x1, poseDrift.compose(pose1)); + rotValues.insert(x2, poseDrift.compose(pose2)); + rotValues.insert(x3, poseDrift.compose(pose3)); + + boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); + // hessianFactorRot->print("Hessian factor \n"); + + // Hessian is invariant to rotations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); + + Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); + + Values tranValues; + tranValues.insert(x1, poseDrift2.compose(pose1)); + tranValues.insert(x2, poseDrift2.compose(pose2)); + tranValues.insert(x3, poseDrift2.compose(pose3)); + + boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); + + // Hessian is invariant to rotations and translations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ + // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K2); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0,0,0)); + StereoCamera cam2(pose2, K2); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,0,0)); + StereoCamera cam3(pose3, K2); + + Point3 landmark1(5, 0.5, 1.2); + + vector measurements_cam1, measurements_cam2, measurements_cam3; + + stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + + SmartFactor::shared_ptr smartFactor(new SmartFactor()); + smartFactor->add(measurements_cam1, views, model, K2); + + + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3); + + 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), gtsam::Point3(0,0,0)); + + Values rotValues; + rotValues.insert(x1, poseDrift.compose(pose1)); + rotValues.insert(x2, poseDrift.compose(pose2)); + rotValues.insert(x3, poseDrift.compose(pose3)); + + boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); + if(isDebugTest) hessianFactorRot->print("Hessian factor \n"); + + // Hessian is invariant to rotations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); + + Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); + + Values tranValues; + tranValues.insert(x1, poseDrift2.compose(pose1)); + tranValues.insert(x2, poseDrift2.compose(pose2)); + tranValues.insert(x3, poseDrift2.compose(pose3)); + + boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); + + // Hessian is invariant to rotations and translations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +} + +/* ************************************************************************* */ //TEST( SmartStereoProjectionPoseFactor, ConstructorWithCal3Bundler) { // SmartStereoProjectionPoseFactor factor1(rankTol, linThreshold); // boost::shared_ptr Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); // factor1.add(measurement1, poseKey1, model, Kbundler); //} -// -///* *************************************************************************/ + +/* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, Cal3Bundler ){ // // cout << " ************************ SmartStereoProjectionPoseFactor: 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), gtsam::Point3(0,0,1)); -// PinholeCamera cam1(pose1, *Kbundler); +// StereoCamera cam1(pose1, *Kbundler); // // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// PinholeCamera cam2(pose2, *Kbundler); +// StereoCamera cam2(pose2, *Kbundler); // // // create third camera 1 meter above the first camera // Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// PinholeCamera cam3(pose3, *Kbundler); +// StereoCamera cam3(pose3, *Kbundler); // // // three landmarks ~5 meters infront of camera // Point3 landmark1(5, 0.5, 1.2); // Point3 landmark2(5, -0.5, 1.2); // Point3 landmark3(3, 0, 3.0); // -// vector measurements_cam1, measurements_cam2, measurements_cam3; +// vector measurements_cam1, measurements_cam2, measurements_cam3; // // // 1. Project three landmarks into three cameras and triangulate -// Point2 cam1_uv1 = cam1.project(landmark1); -// Point2 cam2_uv1 = cam2.project(landmark1); -// Point2 cam3_uv1 = cam3.project(landmark1); +// StereoPoint2 cam1_uv1 = cam1.project(landmark1); +// StereoPoint2 cam2_uv1 = cam2.project(landmark1); +// StereoPoint2 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); +// StereoPoint2 cam1_uv2 = cam1.project(landmark2); +// StereoPoint2 cam2_uv2 = cam2.project(landmark2); +// StereoPoint2 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); +// StereoPoint2 cam1_uv3 = cam1.project(landmark3); +// StereoPoint2 cam2_uv3 = cam2.project(landmark3); +// StereoPoint2 cam3_uv3 = cam3.project(landmark3); // measurements_cam3.push_back(cam1_uv3); // measurements_cam3.push_back(cam2_uv3); // measurements_cam3.push_back(cam3_uv3); @@ -1212,8 +1213,8 @@ TEST( SmartStereoProjectionPoseFactor, Constructor) { // EXPECT(assert_equal(pose3,result.at(x3), 1e-6)); // if(isDebugTest) tictoc_print_(); // } -// -///* *************************************************************************/ + +/* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, Cal3BundlerRotationOnly ){ // // std::vector views; @@ -1223,41 +1224,41 @@ TEST( SmartStereoProjectionPoseFactor, Constructor) { // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) // Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); -// PinholeCamera cam1(pose1, *Kbundler); +// StereoCamera cam1(pose1, *Kbundler); // // // 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); +// StereoCamera cam2(pose2, *Kbundler); // // // 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); +// StereoCamera cam3(pose3, *Kbundler); // // // three landmarks ~5 meters infront of camera // Point3 landmark1(5, 0.5, 1.2); // Point3 landmark2(5, -0.5, 1.2); // Point3 landmark3(3, 0, 3.0); // -// vector measurements_cam1, measurements_cam2, measurements_cam3; +// vector measurements_cam1, measurements_cam2, measurements_cam3; // // // 1. Project three landmarks into three cameras and triangulate -// Point2 cam1_uv1 = cam1.project(landmark1); -// Point2 cam2_uv1 = cam2.project(landmark1); -// Point2 cam3_uv1 = cam3.project(landmark1); +// StereoPoint2 cam1_uv1 = cam1.project(landmark1); +// StereoPoint2 cam2_uv1 = cam2.project(landmark1); +// StereoPoint2 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); +// StereoPoint2 cam1_uv2 = cam1.project(landmark2); +// StereoPoint2 cam2_uv2 = cam2.project(landmark2); +// StereoPoint2 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); +// StereoPoint2 cam1_uv3 = cam1.project(landmark3); +// StereoPoint2 cam2_uv3 = cam2.project(landmark3); +// StereoPoint2 cam3_uv3 = cam3.project(landmark3); // measurements_cam3.push_back(cam1_uv3); // measurements_cam3.push_back(cam2_uv3); // measurements_cam3.push_back(cam3_uv3); From 711c3c071592520d903c4f7176101aee0c3ab6a2 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 9 Jun 2014 16:29:32 -0400 Subject: [PATCH 12/57] temporary triangulation using only first camera --- gtsam/slam/SmartStereoProjectionFactor.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 0d0d2bc0f..01c21e6a0 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -251,6 +251,11 @@ public: //TODO: Chris will replace this with something else for stereo // point_ = triangulatePoint3(cameras, this->measured_, // rankTolerance_, enableEPI_); + + // FIXME: temporary: triangulation using only first camera + const StereoPoint2& z0 = this->measured_.at(0); + point_ = cameras[0].backproject(z0); + degenerate_ = false; cheiralityException_ = false; From 608498ce894258dc03602e8b673f10aa57ae1430 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 9 Jun 2014 16:30:37 -0400 Subject: [PATCH 13/57] minor fixes, now runs without exceptions, but some tests still fail --- .../testSmartStereoProjectionPoseFactor.cpp | 213 +----------------- 1 file changed, 7 insertions(+), 206 deletions(-) diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 5cdb4ff04..4e3cbf70d 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -47,7 +47,7 @@ static double rankTol = 1.0; static double linThreshold = -1.0; static bool manageDegeneracy = true; // Create a noise model for the pixel error -static SharedNoiseModel model(noiseModel::Unit::Create(2)); +static SharedNoiseModel model(noiseModel::Unit::Create(3)); // Convenience for named keys using symbol_shorthand::X; @@ -87,19 +87,19 @@ TEST( SmartStereoProjectionPoseFactor, Constructor2) { SmartFactor factor1(rankTol, linThreshold); } -///* ************************************************************************* */ +/* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor3) { SmartFactor::shared_ptr factor1(new SmartFactor()); factor1->add(measurement1, poseKey1, model, K); } -///* ************************************************************************* */ +/* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor4) { SmartFactor factor1(rankTol, linThreshold); factor1.add(measurement1, poseKey1, model, K); } -///* ************************************************************************* */ +/* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, ConstructorWithTransform) { bool manageDegeneracy = true; bool enableEPI = false; @@ -107,7 +107,7 @@ TEST( SmartStereoProjectionPoseFactor, ConstructorWithTransform) { factor1.add(measurement1, poseKey1, model, K); } -///* ************************************************************************* */ +/* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Equals ) { SmartFactor::shared_ptr factor1(new SmartFactor()); factor1->add(measurement1, poseKey1, model, K); @@ -142,8 +142,8 @@ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ){ values.insert(x2, level_pose_right); SmartFactor factor1; - factor1.add(level_uv, x1, model, K); - factor1.add(level_uv_right, x2, model, K); + factor1.add(level_uv, x1, model, K2); + factor1.add(level_uv_right, x2, model, K2); double actualError = factor1.error(values); double expectedError = 0.0; @@ -1113,205 +1113,6 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); } -/* ************************************************************************* */ -//TEST( SmartStereoProjectionPoseFactor, ConstructorWithCal3Bundler) { -// SmartStereoProjectionPoseFactor factor1(rankTol, linThreshold); -// boost::shared_ptr Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); -// factor1.add(measurement1, poseKey1, model, Kbundler); -//} - -/* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, Cal3Bundler ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: 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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, *Kbundler); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// StereoCamera cam2(pose2, *Kbundler); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// StereoCamera cam3(pose3, *Kbundler); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// StereoPoint2 cam1_uv1 = cam1.project(landmark1); -// StereoPoint2 cam2_uv1 = cam2.project(landmark1); -// StereoPoint2 cam3_uv1 = cam3.project(landmark1); -// measurements_cam1.push_back(cam1_uv1); -// measurements_cam1.push_back(cam2_uv1); -// measurements_cam1.push_back(cam3_uv1); -// -// StereoPoint2 cam1_uv2 = cam1.project(landmark2); -// StereoPoint2 cam2_uv2 = cam2.project(landmark2); -// StereoPoint2 cam3_uv2 = cam3.project(landmark2); -// measurements_cam2.push_back(cam1_uv2); -// measurements_cam2.push_back(cam2_uv2); -// measurements_cam2.push_back(cam3_uv2); -// -// StereoPoint2 cam1_uv3 = cam1.project(landmark3); -// StereoPoint2 cam2_uv3 = cam2.project(landmark3); -// StereoPoint2 cam3_uv3 = cam3.project(landmark3); -// measurements_cam3.push_back(cam1_uv3); -// measurements_cam3.push_back(cam2_uv3); -// measurements_cam3.push_back(cam3_uv3); -// -// std::vector views; -// views.push_back(x1); -// views.push_back(x2); -// views.push_back(x3); -// -// SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); -// smartFactor1->add(measurements_cam1, views, model, Kbundler); -// -// SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); -// smartFactor2->add(measurements_cam2, views, model, Kbundler); -// -// SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); -// smartFactor3->add(measurements_cam3, views, model, Kbundler); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; -// -// Values result; -// gttic_(SmartStereoProjectionPoseFactor); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// gttoc_(SmartStereoProjectionPoseFactor); -// tictoc_finishedIteration_(); -// -// // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// EXPECT(assert_equal(pose3,result.at(x3), 1e-6)); -// if(isDebugTest) tictoc_print_(); -// } - -/* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, Cal3BundlerRotationOnly ){ -// -// std::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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, *Kbundler); -// -// // 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)); -// StereoCamera cam2(pose2, *Kbundler); -// -// // 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)); -// StereoCamera cam3(pose3, *Kbundler); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// StereoPoint2 cam1_uv1 = cam1.project(landmark1); -// StereoPoint2 cam2_uv1 = cam2.project(landmark1); -// StereoPoint2 cam3_uv1 = cam3.project(landmark1); -// measurements_cam1.push_back(cam1_uv1); -// measurements_cam1.push_back(cam2_uv1); -// measurements_cam1.push_back(cam3_uv1); -// -// StereoPoint2 cam1_uv2 = cam1.project(landmark2); -// StereoPoint2 cam2_uv2 = cam2.project(landmark2); -// StereoPoint2 cam3_uv2 = cam3.project(landmark2); -// measurements_cam2.push_back(cam1_uv2); -// measurements_cam2.push_back(cam2_uv2); -// measurements_cam2.push_back(cam3_uv2); -// -// StereoPoint2 cam1_uv3 = cam1.project(landmark3); -// StereoPoint2 cam2_uv3 = cam2.project(landmark3); -// StereoPoint2 cam3_uv3 = cam3.project(landmark3); -// measurements_cam3.push_back(cam1_uv3); -// measurements_cam3.push_back(cam2_uv3); -// measurements_cam3.push_back(cam3_uv3); -// -// double rankTol = 10; -// -// SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); -// smartFactor1->add(measurements_cam1, views, model, Kbundler); -// -// SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); -// smartFactor2->add(measurements_cam2, views, model, Kbundler); -// -// SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); -// smartFactor3->add(measurements_cam3, views, model, Kbundler); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); -// Point3 positionPrior = gtsam::Point3(0,0,1); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); -// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose); -// 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); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// gttoc_(SmartStereoProjectionPoseFactor); -// tictoc_finishedIteration_(); -// -// // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::endl; -// // EXPECT(assert_equal(pose3,result.at(x3))); -// if(isDebugTest) tictoc_print_(); -//} /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } From a3b001be363f7dc29141539388cb7bada8acce54 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 9 Jun 2014 20:39:04 -0400 Subject: [PATCH 14/57] tiny fix to return vector of dim 3 instead 2 --- gtsam/slam/SmartStereoProjectionFactor.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 01c21e6a0..679a6548d 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -110,11 +110,10 @@ public: /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; - /// shorthand for a pinhole camera - // TODO: Switch to stereoCamera: + /// shorthand for a StereoCamera // TODO: Get rid of this? typedef StereoCamera Camera; -// typedef StereoCamera Camera; + /// Vector of cameras typedef std::vector Cameras; /** @@ -278,6 +277,7 @@ public: } i += 1; } + std::cout << "totalReprojError error: " << totalReprojError << std::endl; // we discard smart factors that have large reprojection error if(dynamicOutlierRejectionThreshold_ > 0 && totalReprojError/m > dynamicOutlierRejectionThreshold_) @@ -612,7 +612,7 @@ public: if (nonDegenerate) return reprojectionError(myCameras); else - return zero(myCameras.size() * 2); + return zero(myCameras.size() * 3); } /** From 2eef2c14b55efb3e4c607d3034ad33ce837f2abb Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Tue, 1 Jul 2014 08:40:27 -0400 Subject: [PATCH 15/57] Fixed abort due to unaligned memory allocation in SmartFactorBase --- .../Eigen/Eigen/src/StlSupport/StdVector.h | 3 ++- gtsam/slam/JacobianFactorQ.h | 2 +- gtsam/slam/JacobianFactorSVD.h | 2 +- gtsam/slam/SmartFactorBase.h | 15 +++++++++------ gtsam/slam/SmartStereoProjectionFactor.h | 2 ++ gtsam/slam/SmartStereoProjectionPoseFactor.h | 2 ++ .../tests/testSmartStereoProjectionPoseFactor.cpp | 1 + 7 files changed, 18 insertions(+), 9 deletions(-) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h index 40a9abefa..ea3b571c2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h @@ -11,7 +11,8 @@ #ifndef EIGEN_STDVECTOR_H #define EIGEN_STDVECTOR_H -#include "Eigen/src/StlSupport/details.h" +//#include "Eigen/src/StlSupport/details.h" +#include "gtsam/3rdparty/Eigen/Eigen/src/StlSupport/details.h" /** * This section contains a convenience MACRO which allows an easy specialization of diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index f4dfb9422..1e264ccba 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -37,7 +37,7 @@ public: } /// Constructor - JacobianFactorQ(const std::vector& Fblocks, + JacobianFactorQ(const std::vector>& Fblocks, const Matrix& E, const Matrix3& P, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index e28185038..558a6c740 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -36,7 +36,7 @@ public: } /// Constructor - JacobianFactorSVD(const std::vector& Fblocks, const Matrix& Enull, const Vector& b, + JacobianFactorSVD(const std::vector>& Fblocks, const Matrix& Enull, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { size_t numKeys = Enull.rows() / 2; size_t j = 0, m2 = 2*numKeys-3; diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index eab7810db..a185cefd5 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -33,6 +33,7 @@ #include #include #include +#include namespace gtsam { /// Base class with no internal point, completely functional @@ -65,6 +66,8 @@ protected: public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -258,7 +261,7 @@ public: // **************************************************************************************************** /// Compute F, E only (called below in both vanilla and SVD versions) /// Given a Point3, assumes dimensionality is 3 - double computeJacobians(std::vector& Fblocks, Matrix& E, + double computeJacobians(std::vector>& Fblocks, Matrix& E, Vector& b, const Cameras& cameras, const Point3& point) const { size_t numKeys = this->keys_.size(); @@ -295,7 +298,7 @@ public: // **************************************************************************************************** /// Version that computes PointCov, with optional lambda parameter - double computeJacobians(std::vector& Fblocks, Matrix& E, + double computeJacobians(std::vector>& Fblocks, Matrix& E, Matrix3& PointCov, Vector& b, const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { @@ -326,7 +329,7 @@ public: const double lambda = 0.0) const { size_t numKeys = this->keys_.size(); - std::vector Fblocks; + std::vector> Fblocks; double f = computeJacobians(Fblocks, E, PointCov, b, cameras, point, lambda); F = zeros(Z::Dim() * numKeys, D * numKeys); @@ -339,7 +342,7 @@ public: // **************************************************************************************************** /// SVD version - double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, + double computeJacobiansSVD(std::vector>& Fblocks, Matrix& Enull, Vector& b, const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { @@ -639,7 +642,7 @@ public: boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - std::vector Fblocks; + std::vector> Fblocks; Matrix E; Matrix3 PointCov; Vector b; @@ -652,7 +655,7 @@ public: boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0) const { size_t numKeys = this->keys_.size(); - std::vector < KeyMatrix2D > Fblocks; + std::vector < KeyMatrix2D,Eigen::aligned_allocator > Fblocks; Vector b; Matrix Enull(Z::Dim()*numKeys, Z::Dim()*numKeys-3); computeJacobiansSVD(Fblocks, Enull, b, cameras, point, lambda); diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 679a6548d..96f5568dd 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -43,6 +43,8 @@ protected: public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + SmartStereoProjectionFactorState() { } // Hessian representation (after Schur complement) diff --git a/gtsam/slam/SmartStereoProjectionPoseFactor.h b/gtsam/slam/SmartStereoProjectionPoseFactor.h index b6fad38fa..9b7763ef2 100644 --- a/gtsam/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam/slam/SmartStereoProjectionPoseFactor.h @@ -47,6 +47,8 @@ protected: public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + /// shorthand for base class type typedef SmartStereoProjectionFactor Base; diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 4e3cbf70d..b5ee3d61a 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -79,6 +79,7 @@ void stereo_projectToMultipleCameras( /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor) { + fprintf(stderr,"Test 1 Complete"); SmartFactor::shared_ptr factor1(new SmartFactor()); } From 391a29bcaf6de4a89067894595380b06cc516ad2 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 10 Jul 2014 07:51:24 -0400 Subject: [PATCH 16/57] const correctness --- gtsam/geometry/StereoPoint2.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 186afae55..4093413ca 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -143,12 +143,12 @@ namespace gtsam { } /** convenient function to get a Point2 from the left image */ - inline Point2 point2(){ + inline Point2 point2() const { return Point2(uL_, v_); } /** convenient function to get a Point2 from the right image */ - inline Point2 right(){ + inline Point2 const right(){ return Point2(uR_, v_); } From fc513e584d28fd1dc02ba1518a65f38ad9600e58 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 10 Jul 2014 07:55:52 -0400 Subject: [PATCH 17/57] move derivative for calibration to third slot to be consistent with PinholeCamera interface --- gtsam/geometry/StereoCamera.cpp | 3 ++- gtsam/geometry/StereoCamera.h | 17 +++++++---------- 2 files changed, 9 insertions(+), 11 deletions(-) diff --git a/gtsam/geometry/StereoCamera.cpp b/gtsam/geometry/StereoCamera.cpp index ed531a2bd..7412c42f6 100644 --- a/gtsam/geometry/StereoCamera.cpp +++ b/gtsam/geometry/StereoCamera.cpp @@ -30,7 +30,8 @@ namespace gtsam { /* ************************************************************************* */ StereoPoint2 StereoCamera::project(const Point3& point, - boost::optional H1, boost::optional H2) const { + boost::optional H1, boost::optional H2, + boost::optional H3) const { #ifdef STEREOCAMERA_CHAIN_RULE const Point3 q = leftCamPose_.transform_to(point, H1, H2); diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index 70917b2c4..1e23bf826 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -114,21 +114,18 @@ public: /* * project 3D point and compute optional derivatives + * @param H1 derivative with respect to pose + * @param H2 derivative with respect to point + * @param H3 IGNORED (for calibration) */ StereoPoint2 project(const Point3& point, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const; + boost::optional H2 = boost::none, + boost::optional H3 = boost::none) const; - /* - * to accomodate tsam's assumption that K is estimated, too + /** + * */ - StereoPoint2 project(const Point3& point, - boost::optional H1, - boost::optional H1_k, - boost::optional H2) const { - return project(point, H1, H2); - } - Point3 backproject(const StereoPoint2& z) const { Vector measured = z.vector(); double Z = K_->baseline()*K_->fx()/(measured[0]-measured[1]); From 0801246058c72af0248b2c21bdde65fa2288e03f Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 10 Jul 2014 07:57:19 -0400 Subject: [PATCH 18/57] revert include path change --- gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h index ea3b571c2..40a9abefa 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/StlSupport/StdVector.h @@ -11,8 +11,7 @@ #ifndef EIGEN_STDVECTOR_H #define EIGEN_STDVECTOR_H -//#include "Eigen/src/StlSupport/details.h" -#include "gtsam/3rdparty/Eigen/Eigen/src/StlSupport/details.h" +#include "Eigen/src/StlSupport/details.h" /** * This section contains a convenience MACRO which allows an easy specialization of From d191b0cebbe840b322ea66f5ea788044f66bc4a0 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 10 Jul 2014 07:58:56 -0400 Subject: [PATCH 19/57] space between double angle-brackets --- gtsam/slam/JacobianFactorQ.h | 2 +- gtsam/slam/JacobianFactorSVD.h | 2 +- gtsam/slam/SmartFactorBase.h | 13 +++++++------ 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index 1e264ccba..de13f7ef0 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -37,7 +37,7 @@ public: } /// Constructor - JacobianFactorQ(const std::vector>& Fblocks, + JacobianFactorQ(const std::vector >& Fblocks, const Matrix& E, const Matrix3& P, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index 558a6c740..0d3c04de1 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -36,7 +36,7 @@ public: } /// Constructor - JacobianFactorSVD(const std::vector>& Fblocks, const Matrix& Enull, const Vector& b, + JacobianFactorSVD(const std::vector >& Fblocks, const Matrix& Enull, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { size_t numKeys = Enull.rows() / 2; size_t j = 0, m2 = 2*numKeys-3; diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a185cefd5..ae2dc8b0f 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -33,7 +33,8 @@ #include #include #include -#include +#include +//#include namespace gtsam { /// Base class with no internal point, completely functional @@ -261,7 +262,7 @@ public: // **************************************************************************************************** /// Compute F, E only (called below in both vanilla and SVD versions) /// Given a Point3, assumes dimensionality is 3 - double computeJacobians(std::vector>& Fblocks, Matrix& E, + double computeJacobians(std::vector >& Fblocks, Matrix& E, Vector& b, const Cameras& cameras, const Point3& point) const { size_t numKeys = this->keys_.size(); @@ -298,7 +299,7 @@ public: // **************************************************************************************************** /// Version that computes PointCov, with optional lambda parameter - double computeJacobians(std::vector>& Fblocks, Matrix& E, + double computeJacobians(std::vector >& Fblocks, Matrix& E, Matrix3& PointCov, Vector& b, const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { @@ -329,7 +330,7 @@ public: const double lambda = 0.0) const { size_t numKeys = this->keys_.size(); - std::vector> Fblocks; + std::vector > Fblocks; double f = computeJacobians(Fblocks, E, PointCov, b, cameras, point, lambda); F = zeros(Z::Dim() * numKeys, D * numKeys); @@ -342,7 +343,7 @@ public: // **************************************************************************************************** /// SVD version - double computeJacobiansSVD(std::vector>& Fblocks, Matrix& Enull, + double computeJacobiansSVD(std::vector >& Fblocks, Matrix& Enull, Vector& b, const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { @@ -642,7 +643,7 @@ public: boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - std::vector> Fblocks; + std::vector > Fblocks; Matrix E; Matrix3 PointCov; Vector b; From 3bfdc12ae43366208d207cba2f6cef5832f73add Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 10 Jul 2014 08:48:01 -0400 Subject: [PATCH 20/57] change landmark initialization to use monocular triangulation (doesn't really make a difference, but probably slower), and extra debug statements --- gtsam/slam/SmartStereoProjectionFactor.h | 32 ++++++++++++++++++++---- 1 file changed, 27 insertions(+), 5 deletions(-) diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 96f5568dd..29a942bae 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -253,9 +253,26 @@ public: // point_ = triangulatePoint3(cameras, this->measured_, // rankTolerance_, enableEPI_); + // // // Temporary hack to use monocular triangulation + std::vector mono_measurements; + BOOST_FOREACH(const StereoPoint2& sp, this->measured_) { + mono_measurements.push_back(sp.point2()); + } + + std::vector > mono_cameras; + BOOST_FOREACH(const Camera& camera, cameras) { + const Pose3& pose = camera.pose(); + const Cal3_S2& K = camera.calibration()->calibration(); + mono_cameras.push_back(PinholeCamera(pose, K)); + } + point_ = triangulatePoint3(mono_cameras, mono_measurements, + rankTolerance_, enableEPI_); + + // // // End temporary hack + // FIXME: temporary: triangulation using only first camera - const StereoPoint2& z0 = this->measured_.at(0); - point_ = cameras[0].backproject(z0); +// const StereoPoint2& z0 = this->measured_.at(0); +// point_ = cameras[0].backproject(z0); degenerate_ = false; cheiralityException_ = false; @@ -344,11 +361,12 @@ public: } this->triangulateSafe(cameras); + if (isDebug) std::cout << "point_ = " << point_ << std::endl; if (numKeys < 2 || (!this->manageDegeneracy_ && (this->cheiralityException_ || this->degenerate_))) { - // std::cout << "In linearize: exception" << std::endl; + if (isDebug) std::cout << "In linearize: exception" << std::endl; BOOST_FOREACH(gtsam::Matrix& m, Gs) m = zeros(D, D); BOOST_FOREACH(Vector& v, gs) @@ -360,10 +378,13 @@ 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; } 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 for (size_t i = 0; i < cameras.size(); i++) this->cameraPosesLinearization_[i] = cameras[i].pose(); @@ -397,8 +418,9 @@ public: H.noalias() = F.transpose() * (F - (E * (PointCov * (E.transpose() * F)))); gs_vector.noalias() = F.transpose() * (b - (E * (PointCov * (E.transpose() * b)))); - if (isDebug) - std::cout << "gs_vector size " << gs_vector.size() << 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; From 94ca4463fe5921f4c2218d8d9384c2954d250678 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 10 Jul 2014 08:48:37 -0400 Subject: [PATCH 21/57] throw when reaching parts of code that need to be fixed --- gtsam/slam/SmartStereoProjectionPoseFactor.h | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/gtsam/slam/SmartStereoProjectionPoseFactor.h b/gtsam/slam/SmartStereoProjectionPoseFactor.h index 9b7763ef2..60992281e 100644 --- a/gtsam/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam/slam/SmartStereoProjectionPoseFactor.h @@ -174,12 +174,14 @@ public: const Values& values) const { // depending on flag set on construction we may linearize to different linear factors switch(linearizeTo_){ -// case JACOBIAN_SVD : + case JACOBIAN_SVD : + throw("JacobianSVD not working yet!"); // return this->createJacobianSVDFactor(cameras(values), 0.0); -// break; -// case JACOBIAN_Q : + break; + case JACOBIAN_Q : + throw("JacobianQ not working yet!"); // return this->createJacobianQFactor(cameras(values), 0.0); -// break; + break; default: return this->createHessianFactor(cameras(values)); break; From ff30413f231a8514479a6253539984b6bc39a848 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 10 Jul 2014 08:50:23 -0400 Subject: [PATCH 22/57] minor cleanup. First few tests pass now due to making StereoCamera project like PinholeCamera --- .../testSmartStereoProjectionPoseFactor.cpp | 1510 ++++++++--------- 1 file changed, 754 insertions(+), 756 deletions(-) diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index b5ee3d61a..2659cb274 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -32,7 +32,7 @@ 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 @@ -65,9 +65,11 @@ static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0 typedef SmartStereoProjectionPoseFactor SmartFactor; typedef SmartStereoProjectionPoseFactor SmartFactorBundler; -void stereo_projectToMultipleCameras( - StereoCamera cam1, StereoCamera cam2, StereoCamera cam3, Point3 landmark, - vector& measurements_cam){ +vector stereo_projectToMultipleCameras( + const StereoCamera& cam1, const StereoCamera& cam2, + const StereoCamera& cam3, Point3 landmark){ + + vector measurements_cam; StereoPoint2 cam1_uv1 = cam1.project(landmark); StereoPoint2 cam2_uv1 = cam2.project(landmark); @@ -75,6 +77,8 @@ void stereo_projectToMultipleCameras( measurements_cam.push_back(cam1_uv1); measurements_cam.push_back(cam2_uv1); measurements_cam.push_back(cam3_uv1); + + return measurements_cam; } /* ************************************************************************* */ @@ -217,7 +221,7 @@ TEST( SmartStereoProjectionPoseFactor, noisy ){ /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ){ - // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; + 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), gtsam::Point3(0,0,1)); @@ -236,12 +240,10 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ){ 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 - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); + vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); std::vector views; views.push_back(x1); @@ -321,12 +323,10 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_iterative_smart_projection_factor 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 - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); + vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); SmartFactor::shared_ptr smartFactor1(new SmartFactor()); smartFactor1->add(measurements_cam1, views, model, K); @@ -372,747 +372,745 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_iterative_smart_projection_factor if(isDebugTest) tictoc_print_(); } -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - StereoCamera cam3(pose3, K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - 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_SVD)); - smartFactor1->add(measurements_cam1, views, model, K); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor2->add(measurements_cam2, views, model, K); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor3->add(measurements_cam3, views, model, K); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3*noise_pose); - - LevenbergMarquardtParams params; - Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - EXPECT(assert_equal(pose3,result.at(x3))); -} - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, landmarkDistance ){ - - double excludeLandmarksFutherThanDist = 2; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - StereoCamera cam3(pose3, K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - 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_SVD, excludeLandmarksFutherThanDist)); - smartFactor1->add(measurements_cam1, views, model, K); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor2->add(measurements_cam2, views, model, K); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); - smartFactor3->add(measurements_cam3, views, model, K); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - 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(); - EXPECT(assert_equal(values.at(x3),result.at(x3))); -} - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ - - double excludeLandmarksFutherThanDist = 1e10; - double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - StereoCamera 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); - Point3 landmark4(5, -0.5, 1); - - vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; - - // 1. Project three landmarks into three cameras and triangulate - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); - 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, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor1->add(measurements_cam1, views, model, K); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, 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, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor3->add(measurements_cam3, views, model, K); - - SmartFactor::shared_ptr smartFactor4(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor4->add(measurements_cam4, views, model, K); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(smartFactor4); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - 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(); - EXPECT(assert_equal(pose3,result.at(x3))); -} - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, jacobianQ ){ - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - StereoCamera cam3(pose3, K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - 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)); - smartFactor1->add(measurements_cam1, views, model, K); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor2->add(measurements_cam2, views, model, K); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor3->add(measurements_cam3, views, model, K); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3*noise_pose); - - LevenbergMarquardtParams params; - Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - EXPECT(assert_equal(pose3,result.at(x3))); -} - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ - // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - StereoCamera 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); - - typedef GenericStereoFactor ProjectionFactor; - NonlinearFactorGraph graph; - - // 1. Project three landmarks into three cameras and triangulate - graph.push_back(ProjectionFactor(cam1.project(landmark1), model, x1, L(1), K2)); - graph.push_back(ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); - graph.push_back(ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); - - graph.push_back(ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); - graph.push_back(ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); - graph.push_back(ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); - - graph.push_back(ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); - graph.push_back(ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); - graph.push_back(ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3* noise_pose); - values.insert(L(1), landmark1); - values.insert(L(2), landmark2); - values.insert(L(3), landmark3); - 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))); -} - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, CheckHessian){ - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - StereoCamera cam2(pose2, K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - StereoCamera cam3(pose3, K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - - double rankTol = 10; - - SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); - smartFactor1->add(measurements_cam1, views, model, K); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); - smartFactor2->add(measurements_cam2, views, model, K); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); - smartFactor3->add(measurements_cam3, views, model, K); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose); - if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); - - boost::shared_ptr hessianFactor1 = smartFactor1->linearize(values); - boost::shared_ptr hessianFactor2 = smartFactor2->linearize(values); - boost::shared_ptr hessianFactor3 = smartFactor3->linearize(values); - - Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); - - boost::shared_ptr GaussianGraph = graph.linearize(values); - Matrix GraphInformation = GaussianGraph->hessian().first; - - // Check Hessian - EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); - - Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + - hessianFactor2->augmentedInformation() + hessianFactor3->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( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ - // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K2); - - // 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)); - StereoCamera cam2(pose2, K2); - - // 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)); - StereoCamera cam3(pose3, K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - - double rankTol = 50; - SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, K2); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, K2); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); - Point3 positionPrior = gtsam::Point3(0,0,1); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); - graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2*noise_pose); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose*noise_pose); - 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); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartStereoProjectionPoseFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); - std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::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; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - StereoCamera cam2(pose2, K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); - StereoCamera cam3(pose3, K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - - double rankTol = 10; - - SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, K); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, K); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor3->add(measurements_cam3, views, model, K); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); - Point3 positionPrior = gtsam::Point3(0,0,1); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); - graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose); - 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); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartStereoProjectionPoseFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); - std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::endl; - // EXPECT(assert_equal(pose3,result.at(x3))); - if(isDebugTest) tictoc_print_(); -} - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, Hessian ){ - // cout << " ************************ SmartStereoProjectionPoseFactor: Hessian **********************" << endl; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - - // 1. Project three landmarks into three cameras and triangulate - StereoPoint2 cam1_uv1 = cam1.project(landmark1); - StereoPoint2 cam2_uv1 = cam2.project(landmark1); - vector measurements_cam1; - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1,views, model, K2); - - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - - boost::shared_ptr hessianFactor = smartFactor1->linearize(values); - if(isDebugTest) hessianFactor->print("Hessian factor \n"); - - // compute triangulation from linearization point - // compute reprojection errors (sum squared) - // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) - // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] -} - - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ){ - // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - StereoCamera cam3(pose3, K); - - Point3 landmark1(5, 0.5, 1.2); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - - SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); - smartFactorInstance->add(measurements_cam1, views, model, K); - - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); - - boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); - // hessianFactor->print("Hessian factor \n"); - - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); - - Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); - - boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); - // hessianFactorRot->print("Hessian factor \n"); - - // Hessian is invariant to rotations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); - - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); - - Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); - - boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); - - // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -} - -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ - // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0,0,0)); - StereoCamera cam2(pose2, K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,0,0)); - StereoCamera cam3(pose3, K2); - - Point3 landmark1(5, 0.5, 1.2); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - - SmartFactor::shared_ptr smartFactor(new SmartFactor()); - smartFactor->add(measurements_cam1, views, model, K2); - - - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); - - 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), gtsam::Point3(0,0,0)); - - Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); - - boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); - if(isDebugTest) hessianFactorRot->print("Hessian factor \n"); - - // Hessian is invariant to rotations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); - - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); - - Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); - - boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); - - // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -} +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// StereoCamera cam2(pose2, K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// StereoCamera 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); +// +// // 1. Project three landmarks into three cameras and triangulate +// vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); +// vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); +// vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3*noise_pose); +// +// LevenbergMarquardtParams params; +// Values result; +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// EXPECT(assert_equal(pose3,result.at(x3))); +//} + +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, landmarkDistance ){ +// +// double excludeLandmarksFutherThanDist = 2; +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// StereoCamera cam2(pose2, K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// StereoCamera cam3(pose3, K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// 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_SVD, excludeLandmarksFutherThanDist)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// 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(); +// EXPECT(assert_equal(values.at(x3),result.at(x3))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ +// +// double excludeLandmarksFutherThanDist = 1e10; +// double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// StereoCamera cam2(pose2, K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// StereoCamera 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); +// Point3 landmark4(5, -0.5, 1); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); +// 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, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, 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, +// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// SmartFactor::shared_ptr smartFactor4(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, +// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); +// smartFactor4->add(measurements_cam4, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(smartFactor4); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// 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(); +// EXPECT(assert_equal(pose3,result.at(x3))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, jacobianQ ){ +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K); +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// StereoCamera cam2(pose2, K); +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// StereoCamera cam3(pose3, K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// 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)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3*noise_pose); +// +// LevenbergMarquardtParams params; +// Values result; +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// EXPECT(assert_equal(pose3,result.at(x3))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ +// // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K2); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// StereoCamera cam2(pose2, K2); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// StereoCamera 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); +// +// typedef GenericStereoFactor ProjectionFactor; +// NonlinearFactorGraph graph; +// +// // 1. Project three landmarks into three cameras and triangulate +// graph.push_back(ProjectionFactor(cam1.project(landmark1), model, x1, L(1), K2)); +// graph.push_back(ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); +// graph.push_back(ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); +// +// graph.push_back(ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); +// graph.push_back(ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); +// graph.push_back(ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); +// +// graph.push_back(ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); +// graph.push_back(ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); +// graph.push_back(ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PriorFactor(x2, pose2, noisePrior)); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3* noise_pose); +// values.insert(L(1), landmark1); +// values.insert(L(2), landmark2); +// values.insert(L(3), landmark3); +// 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))); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, CheckHessian){ +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// StereoCamera cam2(pose2, K); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// StereoCamera cam3(pose3, K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// +// double rankTol = 10; +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); +// +// boost::shared_ptr hessianFactor1 = smartFactor1->linearize(values); +// boost::shared_ptr hessianFactor2 = smartFactor2->linearize(values); +// boost::shared_ptr hessianFactor3 = smartFactor3->linearize(values); +// +// Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); +// +// boost::shared_ptr GaussianGraph = graph.linearize(values); +// Matrix GraphInformation = GaussianGraph->hessian().first; +// +// // Check Hessian +// EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); +// +// Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + +// hessianFactor2->augmentedInformation() + hessianFactor3->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( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K2); +// +// // 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)); +// StereoCamera cam2(pose2, K2); +// +// // 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)); +// StereoCamera cam3(pose3, K2); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// +// double rankTol = 50; +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor1->add(measurements_cam1, views, model, K2); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor2->add(measurements_cam2, views, model, K2); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); +// Point3 positionPrior = gtsam::Point3(0,0,1); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); +// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2*noise_pose); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose*noise_pose); +// 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); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::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; +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// StereoCamera cam2(pose2, K); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); +// StereoCamera cam3(pose3, K); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// Point3 landmark2(5, -0.5, 1.2); +// Point3 landmark3(3, 0, 3.0); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// // 1. Project three landmarks into three cameras and triangulate +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); +// +// double rankTol = 10; +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor1->add(measurements_cam1, views, model, K); +// +// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor2->add(measurements_cam2, views, model, K); +// +// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// smartFactor3->add(measurements_cam3, views, model, K); +// +// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); +// const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); +// Point3 positionPrior = gtsam::Point3(0,0,1); +// +// NonlinearFactorGraph graph; +// graph.push_back(smartFactor1); +// graph.push_back(smartFactor2); +// graph.push_back(smartFactor3); +// graph.push_back(PriorFactor(x1, pose1, noisePrior)); +// graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); +// graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); +// +// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// // initialize third pose with some noise, we expect it to move back to original pose3 +// values.insert(x3, pose3*noise_pose); +// 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); +// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// result = optimizer.optimize(); +// gttoc_(SmartStereoProjectionPoseFactor); +// tictoc_finishedIteration_(); +// +// // result.print("results of 3 camera, 3 landmark optimization \n"); +// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); +// std::cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << std::endl; +// // EXPECT(assert_equal(pose3,result.at(x3))); +// if(isDebugTest) tictoc_print_(); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, Hessian ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: Hessian **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K2); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// StereoCamera cam2(pose2, K2); +// +// // three landmarks ~5 meters infront of camera +// Point3 landmark1(5, 0.5, 1.2); +// +// // 1. Project three landmarks into three cameras and triangulate +// StereoPoint2 cam1_uv1 = cam1.project(landmark1); +// StereoPoint2 cam2_uv1 = cam2.project(landmark1); +// vector measurements_cam1; +// measurements_cam1.push_back(cam1_uv1); +// measurements_cam1.push_back(cam2_uv1); +// +// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); +// smartFactor1->add(measurements_cam1,views, model, K2); +// +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// +// boost::shared_ptr hessianFactor = smartFactor1->linearize(values); +// if(isDebugTest) hessianFactor->print("Hessian factor \n"); +// +// // compute triangulation from linearization point +// // compute reprojection errors (sum squared) +// // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) +// // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] +//} +// +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); +// StereoCamera cam2(pose2, K); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); +// StereoCamera cam3(pose3, K); +// +// Point3 landmark1(5, 0.5, 1.2); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// +// SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); +// smartFactorInstance->add(measurements_cam1, views, model, K); +// +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3); +// +// boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); +// // hessianFactor->print("Hessian factor \n"); +// +// Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); +// +// Values rotValues; +// rotValues.insert(x1, poseDrift.compose(pose1)); +// rotValues.insert(x2, poseDrift.compose(pose2)); +// rotValues.insert(x3, poseDrift.compose(pose3)); +// +// boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); +// // hessianFactorRot->print("Hessian factor \n"); +// +// // Hessian is invariant to rotations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); +// +// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); +// +// Values tranValues; +// tranValues.insert(x1, poseDrift2.compose(pose1)); +// tranValues.insert(x2, poseDrift2.compose(pose2)); +// tranValues.insert(x3, poseDrift2.compose(pose3)); +// +// boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); +// +// // Hessian is invariant to rotations and translations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +//} +// +///* *************************************************************************/ +//TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ +// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; +// +// std::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), gtsam::Point3(0,0,1)); +// StereoCamera cam1(pose1, K2); +// +// // create second camera 1 meter to the right of first camera +// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0,0,0)); +// StereoCamera cam2(pose2, K2); +// +// // create third camera 1 meter above the first camera +// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,0,0)); +// StereoCamera cam3(pose3, K2); +// +// Point3 landmark1(5, 0.5, 1.2); +// +// vector measurements_cam1, measurements_cam2, measurements_cam3; +// +// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); +// +// SmartFactor::shared_ptr smartFactor(new SmartFactor()); +// smartFactor->add(measurements_cam1, views, model, K2); +// +// +// Values values; +// values.insert(x1, pose1); +// values.insert(x2, pose2); +// values.insert(x3, pose3); +// +// 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), gtsam::Point3(0,0,0)); +// +// Values rotValues; +// rotValues.insert(x1, poseDrift.compose(pose1)); +// rotValues.insert(x2, poseDrift.compose(pose2)); +// rotValues.insert(x3, poseDrift.compose(pose3)); +// +// boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); +// if(isDebugTest) hessianFactorRot->print("Hessian factor \n"); +// +// // Hessian is invariant to rotations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); +// +// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); +// +// Values tranValues; +// tranValues.insert(x1, poseDrift2.compose(pose1)); +// tranValues.insert(x2, poseDrift2.compose(pose2)); +// tranValues.insert(x3, poseDrift2.compose(pose3)); +// +// boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); +// +// // Hessian is invariant to rotations and translations in the nondegenerate case +// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +//} /* ************************************************************************* */ From 4c076fca2d02d730d17cc25619a3fa74fc38b6b4 Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Tue, 15 Jul 2014 10:14:23 -0400 Subject: [PATCH 23/57] Added SmartStereoProjectionFactor example --- gtsam/slam/SmartStereoProjectionFactor.h | 2 +- .../SmartStereoProjectionFactorExample.cpp | 125 ++++++++++++++++++ 2 files changed, 126 insertions(+), 1 deletion(-) create mode 100644 gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 29a942bae..c79ad1a89 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -296,7 +296,7 @@ public: } i += 1; } - std::cout << "totalReprojError error: " << totalReprojError << std::endl; + //std::cout << "totalReprojError error: " << totalReprojError << std::endl; // we discard smart factors that have large reprojection error if(dynamicOutlierRejectionThreshold_ > 0 && totalReprojError/m > dynamicOutlierRejectionThreshold_) diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp new file mode 100644 index 000000000..d740ebff8 --- /dev/null +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -0,0 +1,125 @@ +/* ---------------------------------------------------------------------------- + +* 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 SmartProjectionFactorExample.cpp +* @brief A stereo visual odometry example +* @date May 30, 2014 +* @author Stephen Camp +* @author Chris Beall +*/ + + +/** + * A smart projection factor example based on stereo data, throwing away the + * measurement from the right camera + * -robot starts at origin + * -moves forward, taking periodic stereo measurements + * -makes monocular observations of many landmarks + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv){ + + typedef SmartStereoProjectionPoseFactor SmartFactor; + + Values initial_estimate; + NonlinearFactorGraph graph; + const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1); + + string calibration_loc = findExampleDataFile("VO_calibration.txt"); + string pose_loc = findExampleDataFile("VO_camera_poses_large.txt"); + string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt"); + + //read camera calibration info from file + // focal lengths fx, fy, skew s, principal point u0, v0, baseline b + cout << "Reading calibration info" << endl; + ifstream calibration_file(calibration_loc.c_str()); + + double fx, fy, s, u0, v0, b; + calibration_file >> fx >> fy >> s >> u0 >> v0 >> b; + const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx, fy, s, u0, v0,b)); + + cout << "Reading camera poses" << endl; + ifstream pose_file(pose_loc.c_str()); + + int pose_id; + 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++) { + pose_file >> m.data()[i]; + } + initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); + } + + // camera and landmark keys + size_t x, 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 + double uL, uR, v, X, Y, Z; + ifstream factor_file(factor_loc.c_str()); + cout << "Reading stereo factors" << endl; + + //read stereo measurements and construct smart factors + + 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) { + + if(current_l != l) { + graph.push_back(factor); + factor = SmartFactor::shared_ptr(new SmartFactor()); + current_l = l; + } + factor->add(StereoPoint2(uL,uR,v), Symbol('x',x), model, K); + } + + Pose3 first_pose = initial_estimate.at(Symbol('x',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)); + + LevenbergMarquardtParams params; + params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + params.verbosity = NonlinearOptimizerParams::ERROR; + + cout << "Optimizing" << endl; + //create Levenberg-Marquardt optimizer to optimize the factor graph + LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate, params); + Values result = optimizer.optimize(); + + cout << "Final result sample:" << endl; + Values pose_values = result.filter(); + pose_values.print("Final camera poses:\n"); + + return 0; +} From 48db3fc6c69d60c88555f64e065dc1a2f60b2a93 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 15 Jul 2014 13:08:51 -0400 Subject: [PATCH 24/57] remove duplicate test --- .../testSmartStereoProjectionPoseFactor.cpp | 74 ------------------- 1 file changed, 74 deletions(-) diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 2659cb274..0b9f55d0b 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -297,80 +297,6 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ){ if(isDebugTest) tictoc_print_(); } -/* *************************************************************************/ -TEST( SmartStereoProjectionPoseFactor, 3poses_iterative_smart_projection_factor ){ - // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; - - std::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), gtsam::Point3(0,0,1)); - StereoCamera cam1(pose1, K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); - StereoCamera cam2(pose2, K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - StereoCamera 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); - - // 1. Project three landmarks into three cameras and triangulate - vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); - vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); - vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); - - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, K); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, K); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3*noise_pose); - if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); - - LevenbergMarquardtParams params; - if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; - - Values result; - gttic_(SmartStereoProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartStereoProjectionPoseFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); - EXPECT(assert_equal(pose3,result.at(x3))); - if(isDebugTest) tictoc_print_(); -} ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ From d68e6b9addcf2fc1564aa5d74b9a311ede06ccf4 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 15 Jul 2014 13:09:12 -0400 Subject: [PATCH 25/57] Noisemodel dimension 2->3 --- gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp index d740ebff8..43e576e05 100644 --- a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -50,7 +50,7 @@ int main(int argc, char** argv){ Values initial_estimate; NonlinearFactorGraph graph; - const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1); + const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1); string calibration_loc = findExampleDataFile("VO_calibration.txt"); string pose_loc = findExampleDataFile("VO_camera_poses_large.txt"); From 089ac4e743b777c7b1e339d11af32bf10618f9fa Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 15 Jul 2014 14:43:01 -0400 Subject: [PATCH 26/57] Additionally templated JacobianFactorSVD on measurement type, and Jacobian_SVD unit tests now pass for SmartStereoFactor --- gtsam/slam/JacobianFactorSVD.h | 10 +- gtsam/slam/SmartFactorBase.h | 2 +- gtsam/slam/SmartProjectionFactor.h | 2 +- gtsam/slam/SmartStereoProjectionFactor.h | 16 +- gtsam/slam/SmartStereoProjectionPoseFactor.h | 3 +- .../testSmartStereoProjectionPoseFactor.cpp | 397 +++++++++--------- 6 files changed, 214 insertions(+), 216 deletions(-) diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index 0d3c04de1..8bed77d0f 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -11,12 +11,12 @@ namespace gtsam { /** * JacobianFactor for Schur complement that uses Q noise model */ -template +template class JacobianFactorSVD: public JacobianSchurFactor { public: - typedef Eigen::Matrix Matrix2D; + typedef Eigen::Matrix Matrix2D; // e.g 2 x 6 with Z=Point2 typedef std::pair KeyMatrix2D; typedef std::pair KeyMatrix; @@ -38,8 +38,8 @@ public: /// Constructor JacobianFactorSVD(const std::vector >& Fblocks, const Matrix& Enull, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { - size_t numKeys = Enull.rows() / 2; - size_t j = 0, m2 = 2*numKeys-3; + size_t numKeys = Enull.rows() / Z::Dim(); + size_t j = 0, m2 = Z::Dim()*numKeys-3; // PLAIN NULL SPACE TRICK // Matrix Q = Enull * Enull.transpose(); // BOOST_FOREACH(const KeyMatrix2D& it, Fblocks) @@ -48,7 +48,7 @@ public: std::vector QF; QF.reserve(numKeys); BOOST_FOREACH(const KeyMatrix2D& it, Fblocks) - QF.push_back(KeyMatrix(it.first, (Enull.transpose()).block(0, 2 * j++, m2, 2) * it.second)); + QF.push_back(KeyMatrix(it.first, (Enull.transpose()).block(0, Z::Dim() * j++, m2, Z::Dim()) * it.second)); JacobianFactor::fillTerms(QF, Enull.transpose() * b, model); } }; diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index ae2dc8b0f..03bd92f21 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -660,7 +660,7 @@ public: Vector b; Matrix Enull(Z::Dim()*numKeys, Z::Dim()*numKeys-3); computeJacobiansSVD(Fblocks, Enull, b, cameras, point, lambda); - return boost::make_shared< JacobianFactorSVD<6> >(Fblocks, Enull, b); + return boost::make_shared< JacobianFactorSVD<6, Z> >(Fblocks, Enull, b); } private: diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 04112e239..a08b79953 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -444,7 +444,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared< JacobianFactorSVD >(this->keys_); + return boost::make_shared< JacobianFactorSVD >(this->keys_); } /// Returns true if nonDegenerate diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index c79ad1a89..71f5e11b3 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -473,14 +473,14 @@ public: // return boost::make_shared< JacobianFactorQ >(this->keys_); // } // -// /// different (faster) way to compute Jacobian factor -// boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, -// double lambda) const { -// if (triangulateForLinearize(cameras)) -// return Base::createJacobianSVDFactor(cameras, point_, lambda); -// else -// return boost::make_shared< JacobianFactorSVD >(this->keys_); -// } + /// different (faster) way to compute Jacobian factor + boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, + double lambda) const { + if (triangulateForLinearize(cameras)) + return Base::createJacobianSVDFactor(cameras, point_, lambda); + else + return boost::make_shared< JacobianFactorSVD >(this->keys_); + } /// Returns true if nonDegenerate bool computeCamerasAndTriangulate(const Values& values, diff --git a/gtsam/slam/SmartStereoProjectionPoseFactor.h b/gtsam/slam/SmartStereoProjectionPoseFactor.h index 60992281e..9448f6498 100644 --- a/gtsam/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam/slam/SmartStereoProjectionPoseFactor.h @@ -175,8 +175,7 @@ public: // depending on flag set on construction we may linearize to different linear factors switch(linearizeTo_){ case JACOBIAN_SVD : - throw("JacobianSVD not working yet!"); -// return this->createJacobianSVDFactor(cameras(values), 0.0); + return this->createJacobianSVDFactor(cameras(values), 0.0); break; case JACOBIAN_Q : throw("JacobianQ not working yet!"); diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 0b9f55d0b..d9b86e158 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -298,206 +298,205 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ){ } -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ -// -// std::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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, K); -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// StereoCamera cam2(pose2, K); -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// StereoCamera 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); -// -// // 1. Project three landmarks into three cameras and triangulate -// vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); -// vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); -// vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); -// -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3*noise_pose); -// -// LevenbergMarquardtParams params; -// Values result; -// LevenbergMarquardtOptimizer optimizer(graph, values, params); -// result = optimizer.optimize(); -// EXPECT(assert_equal(pose3,result.at(x3))); -//} +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, jacobianSVD ){ -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, landmarkDistance ){ -// -// double excludeLandmarksFutherThanDist = 2; -// -// std::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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, K); -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// StereoCamera cam2(pose2, K); -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// StereoCamera cam3(pose3, K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// 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_SVD, excludeLandmarksFutherThanDist)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// 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(); -// EXPECT(assert_equal(values.at(x3),result.at(x3))); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ -// -// double excludeLandmarksFutherThanDist = 1e10; -// double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error -// -// std::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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, K); -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// StereoCamera cam2(pose2, K); -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// StereoCamera 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); -// Point3 landmark4(5, -0.5, 1); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); -// 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, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, 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, -// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// SmartFactor::shared_ptr smartFactor4(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, -// excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); -// smartFactor4->add(measurements_cam4, views, model, K); -// -// const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// graph.push_back(smartFactor4); -// graph.push_back(PriorFactor(x1, pose1, noisePrior)); -// graph.push_back(PriorFactor(x2, pose2, noisePrior)); -// -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// 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(); -// EXPECT(assert_equal(pose3,result.at(x3))); -//} + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera 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); + + // 1. Project three landmarks into three cameras and triangulate + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); + vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3*noise_pose); + + LevenbergMarquardtParams params; + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, params); + result = optimizer.optimize(); + EXPECT(assert_equal(pose3,result.at(x3))); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, landmarkDistance ){ + + double excludeLandmarksFutherThanDist = 2; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera 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); + + // 1. Project three landmarks into three cameras and triangulate + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); + vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); + + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, excludeLandmarksFutherThanDist)); + smartFactor3->add(measurements_cam3, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + 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(); + EXPECT(assert_equal(values.at(x3),result.at(x3))); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ + + double excludeLandmarksFutherThanDist = 1e10; + double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera 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); + Point3 landmark4(5, -0.5, 1); + + // 1. Project four landmarks into three cameras and triangulate + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); + vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); + vector measurements_cam4 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark4); + + + 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, excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, 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, + excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + smartFactor3->add(measurements_cam3, views, model, K); + + SmartFactor::shared_ptr smartFactor4(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, + excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); + smartFactor4->add(measurements_cam4, views, model, K); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(smartFactor4); + graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x2, pose2, noisePrior)); + + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + 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(); + EXPECT(assert_equal(pose3,result.at(x3))); +} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, jacobianQ ){ From e7c82652af3f4652a4587b9a87530e5bba507e8f Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Wed, 16 Jul 2014 14:45:56 -0400 Subject: [PATCH 27/57] Added option to increase initial error in SmartStereoProjectionFactorExample --- .../examples/SmartStereoProjectionFactorExample.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp index 43e576e05..9847ef5ed 100644 --- a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -52,6 +52,8 @@ int main(int argc, char** argv){ NonlinearFactorGraph graph; const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1); + bool add_initial_noise = true; + string calibration_loc = findExampleDataFile("VO_calibration.txt"); string pose_loc = findExampleDataFile("VO_camera_poses_large.txt"); string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt"); @@ -75,6 +77,9 @@ int main(int argc, char** argv){ for (int i = 0; i < 16; i++) { pose_file >> m.data()[i]; } + if(add_initial_noise){ + m(0,3) += (pose_id % 10)/5; + } initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); } From a2974341488152d5afcf88edebf9884f814bed66 Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Tue, 22 Jul 2014 09:08:38 -0400 Subject: [PATCH 28/57] Modified SmartStereoProjectionFactorExample to write optimized poses to file --- .../examples/SmartStereoProjectionFactorExample.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp index 9847ef5ed..f4329e665 100644 --- a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -48,9 +48,12 @@ int main(int argc, char** argv){ typedef SmartStereoProjectionPoseFactor SmartFactor; + bool output_poses = true; + string poseOutput("../../../examples/data/optimized_poses.txt"); Values initial_estimate; NonlinearFactorGraph graph; const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1); + ofstream pose3Out; bool add_initial_noise = true; @@ -126,5 +129,14 @@ int main(int argc, char** argv){ Values pose_values = result.filter(); pose_values.print("Final camera poses:\n"); + if(output_poses){ + pose3Out.open(poseOutput.c_str(),ios::out); + for(int i = 1; i<=pose_values.size(); i++){ + pose3Out << i << " " << pose_values.at(Symbol('x',i)).matrix().format(Eigen::IOFormat(Eigen::StreamPrecision, 0, + " ", " ")) << endl; + } + cout << "Writing output" << endl; + } + return 0; } From 8bad2952099c89465ea4c7e03479c6c6c26f377c Mon Sep 17 00:00:00 2001 From: Stephen Camp Date: Tue, 22 Jul 2014 12:49:09 -0400 Subject: [PATCH 29/57] Changed initial noise generation for SmartStereoProjectionFactorExample to Y direction, changed noise generation scale --- .../SmartStereoProjectionFactorExample.cpp | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp index f4329e665..7950bdb23 100644 --- a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -49,11 +49,13 @@ int main(int argc, char** argv){ typedef SmartStereoProjectionPoseFactor SmartFactor; bool output_poses = true; + bool output_initial_poses = true; string poseOutput("../../../examples/data/optimized_poses.txt"); + string init_poseOutput("../../../examples/data/initial_poses.txt"); Values initial_estimate; NonlinearFactorGraph graph; const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1); - ofstream pose3Out; + ofstream pose3Out, init_pose3Out; bool add_initial_noise = true; @@ -81,10 +83,19 @@ int main(int argc, char** argv){ pose_file >> m.data()[i]; } if(add_initial_noise){ - m(0,3) += (pose_id % 10)/5; + m(1,3) += (pose_id % 10)/10; } initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); } + + Values initial_pose_values = initial_estimate.filter(); + if(output_poses){ + init_pose3Out.open(init_poseOutput.c_str(),ios::out); + for(int i = 1; i<=initial_pose_values.size(); i++){ + init_pose3Out << i << " " << initial_pose_values.at(Symbol('x',i)).matrix().format(Eigen::IOFormat(Eigen::StreamPrecision, 0, + " ", " ")) << endl; + } + } // camera and landmark keys size_t x, l; From f75f26fb637f3fbaa3f108f70ab3aa3e09c12757 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 22 Jul 2014 22:00:33 -0400 Subject: [PATCH 30/57] Fix for Mac --- gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp index 7950bdb23..841092ec9 100644 --- a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -83,7 +83,7 @@ int main(int argc, char** argv){ pose_file >> m.data()[i]; } if(add_initial_noise){ - m(1,3) += (pose_id % 10)/10; + m(1,3) += (pose_id % 10)/10.0; } initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); } From cbad9aa78395b6590928691c4a27cf8e335d68b2 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 22 Jul 2014 22:02:20 -0400 Subject: [PATCH 31/57] Hessian tests work, too --- .../testSmartStereoProjectionPoseFactor.cpp | 409 +++++++++--------- 1 file changed, 201 insertions(+), 208 deletions(-) diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp index d9b86e158..e50616163 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -626,85 +626,84 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ // EXPECT(assert_equal(pose3,result.at(x3))); //} // -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, CheckHessian){ -// -// std::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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, K); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); -// StereoCamera cam2(pose2, K); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); -// StereoCamera cam3(pose3, K); -// -// // three landmarks ~5 meters infront of camera -// Point3 landmark1(5, 0.5, 1.2); -// Point3 landmark2(5, -0.5, 1.2); -// Point3 landmark3(3, 0, 3.0); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// // 1. Project three landmarks into three cameras and triangulate -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); -// -// double rankTol = 10; -// -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); -// smartFactor1->add(measurements_cam1, views, model, K); -// -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); -// smartFactor2->add(measurements_cam2, views, model, K); -// -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); -// smartFactor3->add(measurements_cam3, views, model, K); -// -// NonlinearFactorGraph graph; -// graph.push_back(smartFactor1); -// graph.push_back(smartFactor2); -// graph.push_back(smartFactor3); -// -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// // initialize third pose with some noise, we expect it to move back to original pose3 -// values.insert(x3, pose3*noise_pose); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// boost::shared_ptr hessianFactor1 = smartFactor1->linearize(values); -// boost::shared_ptr hessianFactor2 = smartFactor2->linearize(values); -// boost::shared_ptr hessianFactor3 = smartFactor3->linearize(values); -// -// Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); -// -// boost::shared_ptr GaussianGraph = graph.linearize(values); -// Matrix GraphInformation = GaussianGraph->hessian().first; -// -// // Check Hessian -// EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); -// -// Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + -// hessianFactor2->augmentedInformation() + hessianFactor3->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( SmartStereoProjectionPoseFactor, CheckHessian){ + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); + StereoCamera cam2(pose2, K); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0,0,0)); + StereoCamera 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); + + // 1. Project three landmarks into three cameras and triangulate + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); + vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); + + + double rankTol = 10; + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); + smartFactor1->add(measurements_cam1, views, model, K); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); + smartFactor2->add(measurements_cam2, views, model, K); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); + smartFactor3->add(measurements_cam3, views, model, K); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + + // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, pose3*noise_pose); + if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); + + boost::shared_ptr hessianFactor1 = smartFactor1->linearize(values); + boost::shared_ptr hessianFactor2 = smartFactor2->linearize(values); + boost::shared_ptr hessianFactor3 = smartFactor3->linearize(values); + + Matrix CumulativeInformation = hessianFactor1->information() + hessianFactor2->information() + hessianFactor3->information(); + + boost::shared_ptr GaussianGraph = graph.linearize(values); + Matrix GraphInformation = GaussianGraph->hessian().first; + + // Check Hessian + EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); + + Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() + + hessianFactor2->augmentedInformation() + hessianFactor3->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( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ @@ -907,135 +906,129 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ){ // // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] //} // -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, K); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); -// StereoCamera cam2(pose2, K); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); -// StereoCamera cam3(pose3, K); -// -// Point3 landmark1(5, 0.5, 1.2); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// -// SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); -// smartFactorInstance->add(measurements_cam1, views, model, K); -// -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3); -// -// boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); -// // hessianFactor->print("Hessian factor \n"); -// -// Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); -// -// Values rotValues; -// rotValues.insert(x1, poseDrift.compose(pose1)); -// rotValues.insert(x2, poseDrift.compose(pose2)); -// rotValues.insert(x3, poseDrift.compose(pose3)); -// -// boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); -// // hessianFactorRot->print("Hessian factor \n"); -// -// // Hessian is invariant to rotations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); -// -// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); -// -// Values tranValues; -// tranValues.insert(x1, poseDrift2.compose(pose1)); -// tranValues.insert(x2, poseDrift2.compose(pose2)); -// tranValues.insert(x3, poseDrift2.compose(pose3)); -// -// boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); -// -// // Hessian is invariant to rotations and translations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -//} -// -///* *************************************************************************/ -//TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; -// -// std::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), gtsam::Point3(0,0,1)); -// StereoCamera cam1(pose1, K2); -// -// // create second camera 1 meter to the right of first camera -// Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0,0,0)); -// StereoCamera cam2(pose2, K2); -// -// // create third camera 1 meter above the first camera -// Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,0,0)); -// StereoCamera cam3(pose3, K2); -// -// Point3 landmark1(5, 0.5, 1.2); -// -// vector measurements_cam1, measurements_cam2, measurements_cam3; -// -// stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); -// -// SmartFactor::shared_ptr smartFactor(new SmartFactor()); -// smartFactor->add(measurements_cam1, views, model, K2); -// -// -// Values values; -// values.insert(x1, pose1); -// values.insert(x2, pose2); -// values.insert(x3, pose3); -// -// 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), gtsam::Point3(0,0,0)); -// -// Values rotValues; -// rotValues.insert(x1, poseDrift.compose(pose1)); -// rotValues.insert(x2, poseDrift.compose(pose2)); -// rotValues.insert(x3, poseDrift.compose(pose3)); -// -// boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); -// if(isDebugTest) hessianFactorRot->print("Hessian factor \n"); -// -// // Hessian is invariant to rotations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); -// -// Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); -// -// Values tranValues; -// tranValues.insert(x1, poseDrift2.compose(pose1)); -// tranValues.insert(x2, poseDrift2.compose(pose2)); -// tranValues.insert(x3, poseDrift2.compose(pose3)); -// -// boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); -// -// // Hessian is invariant to rotations and translations in the nondegenerate case -// EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); -//} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ){ + // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K); + + // create second camera 1 meter to the right of first camera + Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); + StereoCamera cam2(pose2, K); + + // create third camera 1 meter above the first camera + Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); + StereoCamera cam3(pose3, K); + + Point3 landmark1(5, 0.5, 1.2); + + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + + SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); + smartFactorInstance->add(measurements_cam1, views, model, K); + + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3); + + boost::shared_ptr hessianFactor = smartFactorInstance->linearize(values); + // hessianFactor->print("Hessian factor \n"); + + Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,0)); + + Values rotValues; + rotValues.insert(x1, poseDrift.compose(pose1)); + rotValues.insert(x2, poseDrift.compose(pose2)); + rotValues.insert(x3, poseDrift.compose(pose3)); + + boost::shared_ptr hessianFactorRot = smartFactorInstance->linearize(rotValues); + // hessianFactorRot->print("Hessian factor \n"); + + // Hessian is invariant to rotations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); + + Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); + + Values tranValues; + tranValues.insert(x1, poseDrift2.compose(pose1)); + tranValues.insert(x2, poseDrift2.compose(pose2)); + tranValues.insert(x3, poseDrift2.compose(pose3)); + + boost::shared_ptr hessianFactorRotTran = smartFactorInstance->linearize(tranValues); + + // Hessian is invariant to rotations and translations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +} + +/* *************************************************************************/ +TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ){ + // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; + + std::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), gtsam::Point3(0,0,1)); + StereoCamera cam1(pose1, K2); + + // Second and third cameras in same place, which is a degenerate configuration + Pose3 pose2 = pose1; + Pose3 pose3 = pose1; + StereoCamera cam2(pose2, K2); + StereoCamera cam3(pose3, K2); + + Point3 landmark1(5, 0.5, 1.2); + + vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); + + SmartFactor::shared_ptr smartFactor(new SmartFactor()); + smartFactor->add(measurements_cam1, views, model, K2); + + + Values values; + values.insert(x1, pose1); + values.insert(x2, pose2); + values.insert(x3, pose3); + + 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), gtsam::Point3(0,0,0)); + + Values rotValues; + rotValues.insert(x1, poseDrift.compose(pose1)); + rotValues.insert(x2, poseDrift.compose(pose2)); + rotValues.insert(x3, poseDrift.compose(pose3)); + + boost::shared_ptr hessianFactorRot = smartFactor->linearize(rotValues); + if(isDebugTest) hessianFactorRot->print("Hessian factor \n"); + + // Hessian is invariant to rotations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-8) ); + + Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI/2, -M_PI/3, -M_PI/2), gtsam::Point3(10,-4,5)); + + Values tranValues; + tranValues.insert(x1, poseDrift2.compose(pose1)); + tranValues.insert(x2, poseDrift2.compose(pose2)); + tranValues.insert(x3, poseDrift2.compose(pose3)); + + boost::shared_ptr hessianFactorRotTran = smartFactor->linearize(tranValues); + + // Hessian is invariant to rotations and translations in the nondegenerate case + EXPECT(assert_equal(hessianFactor->information(), hessianFactorRotTran->information(), 1e-8) ); +} /* ************************************************************************* */ From fb55e2c17f3138f6840e8bf9e524ca6c5093e530 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 22 Jul 2014 22:03:04 -0400 Subject: [PATCH 32/57] print linearization threshold --- gtsam/slam/SmartStereoProjectionFactor.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 71f5e11b3..9a73b84fe 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -156,6 +156,7 @@ 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; Base::print("", keyFormatter); } From dde32f7fe2800b33794e52c598a3f7891715e9b4 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 17 Nov 2014 19:10:27 -0500 Subject: [PATCH 33/57] templated SmartFactor classes on measurement dimension, ZDim --- gtsam/slam/JacobianFactorQ.h | 16 ++++---- gtsam/slam/JacobianFactorQR.h | 12 +++--- gtsam/slam/JacobianFactorSVD.h | 18 ++++----- gtsam/slam/JacobianSchurFactor.h | 4 +- gtsam/slam/SmartFactorBase.h | 38 ++++++++++--------- gtsam/slam/SmartProjectionFactor.h | 12 +++--- gtsam/slam/SmartStereoProjectionFactor.h | 4 +- .../tests/testRegularImplicitSchurFactor.cpp | 4 +- 8 files changed, 57 insertions(+), 51 deletions(-) diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index de13f7ef0..9b9383d7b 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -12,10 +12,10 @@ namespace gtsam { /** * JacobianFactor for Schur complement that uses Q noise model */ -template -class JacobianFactorQ: public JacobianSchurFactor { +template +class JacobianFactorQ: public JacobianSchurFactor { - typedef JacobianSchurFactor Base; + typedef JacobianSchurFactor Base; public: @@ -25,7 +25,7 @@ public: /// Empty constructor with keys JacobianFactorQ(const FastVector& keys, - const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { + const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { Matrix zeroMatrix = Matrix::Zero(0,D); Vector zeroVector = Vector::Zero(0); typedef std::pair KeyMatrix; @@ -37,11 +37,11 @@ public: } /// Constructor - JacobianFactorQ(const std::vector >& Fblocks, + JacobianFactorQ(const std::vector& Fblocks, const Matrix& E, const Matrix3& P, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : - JacobianSchurFactor() { - size_t j = 0, m2 = E.rows(), m = m2 / 2; + JacobianSchurFactor() { + 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 @@ -51,7 +51,7 @@ public: QF.reserve(m); // Below, we compute each 2m*D block A_j = Q_j * F_j = (2m*2) * (2*D) BOOST_FOREACH(const typename Base::KeyMatrix2D& it, Fblocks) - QF.push_back(KeyMatrix(it.first, Q.block(0, 2 * j++, m2, 2) * it.second)); + QF.push_back(KeyMatrix(it.first, Q.block(0, ZDim * j++, m2, ZDim) * it.second)); // 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 a928106a8..ccd6e8756 100644 --- a/gtsam/slam/JacobianFactorQR.h +++ b/gtsam/slam/JacobianFactorQR.h @@ -12,10 +12,10 @@ namespace gtsam { /** * JacobianFactor for Schur complement that uses Q noise model */ -template -class JacobianFactorQR: public JacobianSchurFactor { +template +class JacobianFactorQR: public JacobianSchurFactor { - typedef JacobianSchurFactor Base; + typedef JacobianSchurFactor Base; public: @@ -25,14 +25,14 @@ public: JacobianFactorQR(const std::vector& Fblocks, const Matrix& E, const Matrix3& P, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : - JacobianSchurFactor() { + JacobianSchurFactor() { // Create a number of Jacobian factors in a factor graph GaussianFactorGraph gfg; Symbol pointKey('p', 0); size_t i = 0; BOOST_FOREACH(const typename Base::KeyMatrix2D& it, Fblocks) { - gfg.add(pointKey, E.block<2, 3>(2 * i, 0), it.first, it.second, - b.segment<2>(2 * i), model); + gfg.add(pointKey, E.block(ZDim * i, 0), it.first, it.second, + b.segment(ZDim * i), model); i += 1; } //gfg.print("gfg"); diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index 8bed77d0f..e0a5f4566 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -11,12 +11,12 @@ namespace gtsam { /** * JacobianFactor for Schur complement that uses Q noise model */ -template -class JacobianFactorSVD: public JacobianSchurFactor { +template +class JacobianFactorSVD: public JacobianSchurFactor { public: - typedef Eigen::Matrix Matrix2D; // e.g 2 x 6 with Z=Point2 + typedef Eigen::Matrix Matrix2D; // e.g 2 x 6 with Z=Point2 typedef std::pair KeyMatrix2D; typedef std::pair KeyMatrix; @@ -25,7 +25,7 @@ public: /// Empty constructor with keys JacobianFactorSVD(const FastVector& keys, - const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { + const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { Matrix zeroMatrix = Matrix::Zero(0,D); Vector zeroVector = Vector::Zero(0); std::vector QF; @@ -36,10 +36,10 @@ public: } /// Constructor - JacobianFactorSVD(const std::vector >& Fblocks, const Matrix& Enull, const Vector& b, - const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { - size_t numKeys = Enull.rows() / Z::Dim(); - size_t j = 0, m2 = Z::Dim()*numKeys-3; + JacobianFactorSVD(const std::vector& Fblocks, const Matrix& Enull, const Vector& b, + const SharedDiagonal& model = SharedDiagonal()) : JacobianSchurFactor() { + size_t numKeys = Enull.rows() / ZDim; + size_t j = 0, m2 = ZDim*numKeys-3; // PLAIN NULL SPACE TRICK // Matrix Q = Enull * Enull.transpose(); // BOOST_FOREACH(const KeyMatrix2D& it, Fblocks) @@ -48,7 +48,7 @@ public: std::vector QF; QF.reserve(numKeys); BOOST_FOREACH(const KeyMatrix2D& it, Fblocks) - QF.push_back(KeyMatrix(it.first, (Enull.transpose()).block(0, Z::Dim() * j++, m2, Z::Dim()) * it.second)); + QF.push_back(KeyMatrix(it.first, (Enull.transpose()).block(0, ZDim * j++, m2, ZDim) * it.second)); JacobianFactor::fillTerms(QF, Enull.transpose() * b, model); } }; diff --git a/gtsam/slam/JacobianSchurFactor.h b/gtsam/slam/JacobianSchurFactor.h index 2beecc264..5d28bbada 100644 --- a/gtsam/slam/JacobianSchurFactor.h +++ b/gtsam/slam/JacobianSchurFactor.h @@ -18,12 +18,12 @@ namespace gtsam { /** * JacobianFactor for Schur complement that uses Q noise model */ -template +template class JacobianSchurFactor: public JacobianFactor { public: - typedef Eigen::Matrix Matrix2D; + typedef Eigen::Matrix Matrix2D; typedef std::pair KeyMatrix2D; // Use eigen magic to access raw memory diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index f7751422e..7c5a1175d 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -34,7 +34,6 @@ #include #include #include -//#include namespace gtsam { /// Base class with no internal point, completely functional @@ -50,14 +49,16 @@ protected: boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) + typedef traits::dimension ZDim_t; ///< Dimension trait of measurement type + /// 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 Matrix23; + typedef Eigen::Matrix Matrix23; typedef Eigen::Matrix VectorD; - typedef Eigen::Matrix Matrix2; + typedef Eigen::Matrix Matrix2; /// shorthand for base class type typedef NonlinearFactor Base; @@ -65,6 +66,7 @@ protected: /// shorthand for this class typedef SmartFactorBase This; + public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -262,7 +264,7 @@ public: // **************************************************************************************************** /// Compute F, E only (called below in both vanilla and SVD versions) /// Given a Point3, assumes dimensionality is 3 - double computeJacobians(std::vector >& Fblocks, Matrix& E, + double computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras, const Point3& point) const { size_t numKeys = this->keys_.size(); @@ -292,11 +294,11 @@ public: if (D == 6) { // optimize only camera pose Fblocks.push_back(KeyMatrix2D(this->keys_[i], Fi)); } else { - Hcam.block(0, 0) = Fi; // Z::Dim() x 6 block for the cameras - Hcam.block(0, 6) = Hcali; // Z::Dim() x nrCal block for the cameras + Hcam.block(0, 0) = Fi; // Z::Dim() x 6 block for the cameras + Hcam.block(0, 6) = Hcali; // Z::Dim() x nrCal block for the cameras Fblocks.push_back(KeyMatrix2D(this->keys_[i], Hcam)); } - E.block(Z::dimension * i, 0) = Ei; + E.block(ZDim_t::value * i, 0) = Ei; subInsert(b, bi, Z::Dim() * i); } return f; @@ -304,7 +306,7 @@ public: // **************************************************************************************************** /// Version that computes PointCov, with optional lambda parameter - double computeJacobians(std::vector >& Fblocks, Matrix& E, + double computeJacobians(std::vector& Fblocks, Matrix& E, Matrix3& PointCov, Vector& b, const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { @@ -335,20 +337,20 @@ public: const double lambda = 0.0) const { size_t numKeys = this->keys_.size(); - std::vector > Fblocks; + std::vector Fblocks; double f = computeJacobians(Fblocks, E, PointCov, b, cameras, point, lambda); F = zeros(Z::Dim() * numKeys, D * numKeys); for (size_t i = 0; i < this->keys_.size(); ++i) { - F.block(Z::Dim() * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras + F.block(ZDim_t::value * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras } return f; } // **************************************************************************************************** /// SVD version - double computeJacobiansSVD(std::vector >& Fblocks, Matrix& Enull, + double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, Vector& b, const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { @@ -645,27 +647,27 @@ public: } // **************************************************************************************************** - 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; + std::vector Fblocks; Matrix E; Matrix3 PointCov; Vector b; computeJacobians(Fblocks, E, PointCov, b, cameras, point, lambda, diagonalDamping); - return boost::make_shared >(Fblocks, E, PointCov, b); + return boost::make_shared >(Fblocks, E, PointCov, b); } // **************************************************************************************************** boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0) const { size_t numKeys = this->keys_.size(); - std::vector < KeyMatrix2D,Eigen::aligned_allocator > Fblocks; + std::vector Fblocks; Vector b; Matrix Enull(Z::Dim()*numKeys, Z::Dim()*numKeys-3); computeJacobiansSVD(Fblocks, Enull, b, cameras, point, lambda); - return boost::make_shared< JacobianFactorSVD<6, Z> >(Fblocks, Enull, b); + return boost::make_shared< JacobianFactorSVD<6, ZDim_t::value> >(Fblocks, Enull, b); } private: diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index ee0636142..c4d0867dc 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -104,6 +104,8 @@ protected: /// shorthand for this class typedef SmartProjectionFactor This; + typedef traits::dimension ZDim_t; ///< Dimension trait of measurement type + public: /// shorthand for a smart pointer to a factor @@ -418,16 +420,16 @@ public: } /// 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 myCameras; // TODO triangulate twice ?? @@ -435,7 +437,7 @@ public: if (nonDegenerate) return createJacobianQFactor(myCameras, lambda); else - return boost::make_shared< JacobianFactorQ >(this->keys_); + return boost::make_shared< JacobianFactorQ >(this->keys_); } /// different (faster) way to compute Jacobian factor @@ -444,7 +446,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared< JacobianFactorSVD >(this->keys_); + return boost::make_shared< JacobianFactorSVD >(this->keys_); } /// Returns true if nonDegenerate diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam/slam/SmartStereoProjectionFactor.h index 9a73b84fe..4d2a69ddf 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam/slam/SmartStereoProjectionFactor.h @@ -107,6 +107,8 @@ protected: /// shorthand for this class typedef SmartStereoProjectionFactor This; + typedef traits::dimension ZDim_t; ///< Dimension trait of measurement type + public: /// shorthand for a smart pointer to a factor @@ -480,7 +482,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared< JacobianFactorSVD >(this->keys_); + return boost::make_shared< JacobianFactorSVD >(this->keys_); } /// Returns true if nonDegenerate diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 0161d4fb6..d94304ed5 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -115,7 +115,7 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { // Create JacobianFactor with same error const SharedDiagonal model; - JacobianFactorQ<6> jf(Fblocks, E, P, b, model); + JacobianFactorQ<6, 2> jf(Fblocks, E, P, b, model); { // error double expectedError = jf.error(xvalues); @@ -165,7 +165,7 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { } // Create JacobianFactorQR - JacobianFactorQR<6> jfq(Fblocks, E, P, b, model); + JacobianFactorQR<6, 2> jfq(Fblocks, E, P, b, model); { const SharedDiagonal model; VectorValues yActual = zero; From 600444eeb7ec11affe61e31ca9b48459e5461665 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 17 Nov 2014 19:53:10 -0500 Subject: [PATCH 34/57] absolute paths to includes --- gtsam/slam/SmartFactorBase.h | 8 ++++---- gtsam/slam/SmartProjectionFactor.h | 2 +- gtsam/slam/SmartProjectionPoseFactor.h | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 7c5a1175d..94f287225 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -19,10 +19,10 @@ #pragma once -#include "JacobianFactorQ.h" -#include "JacobianFactorSVD.h" -#include "RegularImplicitSchurFactor.h" -#include "RegularHessianFactor.h" +#include +#include +#include +#include #include #include // for Cheirality exception diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index c4d0867dc..8ade075af 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -19,7 +19,7 @@ #pragma once -#include "SmartFactorBase.h" +#include #include #include diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index f871ab3aa..0fd82414a 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -19,7 +19,7 @@ #pragma once -#include "SmartProjectionFactor.h" +#include namespace gtsam { /** From f3d42a84877719f49b8376bf697238c9cb1e98aa Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 17 Nov 2014 19:53:21 -0500 Subject: [PATCH 35/57] Move to unstable --- {gtsam => gtsam_unstable}/slam/SmartStereoProjectionFactor.h | 2 +- .../slam/SmartStereoProjectionPoseFactor.h | 2 +- .../slam/tests/testSmartStereoProjectionPoseFactor.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) rename {gtsam => gtsam_unstable}/slam/SmartStereoProjectionFactor.h (99%) rename {gtsam => gtsam_unstable}/slam/SmartStereoProjectionPoseFactor.h (99%) rename {gtsam => gtsam_unstable}/slam/tests/testSmartStereoProjectionPoseFactor.cpp (99%) diff --git a/gtsam/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h similarity index 99% rename from gtsam/slam/SmartStereoProjectionFactor.h rename to gtsam_unstable/slam/SmartStereoProjectionFactor.h index 4d2a69ddf..1c0d1bc37 100644 --- a/gtsam/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -19,7 +19,7 @@ #pragma once -#include "SmartFactorBase.h" +#include #include #include diff --git a/gtsam/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h similarity index 99% rename from gtsam/slam/SmartStereoProjectionPoseFactor.h rename to gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 9448f6498..1f2bd1942 100644 --- a/gtsam/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -19,7 +19,7 @@ #pragma once -#include "SmartStereoProjectionFactor.h" +#include namespace gtsam { /** diff --git a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp similarity index 99% rename from gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp rename to gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index e50616163..05260521e 100644 --- a/gtsam/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -18,7 +18,7 @@ * @date Sept 2013 */ -#include "../SmartStereoProjectionPoseFactor.h" +#include #include #include From 1c6dc8a77dff95f30e0276c745ff9bb58dada8e0 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 17 Nov 2014 20:09:19 -0500 Subject: [PATCH 36/57] uncomment/fix reprojectionError and computeEP methods --- gtsam/slam/SmartFactorBase.h | 84 ++++++++++++++++++------------------ 1 file changed, 42 insertions(+), 42 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 94f287225..599fc8f84 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -186,26 +186,26 @@ public: // **************************************************************************************************** // /// Calculate vector of re-projection errors, before applying noise model -// Vector reprojectionError(const Cameras& cameras, const Point3& point) const { -// -// Vector b = zero(2 * cameras.size()); -// -// size_t i = 0; -// BOOST_FOREACH(const Camera& camera, cameras) { -// const Z& zi = this->measured_.at(i); -// try { -// Z e(camera.project(point) - zi); -// b[2 * i] = e.x(); -// b[2 * i + 1] = e.y(); -// } catch (CheiralityException& e) { -// std::cout << "Cheirality exception " << std::endl; -// exit(EXIT_FAILURE); -// } -// i += 1; -// } -// -// return b; -// } + Vector reprojectionError(const Cameras& cameras, const Point3& point) const { + + Vector b = zero(ZDim_t::value * cameras.size()); + + size_t i = 0; + BOOST_FOREACH(const CAMERA& camera, cameras) { + const Z& zi = this->measured_.at(i); + try { + Z e(camera.project(point) - zi); + b[ZDim_t::value * i] = e.x(); + b[ZDim_t::value * i + 1] = e.y(); + } catch (CheiralityException& e) { + std::cout << "Cheirality exception " << std::endl; + exit(EXIT_FAILURE); + } + i += 1; + } + + return b; + } // **************************************************************************************************** /** @@ -238,28 +238,28 @@ public: // **************************************************************************************************** /// Assumes non-degenerate ! -// void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras, -// const Point3& point) const { -// -// int numKeys = this->keys_.size(); -// E = zeros(2 * numKeys, 3); -// Vector b = zero(2 * numKeys); -// -// Matrix Ei(2, 3); -// for (size_t i = 0; i < this->measured_.size(); i++) { -// try { -// cameras[i].project(point, boost::none, Ei); -// } catch (CheiralityException& e) { -// std::cout << "Cheirality exception " << std::endl; -// exit(EXIT_FAILURE); -// } -// this->noise_.at(i)->WhitenSystem(Ei, b); -// E.block<2, 3>(2 * i, 0) = Ei; -// } -// -// // Matrix PointCov; -// PointCov.noalias() = (E.transpose() * E).inverse(); -// } + void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras, + const Point3& point) const { + + int numKeys = this->keys_.size(); + E = zeros(ZDim_t::value * numKeys, 3); + Vector b = zero(2 * numKeys); + + Matrix Ei(ZDim_t::value, 3); + for (size_t i = 0; i < this->measured_.size(); i++) { + try { + cameras[i].project(point, boost::none, Ei); + } catch (CheiralityException& e) { + std::cout << "Cheirality exception " << std::endl; + exit(EXIT_FAILURE); + } + this->noise_.at(i)->WhitenSystem(Ei, b); + E.block(ZDim_t::value * i, 0) = Ei; + } + + // Matrix PointCov; + PointCov.noalias() = (E.transpose() * E).inverse(); + } // **************************************************************************************************** /// Compute F, E only (called below in both vanilla and SVD versions) From 6529b793ccd7c11061785db480240ad3b4086038 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Wed, 19 Nov 2014 12:51:12 -0500 Subject: [PATCH 37/57] Some fixes for feedback reported in pull request #39 --- gtsam/geometry/StereoPoint2.h | 4 +- gtsam/slam/JacobianFactorQ.h | 2 +- gtsam/slam/SmartFactorBase.h | 106 +++++++++--------- .../SmartStereoProjectionFactorExample.cpp | 2 +- 4 files changed, 59 insertions(+), 55 deletions(-) diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 3c92ca46f..694bf525b 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -143,12 +143,12 @@ namespace gtsam { } /** convenient function to get a Point2 from the left image */ - inline Point2 point2() const { + Point2 point2() const { return Point2(uL_, v_); } /** convenient function to get a Point2 from the right image */ - inline Point2 const right(){ + Point2 right() const { return Point2(uR_, v_); } diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index 9b9383d7b..923edddb7 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -49,7 +49,7 @@ public: typedef std::pair KeyMatrix; std::vector < KeyMatrix > QF; QF.reserve(m); - // Below, we compute each 2m*D block A_j = Q_j * F_j = (2m*2) * (2*D) + // Below, we compute each mZDim*D block A_j = Q_j * F_j = (mZDim*ZDim) * (Zdim*D) BOOST_FOREACH(const typename Base::KeyMatrix2D& it, Fblocks) QF.push_back(KeyMatrix(it.first, Q.block(0, ZDim * j++, m2, ZDim) * it.second)); // Which is then passed to the normal JacobianFactor constructor diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 599fc8f84..e0eac6b66 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -33,7 +33,6 @@ #include #include #include -#include namespace gtsam { /// Base class with no internal point, completely functional @@ -49,16 +48,16 @@ protected: boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) - typedef traits::dimension ZDim_t; ///< Dimension trait of measurement type + static const int ZDim = traits::dimension::value; ///< Dimension trait of measurement type /// 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 Matrix23; + typedef Eigen::Matrix Matrix23; typedef Eigen::Matrix VectorD; - typedef Eigen::Matrix Matrix2; + typedef Eigen::Matrix Matrix2; /// shorthand for base class type typedef NonlinearFactor Base; @@ -69,6 +68,8 @@ protected: public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for a smart pointer to a factor @@ -188,15 +189,15 @@ public: // /// Calculate vector of re-projection errors, before applying noise model Vector reprojectionError(const Cameras& cameras, const Point3& point) const { - Vector b = zero(ZDim_t::value * cameras.size()); + Vector b = zero(ZDim * cameras.size()); size_t i = 0; BOOST_FOREACH(const CAMERA& camera, cameras) { const Z& zi = this->measured_.at(i); try { Z e(camera.project(point) - zi); - b[ZDim_t::value * i] = e.x(); - b[ZDim_t::value * i + 1] = e.y(); + b[ZDim * i] = e.x(); + b[ZDim * i + 1] = e.y(); } catch (CheiralityException& e) { std::cout << "Cheirality exception " << std::endl; exit(EXIT_FAILURE); @@ -242,10 +243,10 @@ public: const Point3& point) const { int numKeys = this->keys_.size(); - E = zeros(ZDim_t::value * numKeys, 3); + E = zeros(ZDim * numKeys, 3); Vector b = zero(2 * numKeys); - Matrix Ei(ZDim_t::value, 3); + Matrix Ei(ZDim, 3); for (size_t i = 0; i < this->measured_.size(); i++) { try { cameras[i].project(point, boost::none, Ei); @@ -254,7 +255,7 @@ public: exit(EXIT_FAILURE); } this->noise_.at(i)->WhitenSystem(Ei, b); - E.block(ZDim_t::value * i, 0) = Ei; + E.block(ZDim * i, 0) = Ei; } // Matrix PointCov; @@ -268,11 +269,11 @@ public: Vector& b, const Cameras& cameras, const Point3& point) const { size_t numKeys = this->keys_.size(); - E = zeros(Z::Dim() * numKeys, 3); - b = zero(Z::Dim() * numKeys); + E = zeros(ZDim * numKeys, 3); + b = zero(ZDim * numKeys); double f = 0; - Matrix Fi(Z::Dim(), 6), Ei(Z::Dim(), 3), Hcali(Z::Dim(), D - 6), Hcam(Z::Dim(), D); + Matrix Fi(ZDim, 6), Ei(ZDim, 3), Hcali(ZDim, D - 6), Hcam(ZDim, D); for (size_t i = 0; i < this->measured_.size(); i++) { Vector bi; @@ -294,12 +295,12 @@ public: if (D == 6) { // optimize only camera pose Fblocks.push_back(KeyMatrix2D(this->keys_[i], Fi)); } else { - Hcam.block(0, 0) = Fi; // Z::Dim() x 6 block for the cameras - Hcam.block(0, 6) = Hcali; // Z::Dim() x nrCal block for the cameras + Hcam.block(0, 0) = Fi; // ZDim x 6 block for the cameras + Hcam.block(0, 6) = Hcali; // ZDim x nrCal block for the cameras Fblocks.push_back(KeyMatrix2D(this->keys_[i], Hcam)); } - E.block(ZDim_t::value * i, 0) = Ei; - subInsert(b, bi, Z::Dim() * i); + E.block(ZDim * i, 0) = Ei; + subInsert(b, bi, ZDim * i); } return f; } @@ -340,10 +341,10 @@ public: std::vector Fblocks; double f = computeJacobians(Fblocks, E, PointCov, b, cameras, point, lambda); - F = zeros(Z::Dim() * numKeys, D * numKeys); + F = zeros(This::ZDim * numKeys, D * numKeys); for (size_t i = 0; i < this->keys_.size(); ++i) { - F.block(ZDim_t::value * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras + F.block(This::ZDim * i, D * i) = Fblocks.at(i).second; // ZDim x 6 block for the cameras } return f; } @@ -362,9 +363,9 @@ public: // Do SVD on A Eigen::JacobiSVD svd(E, Eigen::ComputeFullU); Vector s = svd.singularValues(); - // Enull = zeros(Z::Dim() * numKeys, Z::Dim() * numKeys - 3); + // Enull = zeros(ZDim * numKeys, ZDim * numKeys - 3); size_t numKeys = this->keys_.size(); - Enull = svd.matrixU().block(0, 3, Z::Dim() * numKeys, Z::Dim() * numKeys - 3); // last Z::Dim()m-3 columns + Enull = svd.matrixU().block(0, 3, ZDim * numKeys, ZDim * numKeys - 3); // last ZDimm-3 columns return f; } @@ -378,11 +379,11 @@ public: int numKeys = this->keys_.size(); std::vector Fblocks; double f = computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - F.resize(Z::Dim() * numKeys, D * numKeys); + F.resize(ZDim * numKeys, D * numKeys); F.setZero(); for (size_t i = 0; i < this->keys_.size(); ++i) - F.block(Z::Dim() * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras + F.block(ZDim * i, D * i) = Fblocks.at(i).second; // ZDim x 6 block for the cameras return f; } @@ -443,9 +444,9 @@ public: int numKeys = this->keys_.size(); /// Compute Full F ???? - Matrix F = zeros(Z::Dim() * numKeys, D * numKeys); + Matrix F = zeros(ZDim * numKeys, D * numKeys); for (size_t i = 0; i < this->keys_.size(); ++i) - F.block(Z::Dim() * i, D * i) = Fblocks.at(i).second; // Z::Dim() x 6 block for the cameras + F.block(ZDim * i, D * i) = Fblocks.at(i).second; // ZDim x 6 block for the cameras Matrix H(D * numKeys, D * numKeys); Vector gs_vector; @@ -483,16 +484,16 @@ public: for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block(Z::Dim() * i1, 0) * P; + 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 - augmentedHessian(i1, numKeys) = Fi1.transpose() * b.segment(Z::Dim() * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZ::Dim()) * (Z::Dim()x3) * (3*Z::Dim()m) * (Z::Dim()m x 1) + 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) - // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xD) - (Z::Dim()x3) * (3xZ::Dim()) * (Z::Dim()xD) ) + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) augmentedHessian(i1, i1) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block(Z::Dim() * i1, 0).transpose() * Fi1); + * (Fi1 - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1); // upper triangular part of the hessian for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera @@ -500,7 +501,7 @@ public: // (DxD) = (Dx2) * ( (2x2) * (2xD) ) augmentedHessian(i1, i2) = -Fi1.transpose() - * (Ei1_P * E.block(Z::Dim() * i2, 0).transpose() * Fi2); + * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); } } // end of for over cameras } @@ -527,16 +528,16 @@ public: // X X X X 14 const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block(Z::Dim() * i1, 0) * P; + const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; { // for i1 = i2 // D = (Dx2) * (2) - gs.at(i1) = Fi1.transpose() * b.segment(Z::Dim() * i1) // F' * b - -Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZ::Dim()) * (Z::Dim()x3) * (3*Z::Dim()m) * (Z::Dim()m x 1) + 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) - // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xD) - (Z::Dim()x3) * (3xZ::Dim()) * (Z::Dim()xD) ) + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) Gs.at(GsIndex) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block(Z::Dim() * i1, 0).transpose() * Fi1); + * (Fi1 - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1); GsIndex++; } // upper triangular part of the hessian @@ -545,7 +546,7 @@ public: // (DxD) = (Dx2) * ( (2x2) * (2xD) ) Gs.at(GsIndex) = -Fi1.transpose() - * (Ei1_P * E.block(Z::Dim() * i2, 0).transpose() * Fi2); + * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); GsIndex++; } } // end of for over cameras @@ -593,9 +594,9 @@ public: for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera in the current factor const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block(Z::Dim() * i1, 0) * P; + const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; - // D = (DxZ::Dim()) * (Z::Dim()) + // 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_i1 = this->keys_[i1]; @@ -605,15 +606,15 @@ public: // vectorBlock = augmentedHessian(aug_i1, aug_numKeys).knownOffDiagonal(); // add contribution of current factor augmentedHessian(aug_i1, aug_numKeys) = augmentedHessian(aug_i1, aug_numKeys).knownOffDiagonal() - + Fi1.transpose() * b.segment(Z::Dim() * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZ::Dim()) * (Z::Dim()x3) * (3*Z::Dim()m) * (Z::Dim()m x 1) + + Fi1.transpose() * b.segment(ZDim * i1) // F' * b + - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xD) - (Z::Dim()x3) * (3xZ::Dim()) * (Z::Dim()xD) ) + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) // main block diagonal - store previous block matrixBlock = augmentedHessian(aug_i1, aug_i1); // add contribution of current factor augmentedHessian(aug_i1, aug_i1) = matrixBlock + - ( Fi1.transpose() * (Fi1 - Ei1_P * E.block(Z::Dim() * i1, 0).transpose() * Fi1) ); + ( Fi1.transpose() * (Fi1 - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1) ); // upper triangular part of the hessian for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera @@ -622,12 +623,12 @@ public: //Key cameraKey_i2 = this->keys_[i2]; DenseIndex aug_i2 = KeySlotMap[this->keys_[i2]]; - // (DxD) = (DxZ::Dim()) * ( (Z::Dim()xZ::Dim()) * (Z::Dim()xD) ) + // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) // off diagonal block - store previous block // matrixBlock = augmentedHessian(aug_i1, aug_i2).knownOffDiagonal(); // add contribution of current factor augmentedHessian(aug_i1, aug_i2) = augmentedHessian(aug_i1, aug_i2).knownOffDiagonal() - - Fi1.transpose() * (Ei1_P * E.block(Z::Dim() * i2, 0).transpose() * Fi2); + - Fi1.transpose() * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); } } // end of for over cameras @@ -647,7 +648,7 @@ public: } // **************************************************************************************************** - 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; @@ -656,7 +657,7 @@ public: Vector b; computeJacobians(Fblocks, E, PointCov, b, cameras, point, lambda, diagonalDamping); - return boost::make_shared >(Fblocks, E, PointCov, b); + return boost::make_shared >(Fblocks, E, PointCov, b); } // **************************************************************************************************** @@ -665,9 +666,9 @@ public: size_t numKeys = this->keys_.size(); std::vector Fblocks; Vector b; - Matrix Enull(Z::Dim()*numKeys, Z::Dim()*numKeys-3); + Matrix Enull(ZDim*numKeys, ZDim*numKeys-3); computeJacobiansSVD(Fblocks, Enull, b, cameras, point, lambda); - return boost::make_shared< JacobianFactorSVD<6, ZDim_t::value> >(Fblocks, Enull, b); + return boost::make_shared< JacobianFactorSVD<6, ZDim> >(Fblocks, Enull, b); } private: @@ -682,4 +683,7 @@ private: } }; +template +const int SmartFactorBase::ZDim; + } // \ namespace gtsam diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp index 841092ec9..f5e59b1b2 100644 --- a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -35,7 +35,7 @@ #include #include -#include +#include #include #include From dd255eb24c20d07aa3c58f75f1167f450a6215d7 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Wed, 19 Nov 2014 13:07:14 -0500 Subject: [PATCH 38/57] Remove landmark template parameter --- examples/SFMExample_SmartFactor.cpp | 3 +-- gtsam/slam/SmartFactorBase.h | 2 +- gtsam/slam/SmartProjectionFactor.h | 19 +++++++++++-------- gtsam/slam/SmartProjectionPoseFactor.h | 8 ++++---- .../tests/testSmartProjectionPoseFactor.cpp | 6 +++--- .../examples/SmartProjectionFactorExample.cpp | 2 +- 6 files changed, 21 insertions(+), 19 deletions(-) diff --git a/examples/SFMExample_SmartFactor.cpp b/examples/SFMExample_SmartFactor.cpp index b3c5ee5fe..eed389df9 100644 --- a/examples/SFMExample_SmartFactor.cpp +++ b/examples/SFMExample_SmartFactor.cpp @@ -61,8 +61,7 @@ using namespace std; using namespace gtsam; // Make the typename short so it looks much cleaner -typedef gtsam::SmartProjectionPoseFactor SmartFactor; +typedef gtsam::SmartProjectionPoseFactor SmartFactor; /* ************************************************************************* */ int main(int argc, char* argv[]) { diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index e0eac6b66..8ff554104 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -48,7 +48,7 @@ protected: boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) - static const int ZDim = traits::dimension::value; ///< Dimension trait of measurement type + static const int ZDim = traits::dimension::value; ///< Measurement dimension /// Definitions for blocks of F typedef Eigen::Matrix Matrix2D; // F diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 8ade075af..75e4699d9 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -61,7 +61,7 @@ enum LinearizationMode { * SmartProjectionFactor: triangulates point * TODO: why LANDMARK parameter? */ -template +template class SmartProjectionFactor: public SmartFactorBase, D> { protected: @@ -102,9 +102,9 @@ protected: // and the factor is disregarded if the error is large /// shorthand for this class - typedef SmartProjectionFactor This; + typedef SmartProjectionFactor This; - typedef traits::dimension ZDim_t; ///< Dimension trait of measurement type + static const int ZDim = traits::dimension::value; ///< Measurement dimension public: @@ -420,16 +420,16 @@ public: } /// 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 myCameras; // TODO triangulate twice ?? @@ -437,7 +437,7 @@ public: if (nonDegenerate) return createJacobianQFactor(myCameras, lambda); else - return boost::make_shared< JacobianFactorQ >(this->keys_); + return boost::make_shared< JacobianFactorQ >(this->keys_); } /// different (faster) way to compute Jacobian factor @@ -446,7 +446,7 @@ public: if (triangulateForLinearize(cameras)) return Base::createJacobianSVDFactor(cameras, point_, lambda); else - return boost::make_shared< JacobianFactorSVD >(this->keys_); + return boost::make_shared< JacobianFactorSVD >(this->keys_); } /// Returns true if nonDegenerate @@ -709,4 +709,7 @@ private: } }; +template +const int SmartProjectionFactor::ZDim; + } // \ namespace gtsam diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 0fd82414a..3b2e2bcbc 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -37,8 +37,8 @@ namespace gtsam { * The calibration is known here. The factor only constraints poses (variable dimension is 6) * @addtogroup SLAM */ -template -class SmartProjectionPoseFactor: public SmartProjectionFactor { +template +class SmartProjectionPoseFactor: public SmartProjectionFactor { protected: LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) @@ -48,10 +48,10 @@ protected: public: /// shorthand for base class type - typedef SmartProjectionFactor Base; + typedef SmartProjectionFactor Base; /// shorthand for this class - typedef SmartProjectionPoseFactor This; + typedef SmartProjectionPoseFactor This; /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 4e4fde3e4..c2855f09b 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -60,8 +60,8 @@ 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 SmartProjectionPoseFactor SmartFactor; -typedef SmartProjectionPoseFactor SmartFactorBundler; +typedef SmartProjectionPoseFactor SmartFactor; +typedef SmartProjectionPoseFactor SmartFactorBundler; void projectToMultipleCameras( SimpleCamera cam1, SimpleCamera cam2, SimpleCamera cam3, Point3 landmark, @@ -1202,7 +1202,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ){ /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { - SmartProjectionPoseFactor factor1(rankTol, linThreshold); + SmartProjectionPoseFactor factor1(rankTol, linThreshold); boost::shared_ptr Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); factor1.add(measurement1, poseKey1, model, Kbundler); } diff --git a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp index 01c2ab3e1..c8a4e7123 100644 --- a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp @@ -46,7 +46,7 @@ using namespace gtsam; int main(int argc, char** argv){ - typedef SmartProjectionPoseFactor SmartFactor; + typedef SmartProjectionPoseFactor SmartFactor; Values initial_estimate; NonlinearFactorGraph graph; From aebe40d19ff5669fd2f731188d7304c53722ba94 Mon Sep 17 00:00:00 2001 From: Sungtae An Date: Fri, 21 Nov 2014 20:50:30 -0500 Subject: [PATCH 39/57] Add the 4th input argument for calling PinholeCamera::project which does not take default arguments anymore. --- 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 8ff554104..ed60b1a4b 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -249,7 +249,7 @@ public: Matrix Ei(ZDim, 3); for (size_t i = 0; i < this->measured_.size(); i++) { try { - cameras[i].project(point, boost::none, Ei); + cameras[i].project(point, boost::none, Ei, boost::none); } catch (CheiralityException& e) { std::cout << "Cheirality exception " << std::endl; exit(EXIT_FAILURE); From 07044137ebbd054822612eabe60d8fb0ae7154b0 Mon Sep 17 00:00:00 2001 From: Paul Furgale Date: Mon, 24 Nov 2014 21:14:59 +0100 Subject: [PATCH 40/57] A failing unit test for a custom chart --- gtsam/nonlinear/Values-inl.h | 8 +- gtsam/nonlinear/Values.h | 8 +- gtsam_unstable/nonlinear/ExpressionFactor.h | 15 ++- .../tests/testCustomChartExpression.cpp | 119 ++++++++++++++++++ 4 files changed, 139 insertions(+), 11 deletions(-) create mode 100644 gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index 4595a70ed..e983ccb17 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -302,8 +302,8 @@ namespace gtsam { } // overloaded insert with chart initializer - template - void Values::insert(Key j, const ValueType& val, ChartInit chart) { + template + void Values::insert(Key j, const ValueType& val, Chart chart) { insert(j, static_cast(ChartValue(val, chart))); } @@ -320,8 +320,8 @@ namespace gtsam { } // update with chart initializer, /todo: perhaps there is a way to init chart from old value... - template - void Values::update(Key j, const ValueType& val, ChartInit chart) { + template + void Values::update(Key j, const ValueType& val, Chart chart) { update(j, static_cast(ChartValue(val, chart))); } diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index e4a27849d..d00baa0d9 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -263,8 +263,8 @@ namespace gtsam { void insert(Key j, const ValueType& val); /// overloaded insert version that also specifies a chart initializer - template - void insert(Key j, const ValueType& val, ChartInit chart); + template + void insert(Key j, const ValueType& val, Chart chart); /** insert that mimics the STL map insert - if the value already exists, the map is not modified @@ -288,8 +288,8 @@ namespace gtsam { void update(Key j, const T& val); /// overloaded insert version that also specifies a chart initializer - template - void update(Key j, const T& val, ChartInit chart); + template + void update(Key j, const T& val, Chart chart); /** update the current available values without adding new ones */ void update(const Values& values); diff --git a/gtsam_unstable/nonlinear/ExpressionFactor.h b/gtsam_unstable/nonlinear/ExpressionFactor.h index 22a2aefeb..273fb4c12 100644 --- a/gtsam_unstable/nonlinear/ExpressionFactor.h +++ b/gtsam_unstable/nonlinear/ExpressionFactor.h @@ -55,7 +55,7 @@ public: noiseModel_ = noiseModel; // Get dimensions of Jacobian matrices - // An Expression is assumed unmutable, so we do this now + // An Expression is assumed immutable, so we do this now std::map map; expression_.dims(map); size_t n = map.size(); @@ -83,12 +83,12 @@ public: */ virtual Vector unwhitenedError(const Values& x, boost::optional&> H = boost::none) const { - // TODO(PTF) Is this a place for custom charts? DefaultChart chart; if (H) { // H should be pre-allocated assert(H->size()==size()); + // todo...fix for custom charts. VerticalBlockMatrix Ab(dimensions_, Dim); // Wrap keys and VerticalBlockMatrix into structure passed to expression_ @@ -116,11 +116,20 @@ public: if (!active(x)) return boost::shared_ptr(); + // For custom charts, we would have to update the dimensions here + // based on the values that have been passed in. + FastVector::const_iterator kit = keys_.begin(); + std::vector dims; + dims.reserve(keys_.size()); + for(; kit != keys_.end(); ++kit) { + dims.push_back(x.at(*kit).dim()); + } + // Create a writeable JacobianFactor in advance // In case noise model is constrained, we need to provide a noise model bool constrained = noiseModel_->is_constrained(); boost::shared_ptr factor( - constrained ? new JacobianFactor(keys_, dimensions_, Dim, + constrained ? new JacobianFactor(keys_, dims, Dim, boost::static_pointer_cast(noiseModel_)->unit()) : new JacobianFactor(keys_, dimensions_, Dim)); diff --git a/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp new file mode 100644 index 000000000..59df89b32 --- /dev/null +++ b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp @@ -0,0 +1,119 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------1------------------------------------------- */ + +/** + * @file testExpression.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 +using boost::assign::list_of; +using boost::assign::map_list_of; + +using namespace std; +using namespace gtsam; + +// Dynamically sized Vector + +struct ProjectionChart { + typedef Eigen::Vector3d type; + typedef Eigen::Vector2d vector; + enum { dimension = 2 }; + static vector local(const type& origin, const type& other) { + return (other - origin).head<2>(); + } + static type retract(const type& origin, const vector& d) { + return origin + Eigen::Vector3d(2.0 * d[0], 3.0 * d[1], 0.0); + } + static int getDimension(const type& origin) { + return 2; + } +}; + +namespace gtsam { +namespace traits { +template<> struct is_chart : public boost::true_type {}; +template<> struct dimension : public boost::integral_constant {}; +} // namespace traits +} // namespace gtsam + +TEST(ExpressionCustomChart, projection) { + std::cout << "Hello!\n"; + // Create expression + Expression point(1); + + Eigen::Vector3d pval(1.0, 2.0, 3.0); + Values standard; + standard.insert(1, pval); + + Values custom; + custom.insert(1, pval, ProjectionChart()); + + Eigen::Vector3d pstandard = point.value(standard); + Eigen::Vector3d pcustom = point.value(custom); + + // The values should be the same. + EXPECT(assert_equal(Matrix(pstandard), Matrix(pcustom), 1e-10)); + + + EXPECT_LONGS_EQUAL(3, standard.at(1).dim()); + VectorValues vstandard = standard.zeroVectors(); + EXPECT_LONGS_EQUAL(3, vstandard.at(1).size()); + + + EXPECT_LONGS_EQUAL(2, custom.at(1).dim()); + VectorValues vcustom = custom.zeroVectors(); + EXPECT_LONGS_EQUAL(2, vcustom.at(1).size()); + + ExpressionFactor f(noiseModel::Unit::Create(pval.size()), pval, point); + + boost::shared_ptr gfstandard = f.linearize(standard); + boost::shared_ptr jfstandard = // + boost::dynamic_pointer_cast(gfstandard); + + typedef std::pair Jacobian; + Jacobian Jstandard = jfstandard->jacobianUnweighted(); + EXPECT(assert_equal(Eigen::Matrix3d::Identity(), Jstandard.first, 1e-10)); + + boost::shared_ptr gfcustom = f.linearize(custom); + boost::shared_ptr jfcustom = // + boost::dynamic_pointer_cast(gfcustom); + + Eigen::MatrixXd expectedJacobian = Eigen::MatrixXd::Zero(3,2); + expectedJacobian(0,0) = 2.0; + expectedJacobian(1,1) = 3.0; + Jacobian Jcustom = jfcustom->jacobianUnweighted(); + EXPECT(assert_equal(expectedJacobian, Jcustom.first, 1e-10)); + + // Amazingly, the finite differences get the expected Jacobian right. + const double fd_step = 1e-5; + const double tolerance = 1e-5; + EXPECT_CORRECT_EXPRESSION_JACOBIANS(point, custom, fd_step, tolerance); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + From 5b5122d15b0cbc04b30757f725a3b9d8e13ecb22 Mon Sep 17 00:00:00 2001 From: Paul Furgale Date: Mon, 24 Nov 2014 21:23:53 +0100 Subject: [PATCH 41/57] Fixed a copy/paste error --- gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp index 59df89b32..bfd2574ea 100644 --- a/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp +++ b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp @@ -10,7 +10,7 @@ * -------------------------------1------------------------------------------- */ /** - * @file testExpression.cpp + * @file testCustomChartExpression.cpp * @date September 18, 2014 * @author Frank Dellaert * @author Paul Furgale From e413fb3d68c700e60538b954be0889b5facd1d9e Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 00:18:42 +0100 Subject: [PATCH 42/57] target --- .cproject | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.cproject b/.cproject index 1dcc51dfe..d42d2b0e0 100644 --- a/.cproject +++ b/.cproject @@ -2777,6 +2777,14 @@ true true + + make + -j4 + testCustomChartExpression.run + true + true + true + make -j2 From 4790bade85e14f609235264a59776d8587beecc0 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 00:19:01 +0100 Subject: [PATCH 43/57] Moved and refactored testing --- gtsam/base/numericalDerivative.h | 66 --------------- gtsam_unstable/nonlinear/expressionTesting.h | 87 ++++++++++++++++++-- 2 files changed, 78 insertions(+), 75 deletions(-) diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index 30136d9f2..f2c4566bb 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -524,71 +524,5 @@ inline Matrix numericalHessian323(double (*f)(const X1&, const X2&, const X3&), delta); } -// The benefit of this method is that it does not need to know what types are involved -// to evaluate the factor. If all the machinery of gtsam is working correctly, we should -// get the correct numerical derivatives out the other side. -template -JacobianFactor computeNumericalDerivativeJacobianFactor(const FactorType& factor, - const Values& values, - double fd_step) { - Eigen::VectorXd e = factor.unwhitenedError(values); - const size_t rows = e.size(); - - std::map jacobians; - typename FactorType::const_iterator key_it = factor.begin(); - VectorValues dX = values.zeroVectors(); - for(; key_it != factor.end(); ++key_it) { - size_t key = *key_it; - // Compute central differences using the values struct. - const size_t cols = dX.dim(key); - Matrix J = Matrix::Zero(rows, cols); - for(size_t col = 0; col < cols; ++col) { - Eigen::VectorXd dx = Eigen::VectorXd::Zero(cols); - dx[col] = fd_step; - dX[key] = dx; - Values eval_values = values.retract(dX); - Eigen::VectorXd left = factor.unwhitenedError(eval_values); - dx[col] = -fd_step; - dX[key] = dx; - eval_values = values.retract(dX); - Eigen::VectorXd right = factor.unwhitenedError(eval_values); - J.col(col) = (left - right) * (1.0/(2.0 * fd_step)); - } - jacobians[key] = J; - } - - // Next step...return JacobianFactor - return JacobianFactor(jacobians, -e); -} - -template -void testFactorJacobians(TestResult& result_, - const std::string& name_, - const FactorType& f, - const gtsam::Values& values, - double fd_step, - double tolerance) { - // Check linearization - JacobianFactor expected = computeNumericalDerivativeJacobianFactor(f, values, fd_step); - boost::shared_ptr gf = f.linearize(values); - boost::shared_ptr jf = // - boost::dynamic_pointer_cast(gf); - - typedef std::pair Jacobian; - Jacobian evalJ = jf->jacobianUnweighted(); - Jacobian estJ = expected.jacobianUnweighted(); - EXPECT(assert_equal(evalJ.first, estJ.first, tolerance)); - EXPECT(assert_equal(evalJ.second, Eigen::VectorXd::Zero(evalJ.second.size()), tolerance)); - EXPECT(assert_equal(estJ.second, Eigen::VectorXd::Zero(evalJ.second.size()), tolerance)); -} - } // namespace gtsam -/// \brief Check the Jacobians produced by a factor against finite differences. -/// \param factor The factor to test. -/// \param values Values filled in for testing the Jacobians. -/// \param numerical_derivative_step The step to use when computing the numerical derivative Jacobians -/// \param tolerance The numerical tolerance to use when comparing Jacobians. -#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance) \ - { gtsam::testFactorJacobians(result_, name_, factor, values, numerical_derivative_step, tolerance); } - diff --git a/gtsam_unstable/nonlinear/expressionTesting.h b/gtsam_unstable/nonlinear/expressionTesting.h index ae2c1e7e5..92c8f71e8 100644 --- a/gtsam_unstable/nonlinear/expressionTesting.h +++ b/gtsam_unstable/nonlinear/expressionTesting.h @@ -30,19 +30,88 @@ namespace gtsam { +/** + * Linearize a nonlinear factor using numerical differentiation + * The benefit of this method is that it does not need to know what types are + * involved to evaluate the factor. If all the machinery of gtsam is working + * correctly, we should get the correct numerical derivatives out the other side. + */ +JacobianFactor linearizeNumerically(const NoiseModelFactor& factor, + const Values& values, double delta = 1e-5) { + + // We will fill a map of Jacobians + std::map jacobians; + + // Get size + Eigen::VectorXd e = factor.whitenedError(values); + const size_t rows = e.size(); + + // Loop over all variables + VectorValues dX = values.zeroVectors(); + BOOST_FOREACH(Key key, factor) { + // Compute central differences using the values struct. + const size_t cols = dX.dim(key); + Matrix J = Matrix::Zero(rows, cols); + for (size_t col = 0; col < cols; ++col) { + Eigen::VectorXd dx = Eigen::VectorXd::Zero(cols); + dx[col] = delta; + dX[key] = dx; + Values eval_values = values.retract(dX); + Eigen::VectorXd left = factor.whitenedError(eval_values); + dx[col] = -delta; + dX[key] = dx; + eval_values = values.retract(dX); + Eigen::VectorXd right = factor.whitenedError(eval_values); + J.col(col) = (left - right) * (1.0 / (2.0 * delta)); + } + jacobians[key] = J; + } + + // Next step...return JacobianFactor + return JacobianFactor(jacobians, -e); +} + +namespace internal { +// CPPUnitLite-style test for linearization of a factor +void testFactorJacobians(TestResult& result_, const std::string& name_, + const NoiseModelFactor& factor, const gtsam::Values& values, double delta, + double tolerance) { + + // Create expected value by numerical differentiation + JacobianFactor expected = linearizeNumerically(factor, values, delta); + + // Create actual value by linearize + boost::shared_ptr actual = // + boost::dynamic_pointer_cast(factor.linearize(values)); + + // Check cast result and then equality + CHECK(actual); + EXPECT( assert_equal(expected, *actual, tolerance)); +} +} + +/// \brief Check the Jacobians produced by a factor against finite differences. +/// \param factor The factor to test. +/// \param values Values filled in for testing the Jacobians. +/// \param numerical_derivative_step The step to use when computing the numerical derivative Jacobians +/// \param tolerance The numerical tolerance to use when comparing Jacobians. +#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance) \ + { gtsam::internal::testFactorJacobians(result_, name_, factor, values, numerical_derivative_step, tolerance); } + +namespace internal { +// CPPUnitLite-style test for linearization of an ExpressionFactor template -void testExpressionJacobians(TestResult& result_, - const std::string& name_, - const gtsam::Expression& expression, - const gtsam::Values& values, - double nd_step, - double tolerance) { +void testExpressionJacobians(TestResult& result_, const std::string& name_, + const gtsam::Expression& expression, const gtsam::Values& values, + double nd_step, double tolerance) { // Create factor size_t size = traits::dimension::value; - ExpressionFactor f(noiseModel::Unit::Create(size), expression.value(values), expression); + ExpressionFactor f(noiseModel::Unit::Create(size), + expression.value(values), expression); testFactorJacobians(result_, name_, f, values, nd_step, tolerance); } -} // namespace gtsam +} +} // namespace gtsam /// \brief Check the Jacobians produced by an expression against finite differences. /// \param expression The expression to test. @@ -50,4 +119,4 @@ void testExpressionJacobians(TestResult& result_, /// \param numerical_derivative_step The step to use when computing the finite difference Jacobians /// \param tolerance The numerical tolerance to use when comparing Jacobians. #define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance) \ - { gtsam::testExpressionJacobians(result_, name_, expression, values, numerical_derivative_step, tolerance); } + { gtsam::internal::testExpressionJacobians(result_, name_, expression, values, numerical_derivative_step, tolerance); } From 05c98ccafb54b152e3570f89541aff400127bd3d Mon Sep 17 00:00:00 2001 From: Sungtae An Date: Tue, 25 Nov 2014 00:20:23 -0500 Subject: [PATCH 44/57] Add typedef CAMERA and restore a commented function of 'add' as a templated function. --- gtsam/slam/SmartFactorBase.h | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index ed60b1a4b..d9e7b9819 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -76,6 +76,7 @@ public: typedef boost::shared_ptr shared_ptr; /// shorthand for a pinhole camera + typedef CAMERA Camera; typedef std::vector Cameras; /** @@ -134,13 +135,14 @@ public: * The noise is assumed to be the same for all measurements */ // **************************************************************************************************** -// void add(const SfM_Track& trackToAdd, const SharedNoiseModel& noise) { -// 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); -// } -// } + template + void add(const SFM_TRACK& trackToAdd, const SharedNoiseModel& noise) { + 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); + } + } /** return the measurements */ const std::vector& measured() const { From 14b582d268bc45661824b04c8978deac597ee0e4 Mon Sep 17 00:00:00 2001 From: Paul Furgale Date: Tue, 25 Nov 2014 06:42:36 +0100 Subject: [PATCH 45/57] cleaned up the code a bit --- .../nonlinear/tests/testCustomChartExpression.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp index bfd2574ea..02c1803b6 100644 --- a/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp +++ b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp @@ -32,12 +32,17 @@ using boost::assign::map_list_of; using namespace std; using namespace gtsam; -// Dynamically sized Vector - +// A simple prototype custom chart that does two things: +// 1. it reduces the dimension of the variable being estimated +// 2. it scales the input to retract. +// +// The Jacobian of this chart is: +// [ 2 0 ] +// [ 0 3 ] +// [ 0 0 ] struct ProjectionChart { typedef Eigen::Vector3d type; typedef Eigen::Vector2d vector; - enum { dimension = 2 }; static vector local(const type& origin, const type& other) { return (other - origin).head<2>(); } @@ -57,7 +62,6 @@ template<> struct dimension : public boost::integral_constant point(1); From 915c7605240a122b29591cf003cd8b3d03908a72 Mon Sep 17 00:00:00 2001 From: Paul Furgale Date: Tue, 25 Nov 2014 06:43:55 +0100 Subject: [PATCH 46/57] cleaned up the code a bit --- gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp index 02c1803b6..bc2055c55 100644 --- a/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp +++ b/gtsam_unstable/nonlinear/tests/testCustomChartExpression.cpp @@ -25,11 +25,6 @@ #include -#include -using boost::assign::list_of; -using boost::assign::map_list_of; - -using namespace std; using namespace gtsam; // A simple prototype custom chart that does two things: From 084de3350e3925684d590293b19fcab96e9791fd Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 08:47:25 +0100 Subject: [PATCH 47/57] Formatting --- gtsam/nonlinear/NonlinearEquality.h | 489 +++++++++++++++------------- tests/testNonlinearEquality.cpp | 175 +++++----- 2 files changed, 354 insertions(+), 310 deletions(-) diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 5d3319d97..9e3230f34 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -26,280 +26,311 @@ namespace gtsam { +/** + * Template default compare function that assumes a testable T + */ +template +bool compare(const T& a, const T& b) { + GTSAM_CONCEPT_TESTABLE_TYPE(T); + return a.equals(b); +} + +/** + * An equality factor that forces either one variable to a constant, + * or a set of variables to be equal to each other. + * + * Depending on flag, throws an error at linearization if the constraints are not met. + * + * Switchable implementation: + * - ALLLOW_ERROR : if we allow that there can be nonzero error, does not throw, and uses gain + * - ONLY_EXACT : throws error at linearization if not at exact feasible point, and infinite error + * + * \nosubgrouping + */ +template +class NonlinearEquality: public NoiseModelFactor1 { + +public: + typedef VALUE T; + +private: + + // feasible value + T feasible_; + + // error handling flag + bool allow_error_; + + // error gain in allow error case + double error_gain_; + + // typedef to this class + typedef NonlinearEquality This; + + // typedef to base class + typedef NoiseModelFactor1 Base; + +public: + /** - * Template default compare function that assumes a testable T + * Function that compares two values */ - template - bool compare(const T& a, const T& b) { - GTSAM_CONCEPT_TESTABLE_TYPE(T); - return a.equals(b); + bool (*compare_)(const T& a, const T& b); + + /** default constructor - only for serialization */ + NonlinearEquality() { + } + + virtual ~NonlinearEquality() { + } + + /// @name Standard Constructors + /// @{ + + /** + * Constructor - forces exact evaluation + */ + NonlinearEquality(Key j, const T& feasible, + bool (*_compare)(const T&, const T&) = compare) : + Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_( + feasible), allow_error_(false), error_gain_(0.0), compare_(_compare) { } /** - * An equality factor that forces either one variable to a constant, - * or a set of variables to be equal to each other. - * - * Depending on flag, throws an error at linearization if the constraints are not met. - * - * Switchable implementation: - * - ALLLOW_ERROR : if we allow that there can be nonzero error, does not throw, and uses gain - * - ONLY_EXACT : throws error at linearization if not at exact feasible point, and infinite error - * - * \nosubgrouping + * Constructor - allows inexact evaluation */ - template - class NonlinearEquality: public NoiseModelFactor1 { + NonlinearEquality(Key j, const T& feasible, double error_gain, + bool (*_compare)(const T&, const T&) = compare) : + Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_( + feasible), allow_error_(true), error_gain_(error_gain), compare_( + _compare) { + } - public: - typedef VALUE T; + /// @} + /// @name Testable + /// @{ - private: + virtual void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "Constraint: on [" << keyFormatter(this->key()) << "]\n"; + gtsam::print(feasible_, "Feasible Point:\n"); + std::cout << "Variable Dimension: " << feasible_.dim() << std::endl; + } - // feasible value - T feasible_; + /** Check if two factors are equal */ + virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { + const This* e = dynamic_cast(&f); + return e && Base::equals(f) && feasible_.equals(e->feasible_, tol) + && fabs(error_gain_ - e->error_gain_) < tol; + } - // error handling flag - bool allow_error_; + /// @} + /// @name Standard Interface + /// @{ - // error gain in allow error case - double error_gain_; - - // typedef to this class - typedef NonlinearEquality This; - - // typedef to base class - typedef NoiseModelFactor1 Base; - - public: - - /** - * Function that compares two values - */ - bool (*compare_)(const T& a, const T& b); - - - /** default constructor - only for serialization */ - NonlinearEquality() {} - - virtual ~NonlinearEquality() {} - - /// @name Standard Constructors - /// @{ - - /** - * Constructor - forces exact evaluation - */ - NonlinearEquality(Key j, const T& feasible, bool (*_compare)(const T&, const T&) = compare) : - Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_(feasible), - allow_error_(false), error_gain_(0.0), - compare_(_compare) { + /** actual error function calculation */ + virtual double error(const Values& c) const { + const T& xj = c.at(this->key()); + Vector e = this->unwhitenedError(c); + if (allow_error_ || !compare_(xj, feasible_)) { + return error_gain_ * dot(e, e); + } else { + return 0.0; } + } - /** - * Constructor - allows inexact evaluation - */ - NonlinearEquality(Key j, const T& feasible, double error_gain, bool (*_compare)(const T&, const T&) = compare) : - Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_(feasible), - allow_error_(true), error_gain_(error_gain), - compare_(_compare) { + /** error function */ + Vector evaluateError(const T& xj, + boost::optional H = boost::none) const { + size_t nj = feasible_.dim(); + if (allow_error_) { + if (H) + *H = eye(nj); // FIXME: this is not the right linearization for nonlinear compare + return xj.localCoordinates(feasible_); + } else if (compare_(feasible_, xj)) { + if (H) + *H = eye(nj); + return zero(nj); // set error to zero if equal + } else { + if (H) + throw std::invalid_argument( + "Linearization point not feasible for " + + DefaultKeyFormatter(this->key()) + "!"); + return repeat(nj, std::numeric_limits::infinity()); // set error to infinity if not equal } + } - /// @} - /// @name Testable - /// @{ + // Linearize is over-written, because base linearization tries to whiten + virtual GaussianFactor::shared_ptr linearize(const Values& x) const { + const T& xj = x.at(this->key()); + Matrix A; + Vector b = evaluateError(xj, A); + SharedDiagonal model = noiseModel::Constrained::All(b.size()); + return GaussianFactor::shared_ptr( + new JacobianFactor(this->key(), A, b, model)); + } - virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "Constraint: on [" << keyFormatter(this->key()) << "]\n"; - gtsam::print(feasible_,"Feasible Point:\n"); - std::cout << "Variable Dimension: " << feasible_.dim() << std::endl; - } + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } - /** Check if two factors are equal */ - virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { - const This* e = dynamic_cast(&f); - return e && Base::equals(f) && feasible_.equals(e->feasible_, tol) && - fabs(error_gain_ - e->error_gain_) < tol; - } + /// @} - /// @} - /// @name Standard Interface - /// @{ +private: - /** actual error function calculation */ - virtual double error(const Values& c) const { - const T& xj = c.at(this->key()); - Vector e = this->unwhitenedError(c); - if (allow_error_ || !compare_(xj, feasible_)) { - return error_gain_ * dot(e,e); - } else { - return 0.0; - } - } + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar + & boost::serialization::make_nvp("NoiseModelFactor1", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(feasible_); + ar & BOOST_SERIALIZATION_NVP(allow_error_); + ar & BOOST_SERIALIZATION_NVP(error_gain_); + } - /** error function */ - Vector evaluateError(const T& xj, boost::optional H = boost::none) const { - size_t nj = feasible_.dim(); - if (allow_error_) { - if (H) *H = eye(nj); // FIXME: this is not the right linearization for nonlinear compare - return xj.localCoordinates(feasible_); - } else if (compare_(feasible_,xj)) { - if (H) *H = eye(nj); - return zero(nj); // set error to zero if equal - } else { - if (H) throw std::invalid_argument( - "Linearization point not feasible for " + DefaultKeyFormatter(this->key()) + "!"); - return repeat(nj, std::numeric_limits::infinity()); // set error to infinity if not equal - } - } +}; +// \class NonlinearEquality - // Linearize is over-written, because base linearization tries to whiten - virtual GaussianFactor::shared_ptr linearize(const Values& x) const { - const T& xj = x.at(this->key()); - Matrix A; - Vector b = evaluateError(xj, A); - SharedDiagonal model = noiseModel::Constrained::All(b.size()); - return GaussianFactor::shared_ptr(new JacobianFactor(this->key(), A, b, model)); - } +/* ************************************************************************* */ +/** + * Simple unary equality constraint - fixes a value for a variable + */ +template +class NonlinearEquality1: public NoiseModelFactor1 { - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } +public: + typedef VALUE X; - /// @} +protected: + typedef NoiseModelFactor1 Base; + typedef NonlinearEquality1 This; - private: + /** default constructor to allow for serialization */ + NonlinearEquality1() { + } - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("NoiseModelFactor1", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(feasible_); - ar & BOOST_SERIALIZATION_NVP(allow_error_); - ar & BOOST_SERIALIZATION_NVP(error_gain_); - } + X value_; /// fixed value for variable - }; // \class NonlinearEquality + GTSAM_CONCEPT_MANIFOLD_TYPE(X) + ;GTSAM_CONCEPT_TESTABLE_TYPE(X) + ; - /* ************************************************************************* */ - /** - * Simple unary equality constraint - fixes a value for a variable - */ - template - class NonlinearEquality1 : public NoiseModelFactor1 { +public: - public: - typedef VALUE X; + typedef boost::shared_ptr > shared_ptr; - protected: - typedef NoiseModelFactor1 Base; - typedef NonlinearEquality1 This; + ///TODO: comment + NonlinearEquality1(const X& value, Key key1, double mu = 1000.0) : + Base(noiseModel::Constrained::All(value.dim(), fabs(mu)), key1), value_( + value) { + } - /** default constructor to allow for serialization */ - NonlinearEquality1() {} + virtual ~NonlinearEquality1() { + } - X value_; /// fixed value for variable + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } - GTSAM_CONCEPT_MANIFOLD_TYPE(X); - GTSAM_CONCEPT_TESTABLE_TYPE(X); + /** g(x) with optional derivative */ + Vector evaluateError(const X& x1, + boost::optional H = boost::none) const { + if (H) + (*H) = eye(x1.dim()); + // manifold equivalent of h(x)-z -> log(z,h(x)) + return value_.localCoordinates(x1); + } - public: + /** Print */ + virtual void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << ": NonlinearEquality1(" << keyFormatter(this->key()) + << ")," << "\n"; + this->noiseModel_->print(); + value_.print("Value"); + } - typedef boost::shared_ptr > shared_ptr; +private: - ///TODO: comment - NonlinearEquality1(const X& value, Key key1, double mu = 1000.0) - : Base(noiseModel::Constrained::All(value.dim(), fabs(mu)), key1), value_(value) {} + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar + & boost::serialization::make_nvp("NoiseModelFactor1", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(value_); + } +}; +// \NonlinearEquality1 - virtual ~NonlinearEquality1() {} +/* ************************************************************************* */ +/** + * Simple binary equality constraint - this constraint forces two factors to + * be the same. + */ +template +class NonlinearEquality2: public NoiseModelFactor2 { +public: + typedef VALUE X; - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } +protected: + typedef NoiseModelFactor2 Base; + typedef NonlinearEquality2 This; - /** g(x) with optional derivative */ - Vector evaluateError(const X& x1, boost::optional H = boost::none) const { - if (H) (*H) = eye(x1.dim()); - // manifold equivalent of h(x)-z -> log(z,h(x)) - return value_.localCoordinates(x1); - } + GTSAM_CONCEPT_MANIFOLD_TYPE(X) + ; - /** Print */ - virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << ": NonlinearEquality1(" - << keyFormatter(this->key()) << "),"<< "\n"; - this->noiseModel_->print(); - value_.print("Value"); - } + /** default constructor to allow for serialization */ + NonlinearEquality2() { + } - private: +public: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("NoiseModelFactor1", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(value_); - } - }; // \NonlinearEquality1 + typedef boost::shared_ptr > shared_ptr; - /* ************************************************************************* */ - /** - * Simple binary equality constraint - this constraint forces two factors to - * be the same. - */ - template - class NonlinearEquality2 : public NoiseModelFactor2 { - public: - typedef VALUE X; + ///TODO: comment + NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) : + Base(noiseModel::Constrained::All(X::Dim(), fabs(mu)), key1, key2) { + } + virtual ~NonlinearEquality2() { + } - protected: - typedef NoiseModelFactor2 Base; - typedef NonlinearEquality2 This; + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } - GTSAM_CONCEPT_MANIFOLD_TYPE(X); + /** g(x) with optional derivative2 */ + Vector evaluateError(const X& x1, const X& x2, boost::optional H1 = + boost::none, boost::optional H2 = boost::none) const { + const size_t p = X::Dim(); + if (H1) + *H1 = -eye(p); + if (H2) + *H2 = eye(p); + return x1.localCoordinates(x2); + } - /** default constructor to allow for serialization */ - NonlinearEquality2() {} +private: - public: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar + & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); + } +}; +// \NonlinearEquality2 - typedef boost::shared_ptr > shared_ptr; - - ///TODO: comment - NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) - : Base(noiseModel::Constrained::All(X::Dim(), fabs(mu)), key1, key2) {} - virtual ~NonlinearEquality2() {} - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - - /** g(x) with optional derivative2 */ - Vector evaluateError(const X& x1, const X& x2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { - const size_t p = X::Dim(); - if (H1) *H1 = -eye(p); - if (H2) *H2 = eye(p); - return x1.localCoordinates(x2); - } - - private: - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - } - }; // \NonlinearEquality2 - -} // namespace gtsam +}// namespace gtsam diff --git a/tests/testNonlinearEquality.cpp b/tests/testNonlinearEquality.cpp index 6366d9fa5..96039a3cc 100644 --- a/tests/testNonlinearEquality.cpp +++ b/tests/testNonlinearEquality.cpp @@ -42,9 +42,9 @@ typedef PriorFactor PosePrior; typedef NonlinearEquality PoseNLE; typedef boost::shared_ptr shared_poseNLE; -static Symbol key('x',1); +static Symbol key('x', 1); -/* ************************************************************************* */ +//****************************************************************************** TEST ( NonlinearEquality, linearization ) { Pose2 value = Pose2(2.1, 1.0, 2.0); Values linearize; @@ -60,10 +60,10 @@ TEST ( NonlinearEquality, linearization ) { EXPECT(assert_equal((const GaussianFactor&)expLF, *actualLF)); } -/* ********************************************************************** */ +//****************************************************************************** TEST ( NonlinearEquality, linearization_pose ) { - Symbol key('x',1); + Symbol key('x', 1); Pose2 value; Values config; config.insert(key, value); @@ -75,7 +75,7 @@ TEST ( NonlinearEquality, linearization_pose ) { EXPECT(true); } -/* ********************************************************************** */ +//****************************************************************************** TEST ( NonlinearEquality, linearization_fail ) { Pose2 value = Pose2(2.1, 1.0, 2.0); Pose2 wrong = Pose2(2.1, 3.0, 4.0); @@ -89,12 +89,11 @@ TEST ( NonlinearEquality, linearization_fail ) { CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument); } -/* ********************************************************************** */ +//****************************************************************************** TEST ( NonlinearEquality, linearization_fail_pose ) { - Symbol key('x',1); - Pose2 value(2.0, 1.0, 2.0), - wrong(2.0, 3.0, 4.0); + Symbol key('x', 1); + Pose2 value(2.0, 1.0, 2.0), wrong(2.0, 3.0, 4.0); Values bad_linearize; bad_linearize.insert(key, wrong); @@ -105,12 +104,11 @@ TEST ( NonlinearEquality, linearization_fail_pose ) { CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument); } -/* ********************************************************************** */ +//****************************************************************************** TEST ( NonlinearEquality, linearization_fail_pose_origin ) { - Symbol key('x',1); - Pose2 value, - wrong(2.0, 3.0, 4.0); + Symbol key('x', 1); + Pose2 value, wrong(2.0, 3.0, 4.0); Values bad_linearize; bad_linearize.insert(key, wrong); @@ -121,7 +119,7 @@ TEST ( NonlinearEquality, linearization_fail_pose_origin ) { CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument); } -/* ************************************************************************* */ +//****************************************************************************** TEST ( NonlinearEquality, error ) { Pose2 value = Pose2(2.1, 1.0, 2.0); Pose2 wrong = Pose2(2.1, 3.0, 4.0); @@ -137,10 +135,11 @@ TEST ( NonlinearEquality, error ) { EXPECT(assert_equal(actual, zero(3))); actual = nle->unwhitenedError(bad_linearize); - EXPECT(assert_equal(actual, repeat(3, std::numeric_limits::infinity()))); + EXPECT( + assert_equal(actual, repeat(3, std::numeric_limits::infinity()))); } -/* ************************************************************************* */ +//****************************************************************************** TEST ( NonlinearEquality, equals ) { Pose2 value1 = Pose2(2.1, 1.0, 2.0); Pose2 value2 = Pose2(2.1, 3.0, 4.0); @@ -151,14 +150,17 @@ TEST ( NonlinearEquality, equals ) { shared_poseNLE nle3(new PoseNLE(key, value2)); // verify - EXPECT(nle1->equals(*nle2)); // basic equality = true - EXPECT(nle2->equals(*nle1)); // test symmetry of equals() - EXPECT(!nle1->equals(*nle3)); // test config + EXPECT(nle1->equals(*nle2)); + // basic equality = true + EXPECT(nle2->equals(*nle1)); + // test symmetry of equals() + EXPECT(!nle1->equals(*nle3)); + // test config } -/* ************************************************************************* */ +//****************************************************************************** TEST ( NonlinearEquality, allow_error_pose ) { - Symbol key1('x',1); + Symbol key1('x', 1); Pose2 feasible1(1.0, 2.0, 3.0); double error_gain = 500.0; PoseNLE nle(key1, feasible1, error_gain); @@ -177,16 +179,17 @@ TEST ( NonlinearEquality, allow_error_pose ) { // check linearization GaussianFactor::shared_ptr actLinFactor = nle.linearize(config); - Matrix A1 = eye(3,3); + Matrix A1 = eye(3, 3); Vector b = expVec; SharedDiagonal model = noiseModel::Constrained::All(3); - GaussianFactor::shared_ptr expLinFactor(new JacobianFactor(key1, A1, b, model)); + GaussianFactor::shared_ptr expLinFactor( + new JacobianFactor(key1, A1, b, model)); EXPECT(assert_equal(*expLinFactor, *actLinFactor, 1e-5)); } -/* ************************************************************************* */ +//****************************************************************************** TEST ( NonlinearEquality, allow_error_optimize ) { - Symbol key1('x',1); + Symbol key1('x', 1); Pose2 feasible1(1.0, 2.0, 3.0); double error_gain = 500.0; PoseNLE nle(key1, feasible1, error_gain); @@ -211,11 +214,11 @@ TEST ( NonlinearEquality, allow_error_optimize ) { EXPECT(assert_equal(expected, result)); } -/* ************************************************************************* */ +//****************************************************************************** TEST ( NonlinearEquality, allow_error_optimize_with_factors ) { // create a hard constraint - Symbol key1('x',1); + Symbol key1('x', 1); Pose2 feasible1(1.0, 2.0, 3.0); // initialize away from the ideal @@ -245,14 +248,14 @@ TEST ( NonlinearEquality, allow_error_optimize_with_factors ) { EXPECT(assert_equal(expected, actual)); } -/* ************************************************************************* */ +//****************************************************************************** static SharedDiagonal hard_model = noiseModel::Constrained::All(2); static SharedDiagonal soft_model = noiseModel::Isotropic::Sigma(2, 1.0); -/* ************************************************************************* */ +//****************************************************************************** TEST( testNonlinearEqualityConstraint, unary_basics ) { Point2 pt(1.0, 2.0); - Symbol key1('x',1); + Symbol key1('x', 1); double mu = 1000.0; eq2D::UnaryEqualityConstraint constraint(pt, key, mu); @@ -267,38 +270,42 @@ TEST( testNonlinearEqualityConstraint, unary_basics ) { Point2 ptBad1(2.0, 2.0); config2.insert(key, ptBad1); EXPECT(constraint.active(config2)); - EXPECT(assert_equal(Vector2(1.0, 0.0), constraint.evaluateError(ptBad1), tol)); - EXPECT(assert_equal(Vector2(1.0, 0.0), constraint.unwhitenedError(config2), tol)); + EXPECT( + assert_equal(Vector2(1.0, 0.0), constraint.evaluateError(ptBad1), tol)); + EXPECT( + assert_equal(Vector2(1.0, 0.0), constraint.unwhitenedError(config2), tol)); EXPECT_DOUBLES_EQUAL(500.0, constraint.error(config2), tol); } -/* ************************************************************************* */ +//****************************************************************************** TEST( testNonlinearEqualityConstraint, unary_linearization ) { Point2 pt(1.0, 2.0); - Symbol key1('x',1); + Symbol key1('x', 1); double mu = 1000.0; eq2D::UnaryEqualityConstraint constraint(pt, key, mu); Values config1; config1.insert(key, pt); GaussianFactor::shared_ptr actual1 = constraint.linearize(config1); - GaussianFactor::shared_ptr expected1(new JacobianFactor(key, eye(2,2), zero(2), hard_model)); + GaussianFactor::shared_ptr expected1( + new JacobianFactor(key, eye(2, 2), zero(2), hard_model)); EXPECT(assert_equal(*expected1, *actual1, tol)); Values config2; Point2 ptBad(2.0, 2.0); config2.insert(key, ptBad); GaussianFactor::shared_ptr actual2 = constraint.linearize(config2); - GaussianFactor::shared_ptr expected2(new JacobianFactor(key, eye(2,2), Vector2(-1.0,0.0), hard_model)); + GaussianFactor::shared_ptr expected2( + new JacobianFactor(key, eye(2, 2), Vector2(-1.0, 0.0), hard_model)); EXPECT(assert_equal(*expected2, *actual2, tol)); } -/* ************************************************************************* */ +//****************************************************************************** TEST( testNonlinearEqualityConstraint, unary_simple_optimization ) { // create a single-node graph with a soft and hard constraint to // ensure that the hard constraint overrides the soft constraint Point2 truth_pt(1.0, 2.0); - Symbol key('x',1); + Symbol key('x', 1); double mu = 10.0; eq2D::UnaryEqualityConstraint::shared_ptr constraint( new eq2D::UnaryEqualityConstraint(truth_pt, key, mu)); @@ -326,10 +333,10 @@ TEST( testNonlinearEqualityConstraint, unary_simple_optimization ) { EXPECT(assert_equal(expected, actual, tol)); } -/* ************************************************************************* */ +//****************************************************************************** TEST( testNonlinearEqualityConstraint, odo_basics ) { Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0); - Symbol key1('x',1), key2('x',2); + Symbol key1('x', 1), key2('x', 2); double mu = 1000.0; eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu); @@ -347,15 +354,17 @@ TEST( testNonlinearEqualityConstraint, odo_basics ) { config2.insert(key1, x1bad); config2.insert(key2, x2bad); EXPECT(constraint.active(config2)); - EXPECT(assert_equal(Vector2(-1.0, -1.0), constraint.evaluateError(x1bad, x2bad), tol)); - EXPECT(assert_equal(Vector2(-1.0, -1.0), constraint.unwhitenedError(config2), tol)); + EXPECT( + assert_equal(Vector2(-1.0, -1.0), constraint.evaluateError(x1bad, x2bad), tol)); + EXPECT( + assert_equal(Vector2(-1.0, -1.0), constraint.unwhitenedError(config2), tol)); EXPECT_DOUBLES_EQUAL(1000.0, constraint.error(config2), tol); } -/* ************************************************************************* */ +//****************************************************************************** TEST( testNonlinearEqualityConstraint, odo_linearization ) { Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0); - Symbol key1('x',1), key2('x',2); + Symbol key1('x', 1), key2('x', 2); double mu = 1000.0; eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu); @@ -364,8 +373,8 @@ TEST( testNonlinearEqualityConstraint, odo_linearization ) { config1.insert(key2, x2); GaussianFactor::shared_ptr actual1 = constraint.linearize(config1); GaussianFactor::shared_ptr expected1( - new JacobianFactor(key1, -eye(2,2), key2, - eye(2,2), zero(2), hard_model)); + new JacobianFactor(key1, -eye(2, 2), key2, eye(2, 2), zero(2), + hard_model)); EXPECT(assert_equal(*expected1, *actual1, tol)); Values config2; @@ -375,18 +384,18 @@ TEST( testNonlinearEqualityConstraint, odo_linearization ) { config2.insert(key2, x2bad); GaussianFactor::shared_ptr actual2 = constraint.linearize(config2); GaussianFactor::shared_ptr expected2( - new JacobianFactor(key1, -eye(2,2), key2, - eye(2,2), Vector2(1.0, 1.0), hard_model)); + new JacobianFactor(key1, -eye(2, 2), key2, eye(2, 2), Vector2(1.0, 1.0), + hard_model)); EXPECT(assert_equal(*expected2, *actual2, tol)); } -/* ************************************************************************* */ +//****************************************************************************** TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) { // create a two-node graph, connected by an odometry constraint, with // a hard prior on one variable, and a conflicting soft prior // on the other variable - the constraints should override the soft constraint Point2 truth_pt1(1.0, 2.0), truth_pt2(3.0, 2.0); - Symbol key1('x',1), key2('x',2); + Symbol key1('x', 1), key2('x', 2); // hard prior on x1 eq2D::UnaryEqualityConstraint::shared_ptr constraint1( @@ -399,8 +408,8 @@ TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) { // odometry constraint eq2D::OdoEqualityConstraint::shared_ptr constraint2( - new eq2D::OdoEqualityConstraint( - truth_pt1.between(truth_pt2), key1, key2)); + new eq2D::OdoEqualityConstraint(truth_pt1.between(truth_pt2), key1, + key2)); NonlinearFactorGraph graph; graph.push_back(constraint1); @@ -418,7 +427,7 @@ TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) { CHECK(assert_equal(expected, actual, tol)); } -/* ********************************************************************* */ +//****************************************************************************** TEST (testNonlinearEqualityConstraint, two_pose ) { /* * Determining a ground truth linear system @@ -428,19 +437,18 @@ TEST (testNonlinearEqualityConstraint, two_pose ) { NonlinearFactorGraph graph; - Symbol x1('x',1), x2('x',2); - Symbol l1('l',1), l2('l',2); - Point2 pt_x1(1.0, 1.0), - pt_x2(5.0, 6.0); + Symbol x1('x', 1), x2('x', 2); + Symbol l1('l', 1), l2('l', 2); + Point2 pt_x1(1.0, 1.0), pt_x2(5.0, 6.0); graph += eq2D::UnaryEqualityConstraint(pt_x1, x1); graph += eq2D::UnaryEqualityConstraint(pt_x2, x2); Point2 z1(0.0, 5.0); SharedNoiseModel sigma(noiseModel::Isotropic::Sigma(2, 0.1)); - graph += simulated2D::Measurement(z1, sigma, x1,l1); + graph += simulated2D::Measurement(z1, sigma, x1, l1); Point2 z2(-4.0, 0.0); - graph += simulated2D::Measurement(z2, sigma, x2,l2); + graph += simulated2D::Measurement(z2, sigma, x2, l2); graph += eq2D::PointEqualityConstraint(l1, l2); @@ -450,7 +458,8 @@ TEST (testNonlinearEqualityConstraint, two_pose ) { initialEstimate.insert(l1, Point2(1.0, 6.0)); // ground truth initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame - Values actual = LevenbergMarquardtOptimizer(graph, initialEstimate).optimize(); + Values actual = + LevenbergMarquardtOptimizer(graph, initialEstimate).optimize(); Values expected; expected.insert(x1, pt_x1); @@ -460,14 +469,14 @@ TEST (testNonlinearEqualityConstraint, two_pose ) { CHECK(assert_equal(expected, actual, 1e-5)); } -/* ********************************************************************* */ +//****************************************************************************** TEST (testNonlinearEqualityConstraint, map_warp ) { // get a graph NonlinearFactorGraph graph; // keys - Symbol x1('x',1), x2('x',2); - Symbol l1('l',1), l2('l',2); + Symbol x1('x', 1), x2('x', 2); + Symbol l1('l', 1), l2('l', 2); // constant constraint on x1 Point2 pose1(1.0, 1.0); @@ -488,13 +497,14 @@ TEST (testNonlinearEqualityConstraint, map_warp ) { // create an initial estimate Values initialEstimate; - initialEstimate.insert(x1, Point2( 1.0, 1.0)); - initialEstimate.insert(l1, Point2( 1.0, 6.0)); + initialEstimate.insert(x1, Point2(1.0, 1.0)); + initialEstimate.insert(l1, Point2(1.0, 6.0)); initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame - initialEstimate.insert(x2, Point2( 0.0, 0.0)); // other pose starts at origin + initialEstimate.insert(x2, Point2(0.0, 0.0)); // other pose starts at origin // optimize - Values actual = LevenbergMarquardtOptimizer(graph, initialEstimate).optimize(); + Values actual = + LevenbergMarquardtOptimizer(graph, initialEstimate).optimize(); Values expected; expected.insert(x1, Point2(1.0, 1.0)); @@ -506,8 +516,8 @@ TEST (testNonlinearEqualityConstraint, map_warp ) { // make a realistic calibration matrix static double fov = 60; // degrees -static int w=640,h=480; -static Cal3_S2 K(fov,w,h); +static int w = 640, h = 480; +static Cal3_S2 K(fov, w, h); static boost::shared_ptr shK(new Cal3_S2(K)); // typedefs for visual SLAM example @@ -516,14 +526,12 @@ typedef NonlinearFactorGraph VGraph; // factors for visual slam typedef NonlinearEquality2 Point3Equality; -/* ********************************************************************* */ +//****************************************************************************** TEST (testNonlinearEqualityConstraint, stereo_constrained ) { // create initial estimates - Rot3 faceDownY((Matrix)(Matrix(3,3) << - 1.0, 0.0, 0.0, - 0.0, 0.0, 1.0, - 0.0, -1.0, 0.0).finished()); + Rot3 faceDownY( + (Matrix) (Matrix(3, 3) << 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, -1.0, 0.0).finished()); Pose3 pose1(faceDownY, Point3()); // origin, left camera SimpleCamera camera1(pose1, K); Pose3 pose2(faceDownY, Point3(2.0, 0.0, 0.0)); // 2 units to the left @@ -531,8 +539,8 @@ TEST (testNonlinearEqualityConstraint, stereo_constrained ) { Point3 landmark(1.0, 5.0, 0.0); //centered between the cameras, 5 units away // keys - Symbol x1('x',1), x2('x',2); - Symbol l1('l',1), l2('l',2); + Symbol x1('x', 1), x2('x', 2); + Symbol l1('l', 1), l2('l', 2); // create graph VGraph graph; @@ -543,8 +551,10 @@ TEST (testNonlinearEqualityConstraint, stereo_constrained ) { // create factors SharedDiagonal vmodel = noiseModel::Unit::Create(2); - graph += GenericProjectionFactor(camera1.project(landmark), vmodel, x1, l1, shK); - graph += GenericProjectionFactor(camera2.project(landmark), vmodel, x2, l2, shK); + graph += GenericProjectionFactor( + camera1.project(landmark), vmodel, x1, l1, shK); + graph += GenericProjectionFactor( + camera2.project(landmark), vmodel, x2, l2, shK); // add equality constraint graph += Point3Equality(l1, l2); @@ -573,6 +583,9 @@ TEST (testNonlinearEqualityConstraint, stereo_constrained ) { CHECK(assert_equal(truthValues, actual, 1e-5)); } -/* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ +//****************************************************************************** +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +//****************************************************************************** From e0248c3ca77095ab376525d6e77fdcae381b512d Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 10:53:26 +0100 Subject: [PATCH 48/57] Created keysAndDims and safe version of values --- gtsam_unstable/nonlinear/Expression-inl.h | 8 +- gtsam_unstable/nonlinear/Expression.h | 104 ++++++++++++++---- gtsam_unstable/nonlinear/ExpressionFactor.h | 20 +--- .../nonlinear/tests/testExpression.cpp | 32 +++--- 4 files changed, 108 insertions(+), 56 deletions(-) diff --git a/gtsam_unstable/nonlinear/Expression-inl.h b/gtsam_unstable/nonlinear/Expression-inl.h index 58f6de6b4..08dd18ee3 100644 --- a/gtsam_unstable/nonlinear/Expression-inl.h +++ b/gtsam_unstable/nonlinear/Expression-inl.h @@ -252,7 +252,7 @@ public: } /// Return dimensions for each argument, as a map - virtual void dims(std::map& map) const { + virtual void dims(std::map& map) const { } // Return size needed for memory buffer in traceExecution @@ -324,7 +324,7 @@ public: } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + virtual void dims(std::map& map) const { // get dimension from the chart; only works for fixed dimension charts map[key_] = traits::dimension::value; } @@ -371,7 +371,7 @@ public: } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + virtual void dims(std::map& map) const { map[key_] = traits::dimension::value; } @@ -523,7 +523,7 @@ struct GenerateFunctionalNode: Argument, Base { } /// Return dimensions for each argument - virtual void dims(std::map& map) const { + virtual void dims(std::map& map) const { Base::dims(map); This::expression->dims(map); } diff --git a/gtsam_unstable/nonlinear/Expression.h b/gtsam_unstable/nonlinear/Expression.h index 5e1d425ed..3b5026348 100644 --- a/gtsam_unstable/nonlinear/Expression.h +++ b/gtsam_unstable/nonlinear/Expression.h @@ -20,8 +20,12 @@ #pragma once #include "Expression-inl.h" +#include #include + #include +#include +#include namespace gtsam { @@ -31,6 +35,11 @@ namespace gtsam { template class Expression { +public: + + /// Define type so we can apply it as a meta-function + typedef Expression type; + private: // Paul's trick shared pointer, polymorphic root of entire expression tree @@ -55,7 +64,7 @@ public: // Construct a leaf expression, creating Symbol Expression(unsigned char c, size_t j) : - root_(new LeafExpression(Symbol(c, j))) { + root_(new LeafExpression(Symbol(c, j))) { } /// Construct a nullary method expression @@ -87,8 +96,7 @@ public: template Expression(typename BinaryExpression::Function function, const Expression& expression1, const Expression& expression2) : - root_( - new BinaryExpression(function, expression1, expression2)) { + root_(new BinaryExpression(function, expression1, expression2)) { } /// Construct a ternary function expression @@ -101,14 +109,9 @@ public: expression2, expression3)) { } - /// Return keys that play in this expression - std::set keys() const { - return root_->keys(); - } - - /// Return dimensions for each argument, as a map - void dims(std::map& map) const { - root_->dims(map); + /// Return root + const boost::shared_ptr >& root() const { + return root_; } // Return size needed for memory buffer in traceExecution @@ -116,13 +119,77 @@ public: return root_->traceSize(); } - /// trace execution, very unsafe, for testing purposes only //TODO this is not only used for testing, but in value() below! + /// Return keys that play in this expression + std::set keys() const { + return root_->keys(); + } + + /// Return dimensions for each argument, as a map + void dims(std::map& map) const { + root_->dims(map); + } + + /// return keys and dimensions as vectors in same order + std::pair, FastVector > keysAndDims() const { + std::map map; + dims(map); + size_t n = map.size(); + FastVector keys(n); + boost::copy(map | boost::adaptors::map_keys, keys.begin()); + FastVector dims(n); + boost::copy(map | boost::adaptors::map_values, dims.begin()); + return make_pair(keys, dims); + } + + /** + * @brief Return value and optional derivatives, reverse AD version + * Notes: this is not terribly efficient, and H should have correct size. + */ + T value(const Values& values, boost::optional&> H = + boost::none) const { + + if (H) { + // Get keys and dimensions + FastVector keys; + FastVector dims; + boost::tie(keys, dims) = keysAndDims(); + + // H should be pre-allocated + assert(H->size()==keys.size()); + + // Pre-allocate and zero VerticalBlockMatrix + static const int Dim = traits::dimension::value; + VerticalBlockMatrix Ab(dims, Dim); + Ab.matrix().setZero(); + JacobianMap jacobianMap(keys, Ab); + + // Call unsafe version + T result = value(values, jacobianMap); + + // Copy blocks into the vector of jacobians passed in + for (DenseIndex i = 0; i < static_cast(keys.size()); i++) + H->at(i) = Ab(i); + + return result; + } else { + // no derivatives needed, just return value + return root_->value(values); + } + } + +private: + + /// trace execution, very unsafe T traceExecution(const Values& values, ExecutionTrace& trace, ExecutionTraceStorage* traceStorage) const { return root_->traceExecution(values, trace, traceStorage); } - /// Return value and derivatives, reverse AD version + /** + * @brief Return value and derivatives, reverse AD version + * This fairly unsafe method needs a JacobianMap with correctly allocated + * and initialized VerticalBlockMatrix, hence is declared private. + */ T value(const Values& values, JacobianMap& jacobians) const { // The following piece of code is absolutely crucial for performance. // We allocate a block of memory on the stack, which can be done at runtime @@ -137,17 +204,6 @@ public: return value; } - /// Return value - T value(const Values& values) const { - return root_->value(values); - } - - const boost::shared_ptr >& root() const { - return root_; - } - - /// Define type so we can apply it as a meta-function - typedef Expression type; }; // http://stackoverflow.com/questions/16260445/boost-bind-to-operator diff --git a/gtsam_unstable/nonlinear/ExpressionFactor.h b/gtsam_unstable/nonlinear/ExpressionFactor.h index 22a2aefeb..22c2f527f 100644 --- a/gtsam_unstable/nonlinear/ExpressionFactor.h +++ b/gtsam_unstable/nonlinear/ExpressionFactor.h @@ -22,8 +22,6 @@ #include #include #include -#include -#include #include namespace gtsam { @@ -36,7 +34,7 @@ class ExpressionFactor: public NoiseModelFactor { T measurement_; ///< the measurement to be compared with the expression Expression expression_; ///< the expression that is AD enabled - std::vector dimensions_; ///< dimensions of the Jacobian matrices + FastVector dimensions_; ///< dimensions of the Jacobian matrices size_t augmentedCols_; ///< total number of columns + 1 (for RHS) static const int Dim = traits::dimension::value; @@ -54,17 +52,9 @@ public: "ExpressionFactor was created with a NoiseModel of incorrect dimension."); noiseModel_ = noiseModel; - // Get dimensions of Jacobian matrices + // Get keys and dimensions for Jacobian matrices // An Expression is assumed unmutable, so we do this now - std::map map; - expression_.dims(map); - size_t n = map.size(); - - keys_.resize(n); - boost::copy(map | boost::adaptors::map_keys, keys_.begin()); - - dimensions_.resize(n); - boost::copy(map | boost::adaptors::map_values, dimensions_.begin()); + boost::tie(keys_,dimensions_) = expression_.keysAndDims(); // Add sizes to know how much memory to allocate on stack in linearize augmentedCols_ = std::accumulate(dimensions_.begin(), dimensions_.end(), 1); @@ -126,13 +116,13 @@ public: // Wrap keys and VerticalBlockMatrix into structure passed to expression_ VerticalBlockMatrix& Ab = factor->matrixObject(); - JacobianMap map(keys_, Ab); + JacobianMap jacobianMap(keys_, Ab); // Zero out Jacobian so we can simply add to it Ab.matrix().setZero(); // Evaluate error to get Jacobians and RHS vector b - T value = expression_.value(x, map); // <<< Reverse AD happens here ! + T value = expression_.value(x, jacobianMap); // <<< Reverse AD happens here ! Ab(size()).col(0) = -chart.local(measurement_, value); // Whiten the corresponding system, Ab already contains RHS diff --git a/gtsam_unstable/nonlinear/tests/testExpression.cpp b/gtsam_unstable/nonlinear/tests/testExpression.cpp index 4e032b9f2..d02a67b2d 100644 --- a/gtsam_unstable/nonlinear/tests/testExpression.cpp +++ b/gtsam_unstable/nonlinear/tests/testExpression.cpp @@ -114,22 +114,29 @@ TEST(Expression, NullaryMethod) { Values values; values.insert(67, Point3(3, 4, 5)); - // Pre-allocate JacobianMap - FastVector keys; - keys.push_back(67); - FastVector dims; - dims.push_back(3); - VerticalBlockMatrix Ab(dims, 1); - JacobianMap map(keys, Ab); + // Check dims as map + std::map map; + norm.dims(map); + LONGS_EQUAL(1,map.size()); - // Get value and Jacobian - double actual = norm.value(values, map); + // Get and check keys and dims + FastVector keys; + FastVector dims; + boost::tie(keys, dims) = norm.keysAndDims(); + LONGS_EQUAL(1,keys.size()); + LONGS_EQUAL(1,dims.size()); + LONGS_EQUAL(67,keys[0]); + LONGS_EQUAL(3,dims[0]); + + // Get value and Jacobians + std::vector H(1); + double actual = norm.value(values, H); // Check all EXPECT(actual == sqrt(50)); Matrix expected(1, 3); expected << 3.0 / sqrt(50.0), 4.0 / sqrt(50.0), 5.0 / sqrt(50.0); - EXPECT(assert_equal(expected,Ab(0))); + EXPECT(assert_equal(expected,H[0])); } /* ************************************************************************* */ // Binary(Leaf,Leaf) @@ -159,7 +166,7 @@ TEST(Expression, BinaryKeys) { /* ************************************************************************* */ // dimensions TEST(Expression, BinaryDimensions) { - map actual, expected = map_list_of(1, 6)(2, 3); + map actual, expected = map_list_of(1, 6)(2, 3); binary::p_cam.dims(actual); EXPECT(actual==expected); } @@ -190,8 +197,7 @@ TEST(Expression, TreeKeys) { /* ************************************************************************* */ // dimensions TEST(Expression, TreeDimensions) { - map actual, expected = map_list_of(1, 6)(2, 3)(3, - 5); + map actual, expected = map_list_of(1, 6)(2, 3)(3, 5); tree::uv_hat.dims(actual); EXPECT(actual==expected); } From 07e5475b6b47b173e101213fc9bc39c910c2def0 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 11:02:54 +0100 Subject: [PATCH 49/57] Making friends... --- gtsam_unstable/nonlinear/Expression.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/gtsam_unstable/nonlinear/Expression.h b/gtsam_unstable/nonlinear/Expression.h index 3b5026348..40b55c410 100644 --- a/gtsam_unstable/nonlinear/Expression.h +++ b/gtsam_unstable/nonlinear/Expression.h @@ -27,8 +27,13 @@ #include #include +class ExpressionFactorShallowTest; + namespace gtsam { +// Forward declare +template class ExpressionFactor; + /** * Expression class that supports automatic differentiation */ @@ -204,6 +209,10 @@ private: return value; } + // be very selective on who can access these private methods: + friend class ExpressionFactor; + friend class ::ExpressionFactorShallowTest; + }; // http://stackoverflow.com/questions/16260445/boost-bind-to-operator From 2c35cda71f7b9750f8a8d9547c14d6e8e4b075ae Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 11:23:38 +0100 Subject: [PATCH 50/57] Yet another indirection makes public code a bit cleaner. --- gtsam_unstable/nonlinear/Expression.h | 63 +++++++++++++++------------ 1 file changed, 35 insertions(+), 28 deletions(-) diff --git a/gtsam_unstable/nonlinear/Expression.h b/gtsam_unstable/nonlinear/Expression.h index 40b55c410..8f1514a22 100644 --- a/gtsam_unstable/nonlinear/Expression.h +++ b/gtsam_unstable/nonlinear/Expression.h @@ -45,6 +45,8 @@ public: /// Define type so we can apply it as a meta-function typedef Expression type; + typedef std::pair, FastVector > KeysAndDims; + private: // Paul's trick shared pointer, polymorphic root of entire expression tree @@ -135,7 +137,7 @@ public: } /// return keys and dimensions as vectors in same order - std::pair, FastVector > keysAndDims() const { + KeysAndDims keysAndDims() const { std::map map; dims(map); size_t n = map.size(); @@ -153,37 +155,42 @@ public: T value(const Values& values, boost::optional&> H = boost::none) const { - if (H) { - // Get keys and dimensions - FastVector keys; - FastVector dims; - boost::tie(keys, dims) = keysAndDims(); - - // H should be pre-allocated - assert(H->size()==keys.size()); - - // Pre-allocate and zero VerticalBlockMatrix - static const int Dim = traits::dimension::value; - VerticalBlockMatrix Ab(dims, Dim); - Ab.matrix().setZero(); - JacobianMap jacobianMap(keys, Ab); - - // Call unsafe version - T result = value(values, jacobianMap); - - // Copy blocks into the vector of jacobians passed in - for (DenseIndex i = 0; i < static_cast(keys.size()); i++) - H->at(i) = Ab(i); - - return result; - } else { + if (H) + // Call provate version that returns derivatives in H + return value(values, keysAndDims(), *H); + else // no derivatives needed, just return value return root_->value(values); - } } private: + /// private version that takes keys and dimensions, returns derivatives + T value(const Values& values, const KeysAndDims& keysAndDims, + std::vector& H) const { + + const FastVector& keys = keysAndDims.first; + const FastVector& dims = keysAndDims.second; + + // H should be pre-allocated + assert(H->size()==keys.size()); + + // Pre-allocate and zero VerticalBlockMatrix + static const int Dim = traits::dimension::value; + VerticalBlockMatrix Ab(dims, Dim); + Ab.matrix().setZero(); + JacobianMap jacobianMap(keys, Ab); + + // Call unsafe version + T result = value(values, jacobianMap); + + // Copy blocks into the vector of jacobians passed in + for (DenseIndex i = 0; i < static_cast(keys.size()); i++) + H[i] = Ab(i); + + return result; + } + /// trace execution, very unsafe T traceExecution(const Values& values, ExecutionTrace& trace, ExecutionTraceStorage* traceStorage) const { @@ -192,7 +199,7 @@ private: /** * @brief Return value and derivatives, reverse AD version - * This fairly unsafe method needs a JacobianMap with correctly allocated + * This very unsafe method needs a JacobianMap with correctly allocated * and initialized VerticalBlockMatrix, hence is declared private. */ T value(const Values& values, JacobianMap& jacobians) const { @@ -210,7 +217,7 @@ private: } // be very selective on who can access these private methods: - friend class ExpressionFactor; + friend class ExpressionFactor ; friend class ::ExpressionFactorShallowTest; }; From 2ced73ebe189ef12ea2e6ebfcd763d920098f37e Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 11:29:50 +0100 Subject: [PATCH 51/57] We now use safe version in unwhitenedError --- gtsam_unstable/nonlinear/ExpressionFactor.h | 41 +++++++-------------- 1 file changed, 14 insertions(+), 27 deletions(-) diff --git a/gtsam_unstable/nonlinear/ExpressionFactor.h b/gtsam_unstable/nonlinear/ExpressionFactor.h index 22c2f527f..61eb94c89 100644 --- a/gtsam_unstable/nonlinear/ExpressionFactor.h +++ b/gtsam_unstable/nonlinear/ExpressionFactor.h @@ -34,7 +34,7 @@ class ExpressionFactor: public NoiseModelFactor { T measurement_; ///< the measurement to be compared with the expression Expression expression_; ///< the expression that is AD enabled - FastVector dimensions_; ///< dimensions of the Jacobian matrices + FastVector dims_; ///< dimensions of the Jacobian matrices size_t augmentedCols_; ///< total number of columns + 1 (for RHS) static const int Dim = traits::dimension::value; @@ -54,13 +54,13 @@ public: // Get keys and dimensions for Jacobian matrices // An Expression is assumed unmutable, so we do this now - boost::tie(keys_,dimensions_) = expression_.keysAndDims(); + boost::tie(keys_, dims_) = expression_.keysAndDims(); // Add sizes to know how much memory to allocate on stack in linearize - augmentedCols_ = std::accumulate(dimensions_.begin(), dimensions_.end(), 1); + augmentedCols_ = std::accumulate(dims_.begin(), dims_.end(), 1); #ifdef DEBUG_ExpressionFactor - BOOST_FOREACH(size_t d, dimensions_) + BOOST_FOREACH(size_t d, dims_) std::cout << d << " "; std::cout << " -> " << Dim << "x" << augmentedCols_ << std::endl; #endif @@ -76,32 +76,15 @@ public: // TODO(PTF) Is this a place for custom charts? DefaultChart chart; if (H) { - // H should be pre-allocated - assert(H->size()==size()); - - VerticalBlockMatrix Ab(dimensions_, Dim); - - // Wrap keys and VerticalBlockMatrix into structure passed to expression_ - JacobianMap map(keys_, Ab); - Ab.matrix().setZero(); - - // Evaluate error to get Jacobians and RHS vector b - T value = expression_.value(x, map); // <<< Reverse AD happens here ! - - // Copy blocks into the vector of jacobians passed in - for (DenseIndex i = 0; i < static_cast(size()); i++) - H->at(i) = Ab(i); - + const T value = expression_.value(x, std::make_pair(keys_, dims_), *H); return chart.local(measurement_, value); } else { - const T& value = expression_.value(x); + const T value = expression_.value(x); return chart.local(measurement_, value); } } virtual boost::shared_ptr linearize(const Values& x) const { - // TODO(PTF) Is this a place for custom charts? - DefaultChart chart; // Only linearize if the factor is active if (!active(x)) return boost::shared_ptr(); @@ -110,9 +93,9 @@ public: // In case noise model is constrained, we need to provide a noise model bool constrained = noiseModel_->is_constrained(); boost::shared_ptr factor( - constrained ? new JacobianFactor(keys_, dimensions_, Dim, + constrained ? new JacobianFactor(keys_, dims_, Dim, boost::static_pointer_cast(noiseModel_)->unit()) : - new JacobianFactor(keys_, dimensions_, Dim)); + new JacobianFactor(keys_, dims_, Dim)); // Wrap keys and VerticalBlockMatrix into structure passed to expression_ VerticalBlockMatrix& Ab = factor->matrixObject(); @@ -121,13 +104,17 @@ public: // Zero out Jacobian so we can simply add to it Ab.matrix().setZero(); - // Evaluate error to get Jacobians and RHS vector b + // Get value and Jacobians, writing directly into JacobianFactor T value = expression_.value(x, jacobianMap); // <<< Reverse AD happens here ! + + // Evaluate error and set RHS vector b + // TODO(PTF) Is this a place for custom charts? + DefaultChart chart; Ab(size()).col(0) = -chart.local(measurement_, value); // Whiten the corresponding system, Ab already contains RHS Vector dummy(Dim); - noiseModel_->WhitenSystem(Ab.matrix(),dummy); + noiseModel_->WhitenSystem(Ab.matrix(), dummy); return factor; } From df91cf7fadb1e9a8bba3bbd6710e8651f13640d6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 12:36:52 +0100 Subject: [PATCH 52/57] Made vaguely unsafe keysAndDims private (as it relies on keys and dimensions being in same order), as to not tempt people to use it. --- gtsam_unstable/nonlinear/Expression.h | 27 +++++++++---------- .../nonlinear/tests/testExpression.cpp | 9 ------- .../nonlinear/tests/testExpressionFactor.cpp | 11 ++++++++ 3 files changed, 24 insertions(+), 23 deletions(-) diff --git a/gtsam_unstable/nonlinear/Expression.h b/gtsam_unstable/nonlinear/Expression.h index 8f1514a22..4684184b8 100644 --- a/gtsam_unstable/nonlinear/Expression.h +++ b/gtsam_unstable/nonlinear/Expression.h @@ -45,8 +45,6 @@ public: /// Define type so we can apply it as a meta-function typedef Expression type; - typedef std::pair, FastVector > KeysAndDims; - private: // Paul's trick shared pointer, polymorphic root of entire expression tree @@ -136,18 +134,6 @@ public: root_->dims(map); } - /// return keys and dimensions as vectors in same order - KeysAndDims keysAndDims() const { - std::map map; - dims(map); - size_t n = map.size(); - FastVector keys(n); - boost::copy(map | boost::adaptors::map_keys, keys.begin()); - FastVector dims(n); - boost::copy(map | boost::adaptors::map_values, dims.begin()); - return make_pair(keys, dims); - } - /** * @brief Return value and optional derivatives, reverse AD version * Notes: this is not terribly efficient, and H should have correct size. @@ -165,6 +151,19 @@ public: private: + /// Vaguely unsafe keys and dimensions in same order + typedef std::pair, FastVector > KeysAndDims; + KeysAndDims keysAndDims() const { + std::map map; + dims(map); + size_t n = map.size(); + FastVector keys(n); + boost::copy(map | boost::adaptors::map_keys, keys.begin()); + FastVector dims(n); + boost::copy(map | boost::adaptors::map_values, dims.begin()); + return make_pair(keys, dims); + } + /// private version that takes keys and dimensions, returns derivatives T value(const Values& values, const KeysAndDims& keysAndDims, std::vector& H) const { diff --git a/gtsam_unstable/nonlinear/tests/testExpression.cpp b/gtsam_unstable/nonlinear/tests/testExpression.cpp index d02a67b2d..6156d103c 100644 --- a/gtsam_unstable/nonlinear/tests/testExpression.cpp +++ b/gtsam_unstable/nonlinear/tests/testExpression.cpp @@ -119,15 +119,6 @@ TEST(Expression, NullaryMethod) { norm.dims(map); LONGS_EQUAL(1,map.size()); - // Get and check keys and dims - FastVector keys; - FastVector dims; - boost::tie(keys, dims) = norm.keysAndDims(); - LONGS_EQUAL(1,keys.size()); - LONGS_EQUAL(1,dims.size()); - LONGS_EQUAL(67,keys[0]); - LONGS_EQUAL(3,dims[0]); - // Get value and Jacobians std::vector H(1); double actual = norm.value(values, H); diff --git a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp index b9d9896d3..d146ea945 100644 --- a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp +++ b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp @@ -202,6 +202,17 @@ TEST(ExpressionFactor, Shallow) { // 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; From dc4c0b54c0f0169175fc9b2963edc316e8c299f3 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 25 Nov 2014 16:13:30 +0100 Subject: [PATCH 53/57] Addressed code review by @hannessommer --- gtsam_unstable/nonlinear/Expression.h | 26 ++++++++++----------- gtsam_unstable/nonlinear/ExpressionFactor.h | 2 +- 2 files changed, 13 insertions(+), 15 deletions(-) diff --git a/gtsam_unstable/nonlinear/Expression.h b/gtsam_unstable/nonlinear/Expression.h index 4684184b8..68a79ed6b 100644 --- a/gtsam_unstable/nonlinear/Expression.h +++ b/gtsam_unstable/nonlinear/Expression.h @@ -137,14 +137,16 @@ public: /** * @brief Return value and optional derivatives, reverse AD version * Notes: this is not terribly efficient, and H should have correct size. + * The order of the Jacobians is same as keys in either keys() or dims() */ T value(const Values& values, boost::optional&> H = boost::none) const { - if (H) - // Call provate version that returns derivatives in H - return value(values, keysAndDims(), *H); - else + if (H) { + // Call private version that returns derivatives in H + KeysAndDims pair = keysAndDims(); + return value(values, pair.first, pair.second, *H); + } else // no derivatives needed, just return value return root_->value(values); } @@ -157,19 +159,15 @@ private: std::map map; dims(map); size_t n = map.size(); - FastVector keys(n); - boost::copy(map | boost::adaptors::map_keys, keys.begin()); - FastVector dims(n); - boost::copy(map | boost::adaptors::map_values, dims.begin()); - return make_pair(keys, dims); + KeysAndDims pair = std::make_pair(FastVector(n), FastVector(n)); + boost::copy(map | boost::adaptors::map_keys, pair.first.begin()); + boost::copy(map | boost::adaptors::map_values, pair.second.begin()); + return pair; } /// private version that takes keys and dimensions, returns derivatives - T value(const Values& values, const KeysAndDims& keysAndDims, - std::vector& H) const { - - const FastVector& keys = keysAndDims.first; - const FastVector& dims = keysAndDims.second; + T value(const Values& values, const FastVector& keys, + const FastVector& dims, std::vector& H) const { // H should be pre-allocated assert(H->size()==keys.size()); diff --git a/gtsam_unstable/nonlinear/ExpressionFactor.h b/gtsam_unstable/nonlinear/ExpressionFactor.h index 61eb94c89..069fb5e2e 100644 --- a/gtsam_unstable/nonlinear/ExpressionFactor.h +++ b/gtsam_unstable/nonlinear/ExpressionFactor.h @@ -76,7 +76,7 @@ public: // TODO(PTF) Is this a place for custom charts? DefaultChart chart; if (H) { - const T value = expression_.value(x, std::make_pair(keys_, dims_), *H); + const T value = expression_.value(x, keys_, dims_, *H); return chart.local(measurement_, value); } else { const T value = expression_.value(x); From ee63fb0bb43818846344b8ac7104f61ad5ac2160 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 25 Nov 2014 15:44:59 -0500 Subject: [PATCH 54/57] Remove debug cmake messages --- CMakeLists.txt | 1 - gtsam/CMakeLists.txt | 2 -- 2 files changed, 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b6e59cc57..308f7f72e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -330,7 +330,6 @@ endif(GTSAM_BUILD_UNSTABLE) # Install config and export files GtsamMakeConfigFile(GTSAM "${CMAKE_CURRENT_SOURCE_DIR}/gtsam_extra.cmake.in") -message("GTSAM export: ${GTSAM_EXPORTED_TARGETS}") export(TARGETS ${GTSAM_EXPORTED_TARGETS} FILE GTSAM-exports.cmake) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index b58a5b4b8..b77d936dc 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -92,8 +92,6 @@ set(gtsam_version ${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSIO set(gtsam_soversion ${GTSAM_VERSION_MAJOR}) message(STATUS "GTSAM Version: ${gtsam_version}") message(STATUS "Install prefix: ${CMAKE_INSTALL_PREFIX}") -message("GTSAM Additional: ${GTSAM_ADDITIONAL_LIBRARIES}") -message("GTSAM Exports: ${GTSAM_EXPORTED_TARGETS}") # build shared and static versions of the library if (GTSAM_BUILD_STATIC_LIBRARY) From 41197f1ec786d486ff0a139709da742033379f7b Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 25 Nov 2014 15:51:49 -0500 Subject: [PATCH 55/57] Move warning suppression --- CMakeLists.txt | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 308f7f72e..0888a394e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -101,8 +101,6 @@ if(MSVC) add_definitions(-DBOOST_ALL_NO_LIB) add_definitions(-DBOOST_ALL_DYN_LINK) endif() - # Also disable certain warnings - add_definitions(/wd4503) endif() find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time regex timer chrono) @@ -281,7 +279,7 @@ include_directories(BEFORE if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS -D_SCL_SECURE_NO_WARNINGS) - add_definitions(/wd4251 /wd4275 /wd4251 /wd4661 /wd4344) # Disable non-DLL-exported base class and other warnings + add_definitions(/wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings endif() # GCC 4.8+ complains about local typedefs which we use for shared_ptr etc. From a0452bdac9070bdc178ed134bdd2a4c9211239dd Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 25 Nov 2014 15:55:59 -0500 Subject: [PATCH 56/57] Minor format --- gtsam/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index b77d936dc..0ebd6c07d 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -10,7 +10,7 @@ set (gtsam_subdirs linear nonlinear slam - navigation + navigation ) set(gtsam_srcs) @@ -74,8 +74,8 @@ set(gtsam_srcs ${linear_srcs} ${nonlinear_srcs} ${slam_srcs} - ${navigation_srcs} - ${gtsam_core_headers} + ${navigation_srcs} + ${gtsam_core_headers} ) # Generate and install config and dllexport files From e842c9adbc0dd00cda8e342dff4b71d082677749 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 26 Nov 2014 09:34:37 +0100 Subject: [PATCH 57/57] Fixed issue #172 --- gtsam.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam.h b/gtsam.h index 0ceda6db5..d63563028 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2272,7 +2272,7 @@ virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { }; #include -template +template virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { SmartProjectionPoseFactor(double rankTol, double linThreshold, @@ -2288,7 +2288,7 @@ virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { //void serialize() const; }; -typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor; +typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor; #include