set dimension of calibration classes with static const variable

release/4.3a0
Varun Agrawal 2020-03-17 15:20:22 -04:00
parent 16dbf27375
commit 3f8209de21
5 changed files with 26 additions and 15 deletions

View File

@ -33,9 +33,13 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
typedef Cal3DS2_Base Base;
private:
static const size_t dimension_ = 9;
public:
enum { dimension = 9 };
enum { dimension = dimension_ };
/// @name Standard Constructors
/// @{
@ -76,10 +80,10 @@ public:
Vector localCoordinates(const Cal3DS2& T2) const ;
/// Return dimensions of calibration manifold object
virtual size_t dim() const { return 9 ; } //TODO: make a final dimension variable (also, usually size_t in other classes e.g. Pose2)
virtual size_t dim() const { return dimension_ ; }
/// Return dimensions of calibration manifold object
static size_t Dim() { return 9; } //TODO: make a final dimension variable
static size_t Dim() { return dimension_; }
/// @}
/// @name Clone

View File

@ -47,10 +47,11 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
private:
double xi_; // mirror parameter
static const size_t dimension_ = 10;
public:
enum { dimension = 10 };
enum { dimension = dimension_ };
/// @name Standard Constructors
/// @{
@ -118,10 +119,10 @@ public:
Vector10 localCoordinates(const Cal3Unified& T2) const ;
/// Return dimensions of calibration manifold object
virtual size_t dim() const { return 10 ; } //TODO: make a final dimension variable (also, usually size_t in other classes e.g. Pose2)
virtual size_t dim() const { return dimension_ ; }
/// Return dimensions of calibration manifold object
static size_t Dim() { return 10; } //TODO: make a final dimension variable
static size_t Dim() { return dimension_; }
/// Return all parameters as a vector
Vector10 vector() const ;

View File

@ -33,9 +33,10 @@ namespace gtsam {
class GTSAM_EXPORT Cal3_S2 {
private:
double fx_, fy_, s_, u0_, v0_;
static const size_t dimension_ = 5;
public:
enum { dimension = 5 };
enum { dimension = dimension_ };
typedef boost::shared_ptr<Cal3_S2> shared_ptr; ///< shared pointer to calibration object
/// @name Standard Constructors
@ -194,12 +195,12 @@ public:
/// return DOF, dimensionality of tangent space
inline size_t dim() const {
return 5;
return dimension_;
}
/// return DOF, dimensionality of tangent space
static size_t Dim() {
return 5;
return dimension_;
}
/// Given 5-dim tangent vector, create new calibration

View File

@ -32,10 +32,11 @@ namespace gtsam {
Cal3_S2 K_;
double b_;
static const size_t dimension_ = 6;
public:
enum { dimension = 6 };
enum { dimension = dimension_ };
typedef boost::shared_ptr<Cal3_S2Stereo> shared_ptr; ///< shared pointer to stereo calibration object
/// @name Standard Constructors
@ -112,12 +113,12 @@ namespace gtsam {
/// return DOF, dimensionality of tangent space
inline size_t dim() const {
return 6;
return dimension_;
}
/// return DOF, dimensionality of tangent space
static size_t Dim() {
return 6;
return dimension_;
}
/// Given 6-dim tangent vector, create new calibration

View File

@ -248,10 +248,14 @@ private:
*/
class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
private:
static const size_t dimension_ = 6;
public:
enum {
dimension = 6
dimension = dimension_
};
/// @name Standard Constructors
@ -326,12 +330,12 @@ public:
/// @deprecated
inline size_t dim() const {
return 6;
return dimension_;
}
/// @deprecated
inline static size_t Dim() {
return 6;
return dimension_;
}
/// @}