diff --git a/.github/scripts/python.sh b/.github/scripts/python.sh index 718eee5ea..99fddda68 100644 --- a/.github/scripts/python.sh +++ b/.github/scripts/python.sh @@ -79,7 +79,7 @@ function build() -DGTSAM_UNSTABLE_BUILD_PYTHON=${GTSAM_BUILD_UNSTABLE:-ON} \ -DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \ -DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V42=OFF \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V43=OFF \ -DCMAKE_INSTALL_PREFIX=$GITHUB_WORKSPACE/gtsam_install diff --git a/.github/scripts/unix.sh b/.github/scripts/unix.sh index b5a559df5..87b0a3100 100644 --- a/.github/scripts/unix.sh +++ b/.github/scripts/unix.sh @@ -64,7 +64,7 @@ function configure() -DGTSAM_BUILD_UNSTABLE=${GTSAM_BUILD_UNSTABLE:-ON} \ -DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ - -DGTSAM_ALLOW_DEPRECATED_SINCE_V42=${GTSAM_ALLOW_DEPRECATED_SINCE_V42:-OFF} \ + -DGTSAM_ALLOW_DEPRECATED_SINCE_V43=${GTSAM_ALLOW_DEPRECATED_SINCE_V43:-OFF} \ -DGTSAM_USE_QUATERNIONS=${GTSAM_USE_QUATERNIONS:-OFF} \ -DGTSAM_ROT3_EXPMAP=${GTSAM_ROT3_EXPMAP:-ON} \ -DGTSAM_POSE3_EXPMAP=${GTSAM_POSE3_EXPMAP:-ON} \ diff --git a/.github/workflows/build-special.yml b/.github/workflows/build-special.yml index ef7d7723d..458394211 100644 --- a/.github/workflows/build-special.yml +++ b/.github/workflows/build-special.yml @@ -110,8 +110,8 @@ jobs: - name: Set Allow Deprecated Flag if: matrix.flag == 'deprecated' run: | - echo "GTSAM_ALLOW_DEPRECATED_SINCE_V42=ON" >> $GITHUB_ENV - echo "Allow deprecated since version 4.1" + echo "GTSAM_ALLOW_DEPRECATED_SINCE_V43=ON" >> $GITHUB_ENV + echo "Allow deprecated since version 4.3" - name: Set Use Quaternions Flag if: matrix.flag == 'quaternions' diff --git a/CMakeLists.txt b/CMakeLists.txt index 21f8b28a1..9be0d89a9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,11 +6,7 @@ if(NOT DEFINED CMAKE_MACOSX_RPATH) set(CMAKE_MACOSX_RPATH 0) endif() -option(GTSAM_NO_BOOST_CPP17 "Require and use boost" ON) - -if (GTSAM_NO_BOOST_CPP17) - set(CMAKE_CXX_STANDARD 17) -endif() +set(CMAKE_CXX_STANDARD 17) # Set the version number for the library set (GTSAM_VERSION_MAJOR 4) @@ -57,11 +53,7 @@ endif() include(cmake/HandleGeneralOptions.cmake) # CMake build options # Libraries: -if (GTSAM_NO_BOOST_CPP17) - include(cmake/HandleBoost.cmake) # Boost - add_definitions(-DNO_BOOST_CPP17) -endif() - +include(cmake/HandleBoost.cmake) # Boost include(cmake/HandleCCache.cmake) # ccache include(cmake/HandleCPack.cmake) # CPack include(cmake/HandleEigen.cmake) # Eigen3 diff --git a/README.md b/README.md index 87d79d557..10a239f97 100644 --- a/README.md +++ b/README.md @@ -55,11 +55,6 @@ Optional prerequisites - used automatically if findable by CMake: GTSAM 4 introduces several new features, most notably Expressions and a Python toolbox. It also introduces traits, a C++ technique that allows optimizing with non-GTSAM types. That opens the door to retiring geometric types such as Point2 and Point3 to pure Eigen types, which we also do. A significant change which will not trigger a compile error is that zero-initializing of Point2 and Point3 is deprecated, so please be aware that this might render functions using their default constructor incorrect. -GTSAM 4 also deprecated some legacy functionality and wrongly named methods. If you are on a 4.0.X release, you can define the flag `GTSAM_ALLOW_DEPRECATED_SINCE_V4` to use the deprecated methods. - -GTSAM 4.1 added a new pybind wrapper, and **removed** the deprecated functionality. There is a flag `GTSAM_ALLOW_DEPRECATED_SINCE_V42` for newly deprecated methods since the 4.1 release, which is on by default, allowing anyone to just pull version 4.1 and compile. - - ## Wrappers We provide support for [MATLAB](matlab/README.md) and [Python](python/README.md) wrappers for GTSAM. Please refer to the linked documents for more details. diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 0db9538f2..e8f01a1f0 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -142,17 +142,14 @@ endif() if (NOT CMAKE_VERSION VERSION_LESS 3.8) set(GTSAM_COMPILE_FEATURES_PUBLIC "cxx_std_17" CACHE STRING "CMake compile features property for all gtsam targets.") # See: https://cmake.org/cmake/help/latest/prop_tgt/CXX_EXTENSIONS.html - # TODO(dellaert): is following line still needed or was that only for c++11? set(CMAKE_CXX_EXTENSIONS OFF) if (MSVC) # NOTE(jlblanco): seems to be required in addition to the cxx_std_17 above? - # TODO(dellaert): is this the right syntax below? list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC /std:c++latest) endif() else() # Old cmake versions: if (NOT MSVC) - # TODO(dellaert): I just changed 11 to 17 below, hopefully that works list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC $<$:-std=c++17>) endif() endif() diff --git a/cmake/HandleGeneralOptions.cmake b/cmake/HandleGeneralOptions.cmake index 7c8f8533f..64fa6b407 100644 --- a/cmake/HandleGeneralOptions.cmake +++ b/cmake/HandleGeneralOptions.cmake @@ -25,7 +25,7 @@ option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will a option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) option(GTSAM_BUILD_PYTHON "Enable/Disable building & installation of Python module with pybind11" OFF) option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" OFF) -option(GTSAM_ALLOW_DEPRECATED_SINCE_V42 "Allow use of methods/functions deprecated in GTSAM 4.1" ON) +option(GTSAM_ALLOW_DEPRECATED_SINCE_V43 "Allow use of methods/functions deprecated in GTSAM 4.3" ON) option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON) option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" ON) option(GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR "Use the slower but correct version of BetweenFactor" OFF) diff --git a/cmake/HandlePrintConfiguration.cmake b/cmake/HandlePrintConfiguration.cmake index 04d27c27f..dd3f6fc1f 100644 --- a/cmake/HandlePrintConfiguration.cmake +++ b/cmake/HandlePrintConfiguration.cmake @@ -87,7 +87,7 @@ print_enabled_config(${GTSAM_USE_QUATERNIONS} "Quaternions as defaul print_enabled_config(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") print_enabled_config(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") print_enabled_config(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") -print_enabled_config(${GTSAM_ALLOW_DEPRECATED_SINCE_V42} "Allow features deprecated in GTSAM 4.1") +print_enabled_config(${GTSAM_ALLOW_DEPRECATED_SINCE_V43} "Allow features deprecated in GTSAM 4.3") print_enabled_config(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h index 3ade1cc2e..020a5691c 100644 --- a/gtsam/base/TestableAssertions.h +++ b/gtsam/base/TestableAssertions.h @@ -72,37 +72,6 @@ bool assert_equal(const V& expected, const std::optional& actual, double tol } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -/** - * Version of assert_equals to work with vectors - * @deprecated: use container equals instead - */ -template -bool GTSAM_DEPRECATED assert_equal(const std::vector& expected, const std::vector& actual, double tol = 1e-9) { - bool match = true; - if (expected.size() != actual.size()) - match = false; - if(match) { - size_t i = 0; - for(const V& a: expected) { - if (!assert_equal(a, actual[i++], tol)) { - match = false; - break; - } - } - } - if(!match) { - std::cout << "expected: " << std::endl; - for(const V& a: expected) { std::cout << a << " "; } - std::cout << "\nactual: " << std::endl; - for(const V& a: actual) { std::cout << a << " "; } - std::cout << std::endl; - return false; - } - return true; -} -#endif - /** * Function for comparing maps of testable->testable * TODO: replace with more generalized version diff --git a/gtsam/base/Vector.h b/gtsam/base/Vector.h index f7923ff88..f9a5cf079 100644 --- a/gtsam/base/Vector.h +++ b/gtsam/base/Vector.h @@ -204,28 +204,6 @@ inline double inner_prod(const V1 &a, const V2& b) { return a.dot(b); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -/** - * BLAS Level 1 scal: x <- alpha*x - * @deprecated: use operators instead - */ -inline void GTSAM_DEPRECATED scal(double alpha, Vector& x) { x *= alpha; } - -/** - * BLAS Level 1 axpy: y <- alpha*x + y - * @deprecated: use operators instead - */ -template -inline void GTSAM_DEPRECATED axpy(double alpha, const V1& x, V2& y) { - assert (y.size()==x.size()); - y += alpha * x; -} -inline void axpy(double alpha, const Vector& x, SubVector y) { - assert (y.size()==x.size()); - y += alpha * x; -} -#endif - /** * house(x,j) computes HouseHolder vector v and scaling factor beta * from x, such that the corresponding Householder reflection zeroes out diff --git a/gtsam/config.h.in b/gtsam/config.h.in index d47329a62..7f8936d1e 100644 --- a/gtsam/config.h.in +++ b/gtsam/config.h.in @@ -70,7 +70,7 @@ #cmakedefine GTSAM_THROW_CHEIRALITY_EXCEPTION // Make sure dependent projects that want it can see deprecated functions -#cmakedefine GTSAM_ALLOW_DEPRECATED_SINCE_V42 +#cmakedefine GTSAM_ALLOW_DEPRECATED_SINCE_V43 // Support Metis-based nested dissection #cmakedefine GTSAM_SUPPORT_NESTED_DISSECTION diff --git a/gtsam/discrete/DiscreteBayesNet.cpp b/gtsam/discrete/DiscreteBayesNet.cpp index 7cd190cc2..97734c3bb 100644 --- a/gtsam/discrete/DiscreteBayesNet.cpp +++ b/gtsam/discrete/DiscreteBayesNet.cpp @@ -51,26 +51,6 @@ double DiscreteBayesNet::evaluate(const DiscreteValues& values) const { return result; } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -DiscreteValues DiscreteBayesNet::optimize() const { - DiscreteValues result; - return optimize(result); -} - -DiscreteValues DiscreteBayesNet::optimize(DiscreteValues result) const { - // solve each node in turn in topological sort order (parents first) -#ifdef _MSC_VER -#pragma message("DiscreteBayesNet::optimize (deprecated) does not compute MPE!") -#else -#warning "DiscreteBayesNet::optimize (deprecated) does not compute MPE!" -#endif - for (auto conditional : boost::adaptors::reverse(*this)) - conditional->solveInPlace(&result); - return result; -} -#endif - /* ************************************************************************* */ DiscreteValues DiscreteBayesNet::sample() const { DiscreteValues result; diff --git a/gtsam/discrete/DiscreteBayesNet.h b/gtsam/discrete/DiscreteBayesNet.h index 700f81d7e..f3b4a58f5 100644 --- a/gtsam/discrete/DiscreteBayesNet.h +++ b/gtsam/discrete/DiscreteBayesNet.h @@ -149,15 +149,6 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet { /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated functionality - /// @{ - - DiscreteValues GTSAM_DEPRECATED optimize() const; - DiscreteValues GTSAM_DEPRECATED optimize(DiscreteValues given) const; - /// @} -#endif - private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index 214bc64da..b4f58a5bd 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -235,57 +235,6 @@ DecisionTreeFactor::shared_ptr DiscreteConditional::likelihood( return likelihood(values); } -/* ************************************************************************** */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -void DiscreteConditional::solveInPlace(DiscreteValues* values) const { - ADT pFS = choose(*values, true); // P(F|S=parentsValues) - - // Initialize - DiscreteValues mpe; - double maxP = 0; - - // Get all Possible Configurations - const auto allPosbValues = frontalAssignments(); - - // Find the maximum - for (const auto& frontalVals : allPosbValues) { - double pValueS = pFS(frontalVals); // P(F=value|S=parentsValues) - // Update maximum solution if better - if (pValueS > maxP) { - maxP = pValueS; - mpe = frontalVals; - } - } - - // set values (inPlace) to maximum - for (Key j : frontals()) { - (*values)[j] = mpe[j]; - } -} - -/* ************************************************************************** */ -size_t DiscreteConditional::solve(const DiscreteValues& parentsValues) const { - ADT pFS = choose(parentsValues, true); // P(F|S=parentsValues) - - // Then, find the max over all remaining - size_t max = 0; - double maxP = 0; - DiscreteValues frontals; - assert(nrFrontals() == 1); - Key j = (firstFrontalKey()); - for (size_t value = 0; value < cardinality(j); value++) { - frontals[j] = value; - double pValueS = pFS(frontals); // P(F=value|S=parentsValues) - // Update solution if better - if (pValueS > maxP) { - maxP = pValueS; - max = value; - } - } - return max; -} -#endif - /* ************************************************************************** */ size_t DiscreteConditional::argmax() const { size_t maxValue = 0; diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index a4e1f011b..03c44649f 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -263,14 +263,6 @@ class GTSAM_EXPORT DiscreteConditional /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated functionality - /// @{ - size_t GTSAM_DEPRECATED solve(const DiscreteValues& parentsValues) const; - void GTSAM_DEPRECATED solveInPlace(DiscreteValues* parentsValues) const; - /// @} -#endif - protected: /// Internal version of choose DiscreteConditional::ADT choose(const DiscreteValues& given, diff --git a/gtsam/discrete/DiscreteDistribution.h b/gtsam/discrete/DiscreteDistribution.h index bf3f1c9ae..4b690da15 100644 --- a/gtsam/discrete/DiscreteDistribution.h +++ b/gtsam/discrete/DiscreteDistribution.h @@ -93,12 +93,6 @@ class GTSAM_EXPORT DiscreteDistribution : public DiscreteConditional { std::vector pmf() const; /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated functionality - /// @{ - size_t GTSAM_DEPRECATED solve() const { return Base::solve({}); } - /// @} -#endif }; // DiscreteDistribution diff --git a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp index 2d79b9de9..9439ff417 100644 --- a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp +++ b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp @@ -209,13 +209,6 @@ TEST(DiscreteFactorGraph, marginalIsNotMPE) { auto actualMPE = graph.optimize(); EXPECT(assert_equal(mpe, actualMPE)); EXPECT_DOUBLES_EQUAL(0.315789, graph(mpe), 1e-5); // regression - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - // Optimize on BayesNet maximizes marginal, then the conditional marginals: - auto notOptimal = bayesNet.optimize(); - EXPECT(graph(notOptimal) < graph(mpe)); - EXPECT_DOUBLES_EQUAL(0.263158, graph(notOptimal), 1e-5); // regression -#endif } /* ************************************************************************* */ @@ -246,10 +239,6 @@ TEST(DiscreteFactorGraph, testMPE_Darwiche09book_p244) { ordering += Key(0), Key(1), Key(2), Key(3), Key(4); auto chordal = graph.eliminateSequential(ordering); EXPECT_LONGS_EQUAL(5, chordal->size()); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - auto notOptimal = chordal->optimize(); // not MPE ! - EXPECT(graph(notOptimal) < graph(mpe)); -#endif // Let us create the Bayes tree here, just for fun, because we don't use it DiscreteBayesTree::shared_ptr bayesTree = diff --git a/gtsam/geometry/Cal3.h b/gtsam/geometry/Cal3.h index 6f446c8b3..eb7d1ff27 100644 --- a/gtsam/geometry/Cal3.h +++ b/gtsam/geometry/Cal3.h @@ -170,11 +170,6 @@ class GTSAM_EXPORT Cal3 { return K; } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /** @deprecated The following function has been deprecated, use K above */ - Matrix3 GTSAM_DEPRECATED matrix() const { return K(); } -#endif - /// Return inverted calibration matrix inv(K) Matrix3 inverse() const; diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index f333c2f02..2a32f6297 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -100,14 +100,6 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { Vector3 vector() const; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// get parameter u0 - inline double GTSAM_DEPRECATED u0() const { return u0_; } - - /// get parameter v0 - inline double GTSAM_DEPRECATED v0() const { return v0_; } -#endif - /** * @brief: convert intrinsic coordinates xy to image coordinates uv * Version of uncalibrate with derivatives diff --git a/gtsam/geometry/Pose2.cpp b/gtsam/geometry/Pose2.cpp index d7996f74f..0d9f1bc01 100644 --- a/gtsam/geometry/Pose2.cpp +++ b/gtsam/geometry/Pose2.cpp @@ -371,15 +371,5 @@ std::optional Pose2::Align(const Matrix& a, const Matrix& b) { return Pose2::Align(ab_pairs); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -std::optional align(const Point2Pairs& ba_pairs) { - Point2Pairs ab_pairs; - for (const Point2Pair &baPair : ba_pairs) { - ab_pairs.emplace_back(baPair.second, baPair.first); - } - return Pose2::Align(ab_pairs); -} -#endif - /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 7a6a846be..c106cb4d4 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -346,16 +346,6 @@ inline Matrix wedge(const Vector& xi) { return Matrix(Pose2::wedge(xi(0),xi(1),xi(2))).eval(); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -/** - * @deprecated Use static constructor (with reversed pairs!) - * Calculate pose between a vector of 2D point correspondences (p,q) - * where q = Pose2::transformFrom(p) = t + R*p - */ -GTSAM_EXPORT std::optional -GTSAM_DEPRECATED align(const Point2Pairs& pairs); -#endif - // Convenience typedef using Pose2Pair = std::pair; using Pose2Pairs = std::vector; diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 3779d401a..aed055300 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -478,16 +478,6 @@ std::optional Pose3::Align(const Matrix& a, const Matrix& b) { return Pose3::Align(abPointPairs); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -std::optional align(const Point3Pairs &baPointPairs) { - Point3Pairs abPointPairs; - for (const Point3Pair &baPair : baPointPairs) { - abPointPairs.emplace_back(baPair.second, baPair.first); - } - return Pose3::Align(abPointPairs); -} -#endif - /* ************************************************************************* */ Pose3 Pose3::slerp(double t, const Pose3& other, OptionalJacobian<6, 6> Hx, OptionalJacobian<6, 6> Hy) const { return interpolate(*this, other, t, Hx, Hy); diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index 6db5e1919..e854d03b7 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -227,19 +227,6 @@ double Rot3::yaw(OptionalJacobian<1, 3> H) const { return y; } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -Vector Rot3::quaternion() const { - gtsam::Quaternion q = toQuaternion(); - Vector v(4); - v(0) = q.w(); - v(1) = q.x(); - v(2) = q.y(); - v(3) = q.z(); - return v; -} -#endif - /* ************************************************************************* */ pair Rot3::axisAngle() const { const Vector3 omega = Rot3::Logmap(*this); diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 00beeb515..b98c03dce 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -515,17 +515,6 @@ class GTSAM_EXPORT Rot3 : public LieGroup { */ gtsam::Quaternion toQuaternion() const; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /** - * Converts to a generic matrix to allow for use with matlab - * In format: w x y z - * @deprecated: use Rot3::toQuaternion() instead. - * If still using this API, remind that in the returned Vector `V`, - * `V.x()` denotes the actual `qw`, `V.y()` denotes 'qx', `V.z()` denotes `qy`, and `V.w()` denotes 'qz'. - */ - Vector GTSAM_DEPRECATED quaternion() const; -#endif - /** * @brief Spherical Linear intERPolation between *this and other * @param t a value between 0 and 1 diff --git a/gtsam/geometry/SimpleCamera.cpp b/gtsam/geometry/SimpleCamera.cpp deleted file mode 100644 index be6a010b2..000000000 --- a/gtsam/geometry/SimpleCamera.cpp +++ /dev/null @@ -1,51 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file SimpleCamera.cpp - * @brief A simple camera class with a Cal3_S2 calibration - * @date June 30, 2012 - * @author Frank Dellaert - */ - -#include -#include - -namespace gtsam { - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - SimpleCamera GTSAM_DEPRECATED simpleCamera(const Matrix34& P) { - - // P = [A|a] = s K cRw [I|-T], with s the unknown scale - Matrix3 A = P.topLeftCorner(3, 3); - Vector3 a = P.col(3); - - // do RQ decomposition to get s*K and cRw angles - Matrix3 sK; - Vector3 xyz; - boost::tie(sK, xyz) = RQ(A); - - // Recover scale factor s and K - double s = sK(2, 2); - Matrix3 K = sK / s; - - // Recover cRw itself, and its inverse - Rot3 cRw = Rot3::RzRyRx(xyz); - Rot3 wRc = cRw.inverse(); - - // Now, recover T from a = - s K cRw T = - A T - Vector3 T = -(A.inverse() * a); - return SimpleCamera(Pose3(wRc, T), - Cal3_S2(K(0, 0), K(1, 1), K(0, 1), K(0, 2), K(1, 2))); - } -#endif - -} diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index f0776c2e2..794451442 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -37,120 +37,4 @@ namespace gtsam { using PinholeCameraCal3Unified = gtsam::PinholeCamera; using PinholeCameraCal3Fisheye = gtsam::PinholeCamera; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -/** - * @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x - * Use PinholeCameraCal3_S2 instead - */ -class GTSAM_EXPORT SimpleCamera : public PinholeCameraCal3_S2 { - - typedef PinholeCamera Base; - typedef boost::shared_ptr shared_ptr; - -public: - - /// @name Standard Constructors - /// @{ - - /** default constructor */ - SimpleCamera() : - Base() { - } - - /** constructor with pose */ - explicit SimpleCamera(const Pose3& pose) : - Base(pose) { - } - - /** constructor with pose and calibration */ - SimpleCamera(const Pose3& pose, const Cal3_S2& K) : - Base(pose, K) { - } - - /// @} - /// @name Named Constructors - /// @{ - - /** - * Create a level camera at the given 2D pose and height - * @param K the calibration - * @param pose2 specifies the location and viewing direction - * (theta 0 = looking in direction of positive X axis) - * @param height camera height - */ - static SimpleCamera Level(const Cal3_S2 &K, const Pose2& pose2, - double height) { - return SimpleCamera(Base::LevelPose(pose2, height), K); - } - - /// PinholeCamera::level with default calibration - static SimpleCamera Level(const Pose2& pose2, double height) { - return SimpleCamera::Level(Cal3_S2(), pose2, height); - } - - /** - * Create a camera at the given eye position looking at a target point in the scene - * with the specified up direction vector. - * @param eye specifies the camera position - * @param target the point to look at - * @param upVector specifies the camera up direction vector, - * doesn't need to be on the image plane nor orthogonal to the viewing axis - * @param K optional calibration parameter - */ - static SimpleCamera Lookat(const Point3& eye, const Point3& target, - const Point3& upVector, const Cal3_S2& K = Cal3_S2()) { - return SimpleCamera(Base::LookatPose(eye, target, upVector), K); - } - - /// @} - /// @name Advanced Constructors - /// @{ - - /// Init from vector, can be 6D (default calibration) or dim - explicit SimpleCamera(const Vector &v) : - Base(v) { - } - - /// Init from Vector and calibration - SimpleCamera(const Vector &v, const Vector &K) : - Base(v, K) { - } - - /// Copy this object as its actual derived type. - SimpleCamera::shared_ptr clone() const { return boost::make_shared(*this); } - - - /// @} - /// @name Manifold - /// @{ - - /// move a cameras according to d - SimpleCamera retract(const Vector& d) const { - if ((size_t) d.size() == 6) - return SimpleCamera(this->pose().retract(d), calibration()); - else - return SimpleCamera(this->pose().retract(d.head(6)), - calibration().retract(d.tail(calibration().dim()))); - } - - /// @} - -}; - -/// Recover camera from 3*4 camera matrix -GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P); - -// manifold traits -template <> -struct traits : public internal::Manifold {}; - -template <> -struct traits : public internal::Manifold {}; - -// range traits, used in RangeFactor -template -struct Range : HasRange {}; - -#endif - } // namespace gtsam diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index 9aaab8278..599baa7da 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -287,61 +287,6 @@ namespace gtsam { // Access the derived factor graph class FactorGraphType& asDerived() { return static_cast(*this); } - - public: - #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /** @deprecated ordering and orderingType shouldn't both be specified */ - boost::shared_ptr GTSAM_DEPRECATED eliminateSequential( - const Ordering& ordering, - const Eliminate& function, - OptionalVariableIndex variableIndex, - OptionalOrderingType orderingType) const { - return eliminateSequential(ordering, function, variableIndex); - } - - /** @deprecated orderingType specified first for consistency */ - boost::shared_ptr GTSAM_DEPRECATED eliminateSequential( - const Eliminate& function, - OptionalVariableIndex variableIndex = {}, - OptionalOrderingType orderingType = {}) const { - return eliminateSequential(orderingType, function, variableIndex); - } - - /** @deprecated ordering and orderingType shouldn't both be specified */ - boost::shared_ptr GTSAM_DEPRECATED eliminateMultifrontal( - const Ordering& ordering, - const Eliminate& function, - OptionalVariableIndex variableIndex, - OptionalOrderingType orderingType) const { - return eliminateMultifrontal(ordering, function, variableIndex); - } - - /** @deprecated orderingType specified first for consistency */ - boost::shared_ptr GTSAM_DEPRECATED eliminateMultifrontal( - const Eliminate& function, - OptionalVariableIndex variableIndex = {}, - OptionalOrderingType orderingType = {}) const { - return eliminateMultifrontal(orderingType, function, variableIndex); - } - - /** @deprecated */ - boost::shared_ptr GTSAM_DEPRECATED marginalMultifrontalBayesNet( - boost::variant variables, - std::nullptr_t, - const Eliminate& function = EliminationTraitsType::DefaultEliminate, - OptionalVariableIndex variableIndex = {}) const { - return marginalMultifrontalBayesNet(variables, function, variableIndex); - } - - /** @deprecated */ - boost::shared_ptr GTSAM_DEPRECATED marginalMultifrontalBayesTree( - boost::variant variables, - std::nullptr_t, - const Eliminate& function = EliminationTraitsType::DefaultEliminate, - OptionalVariableIndex variableIndex = {}) const { - return marginalMultifrontalBayesTree(variables, function, variableIndex); - } - #endif }; } diff --git a/gtsam/linear/GaussianConditional.cpp b/gtsam/linear/GaussianConditional.cpp index cb8726d7a..811893267 100644 --- a/gtsam/linear/GaussianConditional.cpp +++ b/gtsam/linear/GaussianConditional.cpp @@ -371,15 +371,5 @@ namespace gtsam { } /* ************************************************************************ */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - void GTSAM_DEPRECATED - GaussianConditional::scaleFrontalsBySigma(VectorValues& gy) const { - DenseIndex vectorPosition = 0; - for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) { - gy[*frontal].array() *= model_->sigmas().segment(vectorPosition, getDim(frontal)).array(); - vectorPosition += getDim(frontal); - } - } -#endif } // namespace gtsam diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 4611e30d0..8bb65d8a9 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -273,16 +273,6 @@ namespace gtsam { /// @} - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated - /// @{ - /** Scale the values in \c gy according to the sigmas for the frontal variables in this - * conditional. */ - void GTSAM_DEPRECATED scaleFrontalsBySigma(VectorValues& gy) const; - /// @} -#endif - private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index 4f3a89226..65c22cd04 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -409,18 +409,6 @@ namespace gtsam { void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); } - - public: - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /** @deprecated */ - VectorValues GTSAM_DEPRECATED - optimize(std::nullptr_t, const Eliminate& function = - EliminationTraitsType::DefaultEliminate) const { - return optimize(function); - } -#endif - }; /** diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index e99fa7ae5..625400a1b 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -204,12 +204,6 @@ public: const PreintegratedAhrsMeasurements& pim, const Vector3& omegaCoriolis, const std::optional& body_P_sensor = {}); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @deprecated name - typedef PreintegratedAhrsMeasurements PreintegratedMeasurements; - -#endif - private: /** Serialization function */ diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index ab210a62a..9e337028a 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -135,31 +135,6 @@ public: /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated - /// @{ - ConstantBias GTSAM_DEPRECATED inverse() { return -(*this); } - ConstantBias GTSAM_DEPRECATED compose(const ConstantBias& q) { - return (*this) + q; - } - ConstantBias GTSAM_DEPRECATED between(const ConstantBias& q) { - return q - (*this); - } - Vector6 GTSAM_DEPRECATED localCoordinates(const ConstantBias& q) { - return (q - (*this)).vector(); - } - ConstantBias GTSAM_DEPRECATED retract(const Vector6& v) { - return (*this) + ConstantBias(v); - } - static Vector6 GTSAM_DEPRECATED Logmap(const ConstantBias& p) { - return p.vector(); - } - static ConstantBias GTSAM_DEPRECATED Expmap(const Vector6& v) { - return ConstantBias(v); - } - /// @} -#endif - private: /// @name Advanced Interface diff --git a/gtsam/navigation/tests/testImuBias.cpp b/gtsam/navigation/tests/testImuBias.cpp index f654a8ed9..517182f65 100644 --- a/gtsam/navigation/tests/testImuBias.cpp +++ b/gtsam/navigation/tests/testImuBias.cpp @@ -46,58 +46,6 @@ TEST(ImuBias, Constructor) { Bias bias3(bias2); } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -TEST(ImuBias, inverse) { - Bias biasActual = bias1.inverse(); - Bias biasExpected = Bias(-biasAcc1, -biasGyro1); - EXPECT(assert_equal(biasExpected, biasActual)); -} - -TEST(ImuBias, compose) { - Bias biasActual = bias2.compose(bias1); - Bias biasExpected = Bias(biasAcc1 + biasAcc2, biasGyro1 + biasGyro2); - EXPECT(assert_equal(biasExpected, biasActual)); -} - -TEST(ImuBias, between) { - // p.between(q) == q - p - Bias biasActual = bias2.between(bias1); - Bias biasExpected = Bias(biasAcc1 - biasAcc2, biasGyro1 - biasGyro2); - EXPECT(assert_equal(biasExpected, biasActual)); -} - -TEST(ImuBias, localCoordinates) { - Vector deltaActual = Vector(bias2.localCoordinates(bias1)); - Vector deltaExpected = - (Bias(biasAcc1 - biasAcc2, biasGyro1 - biasGyro2)).vector(); - EXPECT(assert_equal(deltaExpected, deltaActual)); -} - -TEST(ImuBias, retract) { - Vector6 delta; - delta << 0.1, 0.2, -0.3, 0.1, -0.1, 0.2; - Bias biasActual = bias2.retract(delta); - Bias biasExpected = Bias(biasAcc2 + delta.block<3, 1>(0, 0), - biasGyro2 + delta.block<3, 1>(3, 0)); - EXPECT(assert_equal(biasExpected, biasActual)); -} - -TEST(ImuBias, Logmap) { - Vector deltaActual = bias2.Logmap(bias1); - Vector deltaExpected = bias1.vector(); - EXPECT(assert_equal(deltaExpected, deltaActual)); -} - -TEST(ImuBias, Expmap) { - Vector6 delta; - delta << 0.1, 0.2, -0.3, 0.1, -0.1, 0.2; - Bias biasActual = bias2.Expmap(delta); - Bias biasExpected = Bias(delta); - EXPECT(assert_equal(biasExpected, biasActual)); -} -#endif - /* ************************************************************************* */ TEST(ImuBias, operatorSub) { Bias biasActual = -bias1; diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 16d7eff8b..797f47002 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -300,55 +300,4 @@ struct traits> : public Testable> {}; // ExpressionFactorN - -#if defined(GTSAM_ALLOW_DEPRECATED_SINCE_V42) -/** - * Binary specialization of ExpressionFactor meant as a base class for binary - * factors. Enforces an 'expression' method with two keys, and provides - * 'evaluateError'. Derived class (a binary factor!) needs to call 'initialize'. - * - * \sa ExpressionFactorN - * @deprecated Prefer the more general ExpressionFactorN<>. - */ -template -class GTSAM_DEPRECATED ExpressionFactor2 : public ExpressionFactorN { -public: - /// Destructor - ~ExpressionFactor2() override {} - - /// Backwards compatible evaluateError, to make existing tests compile - Vector evaluateError(const A1& a1, const A2& a2, OptionalMatrixType H1 = OptionalNone, - OptionalMatrixType H2 = OptionalNone) const { - Values values; - values.insert(this->keys_[0], a1); - values.insert(this->keys_[1], a2); - std::vector H(2); - Vector error = ExpressionFactor::unwhitenedError(values, H); - if (H1) (*H1) = H[0]; - if (H2) (*H2) = H[1]; - return error; - } - - - /// Recreate expression from given keys_ and measured_, used in load - /// Needed to deserialize a derived factor - virtual Expression expression(Key key1, Key key2) const { - throw std::runtime_error("ExpressionFactor2::expression not provided: cannot deserialize."); - } - Expression expression(const typename ExpressionFactorN::ArrayNKeys& keys) const override { - return expression(keys[0], keys[1]); - } - -protected: - /// Default constructor, for serialization - ExpressionFactor2() {} - - /// Constructor takes care of keys, but still need to call initialize - ExpressionFactor2(Key key1, Key key2, const SharedNoiseModel& noiseModel, - const T &measurement) - : ExpressionFactorN({key1, key2}, noiseModel, measurement) {} -}; -// ExpressionFactor2 -#endif - } // namespace gtsam diff --git a/gtsam/nonlinear/ExtendedKalmanFilter.h b/gtsam/nonlinear/ExtendedKalmanFilter.h index d76a6ea7e..a5d6215c1 100644 --- a/gtsam/nonlinear/ExtendedKalmanFilter.h +++ b/gtsam/nonlinear/ExtendedKalmanFilter.h @@ -51,12 +51,6 @@ class ExtendedKalmanFilter { typedef boost::shared_ptr > shared_ptr; typedef VALUE T; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - //@deprecated: any NoiseModelFactor will do, as long as they have the right keys - typedef NoiseModelFactorN MotionFactor; - typedef NoiseModelFactorN MeasurementFactor; -#endif - protected: T x_; // linearization point JacobianFactor::shared_ptr priorFactor_; // Gaussian density on x_ diff --git a/gtsam/nonlinear/Marginals.h b/gtsam/nonlinear/Marginals.h index 3c5aa9cab..41707ea82 100644 --- a/gtsam/nonlinear/Marginals.h +++ b/gtsam/nonlinear/Marginals.h @@ -129,22 +129,6 @@ protected: /** Compute the Bayes Tree as a helper function to the constructor */ void computeBayesTree(const Ordering& ordering); - -public: -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /** @deprecated argument order changed due to removing boost::optional */ - GTSAM_DEPRECATED Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization, - const Ordering& ordering) : Marginals(graph, solution, ordering, factorization) {} - - /** @deprecated argument order changed due to removing boost::optional */ - GTSAM_DEPRECATED Marginals(const GaussianFactorGraph& graph, const Values& solution, Factorization factorization, - const Ordering& ordering) : Marginals(graph, solution, ordering, factorization) {} - - /** @deprecated argument order changed due to removing boost::optional */ - GTSAM_DEPRECATED Marginals(const GaussianFactorGraph& graph, const VectorValues& solution, Factorization factorization, - const Ordering& ordering) : Marginals(graph, solution, ordering, factorization) {} -#endif - }; /** diff --git a/gtsam/nonlinear/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index d20e7dbb8..0618f4eb1 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -261,39 +261,6 @@ namespace gtsam { ar & boost::serialization::make_nvp("NonlinearFactorGraph", boost::serialization::base_object(*this)); } - - public: - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated - /// @{ - /** @deprecated */ - boost::shared_ptr GTSAM_DEPRECATED linearizeToHessianFactor( - const Values& values, std::nullptr_t, const Dampen& dampen = nullptr) const - {return linearizeToHessianFactor(values, dampen);} - - /** @deprecated */ - Values GTSAM_DEPRECATED updateCholesky(const Values& values, std::nullptr_t, - const Dampen& dampen = nullptr) const - {return updateCholesky(values, dampen);} - - /** @deprecated */ - void GTSAM_DEPRECATED saveGraph( - std::ostream& os, const Values& values = Values(), - const GraphvizFormatting& graphvizFormatting = GraphvizFormatting(), - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - dot(os, values, keyFormatter, graphvizFormatting); - } - /** @deprecated */ - void GTSAM_DEPRECATED - saveGraph(const std::string& filename, const Values& values, - const GraphvizFormatting& graphvizFormatting, - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - saveGraph(filename, values, keyFormatter, graphvizFormatting); - } - /// @} -#endif - }; /// traits diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index 283f8d3a0..4f1577f61 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -107,172 +107,6 @@ namespace gtsam { return result; } -/* ************************************************************************* */ -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - template - class Values::Filtered { - public: - /** A key-value pair, with the value a specific derived Value type. */ - typedef _ValuesKeyValuePair KeyValuePair; - typedef _ValuesConstKeyValuePair ConstKeyValuePair; - typedef KeyValuePair value_type; - - typedef - boost::transform_iterator< - KeyValuePair(*)(Values::KeyValuePair), - boost::filter_iterator< - std::function, - Values::iterator> > - iterator; - - typedef iterator const_iterator; - - typedef - boost::transform_iterator< - ConstKeyValuePair(*)(Values::ConstKeyValuePair), - boost::filter_iterator< - std::function, - Values::const_iterator> > - const_const_iterator; - - iterator begin() { return begin_; } - iterator end() { return end_; } - const_iterator begin() const { return begin_; } - const_iterator end() const { return end_; } - const_const_iterator beginConst() const { return constBegin_; } - const_const_iterator endConst() const { return constEnd_; } - - /** Returns the number of values in this view */ - size_t size() const { - size_t i = 0; - for (const_const_iterator it = beginConst(); it != endConst(); ++it) - ++i; - return i; - } - - private: - Filtered( - const std::function& filter, - Values& values) : - begin_( - boost::make_transform_iterator( - boost::make_filter_iterator(filter, values.begin(), values.end()), - &ValuesCastHelper::cast)), end_( - boost::make_transform_iterator( - boost::make_filter_iterator(filter, values.end(), values.end()), - &ValuesCastHelper::cast)), constBegin_( - boost::make_transform_iterator( - boost::make_filter_iterator(filter, - ((const Values&) values).begin(), - ((const Values&) values).end()), - &ValuesCastHelper::cast)), constEnd_( - boost::make_transform_iterator( - boost::make_filter_iterator(filter, - ((const Values&) values).end(), - ((const Values&) values).end()), - &ValuesCastHelper::cast)) { - } - - friend class Values; - iterator begin_; - iterator end_; - const_const_iterator constBegin_; - const_const_iterator constEnd_; - }; - - template - class Values::ConstFiltered { - public: - /** A const key-value pair, with the value a specific derived Value type. */ - typedef _ValuesConstKeyValuePair KeyValuePair; - typedef KeyValuePair value_type; - - typedef typename Filtered::const_const_iterator iterator; - typedef typename Filtered::const_const_iterator const_iterator; - - /** Conversion from Filtered to ConstFiltered */ - ConstFiltered(const Filtered& rhs) : - begin_(rhs.beginConst()), - end_(rhs.endConst()) {} - - iterator begin() { return begin_; } - iterator end() { return end_; } - const_iterator begin() const { return begin_; } - const_iterator end() const { return end_; } - - /** Returns the number of values in this view */ - size_t size() const { - size_t i = 0; - for (const_iterator it = begin(); it != end(); ++it) - ++i; - return i; - } - - FastList keys() const { - FastList result; - for(const_iterator it = begin(); it != end(); ++it) - result.push_back(it->key); - return result; - } - - private: - friend class Values; - const_iterator begin_; - const_iterator end_; - ConstFiltered( - const std::function& filter, - const Values& values) { - // We remove the const from values to create a non-const Filtered - // view, then pull the const_iterators out of it. - const Filtered filtered(filter, const_cast(values)); - begin_ = filtered.beginConst(); - end_ = filtered.endConst(); - } - }; - - template - Values::Values(const Values::Filtered& view) { - for(const auto key_value: view) { - Key key = key_value.key; - insert(key, static_cast(key_value.value)); - } - } - - template - Values::Values(const Values::ConstFiltered& view) { - for(const auto key_value: view) { - Key key = key_value.key; - insert(key, static_cast(key_value.value)); - } - } - - Values::Filtered - inline Values::filter(const std::function& filterFcn) { - return filter(filterFcn); - } - - template - Values::Filtered - Values::filter(const std::function& filterFcn) { - return Filtered(std::bind(&filterHelper, filterFcn, - std::placeholders::_1), *this); - } - - Values::ConstFiltered - inline Values::filter(const std::function& filterFcn) const { - return filter(filterFcn); - } - - template - Values::ConstFiltered - Values::filter(const std::function& filterFcn) const { - return ConstFiltered(std::bind(&filterHelper, - filterFcn, std::placeholders::_1), *this); - } -#endif - /* ************************************************************************* */ template<> inline bool Values::filterHelper(const std::function filter, diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index d75967eef..4ea330952 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -31,9 +31,6 @@ #include #include #include -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -#include -#endif #include #include @@ -342,42 +339,6 @@ namespace gtsam { std::map // , std::less, Eigen::aligned_allocator extract(const std::function& filterFcn = &_truePredicate) const; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /** A filtered view of a Values, returned from Values::filter. */ - template - class Filtered; - - /** A filtered view of a const Values, returned from Values::filter. */ - template - class ConstFiltered; - - /** Constructor from a Filtered view copies out all values */ - template - Values(const Filtered& view); - - /** Constructor from a Filtered or ConstFiltered view */ - template - Values(const ConstFiltered& view); - - /// A filtered view of the original Values class. - Filtered GTSAM_DEPRECATED - filter(const std::function& filterFcn); - - /// A filtered view of the original Values class, also filter on type. - template - Filtered GTSAM_DEPRECATED - filter(const std::function& filterFcn = &_truePredicate); - - /// A filtered view of the original Values class, const version. - ConstFiltered GTSAM_DEPRECATED - filter(const std::function& filterFcn) const; - - /// A filtered view of the original Values class, also on type, const. - template - ConstFiltered GTSAM_DEPRECATED filter( - const std::function& filterFcn = &_truePredicate) const; -#endif - private: // Filters based on ValueType (if not Value) and also based on the user- // supplied \c filter function. diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 9d22c0daf..9ec1c53d1 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -343,68 +343,6 @@ TEST(Values, filter) { values.insert(2, pose2); values.insert(3, pose3); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - // Filter by key - int i = 0; - Values::Filtered filtered = values.filter(std::bind(std::greater_equal(), std::placeholders::_1, 2)); - EXPECT_LONGS_EQUAL(2, (long)filtered.size()); - for(const auto key_value: filtered) { - if(i == 0) { - LONGS_EQUAL(2, (long)key_value.key); - try {key_value.value.cast();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose2");} - THROWS_EXCEPTION(key_value.value.cast()); - EXPECT(assert_equal(pose2, key_value.value.cast())); - } else if(i == 1) { - LONGS_EQUAL(3, (long)key_value.key); - try {key_value.value.cast();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose3");} - THROWS_EXCEPTION(key_value.value.cast()); - EXPECT(assert_equal(pose3, key_value.value.cast())); - } else { - EXPECT(false); - } - ++ i; - } - EXPECT_LONGS_EQUAL(2, (long)i); - - // construct a values with the view - Values actualSubValues1(filtered); - Values expectedSubValues1; - expectedSubValues1.insert(2, pose2); - expectedSubValues1.insert(3, pose3); - EXPECT(assert_equal(expectedSubValues1, actualSubValues1)); - - // ConstFilter by Key - Values::ConstFiltered constfiltered = values.filter(std::bind(std::greater_equal(), std::placeholders::_1, 2)); - EXPECT_LONGS_EQUAL(2, (long)constfiltered.size()); - Values fromconstfiltered(constfiltered); - EXPECT(assert_equal(expectedSubValues1, fromconstfiltered)); - - // Filter by type - i = 0; - Values::ConstFiltered pose_filtered = values.filter(); - EXPECT_LONGS_EQUAL(2, (long)pose_filtered.size()); - for(const auto key_value: pose_filtered) { - if(i == 0) { - EXPECT_LONGS_EQUAL(1, (long)key_value.key); - EXPECT(assert_equal(pose1, key_value.value)); - } else if(i == 1) { - EXPECT_LONGS_EQUAL(3, (long)key_value.key); - EXPECT(assert_equal(pose3, key_value.value)); - } else { - EXPECT(false); - } - ++ i; - } - EXPECT_LONGS_EQUAL(2, (long)i); - - // construct a values with the view - Values actualSubValues2(pose_filtered); - Values expectedSubValues2; - expectedSubValues2.insert(1, pose1); - expectedSubValues2.insert(3, pose3); - EXPECT(assert_equal(expectedSubValues2, actualSubValues2)); -#endif - // Test counting by type. EXPECT_LONGS_EQUAL(2, (long)values.count()); EXPECT_LONGS_EQUAL(2, (long)values.count()); @@ -412,7 +350,6 @@ TEST(Values, filter) { // Filter by type using extract. auto extracted_pose3s = values.extract(); EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size()); - } /* ************************************************************************* */ @@ -428,27 +365,9 @@ TEST(Values, Symbol_filter) { values.insert(X(2), pose2); values.insert(Symbol('y', 3), pose3); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - int i = 0; - for(const auto key_value: values.filter(Symbol::ChrTest('y'))) { - if(i == 0) { - LONGS_EQUAL(Symbol('y', 1), (long)key_value.key); - EXPECT(assert_equal(pose1, key_value.value.cast())); - } else if(i == 1) { - LONGS_EQUAL(Symbol('y', 3), (long)key_value.key); - EXPECT(assert_equal(pose3, key_value.value.cast())); - } else { - EXPECT(false); - } - ++ i; - } - LONGS_EQUAL(2, (long)i); -#endif - -// Test extract with filter on symbol: + // Test extract with filter on symbol: auto extracted_pose3s = values.extract(Symbol::ChrTest('y')); EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size()); - } /* ************************************************************************* */ diff --git a/gtsam/sfm/SfmData.cpp b/gtsam/sfm/SfmData.cpp index 1e27c332f..6c6b471e6 100644 --- a/gtsam/sfm/SfmData.cpp +++ b/gtsam/sfm/SfmData.cpp @@ -322,25 +322,6 @@ bool writeBAL(const std::string &filename, const SfmData &data) { return true; } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -bool readBundler(const std::string &filename, SfmData &data) { - try { - data = SfmData::FromBundlerFile(filename); - return true; - } catch (const std::exception & /* e */) { - return false; - } -} -bool readBAL(const std::string &filename, SfmData &data) { - try { - data = SfmData::FromBalFile(filename); - return true; - } catch (const std::exception & /* e */) { - return false; - } -} -#endif - SfmData readBal(const std::string &filename) { return SfmData::FromBalFile(filename); } diff --git a/gtsam/sfm/SfmData.h b/gtsam/sfm/SfmData.h index 6b69523a9..dbf0bd1e7 100644 --- a/gtsam/sfm/SfmData.h +++ b/gtsam/sfm/SfmData.h @@ -122,17 +122,6 @@ struct GTSAM_EXPORT SfmData { bool equals(const SfmData& sfmData, double tol = 1e-9) const; /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated - /// @{ - void GTSAM_DEPRECATED add_track(const SfmTrack& t) { tracks.push_back(t); } - void GTSAM_DEPRECATED add_camera(const SfmCamera& cam) { - cameras.push_back(cam); - } - size_t GTSAM_DEPRECATED number_tracks() const { return tracks.size(); } - size_t GTSAM_DEPRECATED number_cameras() const { return cameras.size(); } - /// @} -#endif /// @name Serialization /// @{ @@ -151,13 +140,6 @@ struct GTSAM_EXPORT SfmData { template <> struct traits : public Testable {}; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -GTSAM_EXPORT bool GTSAM_DEPRECATED readBundler(const std::string& filename, - SfmData& data); -GTSAM_EXPORT bool GTSAM_DEPRECATED readBAL(const std::string& filename, - SfmData& data); -#endif - /** * @brief This function parses a "Bundle Adjustment in the Large" (BAL) file and * returns the data as a SfmData structure. Mainly used by wrapped code. diff --git a/gtsam/sfm/SfmTrack.h b/gtsam/sfm/SfmTrack.h index c75199374..60699bc31 100644 --- a/gtsam/sfm/SfmTrack.h +++ b/gtsam/sfm/SfmTrack.h @@ -158,18 +158,6 @@ struct GTSAM_EXPORT SfmTrack : SfmTrack2d { bool equals(const SfmTrack& sfmTrack, double tol = 1e-9) const; /// @} -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - /// @name Deprecated - /// @{ - void GTSAM_DEPRECATED add_measurement(size_t idx, const gtsam::Point2& m) { - measurements.emplace_back(idx, m); - } - - size_t GTSAM_DEPRECATED number_measurements() const { - return measurements.size(); - } - /// @} -#endif /// @name Serialization /// @{ diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index cfd7b8820..318e4dd07 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -962,15 +962,4 @@ parse3DFactors(const std::string &filename, return parseFactors(filename, model, maxIndex); } -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -std::map GTSAM_DEPRECATED -parse3DPoses(const std::string &filename, size_t maxIndex) { - return parseVariables(filename, maxIndex); -} - -std::map GTSAM_DEPRECATED -parse3DLandmarks(const std::string &filename, size_t maxIndex) { - return parseVariables(filename, maxIndex); -} -#endif } // namespace gtsam diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 875f23306..d5bad59b4 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -226,21 +226,4 @@ parse3DFactors(const std::string &filename, using BinaryMeasurementsUnit3 = std::vector>; using BinaryMeasurementsPoint3 = std::vector>; using BinaryMeasurementsRot3 = std::vector>; - -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -inline std::optional GTSAM_DEPRECATED -parseVertex(std::istream& is, const std::string& tag) { - return parseVertexPose(is, tag); -} - -GTSAM_EXPORT std::map GTSAM_DEPRECATED -parse3DPoses(const std::string& filename, size_t maxIndex = 0); - -GTSAM_EXPORT std::map GTSAM_DEPRECATED -parse3DLandmarks(const std::string& filename, size_t maxIndex = 0); - -GTSAM_EXPORT GraphAndValues GTSAM_DEPRECATED -load2D_robust(const std::string& filename, - const noiseModel::Base::shared_ptr& model, size_t maxIndex = 0); -#endif } // namespace gtsam diff --git a/gtsam_unstable/slam/serialization.cpp b/gtsam_unstable/slam/serialization.cpp index d87ca6f2d..4b1ecae54 100644 --- a/gtsam_unstable/slam/serialization.cpp +++ b/gtsam_unstable/slam/serialization.cpp @@ -173,22 +173,6 @@ BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_ BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D"); -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 - -typedef PriorFactor PriorFactorSimpleCamera; -typedef NonlinearEquality NonlinearEqualitySimpleCamera; -typedef RangeFactor RangeFactorSimpleCameraPoint; -typedef RangeFactor RangeFactorSimpleCamera; - -GTSAM_VALUE_EXPORT(gtsam::SimpleCamera); -BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera"); -BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera"); -BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint"); -BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera"); - -#endif - - /* ************************************************************************* */ // Actual implementations of functions /* ************************************************************************* */