diff --git a/.cproject b/.cproject
index 7c8190e6a..ac9b166ec 100644
--- a/.cproject
+++ b/.cproject
@@ -1035,6 +1035,14 @@
true
true
+
+ make
+ -j4
+ testCyclic.run
+ true
+ true
+ true
+
make
-j2
@@ -3190,6 +3198,14 @@
true
true
+
+ make
+ -j4
+ testGroup.run
+ true
+ true
+ true
+
make
-j5
@@ -3414,6 +3430,14 @@
true
true
+
+ make
+ -j4
+ testLie.run
+ true
+ true
+ true
+
make
-j2
diff --git a/gtsam/base/Group.h b/gtsam/base/Group.h
index aec4b5f1c..39541416e 100644
--- a/gtsam/base/Group.h
+++ b/gtsam/base/Group.h
@@ -13,16 +13,20 @@
* @file Group.h
*
* @brief Concept check class for variable types with Group properties
- * @date Nov 5, 2011
+ * @date November, 2011
* @author Alex Cunningham
+ * @author Frank Dellaert
*/
#pragma once
+#include
+
#include
#include
#include
#include
+#include
namespace gtsam {
@@ -83,21 +87,119 @@ check_group_invariants(const G& a, const G& b, double tol = 1e-9) {
&& traits::Equals(traits::Compose(a, traits::Between(a, b)), b, tol);
}
-/// Macro to add group traits, additive flavor
-#define GTSAM_ADDITIVE_GROUP(GROUP) \
- typedef additive_group_tag group_flavor; \
- static GROUP Compose(const GROUP &g, const GROUP & h) { return g + h;} \
- static GROUP Between(const GROUP &g, const GROUP & h) { return h - g;} \
- static GROUP Inverse(const GROUP &g) { return -g;}
+namespace internal {
-/// Macro to add group traits, multiplicative flavor
-#define GTSAM_MULTIPLICATIVE_GROUP(GROUP) \
- typedef additive_group_tag group_flavor; \
- static GROUP Compose(const GROUP &g, const GROUP & h) { return g * h;} \
- static GROUP Between(const GROUP &g, const GROUP & h) { return g.inverse() * h;} \
- static GROUP Inverse(const GROUP &g) { return g.inverse();}
+/// A helper class that implements the traits interface for multiplicative groups.
+/// Assumes existence of identity, operator* and inverse method
+template
+struct MultiplicativeGroupTraits {
+ typedef group_tag structure_category;
+ typedef multiplicative_group_tag group_flavor;
+ static Class Identity() { return Class::identity(); }
+ static Class Compose(const Class &g, const Class & h) { return g * h;}
+ static Class Between(const Class &g, const Class & h) { return g.inverse() * h;}
+ static Class Inverse(const Class &g) { return g.inverse();}
+};
-} // \ namespace gtsam
+/// Both multiplicative group traits and Testable
+template
+struct MultiplicativeGroup : MultiplicativeGroupTraits, Testable {};
+
+/// A helper class that implements the traits interface for additive groups.
+/// Assumes existence of identity and three additive operators
+template
+struct AdditiveGroupTraits {
+ typedef group_tag structure_category;
+ typedef additive_group_tag group_flavor;
+ static Class Identity() { return Class::identity(); }
+ static Class Compose(const Class &g, const Class & h) { return g + h;}
+ static Class Between(const Class &g, const Class & h) { return h - g;}
+ static Class Inverse(const Class &g) { return -g;}
+};
+
+/// Both additive group traits and Testable
+template
+struct AdditiveGroup : AdditiveGroupTraits, Testable {};
+
+} // namespace internal
+
+/// compose multiple times
+template
+BOOST_CONCEPT_REQUIRES(((IsGroup)),(G)) //
+compose_pow(const G& g, size_t n) {
+ if (n == 0) return traits::Identity();
+ else if (n == 1) return g;
+ else return traits::Compose(compose_pow(g, n - 1), g);
+}
+
+/// Template to construct the direct product of two arbitrary groups
+/// Assumes nothing except group structure and Testable from G and H
+template
+class DirectProduct: public std::pair {
+ BOOST_CONCEPT_ASSERT((IsGroup));
+ BOOST_CONCEPT_ASSERT((IsGroup));
+
+public:
+ /// Default constructor yields identity
+ DirectProduct():std::pair(traits::Identity(),traits::Identity()) {}
+
+ // Construct from two subgroup elements
+ DirectProduct(const G& g, const H& h):std::pair(g,h) {}
+
+ // identity
+ static DirectProduct identity() { return DirectProduct(); }
+
+ DirectProduct operator*(const DirectProduct& other) const {
+ return DirectProduct(traits::Compose(this->first, other.first),
+ traits::Compose(this->second, other.second));
+ }
+ DirectProduct inverse() const {
+ return DirectProduct(this->first.inverse(), this->second.inverse());
+ }
+};
+
+// Define any direct product group to be a model of the multiplicative Group concept
+template
+struct traits > :
+ internal::MultiplicativeGroupTraits > {};
+
+/// Template to construct the direct sum of two additive groups
+/// Assumes existence of three additive operators for both groups
+template
+class DirectSum: public std::pair {
+ BOOST_CONCEPT_ASSERT((IsGroup)); // TODO(frank): check additive
+ BOOST_CONCEPT_ASSERT((IsGroup)); // TODO(frank): check additive
+
+ const G& g() const { return this->first; }
+ const H& h() const { return this->second;}
+
+public:
+ /// Default constructor yields identity
+ DirectSum():std::pair(traits::Identity(),traits::Identity()) {}
+
+ // Construct from two subgroup elements
+ DirectSum(const G& g, const H& h):std::pair(g,h) {}
+
+ // identity
+ static DirectSum identity() { return DirectSum(); }
+
+ DirectSum operator+(const DirectSum& other) const {
+ return DirectSum(g()+other.g(), h()+other.h());
+ }
+ DirectSum operator-(const DirectSum& other) const {
+ return DirectSum(g()-other.g(), h()-other.h());
+ }
+ DirectSum operator-() const {
+ return DirectSum(- g(), - h());
+ }
+};
+
+// Define direct sums to be a model of the Additive Group concept
+template
+struct traits > :
+ internal::AdditiveGroupTraits > {};
+
+} // namespace gtsam
/**
* Macros for using the IsGroup
diff --git a/gtsam/base/Lie.h b/gtsam/base/Lie.h
index c9f788992..05c7bc20f 100644
--- a/gtsam/base/Lie.h
+++ b/gtsam/base/Lie.h
@@ -136,8 +136,10 @@ namespace internal {
/// A helper class that implements the traits interface for GTSAM lie groups.
/// To use this for your gtsam type, define:
/// template<> struct traits : public internal::LieGroupTraits {};
+/// Assumes existence of: identity, dimension, localCoordinates, retract,
+/// and additionally Logmap, Expmap, compose, between, and inverse
template
-struct LieGroupTraits : Testable {
+struct LieGroupTraits {
typedef lie_group_tag structure_category;
/// @name Group
@@ -167,12 +169,10 @@ struct LieGroupTraits : Testable {
ChartJacobian Horigin = boost::none, ChartJacobian Hv = boost::none) {
return origin.retract(v, Horigin, Hv);
}
-
/// @}
/// @name Lie Group
/// @{
-
static TangentVector Logmap(const Class& m, ChartJacobian Hm = boost::none) {
return Class::Logmap(m, Hm);
}
@@ -195,11 +195,12 @@ struct LieGroupTraits : Testable {
ChartJacobian H = boost::none) {
return m.inverse(H);
}
-
/// @}
-
};
+/// Both LieGroupTraits and Testable
+template struct LieGroup: LieGroupTraits, Testable {};
+
} // \ namepsace internal
/**
diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h
index 6998b3b18..b20c60822 100644
--- a/gtsam/base/Manifold.h
+++ b/gtsam/base/Manifold.h
@@ -46,7 +46,7 @@ struct manifold_tag {};
* There may be multiple possible retractions for a given manifold, which can be chosen
* between depending on the computational complexity. The important criteria for
* the creation for the retract and localCoordinates functions is that they be
- * inverse operations. The new notion of a Chart guarantees that.
+ * inverse operations.
*
*/
@@ -90,9 +90,9 @@ struct ManifoldImpl {
/// A helper that implements the traits interface for GTSAM manifolds.
/// To use this for your class type, define:
-/// template<> struct traits : public Manifold { };
+/// template<> struct traits : public internal::ManifoldTraits { };
template
-struct Manifold: Testable, ManifoldImpl {
+struct ManifoldTraits: ManifoldImpl {
// Check that Class has the necessary machinery
BOOST_CONCEPT_ASSERT((HasManifoldPrereqs));
@@ -116,6 +116,9 @@ struct Manifold: Testable, ManifoldImpl {
}
};
+/// Both ManifoldTraits and Testable
+template struct Manifold: ManifoldTraits, Testable {};
+
} // \ namespace internal
/// Check invariants for Manifold type
@@ -165,6 +168,53 @@ struct FixedDimension {
"FixedDimension instantiated for dymanically-sized type.");
};
+/// Helper class to construct the product manifold of two other manifolds, M1 and M2
+/// Assumes nothing except manifold structure from M1 and M2
+template
+class ProductManifold: public std::pair {
+ BOOST_CONCEPT_ASSERT((IsManifold));
+ BOOST_CONCEPT_ASSERT((IsManifold));
+
+protected:
+ enum { dimension1 = traits::dimension };
+ enum { dimension2 = traits::dimension };
+
+public:
+ enum { dimension = dimension1 + dimension2 };
+ inline static size_t Dim() { return dimension;}
+ inline size_t dim() const { return dimension;}
+
+ typedef Eigen::Matrix TangentVector;
+ typedef OptionalJacobian ChartJacobian;
+
+ /// Default constructor yields identity
+ ProductManifold():std::pair(traits::Identity(),traits::Identity()) {}
+
+ // Construct from two original manifold values
+ ProductManifold(const M1& m1, const M2& m2):std::pair(m1,m2) {}
+
+ /// Retract delta to manifold
+ ProductManifold retract(const TangentVector& xi) const {
+ M1 m1 = traits::Retract(this->first, xi.template head());
+ M2 m2 = traits::Retract(this->second, xi.template tail());
+ return ProductManifold(m1,m2);
+ }
+
+ /// Compute the coordinates in the tangent space
+ TangentVector localCoordinates(const ProductManifold& other) const {
+ typename traits::TangentVector v1 = traits::Local(this->first, other.first);
+ typename traits::TangentVector v2 = traits::Local(this->second, other.second);
+ TangentVector v;
+ v << v1, v2;
+ return v;
+ }
+};
+
+// Define any direct product group to be a model of the multiplicative Group concept
+template
+struct traits > : internal::Manifold > {
+};
+
} // \ namespace gtsam
///**
diff --git a/gtsam/base/ProductLieGroup.h b/gtsam/base/ProductLieGroup.h
new file mode 100644
index 000000000..90aeb54d1
--- /dev/null
+++ b/gtsam/base/ProductLieGroup.h
@@ -0,0 +1,197 @@
+/* ----------------------------------------------------------------------------
+
+ * GTSAM Copyright 2010, Georgia Tech Research Corporation,
+ * Atlanta, Georgia 30332-0415
+ * All Rights Reserved
+ * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
+
+ * See LICENSE for the license information
+
+ * -------------------------------1------------------------------------------- */
+
+/**
+ * @file ProductLieGroup.h
+ * @date May, 2015
+ * @author Frank Dellaert
+ * @brief Group product of two Lie Groups
+ */
+
+#pragma once
+
+#include
+#include // pair
+
+namespace gtsam {
+
+/// Template to construct the product Lie group of two other Lie groups
+/// Assumes Lie group structure for G and H
+template
+class ProductLieGroup: public std::pair {
+ BOOST_CONCEPT_ASSERT((IsLieGroup));
+ BOOST_CONCEPT_ASSERT((IsLieGroup));
+ typedef std::pair Base;
+
+protected:
+ enum {dimension1 = traits::dimension};
+ enum {dimension2 = traits::dimension};
+
+public:
+ /// Default constructor yields identity
+ ProductLieGroup():Base(traits::Identity(),traits::Identity()) {}
+
+ // Construct from two subgroup elements
+ ProductLieGroup(const G& g, const H& h):Base(g,h) {}
+
+ // Construct from base
+ ProductLieGroup(const Base& base):Base(base) {}
+
+ /// @name Group
+ /// @{
+ typedef multiplicative_group_tag group_flavor;
+ static ProductLieGroup identity() {return ProductLieGroup();}
+
+ ProductLieGroup operator*(const ProductLieGroup& other) const {
+ return ProductLieGroup(traits::Compose(this->first,other.first),
+ traits::Compose(this->second,other.second));
+ }
+ ProductLieGroup inverse() const {
+ return ProductLieGroup(this->first.inverse(), this->second.inverse());
+ }
+ ProductLieGroup compose(const ProductLieGroup& g) const {
+ return (*this) * g;
+ }
+ ProductLieGroup between(const ProductLieGroup& g) const {
+ return this->inverse() * g;
+ }
+ /// @}
+
+ /// @name Manifold
+ /// @{
+ enum {dimension = dimension1 + dimension2};
+ inline static size_t Dim() {return dimension;}
+ inline size_t dim() const {return dimension;}
+
+ typedef Eigen::Matrix TangentVector;
+ typedef OptionalJacobian ChartJacobian;
+
+ static ProductLieGroup Retract(const TangentVector& v) {
+ return ProductLieGroup::ChartAtOrigin::Retract(v);
+ }
+ static TangentVector LocalCoordinates(const ProductLieGroup& g) {
+ return ProductLieGroup::ChartAtOrigin::Local(g);
+ }
+ ProductLieGroup retract(const TangentVector& v) const {
+ return compose(ProductLieGroup::ChartAtOrigin::Retract(v));
+ }
+ TangentVector localCoordinates(const ProductLieGroup& g) const {
+ return ProductLieGroup::ChartAtOrigin::Local(between(g));
+ }
+ /// @}
+
+ /// @name Lie Group
+ /// @{
+protected:
+ typedef Eigen::Matrix Jacobian;
+ typedef Eigen::Matrix Jacobian1;
+ typedef Eigen::Matrix Jacobian2;
+
+public:
+ ProductLieGroup compose(const ProductLieGroup& other, ChartJacobian H1,
+ ChartJacobian H2 = boost::none) const {
+ Jacobian1 D_g_first; Jacobian2 D_h_second;
+ G g = traits::Compose(this->first,other.first, H1 ? &D_g_first : 0);
+ H h = traits::Compose(this->second,other.second, H1 ? &D_h_second : 0);
+ if (H1) {
+ H1->setZero();
+ H1->template topLeftCorner() = D_g_first;
+ H1->template bottomRightCorner() = D_h_second;
+ }
+ if (H2) *H2 = Jacobian::Identity();
+ return ProductLieGroup(g,h);
+ }
+ ProductLieGroup between(const ProductLieGroup& other, ChartJacobian H1,
+ ChartJacobian H2 = boost::none) const {
+ Jacobian1 D_g_first; Jacobian2 D_h_second;
+ G g = traits::Between(this->first,other.first, H1 ? &D_g_first : 0);
+ H h = traits::Between(this->second,other.second, H1 ? &D_h_second : 0);
+ if (H1) {
+ H1->setZero();
+ H1->template topLeftCorner() = D_g_first;
+ H1->template bottomRightCorner() = D_h_second;
+ }
+ if (H2) *H2 = Jacobian::Identity();
+ return ProductLieGroup(g,h);
+ }
+ ProductLieGroup inverse(ChartJacobian D) const {
+ Jacobian1 D_g_first; Jacobian2 D_h_second;
+ G g = traits::Inverse(this->first, D ? &D_g_first : 0);
+ H h = traits::Inverse(this->second, D ? &D_h_second : 0);
+ if (D) {
+ D->setZero();
+ D->template topLeftCorner() = D_g_first;
+ D->template bottomRightCorner() = D_h_second;
+ }
+ return ProductLieGroup(g,h);
+ }
+ static ProductLieGroup Expmap(const TangentVector& v, ChartJacobian Hv = boost::none) {
+ if (Hv) throw std::runtime_error("ProductLieGroup::Expmap derivatives not implemented yet");
+ G g = traits::Expmap(v.template head());
+ H h = traits::Expmap(v.template tail());
+ return ProductLieGroup(g,h);
+ }
+ static TangentVector Logmap(const ProductLieGroup& p, ChartJacobian Hp = boost::none) {
+ if (Hp) throw std::runtime_error("ProductLieGroup::Logmap derivatives not implemented yet");
+ typename traits::TangentVector v1 = traits::Logmap(p.first);
+ typename traits::TangentVector v2 = traits::Logmap(p.second);
+ TangentVector v;
+ v << v1, v2;
+ return v;
+ }
+ struct ChartAtOrigin {
+ static TangentVector Local(const ProductLieGroup& m, ChartJacobian Hm = boost::none) {
+ return Logmap(m, Hm);
+ }
+ static ProductLieGroup Retract(const TangentVector& v, ChartJacobian Hv = boost::none) {
+ return Expmap(v, Hv);
+ }
+ };
+ ProductLieGroup expmap(const TangentVector& v) const {
+ return compose(ProductLieGroup::Expmap(v));
+ }
+ TangentVector logmap(const ProductLieGroup& g) const {
+ return ProductLieGroup::Logmap(between(g));
+ }
+ static ProductLieGroup Retract(const TangentVector& v, ChartJacobian H1) {
+ return ProductLieGroup::ChartAtOrigin::Retract(v,H1);
+ }
+ static TangentVector LocalCoordinates(const ProductLieGroup& g, ChartJacobian H1) {
+ return ProductLieGroup::ChartAtOrigin::Local(g,H1);
+ }
+ ProductLieGroup retract(const TangentVector& v, //
+ ChartJacobian H1, ChartJacobian H2 = boost::none) const {
+ Jacobian D_g_v;
+ ProductLieGroup g = ProductLieGroup::ChartAtOrigin::Retract(v,H2 ? &D_g_v : 0);
+ ProductLieGroup h = compose(g,H1,H2);
+ if (H2) *H2 = (*H2) * D_g_v;
+ return h;
+ }
+ TangentVector localCoordinates(const ProductLieGroup& g, //
+ ChartJacobian H1, ChartJacobian H2 = boost::none) const {
+ ProductLieGroup h = between(g,H1,H2);
+ Jacobian D_v_h;
+ TangentVector v = ProductLieGroup::ChartAtOrigin::Local(h, (H1 || H2) ? &D_v_h : 0);
+ if (H1) *H1 = D_v_h * (*H1);
+ if (H2) *H2 = D_v_h * (*H2);
+ return v;
+ }
+ /// @}
+
+};
+
+// Define any direct product group to be a model of the multiplicative Group concept
+template
+struct traits > : internal::LieGroupTraits<
+ ProductLieGroup > {
+};
+} // namespace gtsam
+
diff --git a/gtsam/base/VectorSpace.h b/gtsam/base/VectorSpace.h
index 558fe52c9..c356dcc07 100644
--- a/gtsam/base/VectorSpace.h
+++ b/gtsam/base/VectorSpace.h
@@ -20,7 +20,7 @@ template struct traits;
namespace internal {
-/// VectorSpace Implementation for Fixed sizes
+/// VectorSpaceTraits Implementation for Fixed sizes
template
struct VectorSpaceImpl {
@@ -83,7 +83,7 @@ struct VectorSpaceImpl {
/// @}
};
-/// VectorSpace implementation for dynamic types.
+/// VectorSpaceTraits implementation for dynamic types.
template
struct VectorSpaceImpl {
@@ -159,11 +159,11 @@ struct VectorSpaceImpl {
/// @}
};
-/// A helper that implements the traits interface for GTSAM lie groups.
+/// A helper that implements the traits interface for GTSAM vector space types.
/// To use this for your gtsam type, define:
-/// template<> struct traits : public VectorSpace { };
+/// template<> struct traits : public VectorSpaceTraits { };
template
-struct VectorSpace: Testable, VectorSpaceImpl {
+struct VectorSpaceTraits: VectorSpaceImpl {
typedef vector_space_tag structure_category;
@@ -178,9 +178,12 @@ struct VectorSpace: Testable, VectorSpaceImpl {
enum { dimension = Class::dimension};
typedef Class ManifoldType;
/// @}
-
};
+/// Both VectorSpaceTRaits and Testable
+template
+struct VectorSpace: Testable, VectorSpaceTraits {};
+
/// A helper that implements the traits interface for GTSAM lie groups.
/// To use this for your gtsam type, define:
/// template<> struct traits : public ScalarTraits { };
diff --git a/gtsam/base/tests/testGroup.cpp b/gtsam/base/tests/testGroup.cpp
new file mode 100644
index 000000000..241f71802
--- /dev/null
+++ b/gtsam/base/tests/testGroup.cpp
@@ -0,0 +1,143 @@
+/* ----------------------------------------------------------------------------
+
+ * GTSAM Copyright 2010, Georgia Tech Research Corporation,
+ * Atlanta, Georgia 30332-0415
+ * All Rights Reserved
+ * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
+
+ * See LICENSE for the license information
+
+ * -------------------------------------------------------------------------- */
+
+/**
+ * @file testGroup.cpp
+ * @brief Unit tests for groups
+ * @author Frank Dellaert
+ **/
+
+#include
+#include
+#include
+#include
+#include
+
+namespace gtsam {
+
+/// Symmetric group
+template
+class Symmetric: private Eigen::PermutationMatrix {
+ Symmetric(const Eigen::PermutationMatrix& P) :
+ Eigen::PermutationMatrix(P) {
+ }
+public:
+ static Symmetric identity() { return Symmetric(); }
+ Symmetric() {
+ Eigen::PermutationMatrix::setIdentity();
+ }
+ static Symmetric Transposition(int i, int j) {
+ Symmetric g;
+ return g.applyTranspositionOnTheRight(i, j);
+ }
+ Symmetric operator*(const Symmetric& other) const {
+ return Eigen::PermutationMatrix::operator*(other);
+ }
+ bool operator==(const Symmetric& other) const {
+ for (size_t i = 0; i < N; i++)
+ if (this->indices()[i] != other.indices()[i])
+ return false;
+ return true;
+ }
+ Symmetric inverse() const {
+ return Eigen::PermutationMatrix(Eigen::PermutationMatrix::inverse());
+ }
+ friend std::ostream &operator<<(std::ostream &os, const Symmetric& m) {
+ for (size_t i = 0; i < N; i++)
+ os << m.indices()[i] << " ";
+ return os;
+ }
+ void print(const std::string& s = "") const {
+ std::cout << s << *this << std::endl;
+ }
+ bool equals(const Symmetric& other, double tol = 0) const {
+ return this->indices() == other.indices();
+ }
+};
+
+/// Define permutation group traits to be a model of the Multiplicative Group concept
+template
+struct traits > : internal::MultiplicativeGroupTraits >,
+ Testable > {
+};
+
+} // namespace gtsam
+
+#include
+#include
+
+using namespace std;
+using namespace gtsam;
+
+//******************************************************************************
+typedef Symmetric<2> S2;
+TEST(Group, S2) {
+ S2 e, s1 = S2::Transposition(0, 1);
+ BOOST_CONCEPT_ASSERT((IsGroup));
+ EXPECT(check_group_invariants(e, s1));
+}
+
+//******************************************************************************
+typedef Symmetric<3> S3;
+TEST(Group, S3) {
+ S3 e, s1 = S3::Transposition(0, 1), s2 = S3::Transposition(1, 2);
+ BOOST_CONCEPT_ASSERT((IsGroup));
+ EXPECT(check_group_invariants(e, s1));
+ EXPECT(assert_equal(s1, s1 * e));
+ EXPECT(assert_equal(s1, e * s1));
+ EXPECT(assert_equal(e, s1 * s1));
+ S3 g = s1 * s2; // 1 2 0
+ EXPECT(assert_equal(s1, g * s2));
+ EXPECT(assert_equal(e, compose_pow(g, 0)));
+ EXPECT(assert_equal(g, compose_pow(g, 1)));
+ EXPECT(assert_equal(e, compose_pow(g, 3))); // g is generator of Z3 subgroup
+}
+
+//******************************************************************************
+// The direct product of S2=Z2 and S3 is the symmetry group of a hexagon,
+// i.e., the dihedral group of order 12 (denoted Dih6 because 6-sided polygon)
+typedef DirectProduct Dih6;
+
+std::ostream &operator<<(std::ostream &os, const Dih6& m) {
+ os << "( " << m.first << ", " << m.second << ")";
+ return os;
+}
+
+// Provide traits with Testable
+namespace gtsam {
+template<>
+struct traits : internal::MultiplicativeGroupTraits {
+ static void Print(const Dih6& m, const string& s = "") {
+ cout << s << m << endl;
+ }
+ static bool Equals(const Dih6& m1, const Dih6& m2, double tol = 1e-8) {
+ return m1 == m2;
+ }
+};
+} // namespace gtsam
+
+TEST(Group, Dih6) {
+ Dih6 e, g(S2::Transposition(0, 1),
+ S3::Transposition(0, 1) * S3::Transposition(1, 2));
+ BOOST_CONCEPT_ASSERT((IsGroup));
+ EXPECT(check_group_invariants(e, g));
+ EXPECT(assert_equal(e, compose_pow(g, 0)));
+ EXPECT(assert_equal(g, compose_pow(g, 1)));
+ EXPECT(assert_equal(e, compose_pow(g, 6))); // g is generator of Z6 subgroup
+}
+
+//******************************************************************************
+int main() {
+ TestResult tr;
+ return TestRegistry::runAllTests(tr);
+}
+//******************************************************************************
+
diff --git a/gtsam/base/tests/testLieScalar.cpp b/gtsam/base/tests/testLieScalar.cpp
index 141b55761..07e666fbe 100644
--- a/gtsam/base/tests/testLieScalar.cpp
+++ b/gtsam/base/tests/testLieScalar.cpp
@@ -37,8 +37,8 @@ TEST(LieScalar , Concept) {
//******************************************************************************
TEST(LieScalar , Invariants) {
LieScalar lie1(2), lie2(3);
- check_group_invariants(lie1, lie2);
- check_manifold_invariants(lie1, lie2);
+ CHECK(check_group_invariants(lie1, lie2));
+ CHECK(check_manifold_invariants(lie1, lie2));
}
/* ************************************************************************* */
diff --git a/gtsam/geometry/Cyclic.h b/gtsam/geometry/Cyclic.h
index 2c883707f..15d8154b8 100644
--- a/gtsam/geometry/Cyclic.h
+++ b/gtsam/geometry/Cyclic.h
@@ -16,10 +16,8 @@
**/
#include
-#include
-#include
-#include
-#include
+#include
+#include // for cout :-(
namespace gtsam {
@@ -33,10 +31,11 @@ public:
i_(i) {
assert(i < N);
}
- /// Idenity element
- static Cyclic Identity() {
- return Cyclic(0);
+ /// Default constructor yields identity
+ Cyclic():i_(0) {
}
+ static Cyclic identity() { return Cyclic();}
+
/// Cast to size_t
operator size_t() const {
return i_;
@@ -63,20 +62,10 @@ public:
}
};
-/// Define cyclic group traits to be a model of the Group concept
+/// Define cyclic group to be a model of the Additive Group concept
template
-struct traits > {
- typedef group_tag structure_category;GTSAM_ADDITIVE_GROUP(Cyclic)
- static Cyclic Identity() {
- return Cyclic::Identity();
- }
- static bool Equals(const Cyclic& a, const Cyclic& b,
- double tol = 1e-9) {
- return a.equals(b, tol);
- }
- static void Print(const Cyclic& c, const std::string &s = "") {
- c.print(s);
- }
+struct traits > : internal::AdditiveGroupTraits >, //
+ Testable > {
};
} // \namespace gtsam
diff --git a/gtsam/geometry/EssentialMatrix.cpp b/gtsam/geometry/EssentialMatrix.cpp
index 062178fea..7b90edc39 100644
--- a/gtsam/geometry/EssentialMatrix.cpp
+++ b/gtsam/geometry/EssentialMatrix.cpp
@@ -13,64 +13,46 @@ using namespace std;
namespace gtsam {
/* ************************************************************************* */
-EssentialMatrix EssentialMatrix::FromPose3(const Pose3& _1P2_,
+EssentialMatrix EssentialMatrix::FromPose3(const Pose3& aPb,
OptionalJacobian<5, 6> H) {
- const Rot3& _1R2_ = _1P2_.rotation();
- const Point3& _1T2_ = _1P2_.translation();
+ const Rot3& aRb = aPb.rotation();
+ const Point3& aTb = aPb.translation();
if (!H) {
// just make a direction out of translation and create E
- Unit3 direction(_1T2_);
- return EssentialMatrix(_1R2_, direction);
+ Unit3 direction(aTb);
+ return EssentialMatrix(aRb, direction);
} else {
// Calculate the 5*6 Jacobian H = D_E_1P2
// D_E_1P2 = [D_E_1R2 D_E_1T2], 5*3 wrpt rotation, 5*3 wrpt translation
// First get 2*3 derivative from Unit3::FromPoint3
Matrix23 D_direction_1T2;
- Unit3 direction = Unit3::FromPoint3(_1T2_, D_direction_1T2);
+ Unit3 direction = Unit3::FromPoint3(aTb, D_direction_1T2);
*H << I_3x3, Z_3x3, //
- Matrix23::Zero(), D_direction_1T2 * _1R2_.matrix();
- return EssentialMatrix(_1R2_, direction);
+ Matrix23::Zero(), D_direction_1T2 * aRb.matrix();
+ return EssentialMatrix(aRb, direction);
}
}
/* ************************************************************************* */
void EssentialMatrix::print(const string& s) const {
cout << s;
- aRb_.print("R:\n");
- aTb_.print("d: ");
-}
-
-/* ************************************************************************* */
-EssentialMatrix EssentialMatrix::retract(const Vector& xi) const {
- assert(xi.size() == 5);
- Vector3 omega(sub(xi, 0, 3));
- Vector2 z(sub(xi, 3, 5));
- Rot3 R = aRb_.retract(omega);
- Unit3 t = aTb_.retract(z);
- return EssentialMatrix(R, t);
-}
-
-/* ************************************************************************* */
-Vector5 EssentialMatrix::localCoordinates(const EssentialMatrix& other) const {
- Vector5 v;
- v << aRb_.localCoordinates(other.aRb_),
- aTb_.localCoordinates(other.aTb_);
- return v;
+ rotation().print("R:\n");
+ direction().print("d: ");
}
/* ************************************************************************* */
Point3 EssentialMatrix::transform_to(const Point3& p, OptionalJacobian<3, 5> DE,
OptionalJacobian<3, 3> Dpoint) const {
- Pose3 pose(aRb_, aTb_.point3());
+ Pose3 pose(rotation(), direction().point3());
Matrix36 DE_;
Point3 q = pose.transform_to(p, DE ? &DE_ : 0, Dpoint);
if (DE) {
// DE returned by pose.transform_to is 3*6, but we need it to be 3*5
// The last 3 columns are derivative with respect to change in translation
- // The derivative of translation with respect to a 2D sphere delta is 3*2 aTb_.basis()
+ // The derivative of translation with respect to a 2D sphere delta is 3*2 direction().basis()
// Duy made an educated guess that this needs to be rotated to the local frame
Matrix35 H;
- H << DE_.block < 3, 3 > (0, 0), -aRb_.transpose() * aTb_.basis();
+ H << DE_.block < 3, 3 > (0, 0), -rotation().transpose() * direction().basis();
*DE = H;
}
return q;
@@ -81,17 +63,17 @@ EssentialMatrix EssentialMatrix::rotate(const Rot3& cRb,
OptionalJacobian<5, 5> HE, OptionalJacobian<5, 3> HR) const {
// The rotation must be conjugated to act in the camera frame
- Rot3 c1Rc2 = aRb_.conjugate(cRb);
+ Rot3 c1Rc2 = rotation().conjugate(cRb);
if (!HE && !HR) {
// Rotate translation direction and return
- Unit3 c1Tc2 = cRb * aTb_;
+ Unit3 c1Tc2 = cRb * direction();
return EssentialMatrix(c1Rc2, c1Tc2);
} else {
// Calculate derivatives
Matrix23 D_c1Tc2_cRb; // 2*3
Matrix2 D_c1Tc2_aTb; // 2*2
- Unit3 c1Tc2 = cRb.rotate(aTb_, D_c1Tc2_cRb, D_c1Tc2_aTb);
+ Unit3 c1Tc2 = cRb.rotate(direction(), D_c1Tc2_cRb, D_c1Tc2_aTb);
if (HE)
*HE << cRb.matrix(), Matrix32::Zero(), //
Matrix23::Zero(), D_c1Tc2_aTb;
@@ -113,8 +95,8 @@ double EssentialMatrix::error(const Vector3& vA, const Vector3& vB, //
if (H) {
// See math.lyx
Matrix13 HR = vA.transpose() * E_ * skewSymmetric(-vB);
- Matrix12 HD = vA.transpose() * skewSymmetric(-aRb_.matrix() * vB)
- * aTb_.basis();
+ Matrix12 HD = vA.transpose() * skewSymmetric(-rotation().matrix() * vB)
+ * direction().basis();
*H << HR, HD;
}
return dot(vA, E_ * vB);
diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h
index c5243c68b..697bd462d 100644
--- a/gtsam/geometry/EssentialMatrix.h
+++ b/gtsam/geometry/EssentialMatrix.h
@@ -10,6 +10,7 @@
#include
#include
#include
+#include
#include
namespace gtsam {
@@ -20,17 +21,18 @@ namespace gtsam {
* but here we choose instead to parameterize it as a (Rot3,Unit3) pair.
* We can then non-linearly optimize immediately on this 5-dimensional manifold.
*/
-class GTSAM_EXPORT EssentialMatrix {
+class GTSAM_EXPORT EssentialMatrix : private ProductManifold {
private:
-
- Rot3 aRb_; ///< Rotation between a and b
- Unit3 aTb_; ///< translation direction from a to b
+ typedef ProductManifold Base;
Matrix3 E_; ///< Essential matrix
-public:
+ /// Construct from Base
+ EssentialMatrix(const Base& base) :
+ Base(base), E_(direction().skew() * rotation().matrix()) {
+ }
- enum { dimension = 5 };
+public:
/// Static function to convert Point2 to homogeneous coordinates
static Vector3 Homogeneous(const Point2& p) {
@@ -42,12 +44,12 @@ public:
/// Default constructor
EssentialMatrix() :
- aTb_(1, 0, 0), E_(aTb_.skew()) {
+ Base(Rot3(), Unit3(1, 0, 0)), E_(direction().skew()) {
}
/// Construct from rotation and translation
EssentialMatrix(const Rot3& aRb, const Unit3& aTb) :
- aRb_(aRb), aTb_(aTb), E_(aTb_.skew() * aRb_.matrix()) {
+ Base(aRb, aTb), E_(direction().skew() * rotation().matrix()) {
}
/// Named constructor converting a Pose3 with scale to EssentialMatrix (no scale)
@@ -72,7 +74,8 @@ public:
/// assert equality up to a tolerance
bool equals(const EssentialMatrix& other, double tol = 1e-8) const {
- return aRb_.equals(other.aRb_, tol) && aTb_.equals(other.aTb_, tol);
+ return rotation().equals(other.rotation(), tol)
+ && direction().equals(other.direction(), tol);
}
/// @}
@@ -80,22 +83,19 @@ public:
/// @name Manifold
/// @{
- /// Dimensionality of tangent space = 5 DOF
- inline static size_t Dim() {
- return 5;
- }
-
- /// Return the dimensionality of the tangent space
- size_t dim() const {
- return 5;
- }
+ using Base::dimension;
+ using Base::dim;
+ using Base::Dim;
/// Retract delta to manifold
- EssentialMatrix retract(const Vector& xi) const;
+ EssentialMatrix retract(const TangentVector& v) const {
+ return Base::retract(v);
+ }
/// Compute the coordinates in the tangent space
- Vector5 localCoordinates(const EssentialMatrix& other) const;
-
+ TangentVector localCoordinates(const EssentialMatrix& other) const {
+ return Base::localCoordinates(other);
+ }
/// @}
/// @name Essential matrix methods
@@ -103,12 +103,12 @@ public:
/// Rotation
inline const Rot3& rotation() const {
- return aRb_;
+ return this->first;
}
/// Direction
inline const Unit3& direction() const {
- return aTb_;
+ return this->second;
}
/// Return 3*3 matrix representation
@@ -118,12 +118,12 @@ public:
/// Return epipole in image_a , as Unit3 to allow for infinity
inline const Unit3& epipole_a() const {
- return aTb_; // == direction()
+ return direction();
}
/// Return epipole in image_b, as Unit3 to allow for infinity
inline Unit3 epipole_b() const {
- return aRb_.unrotate(aTb_); // == rotation.unrotate(direction())
+ return rotation().unrotate(direction());
}
/**
@@ -180,8 +180,8 @@ private:
friend class boost::serialization::access;
template
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
- ar & BOOST_SERIALIZATION_NVP(aRb_);
- ar & BOOST_SERIALIZATION_NVP(aTb_);
+ ar & BOOST_SERIALIZATION_NVP(first);
+ ar & BOOST_SERIALIZATION_NVP(second);
ar & boost::serialization::make_nvp("E11", E_(0,0));
ar & boost::serialization::make_nvp("E12", E_(0,1));
@@ -195,7 +195,6 @@ private:
}
/// @}
-
};
template<>
diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h
index e7a8ab10c..f3cb9e2a1 100644
--- a/gtsam/geometry/Pose2.h
+++ b/gtsam/geometry/Pose2.h
@@ -290,10 +290,10 @@ typedef std::pair Point2Pair;
GTSAM_EXPORT boost::optional align(const std::vector& pairs);
template<>
-struct traits : public internal::LieGroupTraits {};
+struct traits : public internal::LieGroup {};
template<>
-struct traits : public internal::LieGroupTraits {};
+struct traits : public internal::LieGroup {};
} // namespace gtsam
diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h
index 02ad87e80..8a0f23404 100644
--- a/gtsam/geometry/Pose3.h
+++ b/gtsam/geometry/Pose3.h
@@ -324,10 +324,10 @@ GTSAM_EXPORT boost::optional align(const std::vector& pairs);
typedef std::vector Pose3Vector;
template<>
-struct traits : public internal::LieGroupTraits {};
+struct traits : public internal::LieGroup {};
template<>
-struct traits : public internal::LieGroupTraits {};
+struct traits : public internal::LieGroup {};
} // namespace gtsam
diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h
index 9500f0d64..198cd5862 100644
--- a/gtsam/geometry/Rot2.h
+++ b/gtsam/geometry/Rot2.h
@@ -208,9 +208,9 @@ namespace gtsam {
};
template<>
- struct traits : public internal::LieGroupTraits {};
+ struct traits : public internal::LieGroup {};
template<>
- struct traits : public internal::LieGroupTraits {};
+ struct traits : public internal::LieGroup {};
} // gtsam
diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h
index 7520d8d56..881c58579 100644
--- a/gtsam/geometry/Rot3.h
+++ b/gtsam/geometry/Rot3.h
@@ -463,9 +463,9 @@ namespace gtsam {
GTSAM_EXPORT std::pair RQ(const Matrix3& A);
template<>
- struct traits : public internal::LieGroupTraits {};
+ struct traits : public internal::LieGroup {};
template<>
- struct traits : public internal::LieGroupTraits {};
+ struct traits : public internal::LieGroup {};
}
diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h
index a07c3601d..a08168ed8 100644
--- a/gtsam/geometry/SO3.h
+++ b/gtsam/geometry/SO3.h
@@ -129,11 +129,11 @@ public:
};
template<>
-struct traits : public internal::LieGroupTraits {
+struct traits : public internal::LieGroup {
};
template<>
-struct traits : public internal::LieGroupTraits {
+struct traits : public internal::LieGroup {
};
} // end namespace gtsam
diff --git a/gtsam/geometry/tests/testCyclic.cpp b/gtsam/geometry/tests/testCyclic.cpp
index a15d7e2c2..7becfc75f 100644
--- a/gtsam/geometry/tests/testCyclic.cpp
+++ b/gtsam/geometry/tests/testCyclic.cpp
@@ -22,52 +22,114 @@
using namespace std;
using namespace gtsam;
-typedef Cyclic<3> G; // Let's use the cyclic group of order 3
+typedef Cyclic<3> Z3; // Let's use the cyclic group of order 3
+typedef Cyclic<2> Z2;
//******************************************************************************
TEST(Cyclic, Concept) {
- BOOST_CONCEPT_ASSERT((IsGroup));
- EXPECT_LONGS_EQUAL(0, traits