Skip to content

Commit

Permalink
Merge pull request borglab#1460 from borglab/fix/concepts
Browse files Browse the repository at this point in the history
Reverted ill-advised concepts, attempt 2
  • Loading branch information
dellaert authored Feb 13, 2023
2 parents 03de47b + cb66034 commit 32c5bb2
Show file tree
Hide file tree
Showing 21 changed files with 76 additions and 79 deletions.
8 changes: 4 additions & 4 deletions gtsam/base/Group.h
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,8 @@ compose_pow(const G& g, size_t n) {
/// Assumes nothing except group structure and Testable from G and H
template<typename G, typename H>
class DirectProduct: public std::pair<G, H> {
GTSAM_CONCEPT_ASSERT1(IsGroup<G>);
GTSAM_CONCEPT_ASSERT2(IsGroup<H>);
GTSAM_CONCEPT_ASSERT(IsGroup<G>);
GTSAM_CONCEPT_ASSERT(IsGroup<H>);

public:
/// Default constructor yields identity
Expand Down Expand Up @@ -170,8 +170,8 @@ struct traits<DirectProduct<G, H> > :
/// Assumes existence of three additive operators for both groups
template<typename G, typename H>
class DirectSum: public std::pair<G, H> {
GTSAM_CONCEPT_ASSERT1(IsGroup<G>); // TODO(frank): check additive
GTSAM_CONCEPT_ASSERT2(IsGroup<H>); // TODO(frank): check additive
GTSAM_CONCEPT_ASSERT(IsGroup<G>); // TODO(frank): check additive
GTSAM_CONCEPT_ASSERT(IsGroup<H>); // TODO(frank): check additive

const G& g() const { return this->first; }
const H& h() const { return this->second;}
Expand Down
4 changes: 2 additions & 2 deletions gtsam/base/ProductLieGroup.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ namespace gtsam {
/// Assumes Lie group structure for G and H
template<typename G, typename H>
class ProductLieGroup: public std::pair<G, H> {
GTSAM_CONCEPT_ASSERT1(IsLieGroup<G>);
GTSAM_CONCEPT_ASSERT2(IsLieGroup<H>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<G>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<H>);
typedef std::pair<G, H> Base;

protected:
Expand Down
15 changes: 3 additions & 12 deletions gtsam/base/concepts.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,21 +14,12 @@
#include <boost/concept/requires.hpp>
#include <boost/concept_check.hpp>
#define GTSAM_CONCEPT_ASSERT(concept) BOOST_CONCEPT_ASSERT((concept))
#define GTSAM_CONCEPT_ASSERT1(concept) BOOST_CONCEPT_ASSERT((concept))
#define GTSAM_CONCEPT_ASSERT2(concept) BOOST_CONCEPT_ASSERT((concept))
#define GTSAM_CONCEPT_ASSERT3(concept) BOOST_CONCEPT_ASSERT((concept))
#define GTSAM_CONCEPT_ASSERT4(concept) BOOST_CONCEPT_ASSERT((concept))
#define GTSAM_CONCEPT_REQUIRES(concept, return_type) BOOST_CONCEPT_REQUIRES(((concept)), (return_type))
#else
// These do something sensible:
// This does something sensible:
#define BOOST_CONCEPT_USAGE(concept) void check##concept()
// TODO(dellaert): would be nice if it was a single macro...
#define GTSAM_CONCEPT_ASSERT(concept) concept checkConcept [[maybe_unused]]
#define GTSAM_CONCEPT_ASSERT1(concept) concept checkConcept1 [[maybe_unused]]
#define GTSAM_CONCEPT_ASSERT2(concept) concept checkConcept2 [[maybe_unused]]
#define GTSAM_CONCEPT_ASSERT3(concept) concept checkConcept3 [[maybe_unused]]
#define GTSAM_CONCEPT_ASSERT4(concept) concept checkConcept4 [[maybe_unused]]
// This one just ignores concept for now:
// These just ignore the concept checking for now:
#define GTSAM_CONCEPT_ASSERT(concept)
#define GTSAM_CONCEPT_REQUIRES(concept, return_type) return_type
#endif

8 changes: 6 additions & 2 deletions gtsam/base/tests/testMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1151,8 +1151,10 @@ TEST(Matrix, Matrix24IsVectorSpace) {
}

TEST(Matrix, RowMajorIsVectorSpace) {
#ifdef GTSAM_USE_BOOST_FEATURES
typedef Eigen::Matrix<double, 2, 3, Eigen::RowMajor> RowMajor;
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowMajor>);
#endif
}

TEST(Matrix, MatrixIsVectorSpace) {
Expand All @@ -1164,9 +1166,11 @@ TEST(Matrix, VectorIsVectorSpace) {
}

TEST(Matrix, RowVectorIsVectorSpace) {
#ifdef GTSAM_USE_BOOST_FEATURES
typedef Eigen::Matrix<double, 1, -1> RowVector;
GTSAM_CONCEPT_ASSERT1(IsVectorSpace<RowVector>);
GTSAM_CONCEPT_ASSERT2(IsVectorSpace<Vector5>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowVector>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Vector5>);
#endif
}

//******************************************************************************
Expand Down
6 changes: 4 additions & 2 deletions gtsam/base/tests/testVector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -267,13 +267,15 @@ TEST(Vector, linear_dependent3 )

//******************************************************************************
TEST(Vector, VectorIsVectorSpace) {
GTSAM_CONCEPT_ASSERT1(IsVectorSpace<Vector5>);
GTSAM_CONCEPT_ASSERT2(IsVectorSpace<Vector>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Vector5>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Vector>);
}

TEST(Vector, RowVectorIsVectorSpace) {
#ifdef GTSAM_USE_BOOST_FEATURES
typedef Eigen::Matrix<double,1,-1> RowVector;
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowVector>);
#endif
}

/* ************************************************************************* */
Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/tests/testCyclic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,8 +107,8 @@ struct traits<K4> : internal::AdditiveGroupTraits<K4> {
TEST(Cyclic , DirectSum) {
// The Direct sum of Z2 and Z2 is *not* Cyclic<4>, but the
// smallest non-cyclic group called the Klein four-group:
GTSAM_CONCEPT_ASSERT1(IsGroup<K4>);
GTSAM_CONCEPT_ASSERT2(IsTestable<K4>);
GTSAM_CONCEPT_ASSERT(IsGroup<K4>);
GTSAM_CONCEPT_ASSERT(IsTestable<K4>);

// Refer to http://en.wikipedia.org/wiki/Klein_four-group
K4 e(0,0), a(0, 1), b(1, 0), c(1, 1);
Expand Down
12 changes: 6 additions & 6 deletions gtsam/geometry/tests/testPoint2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@ TEST(Point2 , Constructor) {

//******************************************************************************
TEST(Double , Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<double>);
GTSAM_CONCEPT_ASSERT2(IsManifold<double>);
GTSAM_CONCEPT_ASSERT3(IsVectorSpace<double>);
GTSAM_CONCEPT_ASSERT(IsGroup<double>);
GTSAM_CONCEPT_ASSERT(IsManifold<double>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<double>);
}

//******************************************************************************
Expand All @@ -48,9 +48,9 @@ TEST(Double , Invariants) {

//******************************************************************************
TEST(Point2 , Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Point2>);
GTSAM_CONCEPT_ASSERT2(IsManifold<Point2>);
GTSAM_CONCEPT_ASSERT3(IsVectorSpace<Point2>);
GTSAM_CONCEPT_ASSERT(IsGroup<Point2>);
GTSAM_CONCEPT_ASSERT(IsManifold<Point2>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Point2>);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testPoint3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@ TEST(Point3 , Constructor) {

//******************************************************************************
TEST(Point3 , Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Point3>);
GTSAM_CONCEPT_ASSERT2(IsManifold<Point3>);
GTSAM_CONCEPT_ASSERT3(IsVectorSpace<Point3>);
GTSAM_CONCEPT_ASSERT(IsGroup<Point3>);
GTSAM_CONCEPT_ASSERT(IsManifold<Point3>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Point3>);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testPose2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,9 @@ GTSAM_CONCEPT_LIE_INST(Pose2)

//******************************************************************************
TEST(Pose2 , Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Pose2 >);
GTSAM_CONCEPT_ASSERT2(IsManifold<Pose2 >);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<Pose2 >);
GTSAM_CONCEPT_ASSERT(IsGroup<Pose2 >);
GTSAM_CONCEPT_ASSERT(IsManifold<Pose2 >);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Pose2 >);
}

/* ************************************************************************* */
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testQuaternion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@ typedef traits<Q>::ChartJacobian QuaternionJacobian;

//******************************************************************************
TEST(Quaternion , Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Quaternion >);
GTSAM_CONCEPT_ASSERT2(IsManifold<Quaternion >);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<Quaternion >);
GTSAM_CONCEPT_ASSERT(IsGroup<Quaternion >);
GTSAM_CONCEPT_ASSERT(IsManifold<Quaternion >);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Quaternion >);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testRot3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@ static double error = 1e-9, epsilon = 0.001;

//******************************************************************************
TEST(Rot3 , Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Rot3 >);
GTSAM_CONCEPT_ASSERT2(IsManifold<Rot3 >);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<Rot3 >);
GTSAM_CONCEPT_ASSERT(IsGroup<Rot3 >);
GTSAM_CONCEPT_ASSERT(IsManifold<Rot3 >);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Rot3 >);
}

/* ************************************************************************* */
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testSO3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@ TEST(SO3, Identity) {

//******************************************************************************
TEST(SO3, Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<SO3>);
GTSAM_CONCEPT_ASSERT2(IsManifold<SO3>);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<SO3>);
GTSAM_CONCEPT_ASSERT(IsGroup<SO3>);
GTSAM_CONCEPT_ASSERT(IsManifold<SO3>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<SO3>);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testSO4.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,9 @@ TEST(SO4, Identity) {

//******************************************************************************
TEST(SO4, Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<SO4>);
GTSAM_CONCEPT_ASSERT2(IsManifold<SO4>);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<SO4>);
GTSAM_CONCEPT_ASSERT(IsGroup<SO4>);
GTSAM_CONCEPT_ASSERT(IsManifold<SO4>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<SO4>);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testSOn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,9 +84,9 @@ TEST(SOn, SO5) {

//******************************************************************************
TEST(SOn, Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<SOn>);
GTSAM_CONCEPT_ASSERT2(IsManifold<SOn>);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<SOn>);
GTSAM_CONCEPT_ASSERT(IsGroup<SOn>);
GTSAM_CONCEPT_ASSERT(IsManifold<SOn>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<SOn>);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testSimilarity2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,9 @@ static const double s = 4;

//******************************************************************************
TEST(Similarity2, Concepts) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Similarity2>);
GTSAM_CONCEPT_ASSERT2(IsManifold<Similarity2>);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<Similarity2>);
GTSAM_CONCEPT_ASSERT(IsGroup<Similarity2>);
GTSAM_CONCEPT_ASSERT(IsManifold<Similarity2>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Similarity2>);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testSimilarity3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,9 @@ const double degree = M_PI / 180;

//******************************************************************************
TEST(Similarity3, Concepts) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Similarity3 >);
GTSAM_CONCEPT_ASSERT2(IsManifold<Similarity3 >);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<Similarity3 >);
GTSAM_CONCEPT_ASSERT(IsGroup<Similarity3 >);
GTSAM_CONCEPT_ASSERT(IsManifold<Similarity3 >);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Similarity3 >);
}

//******************************************************************************
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/tests/testStereoPoint2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@ GTSAM_CONCEPT_TESTABLE_INST(StereoPoint2)

//******************************************************************************
TEST(StereoPoint2 , Concept) {
GTSAM_CONCEPT_ASSERT1(IsGroup<StereoPoint2>);
GTSAM_CONCEPT_ASSERT2(IsManifold<StereoPoint2 >);
GTSAM_CONCEPT_ASSERT3(IsVectorSpace<StereoPoint2>);
GTSAM_CONCEPT_ASSERT(IsGroup<StereoPoint2>);
GTSAM_CONCEPT_ASSERT(IsManifold<StereoPoint2 >);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<StereoPoint2>);
}

/* ************************************************************************* */
Expand Down
4 changes: 2 additions & 2 deletions gtsam/nonlinear/ExtendedKalmanFilter.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ namespace gtsam {
template <class VALUE>
class ExtendedKalmanFilter {
// Check that VALUE type is a testable Manifold
GTSAM_CONCEPT_ASSERT1(IsTestable<VALUE>);
GTSAM_CONCEPT_ASSERT2(IsManifold<VALUE>);
GTSAM_CONCEPT_ASSERT(IsTestable<VALUE>);
GTSAM_CONCEPT_ASSERT(IsManifold<VALUE>);

public:
typedef std::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr;
Expand Down
4 changes: 2 additions & 2 deletions gtsam/slam/BetweenFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@ namespace gtsam {
class BetweenFactor: public NoiseModelFactorN<VALUE, VALUE> {

// Check that VALUE type is a testable Lie group
GTSAM_CONCEPT_ASSERT1(IsTestable<VALUE>);
GTSAM_CONCEPT_ASSERT2(IsLieGroup<VALUE>);
GTSAM_CONCEPT_ASSERT(IsTestable<VALUE>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<VALUE>);

public:

Expand Down
6 changes: 3 additions & 3 deletions tests/testLie.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,9 @@ template<> struct traits<Product> : internal::LieGroupTraits<Product> {

//******************************************************************************
TEST(Lie, ProductLieGroup) {
GTSAM_CONCEPT_ASSERT1(IsGroup<Product>);
GTSAM_CONCEPT_ASSERT2(IsManifold<Product>);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<Product>);
GTSAM_CONCEPT_ASSERT(IsGroup<Product>);
GTSAM_CONCEPT_ASSERT(IsManifold<Product>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Product>);
Product pair1;
Vector5 d;
d << 1, 2, 0.1, 0.2, 0.3;
Expand Down
24 changes: 12 additions & 12 deletions tests/testManifold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,26 +38,26 @@ typedef PinholeCamera<Cal3Bundler> Camera;
//******************************************************************************
TEST(Manifold, SomeManifoldsGTSAM) {
//GTSAM_CONCEPT_ASSERT(IsManifold<int>); // integer is not a manifold
GTSAM_CONCEPT_ASSERT1(IsManifold<Camera>);
GTSAM_CONCEPT_ASSERT2(IsManifold<Cal3_S2>);
GTSAM_CONCEPT_ASSERT3(IsManifold<Cal3Bundler>);
GTSAM_CONCEPT_ASSERT4(IsManifold<Camera>);
GTSAM_CONCEPT_ASSERT(IsManifold<Camera>);
GTSAM_CONCEPT_ASSERT(IsManifold<Cal3_S2>);
GTSAM_CONCEPT_ASSERT(IsManifold<Cal3Bundler>);
GTSAM_CONCEPT_ASSERT(IsManifold<Camera>);
}

//******************************************************************************
TEST(Manifold, SomeLieGroupsGTSAM) {
GTSAM_CONCEPT_ASSERT1(IsLieGroup<Rot2>);
GTSAM_CONCEPT_ASSERT2(IsLieGroup<Pose2>);
GTSAM_CONCEPT_ASSERT3(IsLieGroup<Rot3>);
GTSAM_CONCEPT_ASSERT4(IsLieGroup<Pose3>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Rot2>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Pose2>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Rot3>);
GTSAM_CONCEPT_ASSERT(IsLieGroup<Pose3>);
}

//******************************************************************************
TEST(Manifold, SomeVectorSpacesGTSAM) {
GTSAM_CONCEPT_ASSERT1(IsVectorSpace<double>);
GTSAM_CONCEPT_ASSERT2(IsVectorSpace<float>);
GTSAM_CONCEPT_ASSERT3(IsVectorSpace<Point2>);
GTSAM_CONCEPT_ASSERT4(IsVectorSpace<Matrix24>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<double>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<float>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Point2>);
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Matrix24>);
}

//******************************************************************************
Expand Down

0 comments on commit 32c5bb2

Please sign in to comment.