Merge branch 'feature/remove_deprecated_code' into verdant/replace-boost-optional-vals
commit
b8fb9fabb4
|
@ -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
|
||||
|
||||
|
||||
|
|
|
@ -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} \
|
||||
|
|
|
@ -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'
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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.
|
||||
|
|
|
@ -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()
|
||||
|
|
|
@ -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)
|
||||
|
|
|
@ -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")
|
||||
|
||||
|
|
|
@ -72,37 +72,6 @@ bool assert_equal(const V& expected, const std::optional<V>& actual, double 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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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 =
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -371,15 +371,5 @@ std::optional<Pose2> Pose2::Align(const Matrix& a, const Matrix& b) {
|
|||
return Pose2::Align(ab_pairs);
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
std::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
|
||||
|
|
|
@ -346,16 +346,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 std::optional<Pose2>
|
||||
GTSAM_DEPRECATED align(const Point2Pairs& pairs);
|
||||
#endif
|
||||
|
||||
// Convenience typedef
|
||||
using Pose2Pair = std::pair<Pose2, Pose2>;
|
||||
using Pose2Pairs = std::vector<Pose2Pair>;
|
||||
|
|
|
@ -478,16 +478,6 @@ std::optional<Pose3> Pose3::Align(const Matrix& a, const Matrix& b) {
|
|||
return Pose3::Align(abPointPairs);
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
std::optional<Pose3> 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);
|
||||
|
|
|
@ -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<Unit3, double> Rot3::axisAngle() const {
|
||||
const Vector3 omega = Rot3::Logmap(*this);
|
||||
|
|
|
@ -515,17 +515,6 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
|
|||
*/
|
||||
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
|
||||
|
|
|
@ -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 <gtsam/geometry/SimpleCamera.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
|
||||
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
|
||||
|
||||
}
|
|
@ -37,120 +37,4 @@ namespace gtsam {
|
|||
using PinholeCameraCal3Unified = gtsam::PinholeCamera<gtsam::Cal3Unified>;
|
||||
using PinholeCameraCal3Fisheye = gtsam::PinholeCamera<gtsam::Cal3Fisheye>;
|
||||
|
||||
#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<Cal3_S2> Base;
|
||||
typedef boost::shared_ptr<SimpleCamera> 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<SimpleCamera>(*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<SimpleCamera> : public internal::Manifold<SimpleCamera> {};
|
||||
|
||||
template <>
|
||||
struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {};
|
||||
|
||||
// range traits, used in RangeFactor
|
||||
template <typename T>
|
||||
struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
|
||||
|
||||
#endif
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -287,61 +287,6 @@ namespace gtsam {
|
|||
|
||||
// Access the derived factor graph class
|
||||
FactorGraphType& asDerived() { return static_cast<FactorGraphType&>(*this); }
|
||||
|
||||
public:
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/** @deprecated ordering and orderingType shouldn't both be specified */
|
||||
boost::shared_ptr<BayesNetType> 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<BayesNetType> 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<BayesTreeType> 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<BayesTreeType> GTSAM_DEPRECATED eliminateMultifrontal(
|
||||
const Eliminate& function,
|
||||
OptionalVariableIndex variableIndex = {},
|
||||
OptionalOrderingType orderingType = {}) const {
|
||||
return eliminateMultifrontal(orderingType, function, variableIndex);
|
||||
}
|
||||
|
||||
/** @deprecated */
|
||||
boost::shared_ptr<BayesNetType> GTSAM_DEPRECATED marginalMultifrontalBayesNet(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
std::nullptr_t,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const {
|
||||
return marginalMultifrontalBayesNet(variables, function, variableIndex);
|
||||
}
|
||||
|
||||
/** @deprecated */
|
||||
boost::shared_ptr<BayesTreeType> GTSAM_DEPRECATED marginalMultifrontalBayesTree(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
std::nullptr_t,
|
||||
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
|
||||
OptionalVariableIndex variableIndex = {}) const {
|
||||
return marginalMultifrontalBayesTree(variables, function, variableIndex);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -204,12 +204,6 @@ public:
|
|||
const PreintegratedAhrsMeasurements& pim, const Vector3& omegaCoriolis,
|
||||
const std::optional<Pose3>& body_P_sensor = {});
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/// @deprecated name
|
||||
typedef PreintegratedAhrsMeasurements PreintegratedMeasurements;
|
||||
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
||||
/** Serialization function */
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -300,55 +300,4 @@ struct traits<ExpressionFactorN<T, Args...>>
|
|||
: public Testable<ExpressionFactorN<T, Args...>> {};
|
||||
// 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 <typename T, typename A1, typename A2>
|
||||
class GTSAM_DEPRECATED ExpressionFactor2 : public ExpressionFactorN<T, A1, A2> {
|
||||
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<Matrix> H(2);
|
||||
Vector error = ExpressionFactor<T>::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<T> expression(Key key1, Key key2) const {
|
||||
throw std::runtime_error("ExpressionFactor2::expression not provided: cannot deserialize.");
|
||||
}
|
||||
Expression<T> expression(const typename ExpressionFactorN<T, A1, A2>::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<T, A1, A2>({key1, key2}, noiseModel, measurement) {}
|
||||
};
|
||||
// ExpressionFactor2
|
||||
#endif
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -51,12 +51,6 @@ class ExtendedKalmanFilter {
|
|||
typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > 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<VALUE, VALUE> MotionFactor;
|
||||
typedef NoiseModelFactorN<VALUE> MeasurementFactor;
|
||||
#endif
|
||||
|
||||
protected:
|
||||
T x_; // linearization point
|
||||
JacobianFactor::shared_ptr priorFactor_; // Gaussian density on x_
|
||||
|
|
|
@ -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<Ordering> */
|
||||
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<Ordering> */
|
||||
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<Ordering> */
|
||||
GTSAM_DEPRECATED Marginals(const GaussianFactorGraph& graph, const VectorValues& solution, Factorization factorization,
|
||||
const Ordering& ordering) : Marginals(graph, solution, ordering, factorization) {}
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -261,39 +261,6 @@ namespace gtsam {
|
|||
ar & boost::serialization::make_nvp("NonlinearFactorGraph",
|
||||
boost::serialization::base_object<Base>(*this));
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/// @name Deprecated
|
||||
/// @{
|
||||
/** @deprecated */
|
||||
boost::shared_ptr<HessianFactor> 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
|
||||
|
|
|
@ -107,172 +107,6 @@ namespace gtsam {
|
|||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
template<class ValueType>
|
||||
class Values::Filtered {
|
||||
public:
|
||||
/** A key-value pair, with the value a specific derived Value type. */
|
||||
typedef _ValuesKeyValuePair<ValueType> KeyValuePair;
|
||||
typedef _ValuesConstKeyValuePair<ValueType> ConstKeyValuePair;
|
||||
typedef KeyValuePair value_type;
|
||||
|
||||
typedef
|
||||
boost::transform_iterator<
|
||||
KeyValuePair(*)(Values::KeyValuePair),
|
||||
boost::filter_iterator<
|
||||
std::function<bool(const Values::ConstKeyValuePair&)>,
|
||||
Values::iterator> >
|
||||
iterator;
|
||||
|
||||
typedef iterator const_iterator;
|
||||
|
||||
typedef
|
||||
boost::transform_iterator<
|
||||
ConstKeyValuePair(*)(Values::ConstKeyValuePair),
|
||||
boost::filter_iterator<
|
||||
std::function<bool(const Values::ConstKeyValuePair&)>,
|
||||
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<bool(const Values::ConstKeyValuePair&)>& filter,
|
||||
Values& values) :
|
||||
begin_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter, values.begin(), values.end()),
|
||||
&ValuesCastHelper<ValueType, KeyValuePair, Values::KeyValuePair>::cast)), end_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter, values.end(), values.end()),
|
||||
&ValuesCastHelper<ValueType, KeyValuePair, Values::KeyValuePair>::cast)), constBegin_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter,
|
||||
((const Values&) values).begin(),
|
||||
((const Values&) values).end()),
|
||||
&ValuesCastHelper<ValueType, ConstKeyValuePair,
|
||||
Values::ConstKeyValuePair>::cast)), constEnd_(
|
||||
boost::make_transform_iterator(
|
||||
boost::make_filter_iterator(filter,
|
||||
((const Values&) values).end(),
|
||||
((const Values&) values).end()),
|
||||
&ValuesCastHelper<ValueType, ConstKeyValuePair,
|
||||
Values::ConstKeyValuePair>::cast)) {
|
||||
}
|
||||
|
||||
friend class Values;
|
||||
iterator begin_;
|
||||
iterator end_;
|
||||
const_const_iterator constBegin_;
|
||||
const_const_iterator constEnd_;
|
||||
};
|
||||
|
||||
template<class ValueType>
|
||||
class Values::ConstFiltered {
|
||||
public:
|
||||
/** A const key-value pair, with the value a specific derived Value type. */
|
||||
typedef _ValuesConstKeyValuePair<ValueType> KeyValuePair;
|
||||
typedef KeyValuePair value_type;
|
||||
|
||||
typedef typename Filtered<ValueType>::const_const_iterator iterator;
|
||||
typedef typename Filtered<ValueType>::const_const_iterator const_iterator;
|
||||
|
||||
/** Conversion from Filtered to ConstFiltered */
|
||||
ConstFiltered(const Filtered<ValueType>& 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<Key> keys() const {
|
||||
FastList<Key> 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<bool(const Values::ConstKeyValuePair&)>& 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<ValueType> filtered(filter, const_cast<Values&>(values));
|
||||
begin_ = filtered.beginConst();
|
||||
end_ = filtered.endConst();
|
||||
}
|
||||
};
|
||||
|
||||
template<class ValueType>
|
||||
Values::Values(const Values::Filtered<ValueType>& view) {
|
||||
for(const auto key_value: view) {
|
||||
Key key = key_value.key;
|
||||
insert(key, static_cast<const ValueType&>(key_value.value));
|
||||
}
|
||||
}
|
||||
|
||||
template<class ValueType>
|
||||
Values::Values(const Values::ConstFiltered<ValueType>& view) {
|
||||
for(const auto key_value: view) {
|
||||
Key key = key_value.key;
|
||||
insert(key, static_cast<const ValueType&>(key_value.value));
|
||||
}
|
||||
}
|
||||
|
||||
Values::Filtered<Value>
|
||||
inline Values::filter(const std::function<bool(Key)>& filterFcn) {
|
||||
return filter<Value>(filterFcn);
|
||||
}
|
||||
|
||||
template<class ValueType>
|
||||
Values::Filtered<ValueType>
|
||||
Values::filter(const std::function<bool(Key)>& filterFcn) {
|
||||
return Filtered<ValueType>(std::bind(&filterHelper<ValueType>, filterFcn,
|
||||
std::placeholders::_1), *this);
|
||||
}
|
||||
|
||||
Values::ConstFiltered<Value>
|
||||
inline Values::filter(const std::function<bool(Key)>& filterFcn) const {
|
||||
return filter<Value>(filterFcn);
|
||||
}
|
||||
|
||||
template<class ValueType>
|
||||
Values::ConstFiltered<ValueType>
|
||||
Values::filter(const std::function<bool(Key)>& filterFcn) const {
|
||||
return ConstFiltered<ValueType>(std::bind(&filterHelper<ValueType>,
|
||||
filterFcn, std::placeholders::_1), *this);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<>
|
||||
inline bool Values::filterHelper<Value>(const std::function<bool(Key)> filter,
|
||||
|
|
|
@ -31,9 +31,6 @@
|
|||
#include <boost/iterator/transform_iterator.hpp>
|
||||
#include <boost/ptr_container/serialize_ptr_map.hpp>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
#include <boost/iterator/filter_iterator.hpp>
|
||||
#endif
|
||||
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
@ -342,42 +339,6 @@ namespace gtsam {
|
|||
std::map<Key, ValueType> // , std::less<Key>, Eigen::aligned_allocator<ValueType>
|
||||
extract(const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>) const;
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/** A filtered view of a Values, returned from Values::filter. */
|
||||
template <class ValueType = Value>
|
||||
class Filtered;
|
||||
|
||||
/** A filtered view of a const Values, returned from Values::filter. */
|
||||
template <class ValueType = Value>
|
||||
class ConstFiltered;
|
||||
|
||||
/** Constructor from a Filtered view copies out all values */
|
||||
template <class ValueType>
|
||||
Values(const Filtered<ValueType>& view);
|
||||
|
||||
/** Constructor from a Filtered or ConstFiltered view */
|
||||
template <class ValueType>
|
||||
Values(const ConstFiltered<ValueType>& view);
|
||||
|
||||
/// A filtered view of the original Values class.
|
||||
Filtered<Value> GTSAM_DEPRECATED
|
||||
filter(const std::function<bool(Key)>& filterFcn);
|
||||
|
||||
/// A filtered view of the original Values class, also filter on type.
|
||||
template <class ValueType>
|
||||
Filtered<ValueType> GTSAM_DEPRECATED
|
||||
filter(const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>);
|
||||
|
||||
/// A filtered view of the original Values class, const version.
|
||||
ConstFiltered<Value> GTSAM_DEPRECATED
|
||||
filter(const std::function<bool(Key)>& filterFcn) const;
|
||||
|
||||
/// A filtered view of the original Values class, also on type, const.
|
||||
template <class ValueType>
|
||||
ConstFiltered<ValueType> GTSAM_DEPRECATED filter(
|
||||
const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>) const;
|
||||
#endif
|
||||
|
||||
private:
|
||||
// Filters based on ValueType (if not Value) and also based on the user-
|
||||
// supplied \c filter function.
|
||||
|
|
|
@ -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<Value> filtered = values.filter(std::bind(std::greater_equal<Key>(), 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<Pose2>();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose2");}
|
||||
THROWS_EXCEPTION(key_value.value.cast<Pose3>());
|
||||
EXPECT(assert_equal(pose2, key_value.value.cast<Pose2>()));
|
||||
} else if(i == 1) {
|
||||
LONGS_EQUAL(3, (long)key_value.key);
|
||||
try {key_value.value.cast<Pose3>();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose3");}
|
||||
THROWS_EXCEPTION(key_value.value.cast<Pose2>());
|
||||
EXPECT(assert_equal(pose3, key_value.value.cast<Pose3>()));
|
||||
} 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<Value> constfiltered = values.filter(std::bind(std::greater_equal<Key>(), 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<Pose3> pose_filtered = values.filter<Pose3>();
|
||||
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<Pose3>());
|
||||
EXPECT_LONGS_EQUAL(2, (long)values.count<Pose2>());
|
||||
|
@ -412,7 +350,6 @@ TEST(Values, filter) {
|
|||
// Filter by type using extract.
|
||||
auto extracted_pose3s = values.extract<Pose3>();
|
||||
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<Pose3>()));
|
||||
} else if(i == 1) {
|
||||
LONGS_EQUAL(Symbol('y', 3), (long)key_value.key);
|
||||
EXPECT(assert_equal(pose3, key_value.value.cast<Pose3>()));
|
||||
} 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<Pose3>(Symbol::ChrTest('y'));
|
||||
EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size());
|
||||
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -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<SfmData> : public Testable<SfmData> {};
|
||||
|
||||
#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.
|
||||
|
|
|
@ -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
|
||||
/// @{
|
||||
|
||||
|
|
|
@ -962,15 +962,4 @@ parse3DFactors(const std::string &filename,
|
|||
return parseFactors<Pose3>(filename, model, maxIndex);
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
std::map<size_t, Pose3> GTSAM_DEPRECATED
|
||||
parse3DPoses(const std::string &filename, size_t maxIndex) {
|
||||
return parseVariables<Pose3>(filename, maxIndex);
|
||||
}
|
||||
|
||||
std::map<size_t, Point3> GTSAM_DEPRECATED
|
||||
parse3DLandmarks(const std::string &filename, size_t maxIndex) {
|
||||
return parseVariables<Point3>(filename, maxIndex);
|
||||
}
|
||||
#endif
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -226,21 +226,4 @@ parse3DFactors(const std::string &filename,
|
|||
using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
|
||||
using BinaryMeasurementsPoint3 = std::vector<BinaryMeasurement<Point3>>;
|
||||
using BinaryMeasurementsRot3 = std::vector<BinaryMeasurement<Rot3>>;
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
inline std::optional<IndexedPose> GTSAM_DEPRECATED
|
||||
parseVertex(std::istream& is, const std::string& tag) {
|
||||
return parseVertexPose(is, tag);
|
||||
}
|
||||
|
||||
GTSAM_EXPORT std::map<size_t, Pose3> GTSAM_DEPRECATED
|
||||
parse3DPoses(const std::string& filename, size_t maxIndex = 0);
|
||||
|
||||
GTSAM_EXPORT std::map<size_t, Point3> 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
|
||||
|
|
|
@ -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<SimpleCamera> PriorFactorSimpleCamera;
|
||||
typedef NonlinearEquality<SimpleCamera> NonlinearEqualitySimpleCamera;
|
||||
typedef RangeFactor<SimpleCamera, Point3> RangeFactorSimpleCameraPoint;
|
||||
typedef RangeFactor<SimpleCamera, SimpleCamera> 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
|
||||
/* ************************************************************************* */
|
||||
|
|
Loading…
Reference in New Issue