Global replace to V42
parent
a38de28535
commit
6d0c55901c
|
@ -75,7 +75,7 @@ cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} \
|
|||
-DGTSAM_UNSTABLE_BUILD_PYTHON=${GTSAM_BUILD_UNSTABLE:-ON} \
|
||||
-DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \
|
||||
-DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \
|
||||
-DGTSAM_ALLOW_DEPRECATED_SINCE_V41=OFF \
|
||||
-DGTSAM_ALLOW_DEPRECATED_SINCE_V42=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_V41=${GTSAM_ALLOW_DEPRECATED_SINCE_V41:-OFF} \
|
||||
-DGTSAM_ALLOW_DEPRECATED_SINCE_V42=${GTSAM_ALLOW_DEPRECATED_SINCE_V42:-OFF} \
|
||||
-DGTSAM_USE_QUATERNIONS=${GTSAM_USE_QUATERNIONS:-OFF} \
|
||||
-DGTSAM_ROT3_EXPMAP=${GTSAM_ROT3_EXPMAP:-ON} \
|
||||
-DGTSAM_POSE3_EXPMAP=${GTSAM_POSE3_EXPMAP:-ON} \
|
||||
|
|
|
@ -110,7 +110,7 @@ jobs:
|
|||
- name: Set Allow Deprecated Flag
|
||||
if: matrix.flag == 'deprecated'
|
||||
run: |
|
||||
echo "GTSAM_ALLOW_DEPRECATED_SINCE_V41=ON" >> $GITHUB_ENV
|
||||
echo "GTSAM_ALLOW_DEPRECATED_SINCE_V42=ON" >> $GITHUB_ENV
|
||||
echo "Allow deprecated since version 4.1"
|
||||
|
||||
- name: Set Use Quaternions Flag
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
As of Dec 2021, the `develop` branch is officially in "Pre 4.2" mode. A great new feature we will be adding in 4.2 is *hybrid inference* a la DCSLAM (Kevin Doherty et al) and we envision several API-breaking changes will happen in the discrete folder.
|
||||
|
||||
In addition, features deprecated in 4.1 will be removed. Please use the last [4.1.1 release](https://github.com/borglab/gtsam/releases/tag/4.1.1) if you need those features. However, most (not all, unfortunately) are easily converted and can be tracked down (in 4.1.1) by disabling the cmake flag `GTSAM_ALLOW_DEPRECATED_SINCE_V41`.
|
||||
In addition, features deprecated in 4.1 will be removed. Please use the last [4.1.1 release](https://github.com/borglab/gtsam/releases/tag/4.1.1) if you need those features. However, most (not all, unfortunately) are easily converted and can be tracked down (in 4.1.1) by disabling the cmake flag `GTSAM_ALLOW_DEPRECATED_SINCE_V42`.
|
||||
|
||||
## What is GTSAM?
|
||||
|
||||
|
@ -57,7 +57,7 @@ GTSAM 4 introduces several new features, most notably Expressions and a Python t
|
|||
|
||||
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_V41` for newly deprecated methods since the 4.1 release, which is on by default, allowing anyone to just pull version 4.1 and compile.
|
||||
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
|
||||
|
|
|
@ -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_V41 "Allow use of methods/functions deprecated in GTSAM 4.1" ON)
|
||||
option(GTSAM_ALLOW_DEPRECATED_SINCE_V42 "Allow use of methods/functions deprecated in GTSAM 4.1" 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)
|
||||
|
|
|
@ -86,7 +86,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_V41} "Allow features deprecated in GTSAM 4.1")
|
||||
print_enabled_config(${GTSAM_ALLOW_DEPRECATED_SINCE_V42} "Allow features deprecated in GTSAM 4.1")
|
||||
print_enabled_config(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ")
|
||||
print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration")
|
||||
|
||||
|
|
|
@ -215,7 +215,7 @@ DenseBase<Derived>::Constant(const Scalar& value)
|
|||
return DenseBase<Derived>::NullaryExpr(RowsAtCompileTime, ColsAtCompileTime, internal::scalar_constant_op<Scalar>(value));
|
||||
}
|
||||
|
||||
/** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(Index,const Scalar&,const Scalar&)
|
||||
/** @deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(Index,const Scalar&,const Scalar&)
|
||||
*
|
||||
* \sa LinSpaced(Index,Scalar,Scalar), setLinSpaced(Index,const Scalar&,const Scalar&)
|
||||
*/
|
||||
|
@ -227,7 +227,7 @@ DenseBase<Derived>::LinSpaced(Sequential_t, Index size, const Scalar& low, const
|
|||
return DenseBase<Derived>::NullaryExpr(size, internal::linspaced_op<Scalar,PacketScalar>(low,high,size));
|
||||
}
|
||||
|
||||
/** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(const Scalar&,const Scalar&)
|
||||
/** @deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(const Scalar&,const Scalar&)
|
||||
*
|
||||
* \sa LinSpaced(Scalar,Scalar)
|
||||
*/
|
||||
|
|
|
@ -298,7 +298,7 @@ template<typename Derived> class DenseBase
|
|||
|
||||
/** \internal
|
||||
* Copies \a other into *this without evaluating other. \returns a reference to *this.
|
||||
* \deprecated */
|
||||
* @deprecated */
|
||||
template<typename OtherDerived>
|
||||
EIGEN_DEVICE_FUNC
|
||||
Derived& lazyAssign(const DenseBase<OtherDerived>& other);
|
||||
|
@ -306,7 +306,7 @@ template<typename Derived> class DenseBase
|
|||
EIGEN_DEVICE_FUNC
|
||||
CommaInitializer<Derived> operator<< (const Scalar& s);
|
||||
|
||||
/** \deprecated it now returns \c *this */
|
||||
/** @deprecated it now returns \c *this */
|
||||
template<unsigned int Added,unsigned int Removed>
|
||||
EIGEN_DEPRECATED
|
||||
const Derived& flagged() const
|
||||
|
|
|
@ -32,7 +32,7 @@ template<typename Derived> struct EigenBase
|
|||
|
||||
/** \brief The interface type of indices
|
||||
* \details To change this, \c \#define the preprocessor symbol \c EIGEN_DEFAULT_DENSE_INDEX_TYPE.
|
||||
* \deprecated Since Eigen 3.3, its usage is deprecated. Use Eigen::Index instead.
|
||||
* @deprecated Since Eigen 3.3, its usage is deprecated. Use Eigen::Index instead.
|
||||
* \sa StorageIndex, \ref TopicPreprocessorDirectives.
|
||||
*/
|
||||
typedef Eigen::Index Index;
|
||||
|
|
|
@ -435,12 +435,12 @@ template<typename _MatrixType, unsigned int _Mode> class TriangularViewImpl<_Mat
|
|||
TriangularViewType& operator=(const TriangularViewImpl& other)
|
||||
{ return *this = other.derived().nestedExpression(); }
|
||||
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
template<typename OtherDerived>
|
||||
EIGEN_DEVICE_FUNC
|
||||
void lazyAssign(const TriangularBase<OtherDerived>& other);
|
||||
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
template<typename OtherDerived>
|
||||
EIGEN_DEVICE_FUNC
|
||||
void lazyAssign(const MatrixBase<OtherDerived>& other);
|
||||
|
@ -523,7 +523,7 @@ template<typename _MatrixType, unsigned int _Mode> class TriangularViewImpl<_Mat
|
|||
call_assignment(derived(), other.const_cast_derived(), internal::swap_assign_op<Scalar>());
|
||||
}
|
||||
|
||||
/** \deprecated
|
||||
/** @deprecated
|
||||
* Shortcut for \code (*this).swap(other.triangularView<(*this)::Mode>()) \endcode */
|
||||
template<typename OtherDerived>
|
||||
EIGEN_DEVICE_FUNC
|
||||
|
|
|
@ -65,7 +65,7 @@ const unsigned int RowMajorBit = 0x1;
|
|||
const unsigned int EvalBeforeNestingBit = 0x2;
|
||||
|
||||
/** \ingroup flags
|
||||
* \deprecated
|
||||
* @deprecated
|
||||
* means the expression should be evaluated before any assignment */
|
||||
EIGEN_DEPRECATED
|
||||
const unsigned int EvalBeforeAssigningBit = 0x4; // FIXME deprecated
|
||||
|
@ -149,7 +149,7 @@ const unsigned int LvalueBit = 0x20;
|
|||
*/
|
||||
const unsigned int DirectAccessBit = 0x40;
|
||||
|
||||
/** \deprecated \ingroup flags
|
||||
/** @deprecated \ingroup flags
|
||||
*
|
||||
* means the first coefficient packet is guaranteed to be aligned.
|
||||
* An expression cannot has the AlignedBit without the PacketAccessBit flag.
|
||||
|
|
|
@ -84,10 +84,10 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim)
|
|||
/** \returns the dimension in which the box holds */
|
||||
EIGEN_DEVICE_FUNC inline Index dim() const { return AmbientDimAtCompileTime==Dynamic ? m_min.size() : Index(AmbientDimAtCompileTime); }
|
||||
|
||||
/** \deprecated use isEmpty() */
|
||||
/** @deprecated use isEmpty() */
|
||||
EIGEN_DEVICE_FUNC inline bool isNull() const { return isEmpty(); }
|
||||
|
||||
/** \deprecated use setEmpty() */
|
||||
/** @deprecated use setEmpty() */
|
||||
EIGEN_DEVICE_FUNC inline void setNull() { setEmpty(); }
|
||||
|
||||
/** \returns true if the box is empty.
|
||||
|
|
|
@ -170,7 +170,7 @@ EIGEN_DEVICE_FUNC inline _Scalar ParametrizedLine<_Scalar, _AmbientDim,_Options>
|
|||
}
|
||||
|
||||
|
||||
/** \deprecated use intersectionParameter()
|
||||
/** @deprecated use intersectionParameter()
|
||||
* \returns the parameter value of the intersection between \c *this and the given \a hyperplane
|
||||
*/
|
||||
template <typename _Scalar, int _AmbientDim, int _Options>
|
||||
|
|
|
@ -142,13 +142,13 @@ template<typename Derived>
|
|||
inline const DiagonalWrapper<const Derived> Scaling(const MatrixBase<Derived>& coeffs)
|
||||
{ return coeffs.asDiagonal(); }
|
||||
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
typedef DiagonalMatrix<float, 2> AlignedScaling2f;
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
typedef DiagonalMatrix<double,2> AlignedScaling2d;
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
typedef DiagonalMatrix<float, 3> AlignedScaling3f;
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
typedef DiagonalMatrix<double,3> AlignedScaling3d;
|
||||
//@}
|
||||
|
||||
|
|
|
@ -493,7 +493,7 @@ public:
|
|||
}
|
||||
};
|
||||
|
||||
/** \deprecated use SimplicialLDLT or class SimplicialLLT
|
||||
/** @deprecated use SimplicialLDLT or class SimplicialLLT
|
||||
* \ingroup SparseCholesky_Module
|
||||
* \class SimplicialCholesky
|
||||
*
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
|
||||
namespace Eigen {
|
||||
|
||||
/** \deprecated Use Map<SparseMatrix<> >
|
||||
/** @deprecated Use Map<SparseMatrix<> >
|
||||
* \class MappedSparseMatrix
|
||||
*
|
||||
* \brief Sparse matrix
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
|
||||
namespace Eigen {
|
||||
|
||||
/** \deprecated use a SparseMatrix in an uncompressed mode
|
||||
/** @deprecated use a SparseMatrix in an uncompressed mode
|
||||
*
|
||||
* \class DynamicSparseMatrix
|
||||
*
|
||||
|
@ -291,7 +291,7 @@ template<typename _Scalar, int _Options, typename _StorageIndex>
|
|||
|
||||
public:
|
||||
|
||||
/** \deprecated
|
||||
/** @deprecated
|
||||
* Set the matrix to zero and reserve the memory for \a reserveSize nonzero coefficients. */
|
||||
EIGEN_DEPRECATED void startFill(Index reserveSize = 1000)
|
||||
{
|
||||
|
@ -299,7 +299,7 @@ template<typename _Scalar, int _Options, typename _StorageIndex>
|
|||
reserve(reserveSize);
|
||||
}
|
||||
|
||||
/** \deprecated use insert()
|
||||
/** @deprecated use insert()
|
||||
* inserts a nonzero coefficient at given coordinates \a row, \a col and returns its reference assuming that:
|
||||
* 1 - the coefficient does not exist yet
|
||||
* 2 - this the coefficient with greater inner coordinate for the given outer coordinate.
|
||||
|
@ -315,7 +315,7 @@ template<typename _Scalar, int _Options, typename _StorageIndex>
|
|||
return insertBack(outer,inner);
|
||||
}
|
||||
|
||||
/** \deprecated use insert()
|
||||
/** @deprecated use insert()
|
||||
* Like fill() but with random inner coordinates.
|
||||
* Compared to the generic coeffRef(), the unique limitation is that we assume
|
||||
* the coefficient does not exist yet.
|
||||
|
@ -325,7 +325,7 @@ template<typename _Scalar, int _Options, typename _StorageIndex>
|
|||
return insert(row,col);
|
||||
}
|
||||
|
||||
/** \deprecated use finalize()
|
||||
/** @deprecated use finalize()
|
||||
* Does nothing. Provided for compatibility with SparseMatrix. */
|
||||
EIGEN_DEPRECATED void endFill() {}
|
||||
|
||||
|
|
|
@ -142,7 +142,7 @@ namespace GeographicLib {
|
|||
NormalGravity(real a, real GM, real omega, real f_J2,
|
||||
bool geometricp = true);
|
||||
/**
|
||||
* \deprecated Old constructor for the normal gravity.
|
||||
* @deprecated Old constructor for the normal gravity.
|
||||
*
|
||||
* @param[in] a equatorial radius (meters).
|
||||
* @param[in] GM mass constant of the ellipsoid
|
||||
|
|
|
@ -380,7 +380,7 @@ namespace GeographicLib {
|
|||
return x;
|
||||
}
|
||||
/**
|
||||
* \deprecated An old name for val<T>(s).
|
||||
* @deprecated An old name for val<T>(s).
|
||||
**********************************************************************/
|
||||
template<typename T>
|
||||
// GEOGRAPHICLIB_DEPRECATED("Use new Utility::val<T>(s)")
|
||||
|
|
|
@ -80,9 +80,10 @@ bool assert_equal(const V& expected, const boost::optional<const V&>& actual, do
|
|||
return assert_equal(expected, *actual, tol);
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/**
|
||||
* Version of assert_equals to work with vectors
|
||||
* \deprecated: use container equals instead
|
||||
* @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) {
|
||||
|
@ -108,6 +109,7 @@ bool GTSAM_DEPRECATED assert_equal(const std::vector<V>& expected, const std::ve
|
|||
}
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Function for comparing maps of testable->testable
|
||||
|
|
|
@ -203,15 +203,16 @@ 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
|
||||
* @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
|
||||
* @deprecated: use operators instead
|
||||
*/
|
||||
template<class V1, class V2>
|
||||
inline void GTSAM_DEPRECATED axpy(double alpha, const V1& x, V2& y) {
|
||||
|
@ -222,6 +223,7 @@ 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
|
||||
|
|
|
@ -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_V41
|
||||
#cmakedefine GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
|
||||
// Support Metis-based nested dissection
|
||||
#cmakedefine GTSAM_SUPPORT_NESTED_DISSECTION
|
||||
|
|
|
@ -170,7 +170,7 @@ class GTSAM_EXPORT Cal3 {
|
|||
return K;
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/** @deprecated The following function has been deprecated, use K above */
|
||||
Matrix3 matrix() const { return K(); }
|
||||
#endif
|
||||
|
|
|
@ -97,7 +97,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
|
|||
|
||||
Vector3 vector() const;
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/// get parameter u0
|
||||
inline double u0() const { return u0_; }
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
SimpleCamera simpleCamera(const Matrix34& P) {
|
||||
|
||||
// P = [A|a] = s K cRw [I|-T], with s the unknown scale
|
||||
|
|
|
@ -37,7 +37,7 @@ namespace gtsam {
|
|||
using PinholeCameraCal3Unified = gtsam::PinholeCamera<gtsam::Cal3Unified>;
|
||||
using PinholeCameraCal3Fisheye = gtsam::PinholeCamera<gtsam::Cal3Fisheye>;
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/**
|
||||
* @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x
|
||||
* Use PinholeCameraCal3_S2 instead
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
|
||||
static const Cal3_S2 K(625, 625, 0, 0, 0);
|
||||
|
||||
|
|
|
@ -288,8 +288,8 @@ namespace gtsam {
|
|||
FactorGraphType& asDerived() { return static_cast<FactorGraphType&>(*this); }
|
||||
|
||||
public:
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
/** \deprecated ordering and orderingType shouldn't both be specified */
|
||||
#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,
|
||||
|
@ -298,7 +298,7 @@ namespace gtsam {
|
|||
return eliminateSequential(ordering, function, variableIndex);
|
||||
}
|
||||
|
||||
/** \deprecated orderingType specified first for consistency */
|
||||
/** @deprecated orderingType specified first for consistency */
|
||||
boost::shared_ptr<BayesNetType> GTSAM_DEPRECATED eliminateSequential(
|
||||
const Eliminate& function,
|
||||
OptionalVariableIndex variableIndex = boost::none,
|
||||
|
@ -306,7 +306,7 @@ namespace gtsam {
|
|||
return eliminateSequential(orderingType, function, variableIndex);
|
||||
}
|
||||
|
||||
/** \deprecated ordering and orderingType shouldn't both be specified */
|
||||
/** @deprecated ordering and orderingType shouldn't both be specified */
|
||||
boost::shared_ptr<BayesTreeType> GTSAM_DEPRECATED eliminateMultifrontal(
|
||||
const Ordering& ordering,
|
||||
const Eliminate& function,
|
||||
|
@ -315,7 +315,7 @@ namespace gtsam {
|
|||
return eliminateMultifrontal(ordering, function, variableIndex);
|
||||
}
|
||||
|
||||
/** \deprecated orderingType specified first for consistency */
|
||||
/** @deprecated orderingType specified first for consistency */
|
||||
boost::shared_ptr<BayesTreeType> GTSAM_DEPRECATED eliminateMultifrontal(
|
||||
const Eliminate& function,
|
||||
OptionalVariableIndex variableIndex = boost::none,
|
||||
|
@ -323,7 +323,7 @@ namespace gtsam {
|
|||
return eliminateMultifrontal(orderingType, function, variableIndex);
|
||||
}
|
||||
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
boost::shared_ptr<BayesNetType> GTSAM_DEPRECATED marginalMultifrontalBayesNet(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
boost::none_t,
|
||||
|
@ -332,7 +332,7 @@ namespace gtsam {
|
|||
return marginalMultifrontalBayesNet(variables, function, variableIndex);
|
||||
}
|
||||
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
boost::shared_ptr<BayesTreeType> GTSAM_DEPRECATED marginalMultifrontalBayesTree(
|
||||
boost::variant<const Ordering&, const KeyVector&> variables,
|
||||
boost::none_t,
|
||||
|
|
|
@ -153,7 +153,6 @@ typedef FastSet<FactorIndex> FactorIndexSet;
|
|||
const std::string& s = "Factor",
|
||||
const KeyFormatter& formatter = DefaultKeyFormatter) const;
|
||||
|
||||
protected:
|
||||
/// check equality
|
||||
bool equals(const This& other, double tol = 1e-9) const;
|
||||
|
||||
|
|
|
@ -125,12 +125,11 @@ namespace gtsam {
|
|||
/** Performs transpose backsubstition in place on values */
|
||||
void solveTransposeInPlace(VectorValues& gy) const;
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/** Scale the values in \c gy according to the sigmas for the frontal variables in this
|
||||
* conditional. */
|
||||
void scaleFrontalsBySigma(VectorValues& gy) const;
|
||||
|
||||
// FIXME: deprecated flag doesn't appear to exist?
|
||||
// __declspec(deprecated) void scaleFrontalsBySigma(VectorValues& gy) const;
|
||||
void GTSAM_DEPRECATED scaleFrontalsBySigma(VectorValues& gy) const;
|
||||
#endif
|
||||
|
||||
private:
|
||||
/** Serialization function */
|
||||
|
|
|
@ -396,11 +396,11 @@ namespace gtsam {
|
|||
|
||||
public:
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
/** \deprecated */
|
||||
VectorValues optimize(boost::none_t,
|
||||
const Eliminate& function =
|
||||
EliminationTraitsType::DefaultEliminate) const {
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/** @deprecated */
|
||||
VectorValues GTSAM_DEPRECATED
|
||||
optimize(boost::none_t, const Eliminate& function =
|
||||
EliminationTraitsType::DefaultEliminate) const {
|
||||
return optimize(function);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -730,6 +730,7 @@ namespace gtsam {
|
|||
|
||||
} // namespace noiseModel
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/** Note, deliberately not in noiseModel namespace.
|
||||
* Deprecated. Only for compatibility with previous version.
|
||||
*/
|
||||
|
@ -738,6 +739,7 @@ namespace gtsam {
|
|||
typedef noiseModel::Diagonal::shared_ptr SharedDiagonal;
|
||||
typedef noiseModel::Constrained::shared_ptr SharedConstrained;
|
||||
typedef noiseModel::Isotropic::shared_ptr SharedIsotropic;
|
||||
#endif
|
||||
|
||||
/// traits
|
||||
template<> struct traits<noiseModel::Gaussian> : public Testable<noiseModel::Gaussian> {};
|
||||
|
|
|
@ -104,14 +104,15 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
|
|||
static Vector DeltaAngles(const Vector& msr_gyro_t, const double msr_dt,
|
||||
const Vector3& delta_angles);
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/// @deprecated constructor
|
||||
PreintegratedAhrsMeasurements(const Vector3& biasHat,
|
||||
const Matrix3& measuredOmegaCovariance)
|
||||
: PreintegratedRotation(boost::make_shared<Params>()),
|
||||
biasHat_(biasHat) {
|
||||
GTSAM_DEPRECATED PreintegratedAhrsMeasurements(
|
||||
const Vector3& biasHat, const Matrix3& measuredOmegaCovariance)
|
||||
: PreintegratedRotation(boost::make_shared<Params>()), biasHat_(biasHat) {
|
||||
p_->gyroscopeCovariance = measuredOmegaCovariance;
|
||||
resetIntegration();
|
||||
}
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
||||
|
@ -186,20 +187,24 @@ public:
|
|||
const Rot3& rot_i, const Vector3& bias,
|
||||
const PreintegratedAhrsMeasurements preintegratedMeasurements);
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/// @deprecated name
|
||||
typedef PreintegratedAhrsMeasurements PreintegratedMeasurements;
|
||||
|
||||
/// @deprecated constructor
|
||||
AHRSFactor(Key rot_i, Key rot_j, Key bias,
|
||||
GTSAM_DEPRECATED AHRSFactor(
|
||||
Key rot_i, Key rot_j, Key bias,
|
||||
const PreintegratedMeasurements& preintegratedMeasurements,
|
||||
const Vector3& omegaCoriolis,
|
||||
const boost::optional<Pose3>& body_P_sensor = boost::none);
|
||||
|
||||
/// @deprecated static function
|
||||
static Rot3 predict(const Rot3& rot_i, const Vector3& bias,
|
||||
const PreintegratedMeasurements preintegratedMeasurements,
|
||||
const Vector3& omegaCoriolis,
|
||||
const boost::optional<Pose3>& body_P_sensor = boost::none);
|
||||
static Rot3 GTSAM_DEPRECATED
|
||||
predict(const Rot3& rot_i, const Vector3& bias,
|
||||
const PreintegratedMeasurements preintegratedMeasurements,
|
||||
const Vector3& omegaCoriolis,
|
||||
const boost::optional<Pose3>& body_P_sensor = boost::none);
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -131,30 +131,30 @@ public:
|
|||
|
||||
/// @}
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/// @name Deprecated
|
||||
/// @{
|
||||
ConstantBias inverse() {
|
||||
return -(*this);
|
||||
}
|
||||
ConstantBias compose(const ConstantBias& q) {
|
||||
ConstantBias GTSAM_DEPRECATED inverse() { return -(*this); }
|
||||
ConstantBias GTSAM_DEPRECATED compose(const ConstantBias& q) {
|
||||
return (*this) + q;
|
||||
}
|
||||
ConstantBias between(const ConstantBias& q) {
|
||||
ConstantBias GTSAM_DEPRECATED between(const ConstantBias& q) {
|
||||
return q - (*this);
|
||||
}
|
||||
Vector6 localCoordinates(const ConstantBias& q) {
|
||||
Vector6 GTSAM_DEPRECATED localCoordinates(const ConstantBias& q) {
|
||||
return between(q).vector();
|
||||
}
|
||||
ConstantBias retract(const Vector6& v) {
|
||||
ConstantBias GTSAM_DEPRECATED retract(const Vector6& v) {
|
||||
return compose(ConstantBias(v));
|
||||
}
|
||||
static Vector6 Logmap(const ConstantBias& p) {
|
||||
static Vector6 GTSAM_DEPRECATED Logmap(const ConstantBias& p) {
|
||||
return p.vector();
|
||||
}
|
||||
static ConstantBias Expmap(const Vector6& v) {
|
||||
static ConstantBias GTSAM_DEPRECATED Expmap(const Vector6& v) {
|
||||
return ConstantBias(v);
|
||||
}
|
||||
/// @}
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -295,14 +295,14 @@ struct traits<ExpressionFactorN<T, Args...>>
|
|||
// ExpressionFactorN
|
||||
|
||||
|
||||
#if defined(GTSAM_ALLOW_DEPRECATED_SINCE_V41)
|
||||
#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<>.
|
||||
* @deprecated Prefer the more general ExpressionFactorN<>.
|
||||
*/
|
||||
template <typename T, typename A1, typename A2>
|
||||
class GTSAM_DEPRECATED ExpressionFactor2 : public ExpressionFactorN<T, A1, A2> {
|
||||
|
|
|
@ -51,9 +51,11 @@ 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 NoiseModelFactor2<VALUE, VALUE> MotionFactor;
|
||||
typedef NoiseModelFactor1<VALUE> MeasurementFactor;
|
||||
#endif
|
||||
|
||||
protected:
|
||||
T x_; // linearization point
|
||||
|
|
|
@ -131,16 +131,16 @@ protected:
|
|||
void computeBayesTree(const Ordering& ordering);
|
||||
|
||||
public:
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
/** \deprecated argument order changed due to removing boost::optional<Ordering> */
|
||||
#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> */
|
||||
/** @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> */
|
||||
/** @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
|
||||
|
|
|
@ -250,25 +250,25 @@ namespace gtsam {
|
|||
|
||||
public:
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
/** \deprecated */
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
/** @deprecated */
|
||||
boost::shared_ptr<HessianFactor> GTSAM_DEPRECATED linearizeToHessianFactor(
|
||||
const Values& values, boost::none_t, const Dampen& dampen = nullptr) const
|
||||
{return linearizeToHessianFactor(values, dampen);}
|
||||
|
||||
/** \deprecated */
|
||||
/** @deprecated */
|
||||
Values GTSAM_DEPRECATED updateCholesky(const Values& values, boost::none_t,
|
||||
const Dampen& dampen = nullptr) const
|
||||
{return updateCholesky(values, dampen);}
|
||||
|
||||
/** \deprecated */
|
||||
/** @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 */
|
||||
/** @deprecated */
|
||||
void GTSAM_DEPRECATED
|
||||
saveGraph(const std::string& filename, const Values& values,
|
||||
const GraphvizFormatting& graphvizFormatting,
|
||||
|
|
|
@ -1304,14 +1304,14 @@ parse3DFactors(const std::string &filename,
|
|||
return parseFactors<Pose3>(filename, model, maxIndex);
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
std::map<size_t, Pose3> parse3DPoses(const std::string &filename,
|
||||
size_t 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> parse3DLandmarks(const std::string &filename,
|
||||
size_t maxIndex) {
|
||||
std::map<size_t, Point3> GTSAM_DEPRECATED
|
||||
parse3DLandmarks(const std::string &filename, size_t maxIndex) {
|
||||
return parseVariables<Point3>(filename, maxIndex);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -172,10 +172,6 @@ GTSAM_EXPORT GraphAndValues load2D(const std::string& filename,
|
|||
false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, //
|
||||
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
||||
|
||||
/// @deprecated load2D now allows for arbitrary models and wrapping a robust kernel
|
||||
GTSAM_EXPORT GraphAndValues load2D_robust(const std::string& filename,
|
||||
const noiseModel::Base::shared_ptr& model, size_t maxIndex = 0);
|
||||
|
||||
/** save 2d graph */
|
||||
GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph,
|
||||
const Values& config, const noiseModel::Diagonal::shared_ptr model,
|
||||
|
@ -504,17 +500,21 @@ parse3DFactors(const std::string &filename,
|
|||
size_t maxIndex = 0);
|
||||
|
||||
using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
inline boost::optional<IndexedPose> parseVertex(std::istream &is,
|
||||
const std::string &tag) {
|
||||
|
||||
#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> parse3DPoses(const std::string &filename,
|
||||
size_t maxIndex = 0);
|
||||
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>
|
||||
parse3DLandmarks(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,7 +173,7 @@ BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_
|
|||
|
||||
BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D");
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||
|
||||
typedef PriorFactor<SimpleCamera> PriorFactorSimpleCamera;
|
||||
typedef NonlinearEquality<SimpleCamera> NonlinearEqualitySimpleCamera;
|
||||
|
|
Loading…
Reference in New Issue