Merge pull request #1399 from borglab/feature/remove_deprecated_code

Remove code deprecated in 4.2
release/4.3a0
Gerry Chen 2023-01-21 17:05:30 -05:00 committed by GitHub
commit 6787bbe048
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
54 changed files with 64 additions and 1278 deletions

View File

@ -79,7 +79,7 @@ function build()
-DGTSAM_UNSTABLE_BUILD_PYTHON=${GTSAM_BUILD_UNSTABLE:-ON} \ -DGTSAM_UNSTABLE_BUILD_PYTHON=${GTSAM_BUILD_UNSTABLE:-ON} \
-DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \ -DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \
-DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \ -DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \
-DGTSAM_ALLOW_DEPRECATED_SINCE_V42=OFF \ -DGTSAM_ALLOW_DEPRECATED_SINCE_V43=OFF \
-DCMAKE_INSTALL_PREFIX=$GITHUB_WORKSPACE/gtsam_install -DCMAKE_INSTALL_PREFIX=$GITHUB_WORKSPACE/gtsam_install

View File

@ -64,7 +64,7 @@ function configure()
-DGTSAM_BUILD_UNSTABLE=${GTSAM_BUILD_UNSTABLE:-ON} \ -DGTSAM_BUILD_UNSTABLE=${GTSAM_BUILD_UNSTABLE:-ON} \
-DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \ -DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \
-DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ -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_USE_QUATERNIONS=${GTSAM_USE_QUATERNIONS:-OFF} \
-DGTSAM_ROT3_EXPMAP=${GTSAM_ROT3_EXPMAP:-ON} \ -DGTSAM_ROT3_EXPMAP=${GTSAM_ROT3_EXPMAP:-ON} \
-DGTSAM_POSE3_EXPMAP=${GTSAM_POSE3_EXPMAP:-ON} \ -DGTSAM_POSE3_EXPMAP=${GTSAM_POSE3_EXPMAP:-ON} \

View File

@ -110,8 +110,8 @@ jobs:
- name: Set Allow Deprecated Flag - name: Set Allow Deprecated Flag
if: matrix.flag == 'deprecated' if: matrix.flag == 'deprecated'
run: | run: |
echo "GTSAM_ALLOW_DEPRECATED_SINCE_V42=ON" >> $GITHUB_ENV echo "GTSAM_ALLOW_DEPRECATED_SINCE_V43=ON" >> $GITHUB_ENV
echo "Allow deprecated since version 4.1" echo "Allow deprecated since version 4.3"
- name: Set Use Quaternions Flag - name: Set Use Quaternions Flag
if: matrix.flag == 'quaternions' if: matrix.flag == 'quaternions'

View File

@ -6,8 +6,6 @@ if(NOT DEFINED CMAKE_MACOSX_RPATH)
set(CMAKE_MACOSX_RPATH 0) set(CMAKE_MACOSX_RPATH 0)
endif() endif()
set(CMAKE_CXX_STANDARD 17)
# Set the version number for the library # Set the version number for the library
set (GTSAM_VERSION_MAJOR 4) set (GTSAM_VERSION_MAJOR 4)
set (GTSAM_VERSION_MINOR 3) set (GTSAM_VERSION_MINOR 3)

View File

@ -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 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 ## 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. 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.

View File

@ -142,17 +142,14 @@ endif()
if (NOT CMAKE_VERSION VERSION_LESS 3.8) 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.") 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 # 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) set(CMAKE_CXX_EXTENSIONS OFF)
if (MSVC) if (MSVC)
# NOTE(jlblanco): seems to be required in addition to the cxx_std_17 above? # 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) list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC /std:c++latest)
endif() endif()
else() else()
# Old cmake versions: # Old cmake versions:
if (NOT MSVC) 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>) list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC $<$<COMPILE_LANGUAGE:CXX>:-std=c++17>)
endif() endif()
endif() endif()

View File

@ -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_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_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_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_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON)
option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" 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) option(GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR "Use the slower but correct version of BetweenFactor" OFF)

View File

@ -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_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ")
print_enabled_config(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") 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_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_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ")
print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration")

View File

@ -27,6 +27,7 @@
#include <gtsam/geometry/Pose3.h> #include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2Stereo.h> #include <gtsam/geometry/Cal3_S2Stereo.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/utilities.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
@ -113,7 +114,7 @@ int main(int argc, char** argv) {
Values result = optimizer.optimize(); Values result = optimizer.optimize();
cout << "Final result sample:" << endl; cout << "Final result sample:" << endl;
Values pose_values = result.filter<Pose3>(); Values pose_values = utilities::allPose3s(result);
pose_values.print("Final camera poses:\n"); pose_values.print("Final camera poses:\n");
return 0; return 0;

View File

@ -80,37 +80,6 @@ bool assert_equal(const V& expected, const boost::optional<const V&>& actual, do
return assert_equal(expected, *actual, tol); 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 * Function for comparing maps of testable->testable
* TODO: replace with more generalized version * TODO: replace with more generalized version

View File

@ -204,28 +204,6 @@ inline double inner_prod(const V1 &a, const V2& b) {
return a.dot(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 * house(x,j) computes HouseHolder vector v and scaling factor beta
* from x, such that the corresponding Householder reflection zeroes out * from x, such that the corresponding Householder reflection zeroes out

View File

@ -70,7 +70,7 @@
#cmakedefine GTSAM_THROW_CHEIRALITY_EXCEPTION #cmakedefine GTSAM_THROW_CHEIRALITY_EXCEPTION
// Make sure dependent projects that want it can see deprecated functions // 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 // Support Metis-based nested dissection
#cmakedefine GTSAM_SUPPORT_NESTED_DISSECTION #cmakedefine GTSAM_SUPPORT_NESTED_DISSECTION

View File

@ -51,26 +51,6 @@ double DiscreteBayesNet::evaluate(const DiscreteValues& values) const {
return result; 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 DiscreteBayesNet::sample() const {
DiscreteValues result; DiscreteValues result;

View File

@ -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: private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;

View File

@ -235,57 +235,6 @@ DecisionTreeFactor::shared_ptr DiscreteConditional::likelihood(
return likelihood(values); 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 DiscreteConditional::argmax() const {
size_t maxValue = 0; size_t maxValue = 0;

View File

@ -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: protected:
/// Internal version of choose /// Internal version of choose
DiscreteConditional::ADT choose(const DiscreteValues& given, DiscreteConditional::ADT choose(const DiscreteValues& given,

View File

@ -93,12 +93,6 @@ class GTSAM_EXPORT DiscreteDistribution : public DiscreteConditional {
std::vector<double> pmf() const; 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 // DiscreteDistribution

View File

@ -209,13 +209,6 @@ TEST(DiscreteFactorGraph, marginalIsNotMPE) {
auto actualMPE = graph.optimize(); auto actualMPE = graph.optimize();
EXPECT(assert_equal(mpe, actualMPE)); EXPECT(assert_equal(mpe, actualMPE));
EXPECT_DOUBLES_EQUAL(0.315789, graph(mpe), 1e-5); // regression 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); ordering += Key(0), Key(1), Key(2), Key(3), Key(4);
auto chordal = graph.eliminateSequential(ordering); auto chordal = graph.eliminateSequential(ordering);
EXPECT_LONGS_EQUAL(5, chordal->size()); 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 // Let us create the Bayes tree here, just for fun, because we don't use it
DiscreteBayesTree::shared_ptr bayesTree = DiscreteBayesTree::shared_ptr bayesTree =

View File

@ -170,11 +170,6 @@ class GTSAM_EXPORT Cal3 {
return K; 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) /// Return inverted calibration matrix inv(K)
Matrix3 inverse() const; Matrix3 inverse() const;

View File

@ -100,14 +100,6 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
Vector3 vector() const; 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 * @brief: convert intrinsic coordinates xy to image coordinates uv
* Version of uncalibrate with derivatives * Version of uncalibrate with derivatives

View File

@ -371,15 +371,5 @@ boost::optional<Pose2> Pose2::Align(const Matrix& a, const Matrix& b) {
return Pose2::Align(ab_pairs); 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 } // namespace gtsam

View File

@ -343,16 +343,6 @@ inline Matrix wedge<Pose2>(const Vector& xi) {
return Matrix(Pose2::wedge(xi(0),xi(1),xi(2))).eval(); 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 // Convenience typedef
using Pose2Pair = std::pair<Pose2, Pose2>; using Pose2Pair = std::pair<Pose2, Pose2>;
using Pose2Pairs = std::vector<Pose2Pair>; using Pose2Pairs = std::vector<Pose2Pair>;

View File

@ -478,16 +478,6 @@ boost::optional<Pose3> Pose3::Align(const Matrix& a, const Matrix& b) {
return Pose3::Align(abPointPairs); return Pose3::Align(abPointPairs);
} }
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
boost::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 { Pose3 Pose3::slerp(double t, const Pose3& other, OptionalJacobian<6, 6> Hx, OptionalJacobian<6, 6> Hy) const {
return interpolate(*this, other, t, Hx, Hy); return interpolate(*this, other, t, Hx, Hy);

View File

@ -227,19 +227,6 @@ double Rot3::yaw(OptionalJacobian<1, 3> H) const {
return y; 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 { pair<Unit3, double> Rot3::axisAngle() const {
const Vector3 omega = Rot3::Logmap(*this); const Vector3 omega = Rot3::Logmap(*this);

View File

@ -515,17 +515,6 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
*/ */
gtsam::Quaternion toQuaternion() const; 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 * @brief Spherical Linear intERPolation between *this and other
* @param t a value between 0 and 1 * @param t a value between 0 and 1

View File

@ -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
}

View File

@ -37,120 +37,4 @@ namespace gtsam {
using PinholeCameraCal3Unified = gtsam::PinholeCamera<gtsam::Cal3Unified>; using PinholeCameraCal3Unified = gtsam::PinholeCamera<gtsam::Cal3Unified>;
using PinholeCameraCal3Fisheye = gtsam::PinholeCamera<gtsam::Cal3Fisheye>; 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 } // namespace gtsam

View File

@ -1,160 +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 testSimpleCamera.cpp
* @author Frank Dellaert
* @brief test SimpleCamera class
*/
#include <gtsam/geometry/SimpleCamera.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/numericalDerivative.h>
#include <CppUnitLite/TestHarness.h>
#include <cmath>
#include <iostream>
using namespace std;
using namespace gtsam;
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
static const Cal3_S2 K(625, 625, 0, 0, 0);
static const Pose3 pose1(Rot3(Vector3(1, -1, -1).asDiagonal()),
Point3(0, 0, 0.5));
static const SimpleCamera camera(pose1, K);
static const Point3 point1(-0.08,-0.08, 0.0);
static const Point3 point2(-0.08, 0.08, 0.0);
static const Point3 point3( 0.08, 0.08, 0.0);
static const Point3 point4( 0.08,-0.08, 0.0);
/* ************************************************************************* */
TEST( SimpleCamera, constructor)
{
CHECK(assert_equal( camera.calibration(), K));
CHECK(assert_equal( camera.pose(), pose1));
}
/* ************************************************************************* */
TEST( SimpleCamera, level2)
{
// Create a level camera, looking in Y-direction
Pose2 pose2(0.4,0.3,M_PI/2.0);
SimpleCamera camera = SimpleCamera::Level(K, pose2, 0.1);
// expected
Point3 x(1,0,0),y(0,0,-1),z(0,1,0);
Rot3 wRc(x,y,z);
Pose3 expected(wRc,Point3(0.4,0.3,0.1));
CHECK(assert_equal( camera.pose(), expected));
}
/* ************************************************************************* */
TEST( SimpleCamera, lookat)
{
// Create a level camera, looking in Y-direction
Point3 C(10,0,0);
SimpleCamera camera = SimpleCamera::Lookat(C, Point3(0,0,0), Point3(0,0,1));
// expected
Point3 xc(0,1,0),yc(0,0,-1),zc(-1,0,0);
Pose3 expected(Rot3(xc,yc,zc),C);
CHECK(assert_equal( camera.pose(), expected));
Point3 C2(30,0,10);
SimpleCamera camera2 = SimpleCamera::Lookat(C2, Point3(0,0,0), Point3(0,0,1));
Matrix R = camera2.pose().rotation().matrix();
Matrix I = trans(R)*R;
CHECK(assert_equal(I, I_3x3));
}
/* ************************************************************************* */
TEST( SimpleCamera, project)
{
CHECK(assert_equal( camera.project(point1), Point2(-100, 100) ));
CHECK(assert_equal( camera.project(point2), Point2(-100, -100) ));
CHECK(assert_equal( camera.project(point3), Point2( 100, -100) ));
CHECK(assert_equal( camera.project(point4), Point2( 100, 100) ));
}
/* ************************************************************************* */
TEST( SimpleCamera, backproject)
{
CHECK(assert_equal( camera.backproject(Point2(-100, 100), 0.5), point1));
CHECK(assert_equal( camera.backproject(Point2(-100, -100), 0.5), point2));
CHECK(assert_equal( camera.backproject(Point2( 100, -100), 0.5), point3));
CHECK(assert_equal( camera.backproject(Point2( 100, 100), 0.5), point4));
}
/* ************************************************************************* */
TEST( SimpleCamera, backproject2)
{
Point3 origin(0,0,0);
Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.); // a camera looking down
SimpleCamera camera(Pose3(rot, origin), K);
Point3 actual = camera.backproject(Point2(0,0), 1.);
Point3 expected(0., 1., 0.);
pair<Point2, bool> x = camera.projectSafe(expected);
CHECK(assert_equal(expected, actual));
CHECK(assert_equal(Point2(0,0), x.first));
CHECK(x.second);
}
/* ************************************************************************* */
static Point2 project2(const Pose3& pose, const Point3& point) {
return SimpleCamera(pose,K).project(point);
}
TEST( SimpleCamera, Dproject_point_pose)
{
Matrix Dpose, Dpoint;
Point2 result = camera.project(point1, Dpose, Dpoint, boost::none);
Matrix numerical_pose = numericalDerivative21(project2, pose1, point1);
Matrix numerical_point = numericalDerivative22(project2, pose1, point1);
CHECK(assert_equal(result, Point2(-100, 100) ));
CHECK(assert_equal(Dpose, numerical_pose, 1e-7));
CHECK(assert_equal(Dpoint, numerical_point,1e-7));
}
/* ************************************************************************* */
TEST( SimpleCamera, simpleCamera)
{
Cal3_S2 K(468.2,427.2,91.2,300,200);
Rot3 R(
0.41380,0.90915,0.04708,
-0.57338,0.22011,0.78917,
0.70711,-0.35355,0.61237);
Point3 T(1000,2000,1500);
SimpleCamera expected(Pose3(R.inverse(),T),K);
// H&Z example, 2nd edition, page 163
Matrix P = (Matrix(3,4) <<
3.53553e2, 3.39645e2, 2.77744e2, -1.44946e6,
-1.03528e2, 2.33212e1, 4.59607e2, -6.32525e5,
7.07107e-1, -3.53553e-1,6.12372e-1, -9.18559e2).finished();
SimpleCamera actual = simpleCamera(P);
// Note precision of numbers given in book
CHECK(assert_equal(expected, actual,1e-1));
}
#endif
/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */

View File

@ -286,61 +286,6 @@ namespace gtsam {
// Access the derived factor graph class // Access the derived factor graph class
FactorGraphType& asDerived() { return static_cast<FactorGraphType&>(*this); } 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 = boost::none,
OptionalOrderingType orderingType = boost::none) 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 = boost::none,
OptionalOrderingType orderingType = boost::none) const {
return eliminateMultifrontal(orderingType, function, variableIndex);
}
/** @deprecated */
boost::shared_ptr<BayesNetType> GTSAM_DEPRECATED marginalMultifrontalBayesNet(
boost::variant<const Ordering&, const KeyVector&> variables,
boost::none_t,
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
OptionalVariableIndex variableIndex = boost::none) const {
return marginalMultifrontalBayesNet(variables, function, variableIndex);
}
/** @deprecated */
boost::shared_ptr<BayesTreeType> GTSAM_DEPRECATED marginalMultifrontalBayesTree(
boost::variant<const Ordering&, const KeyVector&> variables,
boost::none_t,
const Eliminate& function = EliminationTraitsType::DefaultEliminate,
OptionalVariableIndex variableIndex = boost::none) const {
return marginalMultifrontalBayesTree(variables, function, variableIndex);
}
#endif
}; };
} }

View File

@ -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 } // namespace gtsam

View File

@ -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: private:
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;

View File

@ -408,18 +408,6 @@ namespace gtsam {
void serialize(ARCHIVE & ar, const unsigned int /*version*/) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
} }
public:
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
/** @deprecated */
VectorValues GTSAM_DEPRECATED
optimize(boost::none_t, const Eliminate& function =
EliminationTraitsType::DefaultEliminate) const {
return optimize(function);
}
#endif
}; };
/** /**

View File

@ -202,12 +202,6 @@ public:
const PreintegratedAhrsMeasurements& pim, const Vector3& omegaCoriolis, const PreintegratedAhrsMeasurements& pim, const Vector3& omegaCoriolis,
const boost::optional<Pose3>& body_P_sensor = boost::none); const boost::optional<Pose3>& body_P_sensor = boost::none);
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
/// @deprecated name
typedef PreintegratedAhrsMeasurements PreintegratedMeasurements;
#endif
private: private:
/** Serialization function */ /** Serialization function */

View File

@ -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: private:
/// @name Advanced Interface /// @name Advanced Interface

View File

@ -46,58 +46,6 @@ TEST(ImuBias, Constructor) {
Bias bias3(bias2); 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) { TEST(ImuBias, operatorSub) {
Bias biasActual = -bias1; Bias biasActual = -bias1;

View File

@ -300,55 +300,4 @@ struct traits<ExpressionFactorN<T, Args...>>
: public Testable<ExpressionFactorN<T, Args...>> {}; : public Testable<ExpressionFactorN<T, Args...>> {};
// ExpressionFactorN // 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 } // namespace gtsam

View File

@ -51,12 +51,6 @@ class ExtendedKalmanFilter {
typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr; typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr;
typedef VALUE T; 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: protected:
T x_; // linearization point T x_; // linearization point
JacobianFactor::shared_ptr priorFactor_; // Gaussian density on x_ JacobianFactor::shared_ptr priorFactor_; // Gaussian density on x_

View File

@ -129,22 +129,6 @@ protected:
/** Compute the Bayes Tree as a helper function to the constructor */ /** Compute the Bayes Tree as a helper function to the constructor */
void computeBayesTree(const Ordering& ordering); 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
}; };
/** /**

View File

@ -260,39 +260,6 @@ namespace gtsam {
ar & boost::serialization::make_nvp("NonlinearFactorGraph", ar & boost::serialization::make_nvp("NonlinearFactorGraph",
boost::serialization::base_object<Base>(*this)); 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, boost::none_t, const Dampen& dampen = nullptr) const
{return linearizeToHessianFactor(values, dampen);}
/** @deprecated */
Values GTSAM_DEPRECATED updateCholesky(const Values& values, boost::none_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 /// traits

View File

@ -107,172 +107,6 @@ namespace gtsam {
return result; 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<> template<>
inline bool Values::filterHelper<Value>(const std::function<bool(Key)> filter, inline bool Values::filterHelper<Value>(const std::function<bool(Key)> filter,

View File

@ -31,9 +31,6 @@
#include <boost/iterator/transform_iterator.hpp> #include <boost/iterator/transform_iterator.hpp>
#include <boost/ptr_container/serialize_ptr_map.hpp> #include <boost/ptr_container/serialize_ptr_map.hpp>
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
#include <boost/iterator/filter_iterator.hpp>
#endif
#include <string> #include <string>
#include <utility> #include <utility>
@ -342,42 +339,6 @@ namespace gtsam {
std::map<Key, ValueType> // , std::less<Key>, Eigen::aligned_allocator<ValueType> std::map<Key, ValueType> // , std::less<Key>, Eigen::aligned_allocator<ValueType>
extract(const std::function<bool(Key)>& filterFcn = &_truePredicate<Key>) const; 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: private:
// Filters based on ValueType (if not Value) and also based on the user- // Filters based on ValueType (if not Value) and also based on the user-
// supplied \c filter function. // supplied \c filter function.

View File

@ -343,68 +343,6 @@ TEST(Values, filter) {
values.insert(2, pose2); values.insert(2, pose2);
values.insert(3, pose3); 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. // Test counting by type.
EXPECT_LONGS_EQUAL(2, (long)values.count<Pose3>()); EXPECT_LONGS_EQUAL(2, (long)values.count<Pose3>());
EXPECT_LONGS_EQUAL(2, (long)values.count<Pose2>()); EXPECT_LONGS_EQUAL(2, (long)values.count<Pose2>());
@ -412,7 +350,6 @@ TEST(Values, filter) {
// Filter by type using extract. // Filter by type using extract.
auto extracted_pose3s = values.extract<Pose3>(); auto extracted_pose3s = values.extract<Pose3>();
EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size()); EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size());
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -428,27 +365,9 @@ TEST(Values, Symbol_filter) {
values.insert(X(2), pose2); values.insert(X(2), pose2);
values.insert(Symbol('y', 3), pose3); values.insert(Symbol('y', 3), pose3);
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 // Test extract with filter on symbol:
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:
auto extracted_pose3s = values.extract<Pose3>(Symbol::ChrTest('y')); auto extracted_pose3s = values.extract<Pose3>(Symbol::ChrTest('y'));
EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size()); EXPECT_LONGS_EQUAL(2, (long)extracted_pose3s.size());
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -322,25 +322,6 @@ bool writeBAL(const std::string &filename, const SfmData &data) {
return true; 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) { SfmData readBal(const std::string &filename) {
return SfmData::FromBalFile(filename); return SfmData::FromBalFile(filename);
} }

View File

@ -122,17 +122,6 @@ struct GTSAM_EXPORT SfmData {
bool equals(const SfmData& sfmData, double tol = 1e-9) const; 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 /// @name Serialization
/// @{ /// @{
@ -151,13 +140,6 @@ struct GTSAM_EXPORT SfmData {
template <> template <>
struct traits<SfmData> : public Testable<SfmData> {}; 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 * @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. * returns the data as a SfmData structure. Mainly used by wrapped code.

View File

@ -158,18 +158,6 @@ struct GTSAM_EXPORT SfmTrack : SfmTrack2d {
bool equals(const SfmTrack& sfmTrack, double tol = 1e-9) const; 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 /// @name Serialization
/// @{ /// @{

View File

@ -962,15 +962,4 @@ parse3DFactors(const std::string &filename,
return parseFactors<Pose3>(filename, model, maxIndex); 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 } // namespace gtsam

View File

@ -225,21 +225,4 @@ parse3DFactors(const std::string &filename,
using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>; using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
using BinaryMeasurementsPoint3 = std::vector<BinaryMeasurement<Point3>>; using BinaryMeasurementsPoint3 = std::vector<BinaryMeasurement<Point3>>;
using BinaryMeasurementsRot3 = std::vector<BinaryMeasurement<Rot3>>; using BinaryMeasurementsRot3 = std::vector<BinaryMeasurement<Rot3>>;
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
inline boost::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 } // namespace gtsam

View File

@ -20,6 +20,7 @@
#include <gtsam/geometry/Pose3.h> #include <gtsam/geometry/Pose3.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/utilities.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
@ -35,12 +36,15 @@
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
using symbol_shorthand::K;
using symbol_shorthand::L;
using symbol_shorthand::X;
int main(int argc, char** argv){ int main(int argc, char** argv){
Values initial_estimate; Values initial_estimate;
NonlinearFactorGraph graph; NonlinearFactorGraph graph;
const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1); const auto model = noiseModel::Isotropic::Sigma(2,1);
string calibration_loc = findExampleDataFile("VO_calibration00s.txt"); string calibration_loc = findExampleDataFile("VO_calibration00s.txt");
string pose_loc = findExampleDataFile("VO_camera_poses00s.txt"); string pose_loc = findExampleDataFile("VO_camera_poses00s.txt");
@ -54,13 +58,13 @@ int main(int argc, char** argv){
calibration_file >> fx >> fy >> s >> u0 >> v0 >> b; calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
//create stereo camera calibration object //create stereo camera calibration object
const Cal3_S2::shared_ptr K(new Cal3_S2(fx,fy,s,u0,v0)); const Cal3_S2 true_K(fx,fy,s,u0,v0);
const Cal3_S2::shared_ptr noisy_K(new Cal3_S2(fx*1.2,fy*1.2,s,u0-10,v0+10)); const Cal3_S2 noisy_K(fx*1.2,fy*1.2,s,u0-10,v0+10);
initial_estimate.insert(Symbol('K', 0), *noisy_K); initial_estimate.insert(K(0), noisy_K);
noiseModel::Diagonal::shared_ptr calNoise = noiseModel::Diagonal::Sigmas((Vector(5) << 500, 500, 1e-5, 100, 100).finished()); auto calNoise = noiseModel::Diagonal::Sigmas((Vector(5) << 500, 500, 1e-5, 100, 100).finished());
graph.addPrior(Symbol('K', 0), *noisy_K, calNoise); graph.addPrior(K(0), noisy_K, calNoise);
ifstream pose_file(pose_loc.c_str()); ifstream pose_file(pose_loc.c_str());
@ -75,7 +79,7 @@ int main(int argc, char** argv){
initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
} }
noiseModel::Isotropic::shared_ptr poseNoise = noiseModel::Isotropic::Sigma(6, 0.01); auto poseNoise = noiseModel::Isotropic::Sigma(6, 0.01);
graph.addPrior(Symbol('x', pose_id), Pose3(m), poseNoise); graph.addPrior(Symbol('x', pose_id), Pose3(m), poseNoise);
// camera and landmark keys // camera and landmark keys
@ -83,22 +87,22 @@ int main(int argc, char** argv){
// pixel coordinates uL, uR, v (same for left/right images due to rectification) // pixel coordinates uL, uR, v (same for left/right images due to rectification)
// landmark coordinates X, Y, Z in camera frame, resulting from triangulation // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
double uL, uR, v, X, Y, Z; double uL, uR, v, _X, Y, Z;
ifstream factor_file(factor_loc.c_str()); ifstream factor_file(factor_loc.c_str());
cout << "Reading stereo factors" << endl; cout << "Reading stereo factors" << endl;
//read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation //read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation
while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) { while (factor_file >> x >> l >> uL >> uR >> v >> _X >> Y >> Z) {
// graph.emplace_shared<GenericStereoFactor<Pose3, Point3> >(StereoPoint2(uL, uR, v), model, Symbol('x', x), Symbol('l', l), K); // graph.emplace_shared<GenericStereoFactor<Pose3, Point3> >(StereoPoint2(uL, uR, v), model, X(x), L(l), K);
graph.emplace_shared<GeneralSFMFactor2<Cal3_S2> >(Point2(uL,v), model, Symbol('x', x), Symbol('l', l), Symbol('K', 0)); graph.emplace_shared<GeneralSFMFactor2<Cal3_S2> >(Point2(uL,v), model, X(x), L(l), K(0));
//if the landmark variable included in this factor has not yet been added to the initial variable value estimate, add it //if the landmark variable included in this factor has not yet been added to the initial variable value estimate, add it
if (!initial_estimate.exists(Symbol('l', l))) { if (!initial_estimate.exists(L(l))) {
Pose3 camPose = initial_estimate.at<Pose3>(Symbol('x', x)); Pose3 camPose = initial_estimate.at<Pose3>(X(x));
//transformFrom() transforms the input Point3 from the camera pose space, camPose, to the global space //transformFrom() transforms the input Point3 from the camera pose space, camPose, to the global space
Point3 worldPoint = camPose.transformFrom(Point3(X, Y, Z)); Point3 worldPoint = camPose.transformFrom(Point3(_X, Y, Z));
initial_estimate.insert(Symbol('l', l), worldPoint); initial_estimate.insert(L(l), worldPoint);
} }
} }
@ -123,7 +127,7 @@ int main(int argc, char** argv){
double currentError; double currentError;
stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(Symbol('K',0)).vector().transpose() << endl; stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(K(0)).vector().transpose() << endl;
// Iterative loop // Iterative loop
@ -132,7 +136,7 @@ int main(int argc, char** argv){
currentError = optimizer.error(); currentError = optimizer.error();
optimizer.iterate(); optimizer.iterate();
stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(Symbol('K',0)).vector().transpose() << endl; stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(K(0)).vector().transpose() << endl;
if(params.verbosity >= NonlinearOptimizerParams::ERROR) cout << "newError: " << optimizer.error() << endl; if(params.verbosity >= NonlinearOptimizerParams::ERROR) cout << "newError: " << optimizer.error() << endl;
} while(optimizer.iterations() < params.maxIterations && } while(optimizer.iterations() < params.maxIterations &&
@ -142,13 +146,13 @@ int main(int argc, char** argv){
Values result = optimizer.values(); Values result = optimizer.values();
cout << "Final result sample:" << endl; cout << "Final result sample:" << endl;
Values pose_values = result.filter<Pose3>(); Values pose_values = utilities::allPose3s(result);
pose_values.print("Final camera poses:\n"); pose_values.print("Final camera poses:\n");
Values(result.filter<Cal3_S2>()).print("Final K\n"); result.at<Cal3_S2>(K(0)).print("Final K\n");
noisy_K->print("Initial noisy K\n"); noisy_K.print("Initial noisy K\n");
K->print("Initial correct K\n"); true_K.print("Initial correct K\n");
return 0; return 0;
} }

View File

@ -30,6 +30,7 @@
#include <gtsam/slam/dataset.h> #include <gtsam/slam/dataset.h>
#include <gtsam/geometry/Cal3_S2Stereo.h> #include <gtsam/geometry/Cal3_S2Stereo.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/utilities.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
@ -114,7 +115,7 @@ int main(int argc, char** argv){
Values result = optimizer.optimize(); Values result = optimizer.optimize();
cout << "Final result sample:" << endl; cout << "Final result sample:" << endl;
Values pose_values = result.filter<Pose3>(); Values pose_values = utilities::allPose3s(result);
pose_values.print("Final camera poses:\n"); pose_values.print("Final camera poses:\n");
return 0; return 0;

View File

@ -234,9 +234,8 @@ int main(int argc, char** argv) {
} }
} }
countK = 0; countK = 0;
for(const auto it: result.filter<Point2>()) for (const auto& [key, point] : result.extract<Point2>())
os2 << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t1" os2 << key << "\t" << point.x() << "\t" << point.y() << "\t1" << endl;
<< endl;
if (smart) { if (smart) {
for(size_t jj: ids) { for(size_t jj: ids) {
Point2 landmark = smartFactors[jj]->triangulate(result); Point2 landmark = smartFactors[jj]->triangulate(result);
@ -257,9 +256,8 @@ int main(int argc, char** argv) {
// Write result to file // Write result to file
Values result = isam.calculateEstimate(); Values result = isam.calculateEstimate();
ofstream os("rangeResult.txt"); ofstream os("rangeResult.txt");
for(const auto it: result.filter<Pose2>()) for (const auto& [key, pose] : result.extract<Pose2>())
os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t" os << key << "\t" << pose.x() << "\t" << pose.y() << "\t" << pose.theta() << endl;
<< it.value.theta() << endl;
exit(0); exit(0);
} }

View File

@ -202,13 +202,11 @@ int main(int argc, char** argv) {
// Write result to file // Write result to file
Values result = isam.calculateEstimate(); Values result = isam.calculateEstimate();
ofstream os2("rangeResultLM.txt"); ofstream os2("rangeResultLM.txt");
for(const auto it: result.filter<Point2>()) for (const auto& [key, point] : result.extract<Point2>())
os2 << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t1" os2 << key << "\t" << point.x() << "\t" << point.y() << "\t1" << endl;
<< endl;
ofstream os("rangeResult.txt"); ofstream os("rangeResult.txt");
for(const auto it: result.filter<Pose2>()) for (const auto& [key, pose] : result.extract<Pose2>())
os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t" os << key << "\t" << pose.x() << "\t" << pose.y() << "\t" << pose.theta() << endl;
<< it.value.theta() << endl;
exit(0); exit(0);
} }

View File

@ -29,6 +29,7 @@
#include <gtsam/geometry/Pose3.h> #include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2Stereo.h> #include <gtsam/geometry/Cal3_S2Stereo.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/utilities.h>
#include <gtsam/nonlinear/NonlinearEquality.h> #include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
@ -43,6 +44,7 @@
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
using symbol_shorthand::X;
int main(int argc, char** argv){ int main(int argc, char** argv){
@ -84,16 +86,16 @@ int main(int argc, char** argv){
if(add_initial_noise){ if(add_initial_noise){
m(1,3) += (pose_id % 10)/10.0; m(1,3) += (pose_id % 10)/10.0;
} }
initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); initial_estimate.insert(X(pose_id), Pose3(m));
} }
Values initial_pose_values = initial_estimate.filter<Pose3>(); const auto initialPoses = initial_estimate.extract<Pose3>();
if (output_poses) { if (output_poses) {
init_pose3Out.open(init_poseOutput.c_str(), ios::out); init_pose3Out.open(init_poseOutput.c_str(), ios::out);
for (size_t i = 1; i <= initial_pose_values.size(); i++) { for (size_t i = 1; i <= initialPoses.size(); i++) {
init_pose3Out init_pose3Out
<< i << " " << i << " "
<< initial_pose_values.at<Pose3>(Symbol('x', i)).matrix().format( << initialPoses.at(X(i)).matrix().format(
Eigen::IOFormat(Eigen::StreamPrecision, 0, " ", " ")) << endl; Eigen::IOFormat(Eigen::StreamPrecision, 0, " ", " ")) << endl;
} }
} }
@ -103,7 +105,7 @@ int main(int argc, char** argv){
// pixel coordinates uL, uR, v (same for left/right images due to rectification) // pixel coordinates uL, uR, v (same for left/right images due to rectification)
// landmark coordinates X, Y, Z in camera frame, resulting from triangulation // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
double uL, uR, v, X, Y, Z; double uL, uR, v, _X, Y, Z;
ifstream factor_file(factor_loc.c_str()); ifstream factor_file(factor_loc.c_str());
cout << "Reading stereo factors" << endl; cout << "Reading stereo factors" << endl;
@ -112,21 +114,21 @@ int main(int argc, char** argv){
SmartFactor::shared_ptr factor(new SmartFactor(model)); SmartFactor::shared_ptr factor(new SmartFactor(model));
size_t current_l = 3; // hardcoded landmark ID from first measurement size_t current_l = 3; // hardcoded landmark ID from first measurement
while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) { while (factor_file >> x >> l >> uL >> uR >> v >> _X >> Y >> Z) {
if(current_l != l) { if(current_l != l) {
graph.push_back(factor); graph.push_back(factor);
factor = SmartFactor::shared_ptr(new SmartFactor(model)); factor = SmartFactor::shared_ptr(new SmartFactor(model));
current_l = l; current_l = l;
} }
factor->add(StereoPoint2(uL,uR,v), Symbol('x',x), K); factor->add(StereoPoint2(uL,uR,v), X(x), K);
} }
Pose3 first_pose = initial_estimate.at<Pose3>(Symbol('x',1)); Pose3 first_pose = initial_estimate.at<Pose3>(X(1));
//constrain the first pose such that it cannot change from its original value during optimization //constrain the first pose such that it cannot change from its original value during optimization
// NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
// QR is much slower than Cholesky, but numerically more stable // QR is much slower than Cholesky, but numerically more stable
graph.emplace_shared<NonlinearEquality<Pose3> >(Symbol('x',1),first_pose); graph.emplace_shared<NonlinearEquality<Pose3> >(X(1),first_pose);
LevenbergMarquardtParams params; LevenbergMarquardtParams params;
params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
@ -138,13 +140,13 @@ int main(int argc, char** argv){
Values result = optimizer.optimize(); Values result = optimizer.optimize();
cout << "Final result sample:" << endl; cout << "Final result sample:" << endl;
Values pose_values = result.filter<Pose3>(); Values pose_values = utilities::allPose3s(result);
pose_values.print("Final camera poses:\n"); pose_values.print("Final camera poses:\n");
if(output_poses){ if(output_poses){
pose3Out.open(poseOutput.c_str(),ios::out); pose3Out.open(poseOutput.c_str(),ios::out);
for(size_t i = 1; i<=pose_values.size(); i++){ for(size_t i = 1; i<=pose_values.size(); i++){
pose3Out << i << " " << pose_values.at<Pose3>(Symbol('x',i)).matrix().format(Eigen::IOFormat(Eigen::StreamPrecision, 0, pose3Out << i << " " << pose_values.at<Pose3>(X(i)).matrix().format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
" ", " ")) << endl; " ", " ")) << endl;
} }
cout << "Writing output" << endl; cout << "Writing output" << endl;

View File

@ -173,22 +173,6 @@ BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_
BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D"); 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 // Actual implementations of functions
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -10,8 +10,8 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* @file timeVirtual.cpp * @file timeLago.cpp
* @brief Time the overhead of using virtual destructors and methods * @brief Time the LAGO initialization method
* @author Richard Roberts * @author Richard Roberts
* @date Dec 3, 2010 * @date Dec 3, 2010
*/ */
@ -36,16 +36,15 @@ int main(int argc, char *argv[]) {
Values::shared_ptr solution; Values::shared_ptr solution;
NonlinearFactorGraph::shared_ptr g; NonlinearFactorGraph::shared_ptr g;
string inputFile = findExampleDataFile("w10000"); string inputFile = findExampleDataFile("w10000");
SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0).finished()); auto model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0).finished());
boost::tie(g, solution) = load2D(inputFile, model); boost::tie(g, solution) = load2D(inputFile, model);
// add noise to create initial estimate // add noise to create initial estimate
Values initial; Values initial;
Values::ConstFiltered<Pose2> poses = solution->filter<Pose2>(); auto noise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.5, 0.5, 15.0 * M_PI / 180.0).finished());
SharedDiagonal noise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.5, 0.5, 15.0 * M_PI / 180.0).finished());
Sampler sampler(noise); Sampler sampler(noise);
for(const Values::ConstFiltered<Pose2>::KeyValuePair& it: poses) for(const auto& [key,pose]: solution->extract<Pose2>())
initial.insert(it.key, it.value.retract(sampler.sample())); initial.insert(key, pose.retract(sampler.sample()));
// Add prior on the pose having index (key) = 0 // Add prior on the pose having index (key) = 0
noiseModel::Diagonal::shared_ptr priorModel = // noiseModel::Diagonal::shared_ptr priorModel = //