diff --git a/gtsam.h b/gtsam.h index 08c4ed9d3..7cb46fc55 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1167,6 +1167,7 @@ virtual class NonlinearOptimizerParams { virtual class SuccessiveLinearizationParams : gtsam::NonlinearOptimizerParams { SuccessiveLinearizationParams(); + void setOrdering(const gtsam::Ordering& ordering); bool isMultifrontal() const; bool isSequential() const; bool isCholmod() const; @@ -1357,16 +1358,22 @@ typedef gtsam::RangeFactor RangeFactorSimple typedef gtsam::RangeFactor RangeFactorCalibratedCamera; typedef gtsam::RangeFactor RangeFactorSimpleCamera; - -#include -template +template virtual class BearingFactor : gtsam::NonlinearFactor { - BearingFactor(size_t key1, size_t key2, const ROT& measured, const gtsam::noiseModel::Base* noiseModel); + BearingFactor(size_t key1, size_t key2, const ROTATION& measured, const gtsam::noiseModel::Base* noiseModel); }; typedef gtsam::BearingFactor BearingFactor2D; +template +virtual class BearingRangeFactor : gtsam::NonlinearFactor { + BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::BearingRangeFactor BearingRangeFactor2D; + + #include template virtual class GenericProjectionFactor : gtsam::NonlinearFactor { diff --git a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h index 7033613ac..2556134c0 100644 --- a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h +++ b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h @@ -78,20 +78,16 @@ public: } inline bool isMultifrontal() const { - return (linearSolverType == MULTIFRONTAL_CHOLESKY) || (linearSolverType == MULTIFRONTAL_QR); - } + return (linearSolverType == MULTIFRONTAL_CHOLESKY) || (linearSolverType == MULTIFRONTAL_QR); } inline bool isSequential() const { - return (linearSolverType == SEQUENTIAL_CHOLESKY) || (linearSolverType == SEQUENTIAL_QR); - } + return (linearSolverType == SEQUENTIAL_CHOLESKY) || (linearSolverType == SEQUENTIAL_QR); } - inline bool isCholmod() const { - return (linearSolverType == CHOLMOD); - } + inline bool isCholmod() const { return (linearSolverType == CHOLMOD); } - inline bool isCG() const { - return (linearSolverType == CG); - } + inline bool isCG() const { return (linearSolverType == CG); } + + void setOrdering(const Ordering& ordering) { this->ordering = ordering; } GaussianFactorGraph::Eliminate getEliminationFunction() { switch (linearSolverType) { diff --git a/gtsam/slam/BearingFactor.h b/gtsam/slam/BearingFactor.h index 62e46d53e..326491e8c 100644 --- a/gtsam/slam/BearingFactor.h +++ b/gtsam/slam/BearingFactor.h @@ -25,12 +25,12 @@ namespace gtsam { /** * Binary factor for a bearing measurement */ - template + template class BearingFactor: public NoiseModelFactor2 { private: typedef POSE Pose; - typedef ROT Rot; + typedef ROTATION Rot; typedef POINT Point; typedef BearingFactor This; diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 933333fdf..bf5b6b3a5 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -27,12 +27,12 @@ namespace gtsam { /** * Binary factor for a bearing measurement */ - template + template class BearingRangeFactor: public NoiseModelFactor2 { private: typedef POSE Pose; - typedef typename POSE::Rotation Rot; + typedef ROTATION Rot; typedef POINT Point; typedef BearingRangeFactor This;