Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 0 additions & 7 deletions gtsam/geometry/Cal3.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,6 @@ class GTSAM_EXPORT Cal3 {
double u0_ = 0.0f, v0_ = 0.0f; ///< principal point

public:
constexpr static auto dimension = 5;
///< shared pointer to calibration object
using shared_ptr = std::shared_ptr<Cal3>;

Expand Down Expand Up @@ -173,12 +172,6 @@ class GTSAM_EXPORT Cal3 {
/// Return inverted calibration matrix inv(K)
Matrix3 inverse() const;

/// return DOF, dimensionality of tangent space
virtual size_t dim() const { return Dim(); }

/// return DOF, dimensionality of tangent space
static size_t Dim() { return dimension; }

/// @}
/// @name Advanced Interface
/// @{
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3Bundler.h
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3f {
/// @{

/// Return DOF, dimensionality of tangent space
size_t dim() const override { return Dim(); }
size_t dim() const { return Dim(); }

/// Return DOF, dimensionality of tangent space
static size_t Dim() { return dimension; }
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3DS2.h
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
Vector localCoordinates(const Cal3DS2& T2) const;

/// Return dimensions of calibration manifold object
size_t dim() const override { return Dim(); }
size_t dim() const { return Dim(); }

/// Return dimensions of calibration manifold object
static size_t Dim() { return dimension; }
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3DS2_Base.h
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
Matrix29 D2d_calibration(const Point2& p) const;

/// return DOF, dimensionality of tangent space
size_t dim() const override { return Dim(); }
size_t dim() const { return Dim(); }

/// return DOF, dimensionality of tangent space
static size_t Dim() { return dimension; }
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3Fisheye.h
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
/// @{

/// Return dimensions of calibration manifold object
size_t dim() const override { return Dim(); }
size_t dim() const { return Dim(); }

/// Return dimensions of calibration manifold object
static size_t Dim() { return dimension; }
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3Unified.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
Vector localCoordinates(const Cal3Unified& T2) const;

/// Return dimensions of calibration manifold object
size_t dim() const override { return Dim(); }
size_t dim() const { return Dim(); }

/// Return dimensions of calibration manifold object
static size_t Dim() { return dimension; }
Expand Down
3 changes: 3 additions & 0 deletions gtsam/geometry/Cal3_S2.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,9 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 {
/// @name Manifold
/// @{

/// return DOF, dimensionality of tangent space
virtual size_t dim() const { return Dim(); };

/// return DOF, dimensionality of tangent space
static size_t Dim() { return dimension; }

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3f.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class GTSAM_EXPORT Cal3f : public Cal3 {
/// @{

/// Return DOF, dimensionality of tangent space
size_t dim() const override { return Dim(); }
size_t dim() const { return Dim(); }

/// Return DOF, dimensionality of tangent space
static size_t Dim() { return dimension; }
Expand Down
4 changes: 0 additions & 4 deletions gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -784,10 +784,6 @@ virtual class Cal3 {
gtsam::Vector vector() const;
gtsam::Matrix K() const;
gtsam::Matrix inverse() const;

// Manifold
static size_t Dim();
size_t dim() const;
};

#include <gtsam/geometry/Cal3_S2.h>
Expand Down
Loading