diff --git a/corelib/src/optimizer/OptimizerGTSAM.cpp b/corelib/src/optimizer/OptimizerGTSAM.cpp index 484c370021..ac2afff0a4 100644 --- a/corelib/src/optimizer/OptimizerGTSAM.cpp +++ b/corelib/src/optimizer/OptimizerGTSAM.cpp @@ -527,7 +527,7 @@ std::map OptimizerGTSAM::optimize( { float x,y,z,roll,pitch,yaw; std::map tmpPoses; -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40200 for(gtsam::Values::deref_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter) #else for(gtsam::Values::const_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter) @@ -634,7 +634,7 @@ std::map OptimizerGTSAM::optimize( optimizer->iterations(), optimizer->error(), graph.error(initialEstimate), graph.error(optimizer->values()), timer.ticks()); float x,y,z,roll,pitch,yaw; -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40200 for(gtsam::Values::deref_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter) #else for(gtsam::Values::const_iterator iter=optimizer->values().begin(); iter!=optimizer->values().end(); ++iter) diff --git a/corelib/src/optimizer/gtsam/GravityFactor.h b/corelib/src/optimizer/gtsam/GravityFactor.h index 21e0116eec..0ca1a75a77 100644 --- a/corelib/src/optimizer/gtsam/GravityFactor.h +++ b/corelib/src/optimizer/gtsam/GravityFactor.h @@ -63,14 +63,14 @@ class GravityFactor { /** vector of errors */ Vector attitudeError(const Rot3& p, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalJacobian<2,3> H = {}) const; #else OptionalJacobian<2,3> H = boost::none) const; #endif /** Serialization function */ -#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_MAJOR < 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR < 3) +#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_NUMERIC < 40300 friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -91,7 +91,7 @@ class Rot3GravityFactor: public NoiseModelFactor1, public GravityFactor { public: /// shorthand for a smart pointer to a factor -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 typedef std::shared_ptr shared_ptr; #else typedef boost::shared_ptr shared_ptr; @@ -121,7 +121,7 @@ class Rot3GravityFactor: public NoiseModelFactor1, public GravityFactor { /// @return a deep copy of this factor virtual gtsam::NonlinearFactor::shared_ptr clone() const { -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 return std::static_pointer_cast( #else return boost::static_pointer_cast( @@ -138,7 +138,7 @@ class Rot3GravityFactor: public NoiseModelFactor1, public GravityFactor { /** vector of errors */ virtual Vector evaluateError(const Rot3& nRb, // -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H = OptionalNone) const { #else boost::optional H = boost::none) const { @@ -153,7 +153,7 @@ class Rot3GravityFactor: public NoiseModelFactor1, public GravityFactor { } private: -#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_MAJOR < 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR < 3) +#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_NUMERIC < 40300 /** Serialization function */ friend class boost::serialization::access; template @@ -182,7 +182,7 @@ class Pose3GravityFactor: public NoiseModelFactor1, public: /// shorthand for a smart pointer to a factor -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 typedef std::shared_ptr shared_ptr; #else typedef boost::shared_ptr shared_ptr; @@ -211,7 +211,7 @@ class Pose3GravityFactor: public NoiseModelFactor1, /// @return a deep copy of this factor virtual gtsam::NonlinearFactor::shared_ptr clone() const { -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 return std::static_pointer_cast( #else return boost::static_pointer_cast( @@ -228,7 +228,7 @@ class Pose3GravityFactor: public NoiseModelFactor1, /** vector of errors */ virtual Vector evaluateError(const Pose3& nTb, // -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H = OptionalNone) const { #else boost::optional H = boost::none) const { @@ -249,7 +249,7 @@ class Pose3GravityFactor: public NoiseModelFactor1, } private: -#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_MAJOR < 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR < 3) +#if defined(GTSAM_ENABLE_BOOST_SERIALIZATION) || GTSAM_VERSION_NUMERIC < 40300 /** Serialization function */ friend class boost::serialization::access; template diff --git a/corelib/src/optimizer/gtsam/XYFactor.h b/corelib/src/optimizer/gtsam/XYFactor.h index c4afd3a989..8a7c65585c 100644 --- a/corelib/src/optimizer/gtsam/XYFactor.h +++ b/corelib/src/optimizer/gtsam/XYFactor.h @@ -42,7 +42,7 @@ class XYFactor: public gtsam::NoiseModelFactor1 { // @param p the pose in Pose2 // @param H the optional Jacobian matrix, which use boost optional and has default null pointer gtsam::Vector evaluateError(const VALUE& p, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H = OptionalNone) const { #else boost::optional H = boost::none) const { diff --git a/corelib/src/optimizer/gtsam/XYZFactor.h b/corelib/src/optimizer/gtsam/XYZFactor.h index 90b293a22f..42e55d0b83 100644 --- a/corelib/src/optimizer/gtsam/XYZFactor.h +++ b/corelib/src/optimizer/gtsam/XYZFactor.h @@ -42,7 +42,7 @@ class XYZFactor: public gtsam::NoiseModelFactor1 { // @param p the pose in Pose // @param H the optional Jacobian matrix, which use boost optional and has default null pointer gtsam::Vector evaluateError(const gtsam::Pose3& p, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H = OptionalNone) const { #else boost::optional H = boost::none) const { @@ -54,7 +54,7 @@ class XYZFactor: public gtsam::NoiseModelFactor1 { return (gtsam::Vector3() << p.x() - mx_, p.y() - my_, p.z() - mz_).finished(); } gtsam::Vector evaluateError(const gtsam::Point3& p, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H = OptionalNone) const { #else boost::optional H = boost::none) const { diff --git a/corelib/src/optimizer/vertigo/gtsam/DerivedValue.h b/corelib/src/optimizer/vertigo/gtsam/DerivedValue.h index 20cd2849d3..ea502a4c6a 100644 --- a/corelib/src/optimizer/vertigo/gtsam/DerivedValue.h +++ b/corelib/src/optimizer/vertigo/gtsam/DerivedValue.h @@ -72,7 +72,7 @@ class DerivedValue : public gtsam::Value { /** * Clone this value (normal clone on the heap, delete with 'delete' operator) */ -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 virtual std::shared_ptr clone() const { return std::make_shared(static_cast(*this)); } diff --git a/corelib/src/optimizer/vertigo/gtsam/betweenFactorMaxMix.h b/corelib/src/optimizer/vertigo/gtsam/betweenFactorMaxMix.h index 0ee996f64f..40538fc0f0 100644 --- a/corelib/src/optimizer/vertigo/gtsam/betweenFactorMaxMix.h +++ b/corelib/src/optimizer/vertigo/gtsam/betweenFactorMaxMix.h @@ -12,7 +12,7 @@ #include #include -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR==4 && GTSAM_VERSION_MINOR>=1) +#if GTSAM_VERSION_NUMERIC >= 40100 namespace gtsam { gtsam::Matrix inverse(const gtsam::Matrix & matrix) { @@ -49,7 +49,7 @@ namespace vertigo { double nu1 = 1.0/sqrt(gtsam::inverse(info1).determinant()); double l1 = nu1 * exp(-0.5*m1); -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR==4 && GTSAM_VERSION_MINOR>=1) +#if GTSAM_VERSION_NUMERIC >= 40100 double m2 = nullHypothesisModel->squaredMahalanobisDistance(error); #else double m2 = nullHypothesisModel->distance(error); diff --git a/corelib/src/optimizer/vertigo/gtsam/betweenFactorSwitchable.h b/corelib/src/optimizer/vertigo/gtsam/betweenFactorSwitchable.h index 0bc35cc136..de1b4d7364 100644 --- a/corelib/src/optimizer/vertigo/gtsam/betweenFactorSwitchable.h +++ b/corelib/src/optimizer/vertigo/gtsam/betweenFactorSwitchable.h @@ -30,7 +30,7 @@ namespace vertigo { betweenFactor(key1, key2, measured, model) {}; gtsam::Vector evaluateError(const VALUE& p1, const VALUE& p2, const SwitchVariableLinear& s, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H1 = OptionalNone, OptionalMatrixType H2 = OptionalNone, OptionalMatrixType H3 = OptionalNone) const @@ -70,7 +70,7 @@ namespace vertigo { betweenFactor(key1, key2, measured, model) {}; gtsam::Vector evaluateError(const VALUE& p1, const VALUE& p2, const SwitchVariableSigmoid& s, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H1 = OptionalNone, OptionalMatrixType H2 = OptionalNone, OptionalMatrixType H3 = OptionalNone) const diff --git a/corelib/src/optimizer/vertigo/gtsam/switchVariableLinear.h b/corelib/src/optimizer/vertigo/gtsam/switchVariableLinear.h index f6282d67dd..e95e0b568b 100644 --- a/corelib/src/optimizer/vertigo/gtsam/switchVariableLinear.h +++ b/corelib/src/optimizer/vertigo/gtsam/switchVariableLinear.h @@ -76,7 +76,7 @@ namespace vertigo { /** between operation */ inline SwitchVariableLinear between(const SwitchVariableLinear& l2, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H1=OptionalNone, OptionalMatrixType H2=OptionalNone) const { #else @@ -121,7 +121,7 @@ template<> struct traits { typedef OptionalJacobian<3, 3> ChartJacobian; typedef gtsam::Vector TangentVector; static TangentVector Local(const vertigo::SwitchVariableLinear& origin, const vertigo::SwitchVariableLinear& other, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 ChartJacobian Horigin = {}, ChartJacobian Hother = {}) { #else ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) { @@ -129,7 +129,7 @@ template<> struct traits { return origin.localCoordinates(other); } static vertigo::SwitchVariableLinear Retract(const vertigo::SwitchVariableLinear& g, const TangentVector& v, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 ChartJacobian H1 = {}, ChartJacobian H2 = {}) { #else ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { diff --git a/corelib/src/optimizer/vertigo/gtsam/switchVariableSigmoid.h b/corelib/src/optimizer/vertigo/gtsam/switchVariableSigmoid.h index 5cc69c34a0..79e1fca99d 100644 --- a/corelib/src/optimizer/vertigo/gtsam/switchVariableSigmoid.h +++ b/corelib/src/optimizer/vertigo/gtsam/switchVariableSigmoid.h @@ -76,7 +76,7 @@ namespace vertigo { /** between operation */ inline SwitchVariableSigmoid between(const SwitchVariableSigmoid& l2, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 OptionalMatrixType H1=OptionalNone, OptionalMatrixType H2=OptionalNone) const { #else @@ -122,7 +122,7 @@ template<> struct traits { typedef OptionalJacobian<3, 3> ChartJacobian; typedef gtsam::Vector TangentVector; static TangentVector Local(const vertigo::SwitchVariableSigmoid& origin, const vertigo::SwitchVariableSigmoid& other, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 ChartJacobian Horigin = {}, ChartJacobian Hother = {}) { #else ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) { @@ -130,7 +130,7 @@ template<> struct traits { return origin.localCoordinates(other); } static vertigo::SwitchVariableSigmoid Retract(const vertigo::SwitchVariableSigmoid& g, const TangentVector& v, -#if GTSAM_VERSION_MAJOR > 4 || (GTSAM_VERSION_MAJOR == 4 && GTSAM_VERSION_MINOR >= 3) +#if GTSAM_VERSION_NUMERIC >= 40300 ChartJacobian H1 = {}, ChartJacobian H2 = {}) { #else ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {