Change all occurances of unnamed enum (deprecated in C++20) to `constexpr`
parent
d8e4125558
commit
456df093f1
|
@ -22,7 +22,7 @@ In GTSAM, all properties and operations needed to use a type must be defined thr
|
|||
In detail, we ask that the following items are defined in the traits object (although, not all are needed for optimization):
|
||||
|
||||
* values:
|
||||
* `enum { dimension = D};`, an enum that indicates the dimensionality *n* of the manifold. In Eigen-fashion, we also support manifolds whose dimensionality is only defined at runtime, by specifying the value -1.
|
||||
* `inline constexpr static auto dimension = D;`, a constexpr that indicates the dimensionality *n* of the manifold. In Eigen-fashion, we also support manifolds whose dimensionality is only defined at runtime, by specifying the value -1.
|
||||
* types:
|
||||
* `TangentVector`, type that lives in tangent space. This will almost always be an `Eigen::Matrix<double,n,1>`.
|
||||
* `ChartJacobian`, a typedef for `OptionalJacobian<dimension, dimension>`.
|
||||
|
|
|
@ -184,9 +184,8 @@ public:
|
|||
}
|
||||
#endif
|
||||
|
||||
|
||||
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
|
||||
constexpr static const bool NeedsToAlign = (sizeof(T) % 16) == 0;
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||
};
|
||||
|
|
|
@ -36,7 +36,7 @@ namespace gtsam {
|
|||
template <class Class, int N>
|
||||
struct LieGroup {
|
||||
|
||||
enum { dimension = N };
|
||||
inline constexpr static auto dimension = N;
|
||||
typedef OptionalJacobian<N, N> ChartJacobian;
|
||||
typedef Eigen::Matrix<double, N, N> Jacobian;
|
||||
typedef Eigen::Matrix<double, N, 1> TangentVector;
|
||||
|
@ -183,7 +183,7 @@ struct LieGroupTraits: GetDimensionImpl<Class, Class::dimension> {
|
|||
/// @name Manifold
|
||||
/// @{
|
||||
typedef Class ManifoldType;
|
||||
enum { dimension = Class::dimension };
|
||||
inline constexpr static auto dimension = Class::dimension;
|
||||
typedef Eigen::Matrix<double, dimension, 1> TangentVector;
|
||||
typedef OptionalJacobian<dimension, dimension> ChartJacobian;
|
||||
|
||||
|
|
|
@ -55,7 +55,7 @@ namespace internal {
|
|||
template<class Class>
|
||||
struct HasManifoldPrereqs {
|
||||
|
||||
enum { dim = Class::dimension };
|
||||
inline constexpr static auto dim = Class::dimension;
|
||||
|
||||
Class p, q;
|
||||
Eigen::Matrix<double, dim, 1> v;
|
||||
|
@ -95,7 +95,7 @@ struct ManifoldTraits: GetDimensionImpl<Class, Class::dimension> {
|
|||
GTSAM_CONCEPT_ASSERT(HasManifoldPrereqs<Class>);
|
||||
|
||||
// Dimension of the manifold
|
||||
enum { dimension = Class::dimension };
|
||||
inline constexpr static auto dimension = Class::dimension;
|
||||
|
||||
// Typedefs required by all manifold types.
|
||||
typedef Class ManifoldType;
|
||||
|
|
|
@ -479,7 +479,7 @@ struct MultiplyWithInverse {
|
|||
*/
|
||||
template <typename T, int N>
|
||||
struct MultiplyWithInverseFunction {
|
||||
enum { M = traits<T>::dimension };
|
||||
inline constexpr static auto M = traits<T>::dimension;
|
||||
typedef Eigen::Matrix<double, N, 1> VectorN;
|
||||
typedef Eigen::Matrix<double, N, N> MatrixN;
|
||||
|
||||
|
|
|
@ -67,9 +67,9 @@ public:
|
|||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
enum {dimension = dimension1 + dimension2};
|
||||
inline static size_t Dim() {return dimension;}
|
||||
inline size_t dim() const {return dimension;}
|
||||
inline constexpr static auto dimension = dimension1 + dimension2;
|
||||
inline static size_t Dim() { return dimension; }
|
||||
inline size_t dim() const { return dimension; }
|
||||
|
||||
typedef Eigen::Matrix<double, dimension, 1> TangentVector;
|
||||
typedef OptionalJacobian<dimension, dimension> ChartJacobian;
|
||||
|
|
|
@ -163,7 +163,7 @@ struct VectorSpaceImpl<Class,Eigen::Dynamic> {
|
|||
template<class Class>
|
||||
struct HasVectorSpacePrereqs {
|
||||
|
||||
enum { dim = Class::dimension };
|
||||
inline constexpr static auto dim = Class::dimension;
|
||||
|
||||
Class p, q;
|
||||
Vector v;
|
||||
|
@ -197,7 +197,7 @@ GTSAM_CONCEPT_ASSERT(HasVectorSpacePrereqs<Class>);
|
|||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
enum { dimension = Class::dimension};
|
||||
inline constexpr static auto dimension = Class::dimension;
|
||||
typedef Class ManifoldType;
|
||||
/// @}
|
||||
};
|
||||
|
@ -232,7 +232,7 @@ struct ScalarTraits : VectorSpaceImpl<Scalar, 1> {
|
|||
/// @name Manifold
|
||||
/// @{
|
||||
typedef Scalar ManifoldType;
|
||||
enum { dimension = 1 };
|
||||
inline constexpr static auto dimension = 1;
|
||||
typedef Eigen::Matrix<double, 1, 1> TangentVector;
|
||||
typedef OptionalJacobian<1, 1> ChartJacobian;
|
||||
|
||||
|
@ -305,7 +305,7 @@ struct traits<Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > :
|
|||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
enum { dimension = M*N};
|
||||
inline constexpr static auto dimension = M * N;
|
||||
typedef Fixed ManifoldType;
|
||||
typedef Eigen::Matrix<double, dimension, 1> TangentVector;
|
||||
typedef Eigen::Matrix<double, dimension, dimension> Jacobian;
|
||||
|
@ -377,7 +377,7 @@ struct DynamicTraits {
|
|||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
enum { dimension = Eigen::Dynamic };
|
||||
inline constexpr static auto dimension = Eigen::Dynamic;
|
||||
typedef Eigen::VectorXd TangentVector;
|
||||
typedef Eigen::MatrixXd Jacobian;
|
||||
typedef OptionalJacobian<dimension, dimension> ChartJacobian;
|
||||
|
|
|
@ -291,7 +291,7 @@ class Basis {
|
|||
*/
|
||||
template <class T>
|
||||
class ManifoldEvaluationFunctor : public VectorEvaluationFunctor {
|
||||
enum { M = traits<T>::dimension };
|
||||
inline constexpr static auto M = traits<T>::dimension;
|
||||
using Base = VectorEvaluationFunctor;
|
||||
|
||||
public:
|
||||
|
|
|
@ -162,9 +162,7 @@ private:
|
|||
/// @}
|
||||
|
||||
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||
enum {
|
||||
NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0
|
||||
};
|
||||
inline constexpr static auto NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0;
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||
};
|
||||
|
|
|
@ -73,7 +73,7 @@ class GTSAM_EXPORT Cal3 {
|
|||
double u0_ = 0.0f, v0_ = 0.0f; ///< principal point
|
||||
|
||||
public:
|
||||
enum { dimension = 5 };
|
||||
inline constexpr static auto dimension = 5;
|
||||
///< shared pointer to calibration object
|
||||
using shared_ptr = std::shared_ptr<Cal3>;
|
||||
|
||||
|
|
|
@ -37,7 +37,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3f {
|
|||
// Note: u0 and v0 are constants and not optimized.
|
||||
|
||||
public:
|
||||
enum { dimension = 3 };
|
||||
inline constexpr static auto dimension = 3;
|
||||
using shared_ptr = std::shared_ptr<Cal3Bundler>;
|
||||
|
||||
/// @name Constructors
|
||||
|
|
|
@ -36,7 +36,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
|
|||
using Base = Cal3DS2_Base;
|
||||
|
||||
public:
|
||||
enum { dimension = 9 };
|
||||
inline constexpr static auto dimension = 9;
|
||||
|
||||
///< shared pointer to stereo calibration object
|
||||
using shared_ptr = std::shared_ptr<Cal3DS2>;
|
||||
|
|
|
@ -46,7 +46,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
|
|||
double tol_ = 1e-5; ///< tolerance value when calibrating
|
||||
|
||||
public:
|
||||
enum { dimension = 9 };
|
||||
inline constexpr static auto dimension = 9;
|
||||
|
||||
///< shared pointer to stereo calibration object
|
||||
using shared_ptr = std::shared_ptr<Cal3DS2_Base>;
|
||||
|
|
|
@ -55,7 +55,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
|
|||
double tol_ = 1e-5; ///< tolerance value when calibrating
|
||||
|
||||
public:
|
||||
enum { dimension = 9 };
|
||||
inline constexpr static auto dimension = 9;
|
||||
///< shared pointer to fisheye calibration object
|
||||
using shared_ptr = std::shared_ptr<Cal3Fisheye>;
|
||||
|
||||
|
|
|
@ -50,7 +50,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
|
|||
double xi_ = 0.0f; ///< mirror parameter
|
||||
|
||||
public:
|
||||
enum { dimension = 10 };
|
||||
inline constexpr static auto dimension = 10;
|
||||
|
||||
///< shared pointer to stereo calibration object
|
||||
using shared_ptr = std::shared_ptr<Cal3Unified>;
|
||||
|
|
|
@ -33,7 +33,7 @@ namespace gtsam {
|
|||
*/
|
||||
class GTSAM_EXPORT Cal3_S2 : public Cal3 {
|
||||
public:
|
||||
enum { dimension = 5 };
|
||||
inline constexpr static auto dimension = 5;
|
||||
|
||||
///< shared pointer to calibration object
|
||||
using shared_ptr = std::shared_ptr<Cal3_S2>;
|
||||
|
|
|
@ -32,7 +32,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
|
|||
double b_ = 1.0f; ///< Stereo baseline.
|
||||
|
||||
public:
|
||||
enum { dimension = 6 };
|
||||
inline constexpr static auto dimension = 6;
|
||||
|
||||
///< shared pointer to stereo calibration object
|
||||
using shared_ptr = std::shared_ptr<Cal3_S2Stereo>;
|
||||
|
|
|
@ -34,7 +34,7 @@ namespace gtsam {
|
|||
*/
|
||||
class GTSAM_EXPORT Cal3f : public Cal3 {
|
||||
public:
|
||||
enum { dimension = 1 };
|
||||
inline constexpr static auto dimension = 1;
|
||||
using shared_ptr = std::shared_ptr<Cal3f>;
|
||||
|
||||
/// @name Constructors
|
||||
|
|
|
@ -252,9 +252,7 @@ class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
|
|||
|
||||
public:
|
||||
|
||||
enum {
|
||||
dimension = 6
|
||||
};
|
||||
inline constexpr static auto dimension = 6;
|
||||
|
||||
/// @name Standard Constructors
|
||||
/// @{
|
||||
|
|
|
@ -82,7 +82,7 @@ class EssentialMatrix {
|
|||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
enum { dimension = 5 };
|
||||
inline constexpr static auto dimension = 5;
|
||||
inline static size_t Dim() { return dimension;}
|
||||
inline size_t dim() const { return dimension;}
|
||||
|
||||
|
|
|
@ -102,7 +102,7 @@ class GTSAM_EXPORT FundamentalMatrix {
|
|||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
enum { dimension = 7 }; // 3 for U, 1 for s, 3 for V
|
||||
inline constexpr static auto dimension = 7; // 3 for U, 1 for s, 3 for V
|
||||
inline static size_t Dim() { return dimension; }
|
||||
inline size_t dim() const { return dimension; }
|
||||
|
||||
|
@ -179,7 +179,7 @@ class GTSAM_EXPORT SimpleFundamentalMatrix {
|
|||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
enum { dimension = 7 }; // 5 for E, 1 for fa, 1 for fb
|
||||
inline constexpr static auto dimension = 7; // 5 for E, 1 for fa, 1 for fb
|
||||
inline static size_t Dim() { return dimension; }
|
||||
inline size_t dim() const { return dimension; }
|
||||
|
||||
|
|
|
@ -47,7 +47,7 @@ class GTSAM_EXPORT Line3 {
|
|||
double a_, b_; // Intersection of line with the world x-y plane rotated by R_
|
||||
// Also the closest point on line to origin
|
||||
public:
|
||||
enum { dimension = 4 };
|
||||
inline constexpr static auto dimension = 4;
|
||||
|
||||
/** Default constructor is the Z axis **/
|
||||
Line3() :
|
||||
|
|
|
@ -39,9 +39,7 @@ private:
|
|||
double d_; ///< The perpendicular distance to this plane
|
||||
|
||||
public:
|
||||
enum {
|
||||
dimension = 3
|
||||
};
|
||||
inline constexpr static auto dimension = 3;
|
||||
|
||||
/// @name Constructors
|
||||
/// @{
|
||||
|
|
|
@ -51,9 +51,7 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
enum {
|
||||
dimension = 6 + DimK
|
||||
}; ///< Dimension depends on calibration
|
||||
inline constexpr static auto dimension = 6 + DimK; ///< Dimension depends on calibration
|
||||
|
||||
/// @name Standard Constructors
|
||||
/// @{
|
||||
|
|
|
@ -245,9 +245,7 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
enum {
|
||||
dimension = 6
|
||||
}; ///< There are 6 DOF to optimize for
|
||||
inline constexpr static auto dimension = 6; ///< There are 6 DOF to optimize for
|
||||
|
||||
/// @name Standard Constructors
|
||||
/// @{
|
||||
|
|
|
@ -45,9 +45,7 @@ struct traits<QUATERNION_TYPE> {
|
|||
/// @}
|
||||
/// @name Basic manifold traits
|
||||
/// @{
|
||||
enum {
|
||||
dimension = 3
|
||||
};
|
||||
inline constexpr static auto dimension = 3;
|
||||
typedef OptionalJacobian<3, 3> ChartJacobian;
|
||||
typedef Eigen::Matrix<_Scalar, 3, 1, _Options, 3, 1> TangentVector;
|
||||
|
||||
|
|
|
@ -54,7 +54,7 @@ constexpr int NSquaredSO(int N) { return (N < 0) ? Eigen::Dynamic : N * N; }
|
|||
template <int N>
|
||||
class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
|
||||
public:
|
||||
enum { dimension = internal::DimensionSO(N) };
|
||||
inline constexpr static auto dimension = internal::DimensionSO(N);
|
||||
using MatrixNN = Eigen::Matrix<double, N, N>;
|
||||
using VectorN2 = Eigen::Matrix<double, internal::NSquaredSO(N), 1>;
|
||||
using MatrixDD = Eigen::Matrix<double, dimension, dimension>;
|
||||
|
|
|
@ -41,7 +41,7 @@ namespace gtsam {
|
|||
*/
|
||||
class GTSAM_EXPORT EmptyCal {
|
||||
public:
|
||||
enum { dimension = 0 };
|
||||
inline constexpr static auto dimension = 0;
|
||||
EmptyCal() {}
|
||||
virtual ~EmptyCal() = default;
|
||||
using shared_ptr = std::shared_ptr<EmptyCal>;
|
||||
|
@ -73,7 +73,7 @@ class GTSAM_EXPORT EmptyCal {
|
|||
*/
|
||||
class GTSAM_EXPORT SphericalCamera {
|
||||
public:
|
||||
enum { dimension = 6 };
|
||||
inline constexpr static auto dimension = 6;
|
||||
|
||||
using Measurement = Unit3;
|
||||
using MeasurementVector = std::vector<Unit3>;
|
||||
|
|
|
@ -61,9 +61,7 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
enum {
|
||||
dimension = 6
|
||||
};
|
||||
inline constexpr static auto dimension = 6;
|
||||
|
||||
/// @name Standard Constructors
|
||||
/// @{
|
||||
|
|
|
@ -37,7 +37,7 @@ private:
|
|||
double uL_, uR_, v_;
|
||||
|
||||
public:
|
||||
enum { dimension = 3 };
|
||||
inline constexpr static auto dimension = 3;
|
||||
/// @name Standard Constructors
|
||||
/// @{
|
||||
|
||||
|
|
|
@ -53,9 +53,7 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
enum {
|
||||
dimension = 2
|
||||
};
|
||||
inline constexpr static auto dimension = 2;
|
||||
|
||||
/// @name Constructors
|
||||
/// @{
|
||||
|
|
|
@ -42,9 +42,7 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
enum {
|
||||
dimension = 9
|
||||
};
|
||||
inline constexpr static auto dimension = 9;
|
||||
|
||||
typedef std::pair<Point3, Velocity3> PositionAndVelocity;
|
||||
|
||||
|
|
|
@ -224,7 +224,7 @@ private:
|
|||
#endif
|
||||
|
||||
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
|
||||
inline constexpr static auto NeedsToAlign = (sizeof(T) % 16) == 0;
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||
};
|
||||
|
|
|
@ -434,7 +434,7 @@ class NoiseModelFactorN
|
|||
public detail::NoiseModelFactorAliases<ValueTypes...> {
|
||||
public:
|
||||
/// N is the number of variables (N-way factor)
|
||||
enum { N = sizeof...(ValueTypes) };
|
||||
inline constexpr static auto N = sizeof...(ValueTypes);
|
||||
|
||||
using NoiseModelFactor::unwhitenedError;
|
||||
|
||||
|
|
|
@ -118,7 +118,7 @@ namespace gtsam {
|
|||
#endif
|
||||
|
||||
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||
enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
|
||||
inline constexpr static auto NeedsToAlign = (sizeof(T) % 16) == 0;
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||
};
|
||||
|
|
|
@ -115,7 +115,7 @@ TEST(Expression, Unary3) {
|
|||
// Simple test class that implements the `VectorSpace` protocol.
|
||||
class Class : public Point3 {
|
||||
public:
|
||||
enum {dimension = 3};
|
||||
inline constexpr static auto dimension = 3;
|
||||
using Point3::Point3;
|
||||
const Vector3& vector() const { return *this; }
|
||||
inline static Class Identity() { return Class(0,0,0); }
|
||||
|
|
|
@ -54,7 +54,7 @@ int TestValueData::DestructorCount = 0;
|
|||
class TestValue {
|
||||
TestValueData data_;
|
||||
public:
|
||||
enum {dimension = 0};
|
||||
inline constexpr static auto dimension = 0;
|
||||
void print(const std::string& str = "") const {}
|
||||
bool equals(const TestValue& other, double tol = 1e-9) const { return true; }
|
||||
size_t dim() const { return 0; }
|
||||
|
|
|
@ -148,7 +148,7 @@ namespace gtsam {
|
|||
#endif
|
||||
|
||||
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||
enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 };
|
||||
inline constexpr static auto NeedsToAlign = (sizeof(VALUE) % 16) == 0;
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
|
||||
}; // \class BetweenFactor
|
||||
|
|
|
@ -49,7 +49,7 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t n,
|
|||
*/
|
||||
template <class Rot>
|
||||
class FrobeniusPrior : public NoiseModelFactorN<Rot> {
|
||||
enum { Dim = Rot::VectorN2::RowsAtCompileTime };
|
||||
inline constexpr static auto Dim = Rot::VectorN2::RowsAtCompileTime;
|
||||
using MatrixNN = typename Rot::MatrixNN;
|
||||
Eigen::Matrix<double, Dim, 1> vecM_; ///< vectorized matrix to approximate
|
||||
|
||||
|
@ -79,7 +79,7 @@ class FrobeniusPrior : public NoiseModelFactorN<Rot> {
|
|||
*/
|
||||
template <class Rot>
|
||||
class FrobeniusFactor : public NoiseModelFactorN<Rot, Rot> {
|
||||
enum { Dim = Rot::VectorN2::RowsAtCompileTime };
|
||||
inline constexpr static auto Dim = Rot::VectorN2::RowsAtCompileTime;
|
||||
|
||||
public:
|
||||
|
||||
|
@ -111,7 +111,7 @@ class FrobeniusBetweenFactor : public NoiseModelFactorN<Rot, Rot> {
|
|||
Rot R12_; ///< measured rotation between R1 and R2
|
||||
Eigen::Matrix<double, Rot::dimension, Rot::dimension>
|
||||
R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1
|
||||
enum { Dim = Rot::VectorN2::RowsAtCompileTime };
|
||||
inline constexpr static auto Dim = Rot::VectorN2::RowsAtCompileTime;
|
||||
|
||||
public:
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@ template <class T> T FindKarcherMean(std::initializer_list<T> &&rotations);
|
|||
* */
|
||||
template <class T> class KarcherMeanFactor : public NonlinearFactor {
|
||||
// Compile time dimension: can be -1
|
||||
enum { D = traits<T>::dimension };
|
||||
inline constexpr static auto D = traits<T>::dimension;
|
||||
|
||||
// Runtime dimension: always >=0
|
||||
size_t d_;
|
||||
|
|
|
@ -39,7 +39,7 @@ class GTSAM_UNSTABLE_EXPORT Event {
|
|||
Point3 location_; ///< Location at time event was generated
|
||||
|
||||
public:
|
||||
enum { dimension = 4 };
|
||||
inline constexpr static auto dimension = 4;
|
||||
|
||||
/// Default Constructor
|
||||
Event() : time_(0), location_(0, 0, 0) {}
|
||||
|
|
Loading…
Reference in New Issue