traits_x -> traits

release/4.3a0
dellaert 2014-12-26 16:47:51 +01:00
parent 5ead98afb7
commit e5017984a1
125 changed files with 340 additions and 406 deletions

View File

@ -210,11 +210,11 @@
//template<typename T>
//GenericValue<T> convertToChartValue(const T& value,
// boost::optional<
// Eigen::Matrix<double, traits_x<T>::dimension,
// traits_x<T>::dimension>&> H = boost::none) {
// Eigen::Matrix<double, traits<T>::dimension,
// traits<T>::dimension>&> H = boost::none) {
// if (H) {
// *H = Eigen::Matrix<double, traits_x<T>::dimension,
// traits_x<T>::dimension>::Identity();
// *H = Eigen::Matrix<double, traits<T>::dimension,
// traits<T>::dimension>::Identity();
// }
// return GenericValue<T>(value);
//}

View File

@ -19,7 +19,7 @@
#pragma once
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Manifold.h>
#include <gtsam/base/Value.h>
#include <boost/make_shared.hpp>
@ -30,71 +30,6 @@
namespace gtsam {
// To play as a GenericValue, we need the following traits
namespace traits {
// trait to wrap the default equals of types
template<typename T>
struct equals {
typedef T type;
typedef bool result_type;
bool operator()(const T& a, const T& b, double tol) {
return a.equals(b, tol);
}
};
// trait to wrap the default print of types
template<typename T>
struct print {
typedef T type;
typedef void result_type;
void operator()(const T& obj, const std::string& str) {
obj.print(str);
}
};
// equals for scalars
template<>
struct equals<double> {
typedef double type;
typedef bool result_type;
bool operator()(double a, double b, double tol) {
return std::abs(a - b) <= tol;
}
};
// print for scalars
template<>
struct print<double> {
typedef double type;
typedef void result_type;
void operator()(double a, const std::string& str) {
std::cout << str << ": " << a << std::endl;
}
};
// equals for Matrix types
template<int _Rows, int _Cols, int _Options, int _MaxRows, int _MaxCols>
struct equals<Eigen::Matrix<double, _Rows, _Cols, _Options, _MaxRows, _MaxCols> > {
typedef Eigen::Matrix<double, _Rows, _Cols, _Options, _MaxRows, _MaxCols> type;
typedef bool result_type;
bool operator()(const type& A, const type& B, double tol) {
return equal_with_abs_tol(A, B, tol);
}
};
// print for Matrix types
template<int _Rows, int _Cols, int _Options, int _MaxRows, int _MaxCols>
struct print<Eigen::Matrix<double, _Rows, _Cols, _Options, _MaxRows, _MaxCols> > {
typedef Eigen::Matrix<double, _Rows, _Cols, _Options, _MaxRows, _MaxCols> type;
typedef void result_type;
void operator()(const type& A, const std::string& str) {
std::cout << str << ": " << A << std::endl;
}
};
}
/**
* Wraps any type T so it can play as a Value
*/
@ -137,17 +72,17 @@ public:
// Cast the base class Value pointer to a templated generic class pointer
const GenericValue& genericValue2 = static_cast<const GenericValue&>(p);
// Return the result of using the equals traits for the derived class
return traits::equals<T>()(this->value_, genericValue2.value_, tol);
return traits<T>::Equals(this->value_, genericValue2.value_, tol);
}
/// non virtual equals function, uses traits
bool equals(const GenericValue &other, double tol = 1e-9) const {
return traits::equals<T>()(this->value(), other.value(), tol);
return traits<T>::Equals(this->value(), other.value(), tol);
}
/// Virtual print function, uses traits
virtual void print(const std::string& str) const {
traits::print<T>()(value_, str);
traits<T>::Print(value_, str);
}
/**
@ -179,7 +114,7 @@ public:
/// Generic Value interface version of retract
virtual Value* retract_(const Vector& delta) const {
// Call retract on the derived class using the retract trait function
const T retractResult = traits_x<T>::Retract(GenericValue<T>::value(), delta);
const T retractResult = traits<T>::Retract(GenericValue<T>::value(), delta);
// Create a Value pointer copy of the result
void* resultAsValuePlace =
@ -197,12 +132,12 @@ public:
static_cast<const GenericValue<T>&>(value2);
// Return the result of calling localCoordinates trait on the derived class
return traits_x<T>::Local(GenericValue<T>::value(), genericValue2.value());
return traits<T>::Local(GenericValue<T>::value(), genericValue2.value());
}
/// Non-virtual version of retract
GenericValue retract(const Vector& delta) const {
return GenericValue(traits_x<T>::Retract(GenericValue<T>::value(), delta));
return GenericValue(traits<T>::Retract(GenericValue<T>::value(), delta));
}
/// Non-virtual version of localCoordinates
@ -212,7 +147,7 @@ public:
/// Return run-time dimensionality
virtual size_t dim() const {
return traits_x<T>::GetDimension(value_);
return traits<T>::GetDimension(value_);
}
/// Assignment operator

View File

@ -33,7 +33,7 @@ struct group_tag {};
struct multiplicative_group_tag {};
struct additive_group_tag {};
template <typename T> struct traits_x;
template <typename T> struct traits;
/**
* Group Concept
@ -41,18 +41,18 @@ template <typename T> struct traits_x;
template<typename G>
class IsGroup {
public:
typedef typename traits_x<G>::structure_category structure_category_tag;
typedef typename traits_x<G>::group_flavor flavor_tag;
//typedef typename traits_x<G>::identity::value_type identity_value_type;
typedef typename traits<G>::structure_category structure_category_tag;
typedef typename traits<G>::group_flavor flavor_tag;
//typedef typename traits<G>::identity::value_type identity_value_type;
BOOST_CONCEPT_USAGE(IsGroup) {
BOOST_STATIC_ASSERT_MSG(
(boost::is_base_of<group_tag, structure_category_tag>::value),
"This type's structure_category trait does not assert it as a group (or derived)");
e = traits_x<G>::Identity();
e = traits_x<G>::Compose(g, h);
e = traits_x<G>::Between(g, h);
e = traits_x<G>::Inverse(g);
e = traits<G>::Identity();
e = traits<G>::Compose(g, h);
e = traits<G>::Between(g, h);
e = traits<G>::Inverse(g);
operator_usage(flavor);
// todo: how do we test the act concept? or do we even need to?
}
@ -77,10 +77,10 @@ private:
template<typename G>
BOOST_CONCEPT_REQUIRES(((IsGroup<G>)),(bool)) //
check_group_invariants(const G& a, const G& b, double tol = 1e-9) {
G e = traits_x<G>::Identity();
return traits_x<G>::Equals(traits_x<G>::Compose(a, traits_x<G>::Inverse(a)), e, tol)
&& traits_x<G>::Equals(traits_x<G>::Between(a, b), traits_x<G>::Compose(traits_x<G>::Inverse(a), b), tol)
&& traits_x<G>::Equals(traits_x<G>::Compose(a, traits_x<G>::Between(a, b)), b, tol);
G e = traits<G>::Identity();
return traits<G>::Equals(traits<G>::Compose(a, traits<G>::Inverse(a)), e, tol)
&& traits<G>::Equals(traits<G>::Between(a, b), traits<G>::Compose(traits<G>::Inverse(a), b), tol)
&& traits<G>::Equals(traits<G>::Compose(a, traits<G>::Between(a, b)), b, tol);
}
/// Macro to add group traits, additive flavor

View File

@ -238,10 +238,10 @@ inline Class expmap_default(const Class& t, const Vector& d) {
template<typename T>
class IsLieGroup: public IsGroup<T>, public IsManifold<T> {
public:
typedef typename traits_x<T>::structure_category structure_category_tag;
typedef typename traits_x<T>::ManifoldType ManifoldType;
typedef typename traits_x<T>::TangentVector TangentVector;
typedef typename traits_x<T>::ChartJacobian ChartJacobian;
typedef typename traits<T>::structure_category structure_category_tag;
typedef typename traits<T>::ManifoldType ManifoldType;
typedef typename traits<T>::TangentVector TangentVector;
typedef typename traits<T>::ChartJacobian ChartJacobian;
BOOST_CONCEPT_USAGE(IsLieGroup) {
BOOST_STATIC_ASSERT_MSG(
@ -249,15 +249,15 @@ public:
"This type's trait does not assert it is a Lie group (or derived)");
// group opertations with Jacobians
g = traits_x<T>::Compose(g, h, Hg, Hh);
g = traits_x<T>::Between(g, h, Hg, Hh);
g = traits_x<T>::Inverse(g, Hg);
g = traits<T>::Compose(g, h, Hg, Hh);
g = traits<T>::Between(g, h, Hg, Hh);
g = traits<T>::Inverse(g, Hg);
// log and exp map without Jacobians
g = traits_x<T>::Expmap(v);
v = traits_x<T>::Logmap(g);
g = traits<T>::Expmap(v);
v = traits<T>::Logmap(g);
// log and expnential map with Jacobians
g = traits_x<T>::Expmap(v, Hg);
v = traits_x<T>::Logmap(g, Hg);
g = traits<T>::Expmap(v, Hg);
v = traits<T>::Logmap(g, Hg);
}
private:
T g, h;

View File

@ -120,7 +120,7 @@ private:
template<>
struct traits_x<LieMatrix> : public internal::VectorSpace<LieMatrix> {
struct traits<LieMatrix> : public internal::VectorSpace<LieMatrix> {
// Override Retract, as the default version does not know how to initialize
static LieMatrix Retract(const LieMatrix& origin, const TangentVector& v,

View File

@ -67,6 +67,6 @@ namespace gtsam {
};
template<>
struct traits_x<LieScalar> : public internal::ScalarTraits<LieScalar> {};
struct traits<LieScalar> : public internal::ScalarTraits<LieScalar> {};
} // \namespace gtsam

View File

@ -102,6 +102,6 @@ private:
template<>
struct traits_x<LieVector> : public internal::VectorSpace<LieVector> {};
struct traits<LieVector> : public internal::VectorSpace<LieVector> {};
} // \namespace gtsam

View File

@ -50,7 +50,7 @@ struct manifold_tag {};
*
*/
template <typename T> struct traits_x;
template <typename T> struct traits;
namespace internal {
@ -122,10 +122,10 @@ struct Manifold: Testable<Class>, ManifoldImpl<Class, Class::dimension> {
template<typename T>
BOOST_CONCEPT_REQUIRES(((IsTestable<T>)),(bool)) //
check_manifold_invariants(const T& a, const T& b, double tol=1e-9) {
typename traits_x<T>::TangentVector v0 = traits_x<T>::Local(a,a);
typename traits_x<T>::TangentVector v = traits_x<T>::Local(a,b);
T c = traits_x<T>::Retract(a,v);
return v0.norm() < tol && traits_x<T>::Equals(b,c,tol);
typename traits<T>::TangentVector v0 = traits<T>::Local(a,a);
typename traits<T>::TangentVector v = traits<T>::Local(a,b);
T c = traits<T>::Retract(a,v);
return v0.norm() < tol && traits<T>::Equals(b,c,tol);
}
/// Manifold concept
@ -134,10 +134,10 @@ class IsManifold {
public:
typedef typename traits_x<T>::structure_category structure_category_tag;
static const size_t dim = traits_x<T>::dimension;
typedef typename traits_x<T>::ManifoldType ManifoldType;
typedef typename traits_x<T>::TangentVector TangentVector;
typedef typename traits<T>::structure_category structure_category_tag;
static const size_t dim = traits<T>::dimension;
typedef typename traits<T>::ManifoldType ManifoldType;
typedef typename traits<T>::TangentVector TangentVector;
BOOST_CONCEPT_USAGE(IsManifold) {
BOOST_STATIC_ASSERT_MSG(
@ -146,8 +146,8 @@ public:
BOOST_STATIC_ASSERT(TangentVector::SizeAtCompileTime == dim);
// make sure Chart methods are defined
v = traits_x<T>::Local(p, q);
q = traits_x<T>::Retract(p, v);
v = traits<T>::Local(p, q);
q = traits<T>::Retract(p, v);
}
private:
@ -160,7 +160,7 @@ private:
template<typename T>
struct FixedDimension {
typedef const int value_type;
static const int value = traits_x<T>::dimension;
static const int value = traits<T>::dimension;
BOOST_STATIC_ASSERT_MSG(value != Eigen::Dynamic,
"FixedDimension instantiated for dymanically-sized type.");
};

View File

@ -43,7 +43,7 @@
namespace gtsam {
// Forward declaration
template <typename T> struct traits_x;
template <typename T> struct traits;
/**
* A testable concept check that should be placed in applicable unit
@ -61,13 +61,13 @@ namespace gtsam {
BOOST_CONCEPT_USAGE(IsTestable) {
// check print function, with optional string
traits_x<T>::Print(t, std::string());
traits_x<T>::Print(t);
traits<T>::Print(t, std::string());
traits<T>::Print(t);
// check print, with optional threshold
double tol = 1.0;
r1 = traits_x<T>::Equals(t,t,tol);
r2 = traits_x<T>::Equals(t,t);
r1 = traits<T>::Equals(t,t,tol);
r2 = traits<T>::Equals(t,t);
}
}; // \ Testable
@ -81,13 +81,13 @@ namespace gtsam {
/** Call equal on the object */
template<class T>
inline bool equal(const T& obj1, const T& obj2, double tol) {
return traits_x<T>::Equals(obj1,obj2, tol);
return traits<T>::Equals(obj1,obj2, tol);
}
/** Call equal without tolerance (use default tolerance) */
template<class T>
inline bool equal(const T& obj1, const T& obj2) {
return traits_x<T>::Equals(obj1,obj2);
return traits<T>::Equals(obj1,obj2);
}
/**
@ -95,11 +95,11 @@ namespace gtsam {
*/
template<class V>
bool assert_equal(const V& expected, const V& actual, double tol = 1e-9) {
if (traits_x<V>::Equals(actual,expected, tol))
if (traits<V>::Equals(actual,expected, tol))
return true;
printf("Not equal:\n");
traits_x<V>::Print(expected,"expected:\n");
traits_x<V>::Print(actual,"actual:\n");
traits<V>::Print(expected,"expected:\n");
traits<V>::Print(actual,"actual:\n");
return false;
}
@ -111,7 +111,7 @@ namespace gtsam {
double tol_;
equals(double tol = 1e-9) : tol_(tol) {}
bool operator()(const V& expected, const V& actual) {
return (traits_x<V>::Equals(actual, expected, tol_));
return (traits<V>::Equals(actual, expected, tol_));
}
};
@ -124,7 +124,7 @@ namespace gtsam {
equals_star(double tol = 1e-9) : tol_(tol) {}
bool operator()(const boost::shared_ptr<V>& expected, const boost::shared_ptr<V>& actual) {
if (!actual || !expected) return false;
return (traits_x<V>::Equals(*actual,*expected, tol_));
return (traits<V>::Equals(*actual,*expected, tol_));
}
};

View File

@ -16,7 +16,7 @@ namespace gtsam {
struct vector_space_tag: public lie_group_tag {
};
template<typename T> struct traits_x;
template<typename T> struct traits;
namespace internal {
@ -254,16 +254,16 @@ struct ScalarTraits : VectorSpaceImpl<Scalar, 1> {
} // namespace internal
/// double
template<> struct traits_x<double> : public internal::ScalarTraits<double> {
template<> struct traits<double> : public internal::ScalarTraits<double> {
};
/// float
template<> struct traits_x<float> : public internal::ScalarTraits<float> {
template<> struct traits<float> : public internal::ScalarTraits<float> {
};
// traits for any fixed double Eigen matrix
template<int M, int N, int Options, int MaxRows, int MaxCols>
struct traits_x<Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > :
struct traits<Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > :
internal::VectorSpaceImpl<
Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols>, M * N> {
@ -431,19 +431,19 @@ struct DynamicTraits {
// traits for fully dynamic matrix
template<int Options, int MaxRows, int MaxCols>
struct traits_x<Eigen::Matrix<double, -1, -1, Options, MaxRows, MaxCols> > :
struct traits<Eigen::Matrix<double, -1, -1, Options, MaxRows, MaxCols> > :
public internal::DynamicTraits<-1, -1, Options, MaxRows, MaxCols> {
};
// traits for dynamic column vector
template<int Options, int MaxRows, int MaxCols>
struct traits_x<Eigen::Matrix<double, -1, 1, Options, MaxRows, MaxCols> > :
struct traits<Eigen::Matrix<double, -1, 1, Options, MaxRows, MaxCols> > :
public internal::DynamicTraits<-1, 1, Options, MaxRows, MaxCols> {
};
// traits for dynamic row vector
template<int Options, int MaxRows, int MaxCols>
struct traits_x<Eigen::Matrix<double, 1, -1, Options, MaxRows, MaxCols> > :
struct traits<Eigen::Matrix<double, 1, -1, Options, MaxRows, MaxCols> > :
public internal::DynamicTraits<1, -1, Options, MaxRows, MaxCols> {
};
@ -452,7 +452,7 @@ template<typename T>
class IsVectorSpace: public IsLieGroup<T> {
public:
typedef typename traits_x<T>::structure_category structure_category_tag;
typedef typename traits<T>::structure_category structure_category_tag;
BOOST_CONCEPT_USAGE(IsVectorSpace) {
BOOST_STATIC_ASSERT_MSG(

View File

@ -27,6 +27,6 @@
namespace gtsam {
template <typename T> struct traits_x;
template <typename T> struct traits;
}

View File

@ -62,7 +62,7 @@ namespace gtsam {
namespace internal {
template<class Y, class X=double>
struct FixedSizeMatrix {
typedef Eigen::Matrix<double,traits_x<Y>::dimension, traits_x<X>::dimension> type;
typedef Eigen::Matrix<double,traits<Y>::dimension, traits<X>::dimension> type;
};
}
@ -77,12 +77,12 @@ typename internal::FixedSizeMatrix<X>::type numericalGradient(boost::function<do
double factor = 1.0 / (2.0 * delta);
BOOST_STATIC_ASSERT_MSG(
(boost::is_base_of<manifold_tag, typename traits_x<X>::structure_category>::value),
(boost::is_base_of<manifold_tag, typename traits<X>::structure_category>::value),
"Template argument X must be a manifold type.");
static const int N = traits_x<X>::dimension;
static const int N = traits<X>::dimension;
BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type.");
typedef typename traits_x<X>::TangentVector TangentX;
typedef typename traits<X>::TangentVector TangentX;
// Prepare a tangent vector to perturb x with, only works for fixed size
TangentX d;
@ -91,9 +91,9 @@ typename internal::FixedSizeMatrix<X>::type numericalGradient(boost::function<do
Vector g = zero(N); // Can be fixed size
for (int j = 0; j < N; j++) {
d(j) = delta;
double hxplus = h(traits_x<X>::Retract(x, d));
double hxplus = h(traits<X>::Retract(x, d));
d(j) = -delta;
double hxmin = h(traits_x<X>::Retract(x, d));
double hxmin = h(traits<X>::Retract(x, d));
d(j) = 0;
g(j) = (hxplus - hxmin) * factor;
}
@ -115,20 +115,19 @@ template<class Y, class X>
// TODO Should compute fixed-size matrix
typename internal::FixedSizeMatrix<Y,X>::type numericalDerivative11(boost::function<Y(const X&)> h, const X& x,
double delta = 1e-5) {
using namespace traits;
typedef typename internal::FixedSizeMatrix<Y,X>::type Matrix;
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<Y>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type.");
typedef traits_x<Y> TraitsY;
typedef traits<Y> TraitsY;
typedef typename TraitsY::TangentVector TangentY;
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X>::structure_category>::value),
"Template argument X must be a manifold type.");
static const int N = traits_x<X>::dimension;
static const int N = traits<X>::dimension;
BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type.");
typedef traits_x<X> TraitsX;
typedef traits<X> TraitsX;
typedef typename TraitsX::TangentVector TangentX;
// get value at x, and corresponding chart
@ -174,9 +173,9 @@ typename internal::FixedSizeMatrix<Y,X>::type numericalDerivative11(Y (*h)(const
template<class Y, class X1, class X2>
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative21(const boost::function<Y(const X1&, const X2&)>& h,
const X1& x1, const X2& x2, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<Y>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X1>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X1>(boost::bind(h, _1, x2), x1, delta);
}
@ -199,9 +198,9 @@ typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative21(Y (*h)(cons
template<class Y, class X1, class X2>
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative22(boost::function<Y(const X1&, const X2&)> h,
const X1& x1, const X2& x2, double delta = 1e-5) {
// BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X1>::structure_category>::value),
// BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
// "Template argument X1 must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X2>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
"Template argument X2 must be a manifold type.");
return numericalDerivative11<Y, X2>(boost::bind(h, x1, _1), x2, delta);
}
@ -227,9 +226,9 @@ template<class Y, class X1, class X2, class X3>
typename internal::FixedSizeMatrix<Y,X1>::type numericalDerivative31(
boost::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1,
const X2& x2, const X3& x3, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<Y>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X1>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X1>::structure_category>::value),
"Template argument X1 must be a manifold type.");
return numericalDerivative11<Y, X1>(boost::bind(h, _1, x2, x3), x1, delta);
}
@ -255,9 +254,9 @@ template<class Y, class X1, class X2, class X3>
typename internal::FixedSizeMatrix<Y,X2>::type numericalDerivative32(
boost::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1,
const X2& x2, const X3& x3, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<Y>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X2>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X2>::structure_category>::value),
"Template argument X2 must be a manifold type.");
return numericalDerivative11<Y, X2>(boost::bind(h, x1, _1, x3), x2, delta);
}
@ -283,9 +282,9 @@ template<class Y, class X1, class X2, class X3>
typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative33(
boost::function<Y(const X1&, const X2&, const X3&)> h, const X1& x1,
const X2& x2, const X3& x3, double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<Y>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<Y>::structure_category>::value),
"Template argument Y must be a manifold type.");
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X3>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X3>::structure_category>::value),
"Template argument X3 must be a manifold type.");
return numericalDerivative11<Y, X3>(boost::bind(h, x1, x2, _1), x3, delta);
}
@ -308,9 +307,9 @@ inline typename internal::FixedSizeMatrix<Y,X3>::type numericalDerivative33(Y (*
template<class X>
inline typename internal::FixedSizeMatrix<X,X>::type numericalHessian(boost::function<double(const X&)> f, const X& x,
double delta = 1e-5) {
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X>::structure_category>::value),
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits<X>::structure_category>::value),
"Template argument X must be a manifold type.");
typedef Eigen::Matrix<double, traits_x<X>::dimension, 1> VectorD;
typedef Eigen::Matrix<double, traits<X>::dimension, 1> VectorD;
typedef boost::function<double(const X&)> F;
typedef boost::function<VectorD(F, const X&, double)> G;
G ng = static_cast<G>(numericalGradient<X> );

View File

@ -33,7 +33,7 @@ void testLieGroupDerivatives(TestResult& result_, const std::string& name_,
const G& t1, const G& t2) {
Matrix H1, H2;
typedef traits_x<G> T;
typedef traits<G> T;
// Inverse
EXPECT(assert_equal(t1.inverse(),T::Inverse(t1, H1)));
@ -58,7 +58,7 @@ void testChartDerivatives(TestResult& result_, const std::string& name_,
const G& t1, const G& t2) {
Matrix H1, H2;
typedef traits_x<G> T;
typedef traits<G> T;
// Retract
typename G::TangentVector w12 = T::Local(t1, t2);

View File

@ -30,7 +30,7 @@ TEST( LieMatrix, construction ) {
Matrix m = (Matrix(2,2) << 1.0,2.0, 3.0,4.0).finished();
LieMatrix lie1(m), lie2(m);
EXPECT(traits_x<LieMatrix>::GetDimension(m) == 4);
EXPECT(traits<LieMatrix>::GetDimension(m) == 4);
EXPECT(assert_equal(m, lie1.matrix()));
EXPECT(assert_equal(lie1, lie2));
}
@ -50,17 +50,17 @@ TEST(LieMatrix, retract) {
Vector update = (Vector(4) << 3.0, 4.0, 6.0, 7.0).finished();
LieMatrix expected((Matrix(2,2) << 4.0, 6.0, 9.0, 11.0).finished());
LieMatrix actual = traits_x<LieMatrix>::Retract(init,update);
LieMatrix actual = traits<LieMatrix>::Retract(init,update);
EXPECT(assert_equal(expected, actual));
Vector expectedUpdate = update;
Vector actualUpdate = traits_x<LieMatrix>::Local(init,actual);
Vector actualUpdate = traits<LieMatrix>::Local(init,actual);
EXPECT(assert_equal(expectedUpdate, actualUpdate));
Vector expectedLogmap = (Vector(4) << 1, 2, 3, 4).finished();
Vector actualLogmap = traits_x<LieMatrix>::Logmap(LieMatrix((Matrix(2,2) << 1.0, 2.0, 3.0, 4.0).finished()));
Vector actualLogmap = traits<LieMatrix>::Logmap(LieMatrix((Matrix(2,2) << 1.0, 2.0, 3.0, 4.0).finished()));
EXPECT(assert_equal(expectedLogmap, actualLogmap));
}

View File

@ -48,7 +48,7 @@ TEST( testLieScalar, construction ) {
EXPECT_DOUBLES_EQUAL(2., lie1.value(),tol);
EXPECT_DOUBLES_EQUAL(2., lie2.value(),tol);
EXPECT(traits_x<LieScalar>::dimension == 1);
EXPECT(traits<LieScalar>::dimension == 1);
EXPECT(assert_equal(lie1, lie2));
}
@ -56,7 +56,7 @@ TEST( testLieScalar, construction ) {
TEST( testLieScalar, localCoordinates ) {
LieScalar lie1(1.), lie2(3.);
Vector1 actual = traits_x<LieScalar>::Local(lie1, lie2);
Vector1 actual = traits<LieScalar>::Local(lie1, lie2);
EXPECT( assert_equal((Vector)(Vector(1) << 2).finished(), actual));
}

View File

@ -168,6 +168,6 @@ namespace gtsam {
// DecisionTreeFactor
// traits
template<> struct traits_x<DecisionTreeFactor> : public Testable<DecisionTreeFactor> {};
template<> struct traits<DecisionTreeFactor> : public Testable<DecisionTreeFactor> {};
}// namespace gtsam

View File

@ -96,7 +96,7 @@ namespace gtsam {
};
// traits
template<> struct traits_x<DiscreteBayesNet> : public Testable<DiscreteBayesNet> {};
template<> struct traits<DiscreteBayesNet> : public Testable<DiscreteBayesNet> {};
} // \ namespace gtsam

View File

@ -131,7 +131,7 @@ public:
// DiscreteConditional
// traits
template<> struct traits_x<DiscreteConditional> : public Testable<DiscreteConditional> {};
template<> struct traits<DiscreteConditional> : public Testable<DiscreteConditional> {};
/* ************************************************************************* */
template<typename ITERATOR>

View File

@ -103,7 +103,7 @@ public:
// DiscreteFactor
// traits
template<> struct traits_x<DiscreteFactor> : public Testable<DiscreteFactor> {};
template<> struct traits_x<DiscreteFactor::Values> : public Testable<DiscreteFactor::Values> {};
template<> struct traits<DiscreteFactor> : public Testable<DiscreteFactor> {};
template<> struct traits<DiscreteFactor::Values> : public Testable<DiscreteFactor::Values> {};
}// namespace gtsam

View File

@ -148,6 +148,6 @@ public:
}; // \ DiscreteFactorGraph
/// traits
template<> struct traits_x<DiscreteFactorGraph> : public Testable<DiscreteFactorGraph> {};
template<> struct traits<DiscreteFactorGraph> : public Testable<DiscreteFactorGraph> {};
} // \ namespace gtsam

View File

@ -89,8 +89,8 @@ namespace gtsam {
}; // Potentials
// traits
template<> struct traits_x<Potentials> : public Testable<Potentials> {};
template<> struct traits_x<Potentials::ADT> : public Testable<Potentials::ADT> {};
template<> struct traits<Potentials> : public Testable<Potentials> {};
template<> struct traits<Potentials::ADT> : public Testable<Potentials::ADT> {};
} // namespace gtsam

View File

@ -42,7 +42,7 @@ typedef AlgebraicDecisionTree<Key> ADT;
// traits
namespace gtsam {
template<> struct traits_x<ADT> : public Testable<ADT> {};
template<> struct traits<ADT> : public Testable<ADT> {};
}
#define DISABLE_DOT

View File

@ -46,7 +46,7 @@ typedef DecisionTree<string,Crazy> CrazyDecisionTree; // check that DecisionTree
// traits
namespace gtsam {
template<> struct traits_x<CrazyDecisionTree> : public Testable<CrazyDecisionTree> {};
template<> struct traits<CrazyDecisionTree> : public Testable<CrazyDecisionTree> {};
}
/* ******************************************************************************** */
@ -57,7 +57,7 @@ typedef DecisionTree<string, int> DT;
// traits
namespace gtsam {
template<> struct traits_x<DT> : public Testable<DT> {};
template<> struct traits<DT> : public Testable<DT> {};
}
struct Ring {

View File

@ -172,6 +172,6 @@ private:
};
template<>
struct traits_x<Cal3Bundler> : public internal::Manifold<Cal3Bundler> {};
struct traits<Cal3Bundler> : public internal::Manifold<Cal3Bundler> {};
} // namespace gtsam

View File

@ -110,7 +110,7 @@ private:
};
template<>
struct traits_x<Cal3DS2> : public internal::Manifold<Cal3DS2> {};
struct traits<Cal3DS2> : public internal::Manifold<Cal3DS2> {};
}

View File

@ -140,7 +140,7 @@ private:
};
template<>
struct traits_x<Cal3Unified> : public internal::Manifold<Cal3Unified> {};
struct traits<Cal3Unified> : public internal::Manifold<Cal3Unified> {};
}

View File

@ -224,6 +224,6 @@ private:
};
template<>
struct traits_x<Cal3_S2> : public internal::Manifold<Cal3_S2> {};
struct traits<Cal3_S2> : public internal::Manifold<Cal3_S2> {};
} // \ namespace gtsam

View File

@ -155,7 +155,7 @@ namespace gtsam {
// Define GTSAM traits
template<>
struct traits_x<Cal3_S2Stereo> : public internal::Manifold<Cal3_S2Stereo> {
struct traits<Cal3_S2Stereo> : public internal::Manifold<Cal3_S2Stereo> {
};
} // \ namespace gtsam

View File

@ -202,7 +202,7 @@ private:
};
template<>
struct traits_x<CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
struct traits<CalibratedCamera> : public internal::Manifold<CalibratedCamera> {};
}

View File

@ -65,7 +65,7 @@ public:
/// Define cyclic group traits to be a model of the Group concept
template<size_t N>
struct traits_x<Cyclic<N> > {
struct traits<Cyclic<N> > {
typedef group_tag structure_category;GTSAM_ADDITIVE_GROUP(Cyclic<N>)
static Cyclic<N> Identity() {
return Cyclic<N>::Identity();

View File

@ -199,7 +199,7 @@ private:
};
template<>
struct traits_x<EssentialMatrix> : public internal::Manifold<EssentialMatrix> {};
struct traits<EssentialMatrix> : public internal::Manifold<EssentialMatrix> {};
} // gtsam

View File

@ -497,6 +497,6 @@ private:
template<typename Calibration>
struct traits_x< PinholeCamera<Calibration> > : public internal::Manifold<PinholeCamera<Calibration> > {};
struct traits< PinholeCamera<Calibration> > : public internal::Manifold<PinholeCamera<Calibration> > {};
} // \ gtsam

View File

@ -191,7 +191,7 @@ private:
inline Point2 operator*(double s, const Point2& p) {return p*s;}
template<>
struct traits_x<Point2> : public internal::VectorSpace<Point2> {};
struct traits<Point2> : public internal::VectorSpace<Point2> {};
} // \ namespace gtsam

View File

@ -185,5 +185,5 @@ namespace gtsam {
inline Point3 operator*(double s, const Point3& p) { return p*s;}
template<>
struct traits_x<Point3> : public internal::VectorSpace<Point3> {};
struct traits<Point3> : public internal::VectorSpace<Point3> {};
}

View File

@ -291,7 +291,7 @@ typedef std::pair<Point2,Point2> Point2Pair;
GTSAM_EXPORT boost::optional<Pose2> align(const std::vector<Point2Pair>& pairs);
template<>
struct traits_x<Pose2> : public internal::LieGroupTraits<Pose2> {};
struct traits<Pose2> : public internal::LieGroupTraits<Pose2> {};
} // namespace gtsam

View File

@ -323,7 +323,7 @@ typedef std::pair<Point3, Point3> Point3Pair;
GTSAM_EXPORT boost::optional<Pose3> align(const std::vector<Point3Pair>& pairs);
template<>
struct traits_x<Pose3> : public internal::LieGroupTraits<Pose3> {
struct traits<Pose3> : public internal::LieGroupTraits<Pose3> {
};
} // namespace gtsam

View File

@ -24,7 +24,7 @@ namespace gtsam {
// Define traits
template<typename _Scalar, int _Options>
struct traits_x<QUATERNION_TYPE> {
struct traits<QUATERNION_TYPE> {
typedef QUATERNION_TYPE ManifoldType;
typedef QUATERNION_TYPE Q;

View File

@ -208,6 +208,6 @@ namespace gtsam {
};
template<>
struct traits_x<Rot2> : public internal::LieGroupTraits<Rot2> {};
struct traits<Rot2> : public internal::LieGroupTraits<Rot2> {};
} // gtsam

View File

@ -462,6 +462,6 @@ namespace gtsam {
GTSAM_EXPORT std::pair<Matrix3,Vector3> RQ(const Matrix3& A);
template<>
struct traits_x<Rot3> : public internal::LieGroupTraits<Rot3> {};
struct traits<Rot3> : public internal::LieGroupTraits<Rot3> {};
}

View File

@ -63,7 +63,7 @@ public:
};
template<>
struct traits_x<SO3> : public internal::LieGroupTraits<SO3> {};
struct traits<SO3> : public internal::LieGroupTraits<SO3> {};
} // end namespace gtsam

View File

@ -147,6 +147,6 @@ private:
};
template<>
struct traits_x<StereoCamera> : public internal::Manifold<StereoCamera> {};
struct traits<StereoCamera> : public internal::Manifold<StereoCamera> {};
}

View File

@ -175,5 +175,5 @@ namespace gtsam {
};
template<>
struct traits_x<StereoPoint2> : public internal::Manifold<StereoPoint2> {};
struct traits<StereoPoint2> : public internal::Manifold<StereoPoint2> {};
}

View File

@ -163,7 +163,7 @@ private:
};
// Define GTSAM traits
template <> struct traits_x<Unit3> : public internal::Manifold<Unit3> {};
template <> struct traits<Unit3> : public internal::Manifold<Unit3> {};
} // namespace gtsam

View File

@ -27,7 +27,7 @@ typedef Cyclic<3> G; // Let's use the cyclic group of order 3
//******************************************************************************
TEST(Cyclic, Concept) {
BOOST_CONCEPT_ASSERT((IsGroup<G>));
EXPECT_LONGS_EQUAL(0, traits_x<G>::Identity());
EXPECT_LONGS_EQUAL(0, traits<G>::Identity());
}
//******************************************************************************
@ -37,31 +37,31 @@ TEST(Cyclic, Constructor) {
//******************************************************************************
TEST(Cyclic, Compose) {
EXPECT_LONGS_EQUAL(0, traits_x<G>::Compose(G(0),G(0)));
EXPECT_LONGS_EQUAL(1, traits_x<G>::Compose(G(0),G(1)));
EXPECT_LONGS_EQUAL(2, traits_x<G>::Compose(G(0),G(2)));
EXPECT_LONGS_EQUAL(0, traits<G>::Compose(G(0),G(0)));
EXPECT_LONGS_EQUAL(1, traits<G>::Compose(G(0),G(1)));
EXPECT_LONGS_EQUAL(2, traits<G>::Compose(G(0),G(2)));
EXPECT_LONGS_EQUAL(2, traits_x<G>::Compose(G(2),G(0)));
EXPECT_LONGS_EQUAL(0, traits_x<G>::Compose(G(2),G(1)));
EXPECT_LONGS_EQUAL(1, traits_x<G>::Compose(G(2),G(2)));
EXPECT_LONGS_EQUAL(2, traits<G>::Compose(G(2),G(0)));
EXPECT_LONGS_EQUAL(0, traits<G>::Compose(G(2),G(1)));
EXPECT_LONGS_EQUAL(1, traits<G>::Compose(G(2),G(2)));
}
//******************************************************************************
TEST(Cyclic, Between) {
EXPECT_LONGS_EQUAL(0, traits_x<G>::Between(G(0),G(0)));
EXPECT_LONGS_EQUAL(1, traits_x<G>::Between(G(0),G(1)));
EXPECT_LONGS_EQUAL(2, traits_x<G>::Between(G(0),G(2)));
EXPECT_LONGS_EQUAL(0, traits<G>::Between(G(0),G(0)));
EXPECT_LONGS_EQUAL(1, traits<G>::Between(G(0),G(1)));
EXPECT_LONGS_EQUAL(2, traits<G>::Between(G(0),G(2)));
EXPECT_LONGS_EQUAL(1, traits_x<G>::Between(G(2),G(0)));
EXPECT_LONGS_EQUAL(2, traits_x<G>::Between(G(2),G(1)));
EXPECT_LONGS_EQUAL(0, traits_x<G>::Between(G(2),G(2)));
EXPECT_LONGS_EQUAL(1, traits<G>::Between(G(2),G(0)));
EXPECT_LONGS_EQUAL(2, traits<G>::Between(G(2),G(1)));
EXPECT_LONGS_EQUAL(0, traits<G>::Between(G(2),G(2)));
}
//******************************************************************************
TEST(Cyclic, Ivnverse) {
EXPECT_LONGS_EQUAL(0, traits_x<G>::Inverse(G(0)));
EXPECT_LONGS_EQUAL(2, traits_x<G>::Inverse(G(1)));
EXPECT_LONGS_EQUAL(1, traits_x<G>::Inverse(G(2)));
EXPECT_LONGS_EQUAL(0, traits<G>::Inverse(G(0)));
EXPECT_LONGS_EQUAL(2, traits<G>::Inverse(G(1)));
EXPECT_LONGS_EQUAL(1, traits<G>::Inverse(G(2)));
}
//******************************************************************************

View File

@ -66,16 +66,16 @@ TEST(Point2, Lie) {
Point2 p1(1, 2), p2(4, 5);
Matrix H1, H2;
EXPECT(assert_equal(Point2(5,7), traits_x<Point2>::Compose(p1, p2, H1, H2)));
EXPECT(assert_equal(Point2(5,7), traits<Point2>::Compose(p1, p2, H1, H2)));
EXPECT(assert_equal(eye(2), H1));
EXPECT(assert_equal(eye(2), H2));
EXPECT(assert_equal(Point2(3,3), traits_x<Point2>::Between(p1, p2, H1, H2)));
EXPECT(assert_equal(Point2(3,3), traits<Point2>::Between(p1, p2, H1, H2)));
EXPECT(assert_equal(-eye(2), H1));
EXPECT(assert_equal(eye(2), H2));
EXPECT(assert_equal(Point2(5,7), traits_x<Point2>::Retract(p1, Vector2(4., 5.))));
EXPECT(assert_equal(Vector2(3.,3.), traits_x<Point2>::Local(p1,p2)));
EXPECT(assert_equal(Point2(5,7), traits<Point2>::Retract(p1, Vector2(4., 5.))));
EXPECT(assert_equal(Vector2(3.,3.), traits<Point2>::Local(p1,p2)));
}
/* ************************************************************************* */
@ -83,7 +83,7 @@ TEST( Point2, expmap) {
Vector d(2);
d(0) = 1;
d(1) = -1;
Point2 a(4, 5), b = traits_x<Point2>::Retract(a,d), c(5, 4);
Point2 a(4, 5), b = traits<Point2>::Retract(a,d), c(5, 4);
EXPECT(assert_equal(b,c));
}

View File

@ -46,16 +46,16 @@ TEST(Point3, Lie) {
Point3 p2(4, 5, 6);
Matrix H1, H2;
EXPECT(assert_equal(Point3(5, 7, 9), traits_x<Point3>::Compose(p1, p2, H1, H2)));
EXPECT(assert_equal(Point3(5, 7, 9), traits<Point3>::Compose(p1, p2, H1, H2)));
EXPECT(assert_equal(eye(3), H1));
EXPECT(assert_equal(eye(3), H2));
EXPECT(assert_equal(Point3(3, 3, 3), traits_x<Point3>::Between(p1, p2, H1, H2)));
EXPECT(assert_equal(Point3(3, 3, 3), traits<Point3>::Between(p1, p2, H1, H2)));
EXPECT(assert_equal(-eye(3), H1));
EXPECT(assert_equal(eye(3), H2));
EXPECT(assert_equal(Point3(5, 7, 9), traits_x<Point3>::Retract(p1, Vector3(4,5,6))));
EXPECT(assert_equal(Vector3(3, 3, 3), traits_x<Point3>::Local(p1,p2)));
EXPECT(assert_equal(Point3(5, 7, 9), traits<Point3>::Retract(p1, Vector3(4,5,6))));
EXPECT(assert_equal(Vector3(3, 3, 3), traits<Point3>::Local(p1,p2)));
}
/* ************************************************************************* */

View File

@ -23,7 +23,7 @@ using namespace std;
using namespace gtsam;
typedef Quaternion Q; // Typedef
typedef traits_x<Q>::ChartJacobian QuaternionJacobian;
typedef traits<Q>::ChartJacobian QuaternionJacobian;
//******************************************************************************
TEST(Quaternion , Concept) {
@ -52,7 +52,7 @@ TEST(Quaternion , Local) {
Q q2(Eigen::AngleAxisd(0.1, z_axis));
QuaternionJacobian H1, H2;
Vector3 expected(0, 0, 0.1);
Vector3 actual = traits_x<Q>::Local(q1, q2, H1, H2);
Vector3 actual = traits<Q>::Local(q1, q2, H1, H2);
EXPECT(assert_equal((Vector)expected,actual));
}
@ -63,7 +63,7 @@ TEST(Quaternion , Retract) {
Q expected(Eigen::AngleAxisd(0.1, z_axis));
Vector3 v(0, 0, 0.1);
QuaternionJacobian Hq, Hv;
Q actual = traits_x<Q>::Retract(q, v, Hq, Hv);
Q actual = traits<Q>::Retract(q, v, Hq, Hv);
EXPECT(actual.isApprox(expected));
}
@ -75,13 +75,13 @@ TEST(Quaternion , Compose) {
Q expected = q1 * q2;
Matrix actualH1, actualH2;
Q actual = traits_x<Q>::Compose(q1, q2, actualH1, actualH2);
EXPECT(traits_x<Q>::Equals(expected,actual));
Q actual = traits<Q>::Compose(q1, q2, actualH1, actualH2);
EXPECT(traits<Q>::Equals(expected,actual));
Matrix numericalH1 = numericalDerivative21(traits_x<Q>::Compose, q1, q2);
Matrix numericalH1 = numericalDerivative21(traits<Q>::Compose, q1, q2);
EXPECT(assert_equal(numericalH1,actualH1));
Matrix numericalH2 = numericalDerivative22(traits_x<Q>::Compose, q1, q2);
Matrix numericalH2 = numericalDerivative22(traits<Q>::Compose, q1, q2);
EXPECT(assert_equal(numericalH2,actualH2));
}
@ -93,13 +93,13 @@ TEST(Quaternion , Between) {
Q expected = q1.inverse() * q2;
Matrix actualH1, actualH2;
Q actual = traits_x<Q>::Between(q1, q2, actualH1, actualH2);
EXPECT(traits_x<Q>::Equals(expected,actual));
Q actual = traits<Q>::Between(q1, q2, actualH1, actualH2);
EXPECT(traits<Q>::Equals(expected,actual));
Matrix numericalH1 = numericalDerivative21(traits_x<Q>::Between, q1, q2);
Matrix numericalH1 = numericalDerivative21(traits<Q>::Between, q1, q2);
EXPECT(assert_equal(numericalH1,actualH1));
Matrix numericalH2 = numericalDerivative22(traits_x<Q>::Between, q1, q2);
Matrix numericalH2 = numericalDerivative22(traits<Q>::Between, q1, q2);
EXPECT(assert_equal(numericalH2,actualH2));
}
@ -110,10 +110,10 @@ TEST(Quaternion , Inverse) {
Q expected(Eigen::AngleAxisd(-0.1, z_axis));
Matrix actualH;
Q actual = traits_x<Q>::Inverse(q1, actualH);
EXPECT(traits_x<Q>::Equals(expected,actual));
Q actual = traits<Q>::Inverse(q1, actualH);
EXPECT(traits<Q>::Equals(expected,actual));
Matrix numericalH = numericalDerivative11(traits_x<Q>::Inverse, q1);
Matrix numericalH = numericalDerivative11(traits<Q>::Inverse, q1);
EXPECT(assert_equal(numericalH,actualH));
}

View File

@ -51,7 +51,7 @@ TEST(SO3 , Local) {
SO3 q2(Eigen::AngleAxisd(0.1, z_axis));
SO3Jacobian H1,H2;
Vector3 expected(0, 0, 0.1);
Vector3 actual = traits_x<SO3>::Local(q1, q2, H1, H2);
Vector3 actual = traits<SO3>::Local(q1, q2, H1, H2);
EXPECT(assert_equal((Vector)expected,actual));
}
@ -61,7 +61,7 @@ TEST(SO3 , Retract) {
SO3 q(Eigen::AngleAxisd(0, z_axis));
SO3 expected(Eigen::AngleAxisd(0.1, z_axis));
Vector3 v(0, 0, 0.1);
SO3 actual = traits_x<SO3>::Retract(q, v);
SO3 actual = traits<SO3>::Retract(q, v);
EXPECT(actual.isApprox(expected));
}
@ -73,13 +73,13 @@ TEST(SO3 , Compose) {
SO3 expected = q1 * q2;
Matrix actualH1, actualH2;
SO3 actual = traits_x<SO3>::Compose(q1, q2, actualH1, actualH2);
EXPECT(traits_x<SO3>::Equals(expected,actual));
SO3 actual = traits<SO3>::Compose(q1, q2, actualH1, actualH2);
EXPECT(traits<SO3>::Equals(expected,actual));
Matrix numericalH1 = numericalDerivative21(traits_x<SO3>::Compose, q1, q2);
Matrix numericalH1 = numericalDerivative21(traits<SO3>::Compose, q1, q2);
EXPECT(assert_equal(numericalH1,actualH1));
Matrix numericalH2 = numericalDerivative22(traits_x<SO3>::Compose, q1, q2);
Matrix numericalH2 = numericalDerivative22(traits<SO3>::Compose, q1, q2);
EXPECT(assert_equal(numericalH2,actualH2));
}
@ -91,13 +91,13 @@ TEST(SO3 , Between) {
SO3 expected = q1.inverse() * q2;
Matrix actualH1, actualH2;
SO3 actual = traits_x<SO3>::Between(q1, q2, actualH1, actualH2);
EXPECT(traits_x<SO3>::Equals(expected,actual));
SO3 actual = traits<SO3>::Between(q1, q2, actualH1, actualH2);
EXPECT(traits<SO3>::Equals(expected,actual));
Matrix numericalH1 = numericalDerivative21(traits_x<SO3>::Between, q1, q2);
Matrix numericalH1 = numericalDerivative21(traits<SO3>::Between, q1, q2);
EXPECT(assert_equal(numericalH1,actualH1));
Matrix numericalH2 = numericalDerivative22(traits_x<SO3>::Between, q1, q2);
Matrix numericalH2 = numericalDerivative22(traits<SO3>::Between, q1, q2);
EXPECT(assert_equal(numericalH2,actualH2));
}
@ -108,10 +108,10 @@ TEST(SO3 , Inverse) {
SO3 expected(Eigen::AngleAxisd(-0.1, z_axis));
Matrix actualH;
SO3 actual = traits_x<SO3>::Inverse(q1, actualH);
EXPECT(traits_x<SO3>::Equals(expected,actual));
SO3 actual = traits<SO3>::Inverse(q1, actualH);
EXPECT(traits<SO3>::Equals(expected,actual));
Matrix numericalH = numericalDerivative11(traits_x<SO3>::Inverse, q1);
Matrix numericalH = numericalDerivative11(traits<SO3>::Inverse, q1);
EXPECT(assert_equal(numericalH,actualH));
}
#endif

View File

@ -131,7 +131,7 @@ inline unsigned char mrsymbolLabel(Key key) { return LabeledSymbol(key).label();
inline size_t mrsymbolIndex(Key key) { return LabeledSymbol(key).index(); }
/// traits
template<> struct traits_x<LabeledSymbol> : public Testable<LabeledSymbol> {};
template<> struct traits<LabeledSymbol> : public Testable<LabeledSymbol> {};
} // \namespace gtsam

View File

@ -193,7 +193,7 @@ namespace gtsam {
};
/// traits
template<> struct traits_x<Ordering> : public Testable<Ordering> {};
template<> struct traits<Ordering> : public Testable<Ordering> {};
}

View File

@ -162,7 +162,7 @@ inline Key Z(size_t j) { return Symbol('z', j); }
}
/// traits
template<> struct traits_x<Symbol> : public Testable<Symbol> {};
template<> struct traits<Symbol> : public Testable<Symbol> {};
} // \ namespace gtsam

View File

@ -179,7 +179,7 @@ protected:
/// traits
template<>
struct traits_x<VariableIndex> : public Testable<VariableIndex> {
struct traits<VariableIndex> : public Testable<VariableIndex> {
};
} //\ namespace gtsam

View File

@ -83,7 +83,7 @@ public:
};
/// traits
template<> struct traits_x<VariableSlots> : public Testable<VariableSlots> {};
template<> struct traits<VariableSlots> : public Testable<VariableSlots> {};
/* ************************************************************************* */
template<class FG>

View File

@ -73,7 +73,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<Errors> : public Testable<Errors> {
struct traits<Errors> : public Testable<Errors> {
};
} //\ namespace gtsam

View File

@ -173,7 +173,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<GaussianBayesNet> : public Testable<GaussianBayesNet> {
struct traits<GaussianBayesNet> : public Testable<GaussianBayesNet> {
};
} //\ namespace gtsam

View File

@ -130,7 +130,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<GaussianBayesTree> : public Testable<GaussianBayesTree> {
struct traits<GaussianBayesTree> : public Testable<GaussianBayesTree> {
};
} //\ namespace gtsam

View File

@ -143,7 +143,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<GaussianConditional> : public Testable<GaussianConditional> {};
struct traits<GaussianConditional> : public Testable<GaussianConditional> {};
} // \ namespace gtsam

View File

@ -149,7 +149,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<GaussianFactor> : public Testable<GaussianFactor> {
struct traits<GaussianFactor> : public Testable<GaussianFactor> {
};
} // \ namespace gtsam

View File

@ -346,7 +346,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<GaussianFactorGraph> : public Testable<GaussianFactorGraph> {
struct traits<GaussianFactorGraph> : public Testable<GaussianFactorGraph> {
};
} // \ namespace gtsam

View File

@ -445,7 +445,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<HessianFactor> : public Testable<HessianFactor> {};
struct traits<HessianFactor> : public Testable<HessianFactor> {};
} // \ namespace gtsam

View File

@ -362,7 +362,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<JacobianFactor> : public Testable<JacobianFactor> {
struct traits<JacobianFactor> : public Testable<JacobianFactor> {
};
} // \ namespace gtsam

View File

@ -888,11 +888,11 @@ namespace gtsam {
typedef noiseModel::Constrained::shared_ptr SharedConstrained;
/// traits
template<> struct traits_x<noiseModel::Gaussian> : public Testable<noiseModel::Gaussian> {};
template<> struct traits_x<noiseModel::Diagonal> : public Testable<noiseModel::Diagonal> {};
template<> struct traits_x<noiseModel::Constrained> : public Testable<noiseModel::Constrained> {};
template<> struct traits_x<noiseModel::Isotropic> : public Testable<noiseModel::Isotropic> {};
template<> struct traits_x<noiseModel::Unit> : public Testable<noiseModel::Unit> {};
template<> struct traits<noiseModel::Gaussian> : public Testable<noiseModel::Gaussian> {};
template<> struct traits<noiseModel::Diagonal> : public Testable<noiseModel::Diagonal> {};
template<> struct traits<noiseModel::Constrained> : public Testable<noiseModel::Constrained> {};
template<> struct traits<noiseModel::Isotropic> : public Testable<noiseModel::Isotropic> {};
template<> struct traits<noiseModel::Unit> : public Testable<noiseModel::Unit> {};
} //\ namespace gtsam

View File

@ -383,7 +383,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<VectorValues> : public Testable<VectorValues> {
struct traits<VectorValues> : public Testable<VectorValues> {
};
} // \namespace gtsam

View File

@ -132,7 +132,7 @@ private:
};
/// traits
template<> struct traits_x<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFactor> {};
template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFactor> {};
/**
* Version of AttitudeFactor for Pose3
@ -216,7 +216,7 @@ private:
};
/// traits
template<> struct traits_x<Pose3AttitudeFactor> : public Testable<Pose3AttitudeFactor> {};
template<> struct traits<Pose3AttitudeFactor> : public Testable<Pose3AttitudeFactor> {};
} /// namespace gtsam

View File

@ -180,7 +180,7 @@ namespace imuBias {
} // namespace imuBias
template<>
struct traits_x<imuBias::ConstantBias> : public internal::VectorSpace<
struct traits<imuBias::ConstantBias> : public internal::VectorSpace<
imuBias::ConstantBias> {
};

View File

@ -31,7 +31,7 @@ namespace detail {
// By default, we assume an Identity element
template<typename T, typename structure_category>
struct Origin { T operator()() { return traits_x<T>::Identity();} };
struct Origin { T operator()() { return traits<T>::Identity();} };
// but dimple manifolds don't have one, so we just use the default constructor
template<typename T>
@ -50,7 +50,7 @@ struct Canonical {
GTSAM_CONCEPT_MANIFOLD_TYPE(T)
typedef traits_x<T> Traits;
typedef traits<T> Traits;
enum { dimension = Traits::dimension };
typedef typename Traits::TangentVector TangentVector;
typedef typename Traits::structure_category Category;
@ -69,9 +69,9 @@ struct Canonical {
template<typename F, typename T, typename A1, typename A2>
class AdaptAutoDiff {
static const int N = traits_x<T>::dimension;
static const int M1 = traits_x<A1>::dimension;
static const int M2 = traits_x<A2>::dimension;
static const int N = traits<T>::dimension;
static const int M1 = traits<A1>::dimension;
static const int M2 = traits<A2>::dimension;
typedef Eigen::Matrix<double, N, M1, Eigen::RowMajor> RowMajor1;
typedef Eigen::Matrix<double, N, M2, Eigen::RowMajor> RowMajor2;

View File

@ -141,7 +141,7 @@ void handleLeafCase(const Eigen::MatrixBase<Derived>& dTdA,
*/
template<class T>
class ExecutionTrace {
static const int Dim = traits_x<T>::dimension;
static const int Dim = traits<T>::dimension;
enum {
Constant, Leaf, Function
} kind;
@ -326,7 +326,7 @@ public:
/// Return dimensions for each argument
virtual void dims(std::map<Key, int>& map) const {
map[key_] = traits_x<T>::dimension;
map[key_] = traits<T>::dimension;
}
/// Return value
@ -402,15 +402,15 @@ public:
/// meta-function to generate fixed-size JacobianTA type
template<class T, class A>
struct Jacobian {
typedef Eigen::Matrix<double, traits_x<T>::dimension,
traits_x<A>::dimension> type;
typedef Eigen::Matrix<double, traits<T>::dimension,
traits<A>::dimension> type;
};
/// meta-function to generate JacobianTA optional reference
template<class T, class A>
struct MakeOptionalJacobian {
typedef OptionalJacobian<traits_x<T>::dimension,
traits_x<A>::dimension> type;
typedef OptionalJacobian<traits<T>::dimension,
traits<A>::dimension> type;
};
/**
@ -576,7 +576,7 @@ struct FunctionalNode {
/// Provide convenience access to Record storage and implement
/// the virtual function based interface of CallRecord using the CallRecordImplementor
struct Record: public internal::CallRecordImplementor<Record,
traits_x<T>::dimension>, public Base::Record {
traits<T>::dimension>, public Base::Record {
using Base::Record::print;
using Base::Record::startReverseAD4;
using Base::Record::reverseAD4;

View File

@ -173,7 +173,7 @@ private:
assert(H.size()==keys.size());
// Pre-allocate and zero VerticalBlockMatrix
static const int Dim = traits_x<T>::dimension;
static const int Dim = traits<T>::dimension;
VerticalBlockMatrix Ab(dims, Dim);
Ab.matrix().setZero();
JacobianMap jacobianMap(keys, Ab);
@ -237,7 +237,7 @@ private:
template<class T>
struct apply_compose {
typedef T result_type;
static const int Dim = traits_x<T>::dimension;
static const int Dim = traits<T>::dimension;
T operator()(const T& x, const T& y, OptionalJacobian<Dim, Dim> H1 =
boost::none, OptionalJacobian<Dim, Dim> H2 = boost::none) const {
return x.compose(y, H1, H2);

View File

@ -43,7 +43,7 @@ namespace gtsam {
// Extract the current estimate of x1,P1
VectorValues result = marginal->solve(VectorValues());
const T& current = linearizationPoints.at<T>(lastKey);
T x = traits_x<T>::Retract(current, result[lastKey]);
T x = traits<T>::Retract(current, result[lastKey]);
// Create a Jacobian Factor from the root node of the produced Bayes Net.
// This will act as a prior for the next iteration.
@ -71,7 +71,7 @@ namespace gtsam {
// Create a Jacobian Prior Factor directly P_initial.
// Since x0 is set to the provided mean, the b vector in the prior will be zero
// TODO Frank asks: is there a reason why noiseModel is not simply P_initial ?
int n = traits_x<T>::GetDimension(x_initial);
int n = traits<T>::GetDimension(x_initial);
priorFactor_ = JacobianFactor::shared_ptr(
new JacobianFactor(key_initial, P_initial->R(), Vector::Zero(n),
noiseModel::Unit::Create(n)));

View File

@ -29,7 +29,7 @@ namespace gtsam {
template<class VALUE>
VALUE ISAM2::calculateEstimate(Key key) const {
const Vector& delta = getDelta()[key];
return traits_x<VALUE>::Retract(theta_.at<VALUE>(key), delta);
return traits<VALUE>::Retract(theta_.at<VALUE>(key), delta);
}
/* ************************************************************************* */

View File

@ -634,7 +634,7 @@ protected:
}; // ISAM2
/// traits
template<> struct traits_x<ISAM2> : public Testable<ISAM2> {};
template<> struct traits<ISAM2> : public Testable<ISAM2> {};
/// Optimize the BayesTree, starting from the root.
/// @param replaced Needs to contain

View File

@ -155,7 +155,7 @@ private:
}; // \class LinearContainerFactor
template<> struct traits_x<LinearContainerFactor> : public Testable<LinearContainerFactor> {};
template<> struct traits<LinearContainerFactor> : public Testable<LinearContainerFactor> {};
} // \namespace gtsam

View File

@ -93,7 +93,7 @@ public:
*/
NonlinearEquality(Key j, const T& feasible,
bool (*_compare)(const T&, const T&) = compare<T>) :
Base(noiseModel::Constrained::All(traits_x<T>::GetDimension(feasible)),
Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
j), feasible_(feasible), allow_error_(false), error_gain_(0.0), //
compare_(_compare) {
}
@ -103,7 +103,7 @@ public:
*/
NonlinearEquality(Key j, const T& feasible, double error_gain,
bool (*_compare)(const T&, const T&) = compare<T>) :
Base(noiseModel::Constrained::All(traits_x<T>::GetDimension(feasible)),
Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
j), feasible_(feasible), allow_error_(true), error_gain_(error_gain), //
compare_(_compare) {
}
@ -115,8 +115,8 @@ public:
virtual void print(const std::string& s = "",
const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << "Constraint: on [" << keyFormatter(this->key()) << "]\n";
traits_x<VALUE>::Print(feasible_, "Feasible Point:\n");
std::cout << "Variable Dimension: " << traits_x<T>::GetDimension(feasible_) << std::endl;
traits<VALUE>::Print(feasible_, "Feasible Point:\n");
std::cout << "Variable Dimension: " << traits<T>::GetDimension(feasible_) << std::endl;
}
/** Check if two factors are equal */
@ -144,11 +144,11 @@ public:
/** error function */
Vector evaluateError(const T& xj,
boost::optional<Matrix&> H = boost::none) const {
const size_t nj = traits_x<T>::GetDimension(feasible_);
const size_t nj = traits<T>::GetDimension(feasible_);
if (allow_error_) {
if (H)
*H = eye(nj); // FIXME: this is not the right linearization for nonlinear compare
return traits_x<T>::Local(xj,feasible_);
return traits<T>::Local(xj,feasible_);
} else if (compare_(feasible_, xj)) {
if (H)
*H = eye(nj);
@ -198,7 +198,7 @@ private:
// \class NonlinearEquality
template<typename VALUE>
struct traits_x<NonlinearEquality<VALUE> > : Testable<NonlinearEquality<VALUE> > {
struct traits<NonlinearEquality<VALUE> > : Testable<NonlinearEquality<VALUE> > {
};
/* ************************************************************************* */
@ -237,7 +237,7 @@ public:
*
*/
NonlinearEquality1(const X& value, Key key, double mu = 1000.0) :
Base( noiseModel::Constrained::All(traits_x<X>::GetDimension(value),
Base( noiseModel::Constrained::All(traits<X>::GetDimension(value),
std::abs(mu)), key), value_(value) {
}
@ -254,9 +254,9 @@ public:
Vector evaluateError(const X& x1,
boost::optional<Matrix&> H = boost::none) const {
if (H)
(*H) = eye(traits_x<X>::GetDimension(x1));
(*H) = eye(traits<X>::GetDimension(x1));
// manifold equivalent of h(x)-z -> log(z,h(x))
return traits_x<X>::Local(value_,x1);
return traits<X>::Local(value_,x1);
}
/** Print */
@ -283,7 +283,7 @@ private:
// \NonlinearEquality1
template<typename VALUE>
struct traits_x<NonlinearEquality1<VALUE> > : Testable<NonlinearEquality1<VALUE> > {
struct traits<NonlinearEquality1<VALUE> > : Testable<NonlinearEquality1<VALUE> > {
};
/* ************************************************************************* */
@ -312,7 +312,7 @@ public:
///TODO: comment
NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) :
Base(noiseModel::Constrained::All(traits_x<X>::dimension, std::abs(mu)), key1, key2) {
Base(noiseModel::Constrained::All(traits<X>::dimension, std::abs(mu)), key1, key2) {
}
virtual ~NonlinearEquality2() {
}
@ -326,10 +326,10 @@ public:
/** g(x) with optional derivative2 */
Vector evaluateError(const X& x1, const X& x2, boost::optional<Matrix&> H1 =
boost::none, boost::optional<Matrix&> H2 = boost::none) const {
static const size_t p = traits_x<X>::dimension;
static const size_t p = traits<X>::dimension;
if (H1) *H1 = -eye(p);
if (H2) *H2 = eye(p);
return traits_x<X>::Local(x1,x2);
return traits<X>::Local(x1,x2);
}
private:
@ -346,7 +346,7 @@ private:
// \NonlinearEquality2
template<typename VALUE>
struct traits_x<NonlinearEquality2<VALUE> > : Testable<NonlinearEquality2<VALUE> > {
struct traits<NonlinearEquality2<VALUE> > : Testable<NonlinearEquality2<VALUE> > {
};

View File

@ -145,7 +145,7 @@ public:
}; // \class NonlinearFactor
/// traits
template<> struct traits_x<NonlinearFactor> : public Testable<NonlinearFactor> {
template<> struct traits<NonlinearFactor> : public Testable<NonlinearFactor> {
};
/* ************************************************************************* */

View File

@ -163,7 +163,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<NonlinearFactorGraph> : public Testable<NonlinearFactorGraph> {
struct traits<NonlinearFactorGraph> : public Testable<NonlinearFactorGraph> {
};
} //\ namespace gtsam

View File

@ -525,7 +525,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<Values> : public Testable<Values> {
struct traits<Values> : public Testable<Values> {
};
} //\ namespace gtsam

View File

@ -49,7 +49,7 @@ struct Cal: public Cal3Bundler {
};
template<>
struct traits_x<Cal> : public internal::Manifold<Cal> {};
struct traits<Cal> : public internal::Manifold<Cal> {};
// With that, camera below behaves like Snavely's 9-dim vector
typedef PinholeCamera<Cal> Camera;

View File

@ -72,7 +72,7 @@ public:
};
namespace gtsam {
template <> struct traits_x<TestValue> : public internal::Manifold<TestValue> {};
template <> struct traits<TestValue> : public internal::Manifold<TestValue> {};
}

View File

@ -74,14 +74,14 @@ namespace gtsam {
std::cout << s << "BetweenFactor("
<< keyFormatter(this->key1()) << ","
<< keyFormatter(this->key2()) << ")\n";
traits_x<T>::Print(measured_, " measured: ");
traits<T>::Print(measured_, " measured: ");
this->noiseModel_->print(" noise model: ");
}
/** equals */
virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const {
const This *e = dynamic_cast<const This*> (&expected);
return e != NULL && Base::equals(*e, tol) && traits_x<T>::Equals(this->measured_, e->measured_, tol);
return e != NULL && Base::equals(*e, tol) && traits<T>::Equals(this->measured_, e->measured_, tol);
}
/** implement functions needed to derive from Factor */
@ -89,16 +89,16 @@ namespace gtsam {
/** vector of errors */
Vector evaluateError(const T& p1, const T& p2, boost::optional<Matrix&> H1 =
boost::none, boost::optional<Matrix&> H2 = boost::none) const {
T hx = traits_x<T>::Between(p1, p2, H1, H2); // h(x)
T hx = traits<T>::Between(p1, p2, H1, H2); // h(x)
// manifold equivalent of h(x)-z -> log(z,h(x))
#ifdef SLOW_BUT_CORRECT_BETWEENFACTOR
typename traits_x<T>::ChartJacobian::Fixed Hlocal;
Vector rval = traits_x<T>::Local(measured_, hx, boost::none, (H1 || H2) ? &Hlocal : 0);
typename traits<T>::ChartJacobian::Fixed Hlocal;
Vector rval = traits<T>::Local(measured_, hx, boost::none, (H1 || H2) ? &Hlocal : 0);
if (H1) *H1 = Hlocal * (*H1);
if (H1) *H2 = Hlocal * (*H2);
return rval;
#else
return traits_x<T>::Local(measured_, hx);
return traits<T>::Local(measured_, hx);
#endif
}
@ -126,7 +126,7 @@ namespace gtsam {
/// traits
template<class VALUE>
struct traits_x<BetweenFactor<VALUE> > : public Testable<BetweenFactor<VALUE> > {};
struct traits<BetweenFactor<VALUE> > : public Testable<BetweenFactor<VALUE> > {};
/**
* Binary between constraint - forces between to a given value
@ -141,7 +141,7 @@ namespace gtsam {
/** Syntactic sugar for constrained version */
BetweenConstraint(const VALUE& measured, Key key1, Key key2, double mu = 1000.0) :
BetweenFactor<VALUE>(key1, key2, measured,
noiseModel::Constrained::All(traits_x<VALUE>::GetDimension(measured), fabs(mu)))
noiseModel::Constrained::All(traits<VALUE>::GetDimension(measured), fabs(mu)))
{}
private:
@ -157,6 +157,6 @@ namespace gtsam {
/// traits
template<class VALUE>
struct traits_x<BetweenConstraint<VALUE> > : public Testable<BetweenConstraint<VALUE> > {};
struct traits<BetweenConstraint<VALUE> > : public Testable<BetweenConstraint<VALUE> > {};
} /// namespace gtsam

View File

@ -128,7 +128,7 @@ namespace gtsam {
};
template<class CAMERA, class LANDMARK>
struct traits_x<GeneralSFMFactor<CAMERA, LANDMARK> > : Testable<
struct traits<GeneralSFMFactor<CAMERA, LANDMARK> > : Testable<
GeneralSFMFactor<CAMERA, LANDMARK> > {
};
@ -230,7 +230,7 @@ namespace gtsam {
};
template<class CALIBRATION>
struct traits_x<GeneralSFMFactor2<CALIBRATION> > : Testable<
struct traits<GeneralSFMFactor2<CALIBRATION> > : Testable<
GeneralSFMFactor2<CALIBRATION> > {
};

View File

@ -62,8 +62,8 @@ public:
Vector evaluateError(const Pose& pose, boost::optional<Matrix&> H = boost::none) const {
const Translation& newTrans = pose.translation();
const Rotation& R = pose.rotation();
const int tDim = traits_x<Translation>::GetDimension(newTrans);
const int xDim = traits_x<Pose>::GetDimension(pose);
const int tDim = traits<Translation>::GetDimension(newTrans);
const int xDim = traits<Pose>::GetDimension(pose);
if (H) {
*H = gtsam::zeros(tDim, xDim);
std::pair<size_t, size_t> transInterval = POSE::translationInterval();

View File

@ -67,24 +67,24 @@ namespace gtsam {
/** print */
virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << "PriorFactor on " << keyFormatter(this->key()) << "\n";
traits_x<T>::Print(prior_, " prior mean: ");
traits<T>::Print(prior_, " prior mean: ");
this->noiseModel_->print(" noise model: ");
}
/** equals */
virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const {
const This* e = dynamic_cast<const This*> (&expected);
return e != NULL && Base::equals(*e, tol) && traits_x<T>::Equals(prior_, e->prior_, tol);
return e != NULL && Base::equals(*e, tol) && traits<T>::Equals(prior_, e->prior_, tol);
}
/** implement functions needed to derive from Factor */
/** vector of errors */
Vector evaluateError(const T& p, boost::optional<Matrix&> H = boost::none) const {
if (H) (*H) = eye(traits_x<T>::GetDimension(p));
if (H) (*H) = eye(traits<T>::GetDimension(p));
// manifold equivalent of h(x)-z -> log(z,h(x))
// TODO(ASL) Add Jacobians.
return traits_x<T>::Local(prior_,p);
return traits<T>::Local(prior_,p);
}
const VALUE & prior() const { return prior_; }

View File

@ -190,7 +190,7 @@ namespace gtsam {
/// traits
template<class POSE, class LANDMARK, class CALIBRATION>
struct traits_x<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > :
struct traits<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > :
public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
};

View File

@ -100,7 +100,7 @@ private:
/// traits
template<class T1, class T2>
struct traits_x<RangeFactor<T1,T2> > : public Testable<RangeFactor<T1,T2> > {};
struct traits<RangeFactor<T1,T2> > : public Testable<RangeFactor<T1,T2> > {};
/**
* Binary factor for a range measurement, with a transform applied
@ -192,6 +192,6 @@ private:
/// traits
template<class T1, class T2>
struct traits_x<RangeFactorWithTransform<T1, T2> > : public Testable<RangeFactorWithTransform<T1, T2> > {};
struct traits<RangeFactorWithTransform<T1, T2> > : public Testable<RangeFactorWithTransform<T1, T2> > {};
} // \ namespace gtsam

View File

@ -101,7 +101,7 @@ public:
Point newlocal = transform_point<Transform,Point>(trans, global, Dtrans, Dforeign);
if (Dlocal)
*Dlocal = -1* gtsam::eye(Point::dimension);
return traits_x<Point>::Local(local,newlocal);
return traits<Point>::Local(local,newlocal);
}
virtual void print(const std::string& s="",
@ -130,6 +130,6 @@ private:
/// traits
template<class T1, class T2>
struct traits_x<ReferenceFrameFactor<T1, T2> > : public Testable<ReferenceFrameFactor<T1, T2> > {};
struct traits<ReferenceFrameFactor<T1, T2> > : public Testable<ReferenceFrameFactor<T1, T2> > {};
} // \namespace gtsam

View File

@ -48,7 +48,7 @@ protected:
boost::optional<POSE> body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras)
static const int ZDim = traits_x<Z>::dimension; ///< Measurement dimension
static const int ZDim = traits<Z>::dimension; ///< Measurement dimension
/// Definitions for blocks of F
typedef Eigen::Matrix<double, ZDim, D> Matrix2D; // F

View File

@ -217,6 +217,6 @@ private:
/// traits
template<class T1, class T2>
struct traits_x<SmartProjectionPoseFactor<T1, T2> > : public Testable<SmartProjectionPoseFactor<T1, T2> > {};
struct traits<SmartProjectionPoseFactor<T1, T2> > : public Testable<SmartProjectionPoseFactor<T1, T2> > {};
} // \ namespace gtsam

View File

@ -182,6 +182,6 @@ private:
/// traits
template<class T1, class T2>
struct traits_x<GenericStereoFactor<T1, T2> > : public Testable<GenericStereoFactor<T1, T2> > {};
struct traits<GenericStereoFactor<T1, T2> > : public Testable<GenericStereoFactor<T1, T2> > {};
} // \ namespace gtsam

View File

@ -83,7 +83,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<SymbolicBayesNet> : public Testable<SymbolicBayesNet> {
struct traits<SymbolicBayesNet> : public Testable<SymbolicBayesNet> {
};
} //\ namespace gtsam

View File

@ -71,8 +71,8 @@ namespace gtsam {
};
/// traits
template<> struct traits_x<SymbolicBayesTreeClique> : public Testable<SymbolicBayesTreeClique> {};
template<> struct traits_x<SymbolicBayesTree> : public Testable<SymbolicBayesTree> {};
template<> struct traits<SymbolicBayesTreeClique> : public Testable<SymbolicBayesTreeClique> {};
template<> struct traits<SymbolicBayesTree> : public Testable<SymbolicBayesTree> {};
} //\ namespace gtsam

View File

@ -124,7 +124,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<SymbolicConditional> : public Testable<SymbolicConditional> {
struct traits<SymbolicConditional> : public Testable<SymbolicConditional> {
};
} //\ namespace gtsam

View File

@ -61,7 +61,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<SymbolicEliminationTree> : public Testable<SymbolicEliminationTree> {
struct traits<SymbolicEliminationTree> : public Testable<SymbolicEliminationTree> {
};
} //\ namespace gtsam

View File

@ -162,7 +162,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<SymbolicFactor> : public Testable<SymbolicFactor> {
struct traits<SymbolicFactor> : public Testable<SymbolicFactor> {
};
} //\ namespace gtsam

View File

@ -118,7 +118,7 @@ namespace gtsam {
/// traits
template<>
struct traits_x<SymbolicFactorGraph> : public Testable<SymbolicFactorGraph> {
struct traits<SymbolicFactorGraph> : public Testable<SymbolicFactorGraph> {
};
} //\ namespace gtsam

View File

@ -190,6 +190,6 @@ private:
template<>
struct traits_x<PoseRTV> : public internal::LieGroupTraits<PoseRTV> {};
struct traits<PoseRTV> : public internal::LieGroupTraits<PoseRTV> {};
} // \namespace gtsam

View File

@ -100,6 +100,6 @@ private:
};
/// traits
template<> struct traits_x<BearingS2> : public Testable<BearingS2> {};
template<> struct traits<BearingS2> : public Testable<BearingS2> {};
} // \namespace gtsam

View File

@ -141,7 +141,7 @@ private:
}; // \class Pose3Upright
template<>
struct traits_x<Pose3Upright> : public internal::Manifold<Pose3Upright> {};
struct traits<Pose3Upright> : public internal::Manifold<Pose3Upright> {};
} // \namespace gtsam

View File

@ -69,7 +69,7 @@ namespace gtsam {
typedef std::vector<SimWall2D> SimWall2DVector;
/// traits
template<> struct traits_x<SimWall2D> : public Testable<SimWall2D> {};
template<> struct traits<SimWall2D> : public Testable<SimWall2D> {};
/**
* Calculates the next pose in a trajectory constrained by walls, with noise on

View File

@ -117,7 +117,7 @@ public:
/// traits
template<> struct traits_x<LinearEquality> : public Testable<LinearEquality> {};
template<> struct traits<LinearEquality> : public Testable<LinearEquality> {};
} // \ namespace gtsam

View File

@ -29,7 +29,7 @@ public:
};
/// traits
template<> struct traits_x<LinearEqualityFactorGraph> : public Testable<
template<> struct traits<LinearEqualityFactorGraph> : public Testable<
LinearEqualityFactorGraph> {
};

Some files were not shown because too many files have changed in this diff Show More