diff --git a/CMakeLists.txt b/CMakeLists.txt index f0308a8f3..91811264c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ option(GTSAM_NO_BOOST_CPP17 "Require and use boost" ON) add_definitions(-Wno-deprecated-declarations) add_definitions(-ftemplate-backtrace-limit=0) - set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD 17) if (GTSAM_NO_BOOST_CPP17) add_definitions(-DNO_BOOST_CPP17) endif() @@ -99,7 +99,7 @@ add_subdirectory(timing) # Build gtsam_unstable if (GTSAM_BUILD_UNSTABLE) - # add_subdirectory(gtsam_unstable) + add_subdirectory(gtsam_unstable) endif() # This is the new wrapper diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 4e9632644..be8ad7cf0 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -52,7 +52,8 @@ namespace gtsam { public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor2 Base; + using Base::evaluateError; /// shorthand for this class typedef GenericProjectionFactor This; @@ -60,8 +61,6 @@ namespace gtsam { /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; - using Base::evaluateError; - /// Default constructor GenericProjectionFactor() : measured_(0, 0), throwCheirality_(false), verboseCheirality_(false) { diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index dcca22695..16409d866 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -34,6 +34,7 @@ protected: double dt_; /// time between measurements public: + using Base::evaluateError; /** Standard constructor */ FullIMUFactor(const Vector3& accel, const Vector3& gyro, @@ -84,8 +85,7 @@ public: * z - h(x1,x2) */ Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { Vector9 z; z.head(3).operator=(accel_); // Strange syntax to work around ambiguous operator error with clang z.segment(3, 3).operator=(gyro_); // Strange syntax to work around ambiguous operator error with clang @@ -99,8 +99,7 @@ public: /** dummy version that fails for non-dynamic poses */ virtual Vector evaluateError(const Pose3& x1, const Pose3& x2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + OptionalMatrixType H1, OptionalMatrixType H2) const { assert(false); return Vector6::Zero(); } diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index 4eaa3139d..90a37751c 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -32,6 +32,7 @@ protected: double dt_; /// time between measurements public: + using Base::evaluateError; /** Standard constructor */ IMUFactor(const Vector3& accel, const Vector3& gyro, @@ -77,8 +78,7 @@ public: * z - h(x1,x2) */ Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { const Vector6 meas = z(); if (H1) *H1 = numericalDerivative21( std::bind(This::predict_proxy, std::placeholders::_1, std::placeholders::_2, dt_, meas), x1, x2, 1e-5); @@ -89,8 +89,7 @@ public: /** dummy version that fails for non-dynamic poses */ virtual Vector evaluateError(const Pose3& x1, const Pose3& x2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const { + OptionalMatrixType H1, OptionalMatrixType H2) const { assert(false); // no corresponding factor here return Vector6::Zero(); } diff --git a/gtsam_unstable/dynamics/Pendulum.h b/gtsam_unstable/dynamics/Pendulum.h index d7301a576..6d3126369 100644 --- a/gtsam_unstable/dynamics/Pendulum.h +++ b/gtsam_unstable/dynamics/Pendulum.h @@ -32,6 +32,7 @@ protected: double h_; // time step public: + using Base::evaluateError; typedef boost::shared_ptr shared_ptr; @@ -46,9 +47,8 @@ public: /** q_k + h*v - q_k1 = 0, with optional derivatives */ Vector evaluateError(const double& qk1, const double& qk, const double& v, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const override { const size_t p = 1; if (H1) *H1 = -Matrix::Identity(p,p); if (H2) *H2 = Matrix::Identity(p,p); @@ -81,6 +81,8 @@ protected: public: + using Base::evaluateError; + typedef boost::shared_ptr shared_ptr; ///Constructor. vk1: v_{k+1}, vk: v_k, qkey: q's key depending on the chosen method, h: time step @@ -94,9 +96,8 @@ public: /** v_k - h*g/L*sin(q) - v_k1 = 0, with optional derivatives */ Vector evaluateError(const double & vk1, const double & vk, const double & q, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const override { const size_t p = 1; if (H1) *H1 = -Matrix::Identity(p,p); if (H2) *H2 = Matrix::Identity(p,p); @@ -130,6 +131,8 @@ protected: public: + using Base::evaluateError; + typedef boost::shared_ptr shared_ptr; ///Constructor @@ -145,9 +148,8 @@ public: /** 1/h mr^2 (qk1-qk)+mgrh (1-a) sin((1-a)pk + a*pk1) - pk = 0, with optional derivatives */ Vector evaluateError(const double & pk, const double & qk, const double & qk1, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const override { const size_t p = 1; double qmid = (1-alpha_)*qk + alpha_*qk1; @@ -185,6 +187,7 @@ protected: double alpha_; //! in [0,1], define the mid-point between [q_k,q_{k+1}] for approximation. The sympletic rule above can be obtained as a special case when alpha = 0. public: + using Base::evaluateError; typedef boost::shared_ptr shared_ptr; @@ -201,9 +204,8 @@ public: /** 1/h mr^2 (qk1-qk) - mgrh a sin((1-a)pk + a*pk1) - pk1 = 0, with optional derivatives */ Vector evaluateError(const double & pk1, const double & qk, const double & qk1, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const override { const size_t p = 1; double qmid = (1-alpha_)*qk + alpha_*qk1; diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 941b7c7ac..893d667c8 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -29,6 +29,7 @@ class Reconstruction : public NoiseModelFactorN { double h_; // time step typedef NoiseModelFactorN Base; public: + using Base::evaluateError; Reconstruction(Key gKey1, Key gKey, Key xiKey, double h, double mu = 1000.0) : Base(noiseModel::Constrained::All(6, std::abs(mu)), gKey1, gKey, xiKey), h_(h) { @@ -42,9 +43,8 @@ public: /** \f$ log((g_k\exp(h\xi_k))^{-1}g_{k+1}) = 0 \f$, with optional derivatives */ Vector evaluateError(const Pose3& gk1, const Pose3& gk, const Vector6& xik, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const override { Matrix6 D_exphxi_xi; Pose3 exphxi = Pose3::Expmap(h_ * xik, H3 ? &D_exphxi_xi : 0); @@ -89,6 +89,8 @@ class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN Base; public: + using Base::evaluateError; + DiscreteEulerPoincareHelicopter(Key xiKey1, Key xiKey_1, Key gKey, double h, const Matrix& Inertia, const Vector& Fu, double m, double mu = 1000.0) : @@ -108,9 +110,8 @@ public: * pk_1 = CT_TLN(-h*xi_k_1)*Inertia*xi_k_1 * */ Vector evaluateError(const Vector6& xik, const Vector6& xik_1, const Pose3& gk, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const override { Vector muk = Inertia_*xik; Vector muk_1 = Inertia_*xik_1; @@ -161,9 +162,8 @@ public: } Vector evaluateError(const Vector6& xik, const Vector6& xik_1, const Pose3& gk, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const { if (H1) { (*H1) = numericalDerivative31( std::function( diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index 0fa3d9cb7..ece781f1c 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -34,7 +34,8 @@ typedef enum { */ class VelocityConstraint : public gtsam::NoiseModelFactorN { public: - typedef gtsam::NoiseModelFactorN Base; + typedef gtsam::NoiseModelFactor2 Base; + using Base::evaluateError; protected: @@ -83,8 +84,7 @@ public: * Calculates the error for trapezoidal model given */ gtsam::Vector evaluateError(const PoseRTV& x1, const PoseRTV& x2, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { if (H1) *H1 = gtsam::numericalDerivative21( std::bind(VelocityConstraint::evaluateError_, std::placeholders::_1, std::placeholders::_2, dt_, integration_mode_), x1, x2, 1e-5); diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index 2880b9c8c..0b4f5b0b6 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -23,6 +23,7 @@ protected: public: + using Base::evaluateError; typedef boost::shared_ptr shared_ptr; ///TODO: comment @@ -37,9 +38,8 @@ public: /** x1 + v*dt - x2 = 0, with optional derivatives */ Vector evaluateError(const double& x1, const double& x2, const double& v, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const override { const size_t p = 1; if (H1) *H1 = Matrix::Identity(p,p); if (H2) *H2 = -Matrix::Identity(p,p); diff --git a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp index 882d5423a..5cd72d377 100644 --- a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp +++ b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp @@ -7,6 +7,8 @@ #include #include #include +#include "gtsam/base/Vector.h" +#include "gtsam/geometry/Pose3.h" /* ************************************************************************* */ using namespace std::placeholders; @@ -56,29 +58,15 @@ TEST( Reconstruction, evaluateError) { EXPECT( assert_equal(Z_6x1, constraint.evaluateError(g2, g1, V1_g1, H1, H2, H3), tol)); - Matrix numericalH1 = numericalDerivative31( - std::function( - std::bind(&Reconstruction::evaluateError, constraint, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - g2, g1, V1_g1, 1e-5); + std::function f = [&constraint](const Pose3& a1, const Pose3& a2, + const Vector6& a3) { + return constraint.evaluateError(a1, a2, a3); + }; + Matrix numericalH1 = numericalDerivative31(f, g2, g1, V1_g1, 1e-5); - Matrix numericalH2 = numericalDerivative32( - std::function( - std::bind(&Reconstruction::evaluateError, constraint, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - g2, g1, V1_g1, 1e-5); + Matrix numericalH2 = numericalDerivative32(f, g2, g1, V1_g1, 1e-5); - Matrix numericalH3 = numericalDerivative33( - std::function( - std::bind(&Reconstruction::evaluateError, constraint, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - g2, g1, V1_g1, 1e-5); + Matrix numericalH3 = numericalDerivative33(f, g2, g1, V1_g1, 1e-5); EXPECT(assert_equal(numericalH1,H1,1e-5)); EXPECT(assert_equal(numericalH2,H2,1e-5)); @@ -118,26 +106,16 @@ TEST( DiscreteEulerPoincareHelicopter, evaluateError) { Matrix H1, H2, H3; EXPECT(assert_equal(Z_6x1, constraint.evaluateError(expectedv2, V1_g1, g2, H1, H2, H3), 1e0)); - Matrix numericalH1 = numericalDerivative31( - std::function( - std::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, boost::none, boost::none, boost::none) - ), - expectedv2, V1_g1, g2, 1e-5 - ); + std::function f = + [&constraint](const Vector6& a1, const Vector6& a2, const Pose3& a3) { + return constraint.evaluateError(a1, a2, a3); + }; - Matrix numericalH2 = numericalDerivative32( - std::function( - std::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, boost::none, boost::none, boost::none) - ), - expectedv2, V1_g1, g2, 1e-5 - ); + Matrix numericalH1 = numericalDerivative31(f, expectedv2, V1_g1, g2, 1e-5); - Matrix numericalH3 = numericalDerivative33( - std::function( - std::bind(&DiscreteEulerPoincareHelicopter::evaluateError, constraint, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, boost::none, boost::none, boost::none) - ), - expectedv2, V1_g1, g2, 1e-5 - ); + Matrix numericalH2 = numericalDerivative32(f, expectedv2, V1_g1, g2, 1e-5); + + Matrix numericalH3 = numericalDerivative33(f, expectedv2, V1_g1, g2, 1e-5); EXPECT(assert_equal(numericalH1,H1,1e-5)); EXPECT(assert_equal(numericalH2,H2,1e-5)); diff --git a/gtsam_unstable/geometry/InvDepthCamera3.h b/gtsam_unstable/geometry/InvDepthCamera3.h index 70ec6f513..7e070ca72 100644 --- a/gtsam_unstable/geometry/InvDepthCamera3.h +++ b/gtsam_unstable/geometry/InvDepthCamera3.h @@ -19,6 +19,7 @@ #include #include #include +#include namespace gtsam { @@ -83,9 +84,9 @@ public: */ inline gtsam::Point2 project(const Vector5& pw, double rho, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const { + OptionalJacobian<2,6> H1 = {}, + OptionalJacobian<2,5> H2 = {}, + OptionalJacobian<2,1> H3 = {}) const { gtsam::Point3 ray_base(pw.segment(0,3)); double theta = pw(3), phi = pw(4); diff --git a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp index 4c6251831..11a24286a 100644 --- a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp +++ b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp @@ -94,7 +94,7 @@ TEST( InvDepthFactor, Dproject_pose) Matrix expected = numericalDerivative31(project_,level_pose, landmark, inv_depth); InvDepthCamera3 inv_camera(level_pose,K); Matrix actual; - inv_camera.project(landmark, inv_depth, actual, boost::none, boost::none); + inv_camera.project(landmark, inv_depth, actual, {}, {}); EXPECT(assert_equal(expected,actual,1e-6)); } @@ -106,7 +106,7 @@ TEST( InvDepthFactor, Dproject_landmark) Matrix expected = numericalDerivative32(project_,level_pose, landmark, inv_depth); InvDepthCamera3 inv_camera(level_pose,K); Matrix actual; - inv_camera.project(landmark, inv_depth, boost::none, actual, boost::none); + inv_camera.project(landmark, inv_depth, {}, actual, {}); EXPECT(assert_equal(expected,actual,1e-7)); } @@ -118,7 +118,7 @@ TEST( InvDepthFactor, Dproject_inv_depth) Matrix expected = numericalDerivative33(project_,level_pose, landmark, inv_depth); InvDepthCamera3 inv_camera(level_pose,K); Matrix actual; - inv_camera.project(landmark, inv_depth, boost::none, boost::none, actual); + inv_camera.project(landmark, inv_depth, {}, {}, actual); EXPECT(assert_equal(expected,actual,1e-7)); } diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index ea1ce0d43..871dd3eee 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -145,7 +145,7 @@ public: /* ************************************************************************* */ Vector whitenedError(const Values& x, - boost::optional&> H = boost::none) const { + OptionalMatrixVecType H = OptionalMatrixVecNone) const { bool debug = true; @@ -228,6 +228,12 @@ public: return err_wh_eq; } +#ifdef NO_BOOST_CPP17 + Vector whitenedError(const Values& x, std::vector& H) const { + return whitenedError(x, &H); + } +#endif + /* ************************************************************************* */ Vector calcIndicatorProb(const Values& x) const { diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index 07706a6a5..0d4c2619d 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -37,6 +37,7 @@ namespace gtsam { Point3 measured_; /** The measurement */ public: + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -73,8 +74,7 @@ namespace gtsam { /** vector of errors */ Vector evaluateError(const Pose3& pose, const Point3& bias, - boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { if (H1 || H2){ H1->resize(3,6); // jacobian wrt pose diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index e52837fb4..a333ce439 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -110,6 +110,8 @@ private: boost::optional body_P_sensor_; // The pose of the sensor in the body frame public: + + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; @@ -299,11 +301,8 @@ public: } Vector evaluateError(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1, const POSE& Pose2, const VELOCITY& Vel2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none, - boost::optional H4 = boost::none, - boost::optional H5 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4, + OptionalMatrixType H5) const override { // TODO: Write analytical derivative calculations // Jacobian w.r.t. Pose1 diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 6423fabda..7fca72fb0 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -109,6 +109,7 @@ private: public: + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; @@ -270,10 +271,8 @@ public: } Vector evaluateError(const POSE& Pose1, const VELOCITY& Vel1, const POSE& Pose2, const VELOCITY& Vel2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none, - boost::optional H4 = boost::none) const { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, + OptionalMatrixType H4) const { // TODO: Write analytical derivative calculations // Jacobian w.r.t. Pose1 diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index 5d677b82e..2f087cedf 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -53,6 +53,7 @@ private: Vector tau_; public: + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; @@ -88,8 +89,7 @@ public: /** vector of errors */ Vector evaluateError(const VALUE& p1, const VALUE& p2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { Vector v1( traits::Logmap(p1) ); Vector v2( traits::Logmap(p2) ); diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index fd3ab729d..ad3c1287b 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -95,6 +95,7 @@ private: boost::optional body_P_sensor_; // The pose of the sensor in the body frame public: + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; @@ -226,11 +227,8 @@ public: /** implement functions needed to derive from Factor */ Vector evaluateError(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1, const POSE& Pose2, const VELOCITY& Vel2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none, - boost::optional H4 = boost::none, - boost::optional H5 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4, + OptionalMatrixType H5) const override { // TODO: Write analytical derivative calculations // Jacobian w.r.t. Pose1 diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 2d0d57437..98eadb9e2 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -34,7 +34,8 @@ protected: public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor3 Base; + using Base::evaluateError; /// shorthand for this class typedef InvDepthFactor3 This; @@ -83,9 +84,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const POSE& pose, const Vector5& point, const INVDEPTH& invDepth, - boost::optional H1=boost::none, - boost::optional H2=boost::none, - boost::optional H3=boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override { try { InvDepthCamera3 camera(pose, K_); return camera.project(point, invDepth, H1, H2, H3) - measured_; diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index a41a06ccd..39c7924d8 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -34,7 +34,8 @@ protected: public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor2 Base; + using Base::evaluateError; /// shorthand for this class typedef InvDepthFactorVariant1 This; @@ -103,8 +104,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Vector6& landmark, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { if (H1) { (*H1) = numericalDerivative11( diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index d120eff32..51dfb02e9 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -36,7 +36,8 @@ protected: public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor2 Base; + using Base::evaluateError; /// shorthand for this class typedef InvDepthFactorVariant2 This; @@ -106,8 +107,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Vector3& landmark, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { if (H1) { (*H1) = numericalDerivative11( diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index cade280f0..063128534 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -34,7 +34,8 @@ protected: public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor2 Base; + using Base::evaluateError; /// shorthand for this class typedef InvDepthFactorVariant3a This; @@ -106,8 +107,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Vector3& landmark, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { if(H1) { (*H1) = numericalDerivative11( @@ -232,9 +232,7 @@ public: /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose1, const Pose3& pose2, const Vector3& landmark, - boost::optional H1=boost::none, - boost::optional H2=boost::none, - boost::optional H3=boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override { if(H1) (*H1) = numericalDerivative11( diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.cpp b/gtsam_unstable/slam/LocalOrientedPlane3Factor.cpp index 3a8cd0c6c..8854df5c7 100644 --- a/gtsam_unstable/slam/LocalOrientedPlane3Factor.cpp +++ b/gtsam_unstable/slam/LocalOrientedPlane3Factor.cpp @@ -24,8 +24,8 @@ void LocalOrientedPlane3Factor::print(const string& s, //*************************************************************************** Vector LocalOrientedPlane3Factor::evaluateError(const Pose3& wTwi, const Pose3& wTwa, const OrientedPlane3& a_plane, - boost::optional H1, boost::optional H2, - boost::optional H3) const { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const { Matrix66 aTai_H_wTwa, aTai_H_wTwi; Matrix36 predicted_H_aTai; diff --git a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h index f2c5dd3a9..0bc456234 100644 --- a/gtsam_unstable/slam/LocalOrientedPlane3Factor.h +++ b/gtsam_unstable/slam/LocalOrientedPlane3Factor.h @@ -40,6 +40,7 @@ class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor OrientedPlane3 measured_p_; typedef NoiseModelFactorN Base; public: + using Base::evaluateError; /// Constructor LocalOrientedPlane3Factor() {} @@ -84,10 +85,8 @@ public: * world frame. */ Vector evaluateError(const Pose3& wTwi, const Pose3& wTwa, - const OrientedPlane3& a_plane, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override; + const OrientedPlane3& a_plane, OptionalMatrixType H1, + OptionalMatrixType H2, OptionalMatrixType H3) const override; }; } // namespace gtsam diff --git a/gtsam_unstable/slam/MultiProjectionFactor.h b/gtsam_unstable/slam/MultiProjectionFactor.h index dbc4bc907..d1a2fc067 100644 --- a/gtsam_unstable/slam/MultiProjectionFactor.h +++ b/gtsam_unstable/slam/MultiProjectionFactor.h @@ -23,6 +23,7 @@ #include #include #include +#include "gtsam/geometry/Cal3_S2.h" namespace gtsam { @@ -164,7 +165,7 @@ namespace gtsam { Vector evaluateError(const Pose3& pose, const Point3& point, - boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { + OptionalJacobian<2, 6> H1 = {}, OptionalJacobian<2,3> H2 = {}) const { try { if(body_P_sensor_) { if(H1) { diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index b49b49131..3238bcdec 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -61,6 +61,7 @@ namespace gtsam { : Base(model, key) {} public: + using Base::evaluateError; ~PartialPriorFactor() override {} @@ -106,7 +107,7 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /** Returns a vector of errors for the measured tangent parameters. */ - Vector evaluateError(const T& p, boost::optional H = boost::none) const override { + Vector evaluateError(const T& p, OptionalMatrixType H) const override { Eigen::Matrix H_local; // If the Rot3 Cayley map is used, Rot3::LocalCoordinates will throw a runtime error diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index aaf00b45d..9d5324c26 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -43,6 +43,7 @@ namespace gtsam { GTSAM_CONCEPT_TESTABLE_TYPE(POSE) GTSAM_CONCEPT_POSE_TYPE(POSE) public: + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef typename boost::shared_ptr shared_ptr; @@ -89,8 +90,7 @@ namespace gtsam { /** vector of errors */ Vector evaluateError(const POSE& p1, const POSE& p2, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { if(body_P_sensor_) { POSE hx; if(H1 || H2) { diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index c7a094bda..f3bc3af57 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -40,6 +40,7 @@ namespace gtsam { GTSAM_CONCEPT_TESTABLE_TYPE(POSE) GTSAM_CONCEPT_POSE_TYPE(POSE) public: + using Base::evaluateError; /// shorthand for a smart pointer to a factor typedef typename boost::shared_ptr > shared_ptr; @@ -83,7 +84,7 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /** vector of errors */ - Vector evaluateError(const POSE& p, boost::optional H = boost::none) const override { + Vector evaluateError(const POSE& p, OptionalMatrixType H) const override { if(body_P_sensor_) { // manifold equivalent of h(x)-z -> log(z,h(x)) return prior_.localCoordinates(p.compose(*body_P_sensor_, H)); diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index 0d295113d..164f8fafa 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -29,6 +29,8 @@ class PoseToPointFactor : public NoiseModelFactorN { POINT measured_; /** the point measurement in local coordinates */ public: + + using Base::evaluateError; // shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -79,8 +81,8 @@ class PoseToPointFactor : public NoiseModelFactorN { */ Vector evaluateError( const POSE& w_T_b, const POINT& w_P, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { + OptionalMatrixType H1, + OptionalMatrixType H2) const override { return w_T_b.transformTo(w_P, H1, H2) - measured_; } diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index ab8cba481..f19cefb1f 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -45,7 +45,8 @@ namespace gtsam { public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor3 Base; + using Base::evaluateError; /// shorthand for this class typedef ProjectionFactorPPP This; @@ -122,9 +123,7 @@ namespace gtsam { /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override { try { if(H1 || H2 || H3) { Matrix H0, H02; diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index dec893af4..8068d1e27 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -44,7 +44,8 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor4 Base; + using Base::evaluateError; /// shorthand for this class typedef ProjectionFactorPPPC This; @@ -108,10 +109,8 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point, const CALIBRATION& K, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none, - boost::optional H4 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, + OptionalMatrixType H4) const override { try { if(H1 || H2 || H3 || H4) { Matrix H0, H02; diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.cpp b/gtsam_unstable/slam/ProjectionFactorRollingShutter.cpp index 8173c9dbd..003f2f921 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.cpp +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.cpp @@ -21,8 +21,8 @@ namespace gtsam { Vector ProjectionFactorRollingShutter::evaluateError( const Pose3& pose_a, const Pose3& pose_b, const Point3& point, - boost::optional H1, boost::optional H2, - boost::optional H3) const { + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3) const { try { Pose3 pose = interpolate(pose_a, pose_b, alpha_, H1, H2); gtsam::Matrix Hprj; diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 806f54fa5..4fc79863d 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -60,7 +60,8 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter public: /// shorthand for base class type - typedef NoiseModelFactorN Base; + typedef NoiseModelFactor3 Base; + using Base::evaluateError; /// shorthand for this class typedef ProjectionFactorRollingShutter This; @@ -173,9 +174,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter /// Evaluate error h(x)-z and optionally derivatives Vector evaluateError( const Pose3& pose_a, const Pose3& pose_b, const Point3& point, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none, - boost::optional H3 = boost::none) const override; + OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override; /** return the measurement */ const Point2& measured() const { return measured_; } diff --git a/gtsam_unstable/slam/RelativeElevationFactor.cpp b/gtsam_unstable/slam/RelativeElevationFactor.cpp index b35171041..3837658d2 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.cpp +++ b/gtsam_unstable/slam/RelativeElevationFactor.cpp @@ -18,7 +18,7 @@ RelativeElevationFactor::RelativeElevationFactor(Key poseKey, Key pointKey, doub /* ************************************************************************* */ Vector RelativeElevationFactor::evaluateError(const Pose3& pose, const Point3& point, - boost::optional H1, boost::optional H2) const { + OptionalMatrixType H1, OptionalMatrixType H2) const { double hx = pose.z() - point.z(); if (H1) { *H1 = Matrix::Zero(1,6); diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index c6273ff4b..c617c80b7 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -34,6 +34,7 @@ private: typedef NoiseModelFactorN Base; public: + using Base::evaluateError; RelativeElevationFactor() : measured_(0.0) {} /* Default constructor */ @@ -49,7 +50,7 @@ public: /** h(x)-z */ Vector evaluateError(const Pose3& pose, const Point3& point, - boost::optional H1 = boost::none, boost::optional H2 = boost::none) const override; + OptionalMatrixType H1, OptionalMatrixType H2) const override; /** return the measured */ inline double measured() const { return measured_; } diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 1c035331b..f3a4440be 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -42,6 +42,7 @@ class SmartRangeFactor: public NoiseModelFactor { double variance_; ///< variance on noise public: + using NoiseModelFactor::unwhitenedError; /** Default constructor: don't use directly */ SmartRangeFactor() { } @@ -143,8 +144,7 @@ class SmartRangeFactor: public NoiseModelFactor { /** * Error function *without* the NoiseModel, \f$ z-h(x) \f$. */ - Vector unwhitenedError(const Values& x, - boost::optional&> H = boost::none) const override { + Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = OptionalMatrixVecNone) const override { size_t n = size(); if (n < 3) { if (H) { diff --git a/gtsam_unstable/slam/TSAMFactors.h b/gtsam_unstable/slam/TSAMFactors.h index 2e024c5bb..fe5e63848 100644 --- a/gtsam_unstable/slam/TSAMFactors.h +++ b/gtsam_unstable/slam/TSAMFactors.h @@ -37,6 +37,7 @@ private: Point2 measured_; ///< the measurement public: + using Base::evaluateError; /// Constructor DeltaFactor(Key i, Key j, const Point2& measured, @@ -46,8 +47,7 @@ public: /// Evaluate measurement error h(x)-z Vector evaluateError(const Pose2& pose, const Point2& point, - boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2) const override { return pose.transformTo(point, H1, H2) - measured_; } }; @@ -66,7 +66,7 @@ private: Point2 measured_; ///< the measurement public: - + using Base::evaluateError; /// Constructor DeltaFactorBase(Key b1, Key i, Key b2, Key j, const Point2& measured, const SharedNoiseModel& model) : @@ -76,10 +76,8 @@ public: /// Evaluate measurement error h(x)-z Vector evaluateError(const Pose2& base1, const Pose2& pose, const Pose2& base2, const Point2& point, // - boost::optional H1 = boost::none, // - boost::optional H2 = boost::none, // - boost::optional H3 = boost::none, // - boost::optional H4 = boost::none) const override { + OptionalMatrixType H1, OptionalMatrixType H2, // + OptionalMatrixType H3, OptionalMatrixType H4) const override { if (H1 || H2 || H3 || H4) { // TODO use fixed-size matrices Matrix D_pose_g_base1, D_pose_g_pose; @@ -121,6 +119,7 @@ private: Pose2 measured_; ///< the measurement public: + using Base::evaluateError; /// Constructor OdometryFactorBase(Key b1, Key i, Key b2, Key j, const Pose2& measured, @@ -130,11 +129,9 @@ public: /// Evaluate measurement error h(x)-z Vector evaluateError(const Pose2& base1, const Pose2& pose1, - const Pose2& base2, const Pose2& pose2, // - boost::optional H1 = boost::none, // - boost::optional H2 = boost::none, // - boost::optional H3 = boost::none, // - boost::optional H4 = boost::none) const override { + const Pose2& base2, const Pose2& pose2, + OptionalMatrixType H1, OptionalMatrixType H2, + OptionalMatrixType H3, OptionalMatrixType H4) const override { if (H1 || H2 || H3 || H4) { // TODO use fixed-size matrices Matrix D_pose1_g_base1, D_pose1_g_pose1; diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h index 0318c3eb1..6d1ca832c 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h @@ -156,8 +156,7 @@ namespace gtsam { /* ************************************************************************* */ - gtsam::Vector whitenedError(const gtsam::Values& x, - boost::optional&> H = boost::none) const { + gtsam::Vector whitenedError(const gtsam::Values& x, OptionalMatrixVecType H = OptionalMatrixVecNone) const { T orgA_T_currA = valA_.at(keyA_); T orgB_T_currB = valB_.at(keyB_); @@ -186,6 +185,13 @@ namespace gtsam { return error; } + /* ************************************************************************* */ +#ifdef NO_BOOST_CPP17 + gtsam::Vector whitenedError(const gtsam::Values& x, std::vector& H) const { + return whitenedError(x, &H); + } +#endif + /* ************************************************************************* */ gtsam::Vector unwhitenedError(const gtsam::Values& x) const { diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 58553b81f..52ff220e1 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -179,8 +179,7 @@ namespace gtsam { /* ************************************************************************* */ - Vector whitenedError(const Values& x, - boost::optional&> H = boost::none) const { + Vector whitenedError(const Values& x, OptionalMatrixVecType H = OptionalMatrixVecNone) const { bool debug = true; @@ -244,6 +243,13 @@ namespace gtsam { return err_wh_eq; } + + /* ************************************************************************* */ +#ifdef NO_BOOST_CPP17 + Vector whitenedError(const Values& x, std::vector& H) const { + return whitenedError(x, &H); + } +#endif /* ************************************************************************* */ Vector calcIndicatorProb(const Values& x) const { diff --git a/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp index 59c4fdf53..952c4f8b3 100644 --- a/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp +++ b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp @@ -66,18 +66,13 @@ TEST(BiasedGPSFactor, jacobian) { Matrix actualH1, actualH2; factor.evaluateError(pose,bias, actualH1, actualH2); - Matrix numericalH1 = numericalDerivative21( - std::function(std::bind( - &BiasedGPSFactor::evaluateError, factor, std::placeholders::_1, - std::placeholders::_2, boost::none, boost::none)), - pose, bias, 1e-5); + std::function f = [&factor](const Pose3& pose, const Point3& bias) { + return factor.evaluateError(pose, bias); + }; + Matrix numericalH1 = numericalDerivative21(f, pose, bias, 1e-5); EXPECT(assert_equal(numericalH1,actualH1, 1E-5)); - Matrix numericalH2 = numericalDerivative22( - std::function(std::bind( - &BiasedGPSFactor::evaluateError, factor, std::placeholders::_1, - std::placeholders::_2, boost::none, boost::none)), - pose, bias, 1e-5); + Matrix numericalH2 = numericalDerivative22(f, pose, bias, 1e-5); EXPECT(assert_equal(numericalH2,actualH2, 1E-5)); } diff --git a/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp b/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp index c2b526ecd..0942af017 100644 --- a/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp +++ b/gtsam_unstable/slam/tests/testLocalOrientedPlane3Factor.cpp @@ -23,6 +23,9 @@ #include #include +#include "gtsam/base/Vector.h" +#include "gtsam/geometry/OrientedPlane3.h" +#include "gtsam/geometry/Pose3.h" using namespace std::placeholders; using namespace gtsam; @@ -141,10 +144,10 @@ TEST(LocalOrientedPlane3Factor, Derivatives) { LocalOrientedPlane3Factor factor(p, noise, poseKey, anchorPoseKey, planeKey); // Calculate numerical derivatives - auto f = - std::bind(&LocalOrientedPlane3Factor::evaluateError, factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, boost::none); + auto f = [&factor] (const Pose3& p1, const Pose3& p2, const OrientedPlane3& a_plane) { + return factor.evaluateError(p1, p2, a_plane); + }; + Matrix numericalH1 = numericalDerivative31(f, poseLin, anchorPoseLin, pLin); Matrix numericalH2 = numericalDerivative32( - std::bind(&TestPartialPriorFactor2::evaluateError, &factor, - std::placeholders::_1, boost::none), - pose); + [&factor](const Pose2& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -107,9 +105,7 @@ TEST(PartialPriorFactor, JacobianFullTranslation2) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPartialPriorFactor2::evaluateError, &factor, - std::placeholders::_1, boost::none), - pose); + [&factor](const Pose2& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -131,7 +127,7 @@ TEST(PartialPriorFactor, JacobianTheta) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPartialPriorFactor2::evaluateError, &factor, std::placeholders::_1, boost::none), pose); + [&factor](const Pose2& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -182,7 +178,7 @@ TEST(PartialPriorFactor, JacobianAtIdentity3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); + [&factor](const Pose3& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -204,7 +200,7 @@ TEST(PartialPriorFactor, JacobianPartialTranslation3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); + [&factor](const Pose3& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -228,7 +224,7 @@ TEST(PartialPriorFactor, JacobianFullTranslation3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); + [&factor](const Pose3& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -252,7 +248,7 @@ TEST(PartialPriorFactor, JacobianTxTz3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); + [&factor](const Pose3& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -275,7 +271,7 @@ TEST(PartialPriorFactor, JacobianFullRotation3) { // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPartialPriorFactor3::evaluateError, &factor, std::placeholders::_1, boost::none), pose); + [&factor](const Pose3& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative. Matrix actualH1; diff --git a/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp b/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp index cd5bf1d9e..977dad922 100644 --- a/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp +++ b/gtsam_unstable/slam/tests/testPoseBetweenFactor.cpp @@ -199,13 +199,9 @@ TEST( PoseBetweenFactor, Jacobian ) { // Calculate numerical derivatives Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPoseBetweenFactor::evaluateError, &factor, - std::placeholders::_1, pose2, boost::none, boost::none), - pose1); + [&factor, &pose2](const Pose3& p) { return factor.evaluateError(p, pose2); }, pose1); Matrix expectedH2 = numericalDerivative11( - std::bind(&TestPoseBetweenFactor::evaluateError, &factor, pose1, - std::placeholders::_1, boost::none, boost::none), - pose2); + [&factor, &pose1](const Pose3& p) { return factor.evaluateError(pose1, p); }, pose2); // Use the factor to calculate the derivative Matrix actualH1; @@ -234,13 +230,9 @@ TEST( PoseBetweenFactor, JacobianWithTransform ) { // Calculate numerical derivatives Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPoseBetweenFactor::evaluateError, &factor, - std::placeholders::_1, pose2, boost::none, boost::none), - pose1); + [&factor, &pose2](const Pose3& p) { return factor.evaluateError(p, pose2); }, pose1); Matrix expectedH2 = numericalDerivative11( - std::bind(&TestPoseBetweenFactor::evaluateError, &factor, pose1, - std::placeholders::_1, boost::none, boost::none), - pose2); + [&factor, &pose1](const Pose3& p) { return factor.evaluateError(pose1, p); }, pose2); // Use the factor to calculate the derivative Matrix actualH1; diff --git a/gtsam_unstable/slam/tests/testPosePriorFactor.cpp b/gtsam_unstable/slam/tests/testPosePriorFactor.cpp index dbbc02a8b..4bd3f9f9d 100644 --- a/gtsam_unstable/slam/tests/testPosePriorFactor.cpp +++ b/gtsam_unstable/slam/tests/testPosePriorFactor.cpp @@ -188,9 +188,7 @@ TEST( PosePriorFactor, Jacobian ) { // Calculate numerical derivatives Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPosePriorFactor::evaluateError, &factor, - std::placeholders::_1, boost::none), - pose); + [&factor](const Pose3& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative Matrix actualH1; @@ -215,9 +213,7 @@ TEST( PosePriorFactor, JacobianWithTransform ) { // Calculate numerical derivatives Matrix expectedH1 = numericalDerivative11( - std::bind(&TestPosePriorFactor::evaluateError, &factor, - std::placeholders::_1, boost::none), - pose); + [&factor](const Pose3& p) { return factor.evaluateError(p); }, pose); // Use the factor to calculate the derivative Matrix actualH1; diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.cpp b/gtsam_unstable/slam/tests/testPoseToPointFactor.cpp index 7345e2308..56df1c1e9 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.cpp +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.cpp @@ -67,9 +67,9 @@ TEST(PoseToPointFactor, jacobian_2D) { PoseToPointFactor factor(pose_key, point_key, l_meas, noise); // Calculate numerical derivatives - auto f = std::bind(&PoseToPointFactor::evaluateError, factor, - std::placeholders::_1, std::placeholders::_2, boost::none, - boost::none); + auto f = [&factor] (const Pose2& pose, const Point2& pt) { + return factor.evaluateError(pose, pt); + }; Matrix numerical_H1 = numericalDerivative21(f, p, l); Matrix numerical_H2 = numericalDerivative22(f, p, l); @@ -137,9 +137,10 @@ TEST(PoseToPointFactor, jacobian_3D) { PoseToPointFactor factor(pose_key, point_key, l_meas, noise); // Calculate numerical derivatives - auto f = std::bind(&PoseToPointFactor::evaluateError, factor, - std::placeholders::_1, std::placeholders::_2, boost::none, - boost::none); + auto f = [&factor] (const Pose3& pose, const Point3& pt) { + return factor.evaluateError(pose, pt); + }; + Matrix numerical_H1 = numericalDerivative21(f, p, l); Matrix numerical_H2 = numericalDerivative22(f, p, l); diff --git a/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp b/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp index c05f83a23..b40449703 100644 --- a/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp +++ b/gtsam_unstable/slam/tests/testProjectionFactorPPP.cpp @@ -177,11 +177,9 @@ TEST( ProjectionFactorPPP, Jacobian ) { // Verify H2 with numerical derivative Matrix H2Expected = numericalDerivative32( - std::function( - std::bind(&TestProjectionFactor::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), + [&factor](const Pose3& pose, const Pose3& transform, const Point3& point) { + return factor.evaluateError(pose, transform, point); + }, pose, Pose3(), point); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); @@ -215,11 +213,9 @@ TEST( ProjectionFactorPPP, JacobianWithTransform ) { // Verify H2 with numerical derivative Matrix H2Expected = numericalDerivative32( - std::function( - std::bind(&TestProjectionFactor::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), + [&factor](const Pose3& pose, const Pose3& transform, const Point3& point) { + return factor.evaluateError(pose, transform, point); + }, pose, body_P_sensor, point); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); diff --git a/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp b/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp index 6490dfc75..eafa97fa3 100644 --- a/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp +++ b/gtsam_unstable/slam/tests/testProjectionFactorPPPC.cpp @@ -136,15 +136,11 @@ TEST( ProjectionFactorPPPC, Jacobian ) { // Verify H2 and H4 with numerical derivatives Matrix H2Expected = numericalDerivative11( - std::bind(&TestProjectionFactor::evaluateError, &factor, pose, - std::placeholders::_1, point, *K1, boost::none, boost::none, - boost::none, boost::none), + [&factor, &point, &pose](const Pose3& pose_arg) { return factor.evaluateError(pose, pose_arg, point, *K1); }, Pose3()); Matrix H4Expected = numericalDerivative11( - std::bind(&TestProjectionFactor::evaluateError, &factor, pose, Pose3(), - point, std::placeholders::_1, boost::none, boost::none, - boost::none, boost::none), + [&factor, &point, &pose](const Cal3_S2& K_arg) { return factor.evaluateError(pose, Pose3(), point, K_arg); }, *K1); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); @@ -176,12 +172,16 @@ TEST( ProjectionFactorPPPC, JacobianWithTransform ) { // Verify H2 and H4 with numerical derivatives Matrix H2Expected = numericalDerivative11( - std::bind(&TestProjectionFactor::evaluateError, &factor, pose, std::placeholders::_1, point, - *K1, boost::none, boost::none, boost::none, boost::none), body_P_sensor); + [&factor, &pose, &point](const Pose3& body_P_sensor) { + return factor.evaluateError(pose, body_P_sensor, point, *K1); + }, + body_P_sensor); Matrix H4Expected = numericalDerivative11( - std::bind(&TestProjectionFactor::evaluateError, &factor, pose, body_P_sensor, point, - std::placeholders::_1, boost::none, boost::none, boost::none, boost::none), *K1); + [&factor, &pose, &body_P_sensor, &point](const Cal3_S2& K) { + return factor.evaluateError(pose, body_P_sensor, point, K); + }, + *K1); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); CHECK(assert_equal(H4Expected, H4Actual, 1e-5)); diff --git a/gtsam_unstable/slam/tests/testProjectionFactorRollingShutter.cpp b/gtsam_unstable/slam/tests/testProjectionFactorRollingShutter.cpp index 161c9aa55..3c7c39f48 100644 --- a/gtsam_unstable/slam/tests/testProjectionFactorRollingShutter.cpp +++ b/gtsam_unstable/slam/tests/testProjectionFactorRollingShutter.cpp @@ -230,30 +230,15 @@ TEST(ProjectionFactorRollingShutter, Jacobian) { Matrix H1Actual, H2Actual, H3Actual; factor.evaluateError(pose1, pose2, point, H1Actual, H2Actual, H3Actual); + auto f = [&factor](const Pose3& p1, const Pose3& p2, const Point3& p3) { + return factor.evaluateError(p1, p2, p3); + }; // Expected Jacobians via numerical derivatives - Matrix H1Expected = numericalDerivative31( - std::function( - std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - pose1, pose2, point); + Matrix H1Expected = numericalDerivative31(f, pose1, pose2, point); - Matrix H2Expected = numericalDerivative32( - std::function( - std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - pose1, pose2, point); + Matrix H2Expected = numericalDerivative32(f, pose1, pose2, point); - Matrix H3Expected = numericalDerivative33( - std::function( - std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - pose1, pose2, point); + Matrix H3Expected = numericalDerivative33(f, pose1, pose2, point); CHECK(assert_equal(H1Expected, H1Actual, 1e-5)); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); @@ -280,30 +265,15 @@ TEST(ProjectionFactorRollingShutter, JacobianWithTransform) { Matrix H1Actual, H2Actual, H3Actual; factor.evaluateError(pose1, pose2, point, H1Actual, H2Actual, H3Actual); + auto f = [&factor](const Pose3& p1, const Pose3& p2, const Point3& p3) { + return factor.evaluateError(p1, p2, p3); + }; // Expected Jacobians via numerical derivatives - Matrix H1Expected = numericalDerivative31( - std::function( - std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - pose1, pose2, point); + Matrix H1Expected = numericalDerivative31(f, pose1, pose2, point); - Matrix H2Expected = numericalDerivative32( - std::function( - std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - pose1, pose2, point); + Matrix H2Expected = numericalDerivative32(f, pose1, pose2, point); - Matrix H3Expected = numericalDerivative33( - std::function( - std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor, - std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, boost::none, boost::none, - boost::none)), - pose1, pose2, point); + Matrix H3Expected = numericalDerivative33(f, pose1, pose2, point); CHECK(assert_equal(H1Expected, H1Actual, 1e-5)); CHECK(assert_equal(H2Expected, H2Actual, 1e-5)); diff --git a/gtsam_unstable/slam/tests/testTSAMFactors.cpp b/gtsam_unstable/slam/tests/testTSAMFactors.cpp index fbb21e191..5283388a0 100644 --- a/gtsam_unstable/slam/tests/testTSAMFactors.cpp +++ b/gtsam_unstable/slam/tests/testTSAMFactors.cpp @@ -20,6 +20,7 @@ #include #include +#include "gtsam/geometry/Point2.h" using namespace std::placeholders; using namespace std; @@ -46,12 +47,11 @@ TEST( DeltaFactor, all ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected; + H1Expected = numericalDerivative11( - std::bind(&DeltaFactor::evaluateError, &factor, std::placeholders::_1, point, boost::none, - boost::none), pose); + [&factor, &point](const Pose2& pose) { return factor.evaluateError(pose, point); }, pose); H2Expected = numericalDerivative11( - std::bind(&DeltaFactor::evaluateError, &factor, pose, std::placeholders::_1, boost::none, - boost::none), point); + [&factor, &pose](const Point2& point) { return factor.evaluateError(pose, point); }, point); // Verify the Jacobians are correct EXPECT(assert_equal(H1Expected, H1Actual, 1e-9)); @@ -81,17 +81,25 @@ TEST( DeltaFactorBase, all ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected, H3Expected, H4Expected; H1Expected = numericalDerivative11( - std::bind(&DeltaFactorBase::evaluateError, &factor, std::placeholders::_1, pose, base2, - point, boost::none, boost::none, boost::none, boost::none), base1); + [&factor, &pose, &base2, &point](const Pose2& pose_arg) { + return factor.evaluateError(pose_arg, pose, base2, point); + }, + base1); H2Expected = numericalDerivative11( - std::bind(&DeltaFactorBase::evaluateError, &factor, base1, std::placeholders::_1, base2, - point, boost::none, boost::none, boost::none, boost::none), pose); + [&factor, &point, &base1, &base2](const Pose2& pose_arg) { + return factor.evaluateError(base1, pose_arg, base2, point); + }, + pose); H3Expected = numericalDerivative11( - std::bind(&DeltaFactorBase::evaluateError, &factor, base1, pose, std::placeholders::_1, - point, boost::none, boost::none, boost::none, boost::none), base2); + [&factor, &pose, &base1, &point](const Pose2& pose_arg) { + return factor.evaluateError(base1, pose, pose_arg, point); + }, + base2); H4Expected = numericalDerivative11( - std::bind(&DeltaFactorBase::evaluateError, &factor, base1, pose, base2, - std::placeholders::_1, boost::none, boost::none, boost::none, boost::none), point); + [&factor, &pose, &base1, &base2](const Point2& point_arg) { + return factor.evaluateError(base1, pose, base2, point_arg); + }, + point); // Verify the Jacobians are correct EXPECT(assert_equal(H1Expected, H1Actual, 1e-9)); @@ -121,18 +129,26 @@ TEST( OdometryFactorBase, all ) { // Use numerical derivatives to calculate the Jacobians Matrix H1Expected, H2Expected, H3Expected, H4Expected; + // using lambdas to replace bind H1Expected = numericalDerivative11( - std::bind(&OdometryFactorBase::evaluateError, &factor, std::placeholders::_1, pose1, base2, - pose2, boost::none, boost::none, boost::none, boost::none), base1); + [&factor, &pose1, &pose2, &base2](const Pose2& pose_arg) { + return factor.evaluateError(pose_arg, pose1, base2, pose2); + }, + base1); H2Expected = numericalDerivative11( - std::bind(&OdometryFactorBase::evaluateError, &factor, base1, std::placeholders::_1, base2, - pose2, boost::none, boost::none, boost::none, boost::none), pose1); + [&factor, &pose2, &base1, &base2](const Pose2& pose_arg) { + return factor.evaluateError(base1, pose_arg, base2, pose2); + }, + pose1); H3Expected = numericalDerivative11( - std::bind(&OdometryFactorBase::evaluateError, &factor, base1, pose1, std::placeholders::_1, - pose2, boost::none, boost::none, boost::none, boost::none), base2); + [&factor, &pose1, &base1, &pose2](const Pose2& pose_arg) { + return factor.evaluateError(base1, pose1, pose_arg, pose2); + }, + base2); H4Expected = numericalDerivative11( - std::bind(&OdometryFactorBase::evaluateError, &factor, base1, pose1, - base2, std::placeholders::_1, boost::none, boost::none, boost::none, boost::none), + [&factor, &pose1, &base1, &base2](const Pose2& pose_arg) { + return factor.evaluateError(base1, pose1, base2, pose_arg); + }, pose2); // Verify the Jacobians are correct