Skip to content

Commit

Permalink
Merge pull request #1399 from borglab/feature/remove_deprecated_code
Browse files Browse the repository at this point in the history
Remove code deprecated in 4.2
  • Loading branch information
gchenfc authored Jan 21, 2023
2 parents c7e18e6 + c71d07b commit 6787bbe
Show file tree
Hide file tree
Showing 54 changed files with 64 additions and 1,278 deletions.
2 changes: 1 addition & 1 deletion .github/scripts/python.sh
Original file line number Diff line number Diff line change
Expand Up @@ -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


Expand Down
2 changes: 1 addition & 1 deletion .github/scripts/unix.sh
Original file line number Diff line number Diff line change
Expand Up @@ -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} \
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/build-special.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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'
Expand Down
2 changes: 0 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@ if(NOT DEFINED CMAKE_MACOSX_RPATH)
set(CMAKE_MACOSX_RPATH 0)
endif()

set(CMAKE_CXX_STANDARD 17)

# Set the version number for the library
set (GTSAM_VERSION_MAJOR 4)
set (GTSAM_VERSION_MINOR 3)
Expand Down
5 changes: 0 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
3 changes: 0 additions & 3 deletions cmake/GtsamBuildTypes.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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 $<$<COMPILE_LANGUAGE:CXX>:-std=c++17>)
endif()
endif()
Expand Down
2 changes: 1 addition & 1 deletion cmake/HandleGeneralOptions.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion cmake/HandlePrintConfiguration.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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")

Expand Down
3 changes: 2 additions & 1 deletion examples/StereoVOExample_large.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2Stereo.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/utilities.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
Expand Down Expand Up @@ -113,7 +114,7 @@ int main(int argc, char** argv) {
Values result = optimizer.optimize();

cout << "Final result sample:" << endl;
Values pose_values = result.filter<Pose3>();
Values pose_values = utilities::allPose3s(result);
pose_values.print("Final camera poses:\n");

return 0;
Expand Down
31 changes: 0 additions & 31 deletions gtsam/base/TestableAssertions.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,37 +80,6 @@ bool assert_equal(const V& expected, const boost::optional<const V&>& actual, do
return assert_equal(expected, *actual, tol);
}

#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
/**
* Version of assert_equals to work with vectors
* @deprecated: use container equals instead
*/
template<class V>
bool GTSAM_DEPRECATED assert_equal(const std::vector<V>& expected, const std::vector<V>& 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
Expand Down
22 changes: 0 additions & 22 deletions gtsam/base/Vector.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<class V1, class V2>
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
Expand Down
2 changes: 1 addition & 1 deletion gtsam/config.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
20 changes: 0 additions & 20 deletions gtsam/discrete/DiscreteBayesNet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
9 changes: 0 additions & 9 deletions gtsam/discrete/DiscreteBayesNet.h
Original file line number Diff line number Diff line change
Expand Up @@ -149,15 +149,6 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet<DiscreteConditional> {

/// @}

#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;
Expand Down
51 changes: 0 additions & 51 deletions gtsam/discrete/DiscreteConditional.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
8 changes: 0 additions & 8 deletions gtsam/discrete/DiscreteConditional.h
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
6 changes: 0 additions & 6 deletions gtsam/discrete/DiscreteDistribution.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,6 @@ class GTSAM_EXPORT DiscreteDistribution : public DiscreteConditional {
std::vector<double> pmf() const;

/// @}
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
/// @name Deprecated functionality
/// @{
size_t GTSAM_DEPRECATED solve() const { return Base::solve({}); }
/// @}
#endif
};
// DiscreteDistribution

Expand Down
11 changes: 0 additions & 11 deletions gtsam/discrete/tests/testDiscreteFactorGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}

/* ************************************************************************* */
Expand Down Expand Up @@ -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 =
Expand Down
5 changes: 0 additions & 5 deletions gtsam/geometry/Cal3.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
8 changes: 0 additions & 8 deletions gtsam/geometry/Cal3Bundler.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
10 changes: 0 additions & 10 deletions gtsam/geometry/Pose2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -371,15 +371,5 @@ boost::optional<Pose2> Pose2::Align(const Matrix& a, const Matrix& b) {
return Pose2::Align(ab_pairs);
}

#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
boost::optional<Pose2> 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
10 changes: 0 additions & 10 deletions gtsam/geometry/Pose2.h
Original file line number Diff line number Diff line change
Expand Up @@ -343,16 +343,6 @@ inline Matrix wedge<Pose2>(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 boost::optional<Pose2>
GTSAM_DEPRECATED align(const Point2Pairs& pairs);
#endif

// Convenience typedef
using Pose2Pair = std::pair<Pose2, Pose2>;
using Pose2Pairs = std::vector<Pose2Pair>;
Expand Down
Loading

0 comments on commit 6787bbe

Please sign in to comment.