MASSIVE edit: made Testable its own concept, and moderinized Testable.h to use Testable traits. This required adding Testable traits in many classes.

release/4.3a0
dellaert 2014-12-21 22:02:06 +01:00
parent ede01ac6d3
commit 79d8514528
69 changed files with 481 additions and 156 deletions

View File

@ -19,7 +19,7 @@
* The concept checking function will check whether or not
* the function exists in derived class and throw compile-time errors.
*
* print with optional string naming the object
* print with optional string naming the t
* void print(const std::string& name) const = 0;
*
* equality up to tolerance
@ -42,6 +42,9 @@
namespace gtsam {
// Forward declaration
template <typename T> struct traits_x;
/**
* A testable concept check that should be placed in applicable unit
* tests and in generic algorithms.
@ -51,27 +54,27 @@ namespace gtsam {
* @tparam T is the type this constrains to be testable - assumes print() and equals()
*/
template <class T>
class Testable {
class IsTestable {
T t;
bool r1,r2;
public:
BOOST_CONCEPT_USAGE(Testable) {
BOOST_CONCEPT_USAGE(IsTestable) {
// check print function, with optional string
t.print(std::string());
t.print();
traits_x<T>::Print(t, std::string());
traits_x<T>::Print(t);
// check print, with optional threshold
double tol = 1.0;
r1 = t.equals(t, tol);
r2 = t.equals(t);
r1 = traits_x<T>::Equals(t,t,tol);
r2 = traits_x<T>::Equals(t,t);
}
};
}; // \ Testable
/** Call print on the object */
/** Call print on the t */
template<class T>
inline void print(const T& object, const std::string& s = "") {
object.print(s);
inline void print(const T& t, const std::string& s = "") {
traits_x<T>::Print(t,s);
}
inline void print(float v, const std::string& s = "") {
printf("%s%f\n",s.c_str(),v);
@ -80,16 +83,16 @@ namespace gtsam {
printf("%s%lf\n",s.c_str(),v);
}
/** Call equal on the object */
/** Call equal on the t */
template<class T>
inline bool equal(const T& obj1, const T& obj2, double tol) {
return obj1.equals(obj2, tol);
return traits_x<T>::Equals(obj1,obj2, tol);
}
/** Call equal on the object without tolerance (use default tolerance) */
/** Call equal without tolerance (use default tolerance) */
template<class T>
inline bool equal(const T& obj1, const T& obj2) {
return obj1.equals(obj2);
return traits_x<T>::Equals(obj1,obj2);
}
/**
@ -97,11 +100,11 @@ namespace gtsam {
*/
template<class V>
bool assert_equal(const V& expected, const V& actual, double tol = 1e-9) {
if (actual.equals(expected, tol))
if (traits_x<V>::Equals(actual,expected, tol))
return true;
printf("Not equal:\n");
expected.print("expected:\n");
actual.print("actual:\n");
traits_x<V>::Print(expected,"expected:\n");
traits_x<V>::Print(actual,"actual:\n");
return false;
}
@ -113,7 +116,7 @@ namespace gtsam {
double tol_;
equals(double tol = 1e-9) : tol_(tol) {}
bool operator()(const V& expected, const V& actual) {
return (actual.equals(expected, tol_));
return (traits_x<V>::Equals(actual, expected, tol_));
}
};
@ -126,7 +129,20 @@ 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 (actual->equals(*expected, tol_));
return (traits_x<V>::Equals(*actual,*expected, tol_));
}
};
/// A helper that implements the traits interface for GTSAM types.
/// To use this for your gtsam type, define:
/// template<> struct traits<Type> : public LieGroup<Type> { };
template<typename T>
struct Testable {
static void Print(const T& m, const std::string& str = "") {
m.print(str);
}
static bool Equals(const T& m1, const T& m2, double tol = 1e-8) {
return m1.equals(m2, tol);
}
};
@ -141,5 +157,5 @@ namespace gtsam {
* the gtsam namespace to be more easily enforced as testable
* @deprecated please use BOOST_CONCEPT_ASSERT and
*/
#define GTSAM_CONCEPT_TESTABLE_INST(T) template class gtsam::Testable<T>;
#define GTSAM_CONCEPT_TESTABLE_TYPE(T) typedef gtsam::Testable<T> _gtsam_Testable_##T;
#define GTSAM_CONCEPT_TESTABLE_INST(T) template class gtsam::IsTestable<T>;
#define GTSAM_CONCEPT_TESTABLE_TYPE(T) typedef gtsam::IsTestable<T> _gtsam_Testable_##T;

View File

@ -48,19 +48,7 @@ struct vector_space_tag: public lie_group_tag {};
struct multiplicative_group_tag {};
struct additive_group_tag {};
// TODO: Remove
namespace traits {
template<typename T>
struct dimension{};
}
template <typename T> struct traits_x {
// TODO: remove anything in here ASAP.
// This is just here during development to avoid compilation
// errors while implmenting traits for everything.
enum { dimension = traits::dimension<T>::value };
typedef manifold_tag structure_category;
};
template <typename T> struct traits_x;
namespace internal {
@ -68,7 +56,7 @@ namespace internal {
/// To use this for your gtsam type, define:
/// template<> struct traits<Type> : public Manifold<Type> { };
template<typename _ManifoldType>
struct Manifold {
struct Manifold : Testable<_ManifoldType> {
// Typedefs required by all manifold types.
typedef _ManifoldType ManifoldType;
typedef manifold_tag structure_category;
@ -76,16 +64,6 @@ struct Manifold {
typedef Eigen::Matrix<double, dimension, 1> TangentVector;
typedef OptionalJacobian<dimension, dimension> ChartJacobian;
// For Testable
static void Print(const ManifoldType& m, const std::string& str = "") {
m.print(str);
}
static bool Equals(const ManifoldType& m1,
const ManifoldType& m2,
double tol = 1e-8) {
return m1.equals(m2, tol);
}
static TangentVector Local(const ManifoldType& origin,
const ManifoldType& other) {
return origin.localCoordinates(other);
@ -119,7 +97,7 @@ struct Manifold {
/// To use this for your gtsam type, define:
/// template<> struct traits<Type> : public LieGroup<Type> { };
template<typename _ManifoldType,typename _group_flavor = additive_group_tag>
struct LieGroup {
struct LieGroup : Testable<_ManifoldType> {
// Typedefs required by all manifold types.
typedef _ManifoldType ManifoldType;
typedef lie_group_tag structure_category;
@ -129,16 +107,6 @@ struct LieGroup {
typedef Eigen::Matrix<double, dimension, 1> TangentVector;
typedef OptionalJacobian<dimension, dimension> ChartJacobian;
// For Testable
static void Print(const ManifoldType& m, const std::string& str = "") {
m.print();
}
static bool Equals(const ManifoldType& m1,
const ManifoldType& m2,
double tol = 1e-8) {
return m1.equals(m2, tol);
}
static TangentVector Local(const ManifoldType& origin,
const ManifoldType& other) {
return origin.localCoordinates(other);
@ -341,8 +309,7 @@ struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
static void Print(const ManifoldType& m, const std::string& str = "") {
gtsam::print(Eigen::MatrixXd(m), str);
}
static bool Equals(const ManifoldType& m1,
const ManifoldType& m2,
static bool Equals(const ManifoldType& m1, const ManifoldType& m2,
double tol = 1e-8) {
return equal_with_abs_tol(m1, m2, 1e-9);
}
@ -374,7 +341,6 @@ struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
ChartJacobian H2 = boost::none) {
if (H1) *H1 = Eye(m1);
if (H2) *H2 = Eye(m1);
return m1+m2;
}
@ -384,7 +350,6 @@ struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
ChartJacobian H2 = boost::none) {
if (H1) *H1 = -Eye(m1);
if (H2) *H2 = Eye(m1);
return m2-m1;
}
@ -450,7 +415,7 @@ struct Canonical {
/// Check invariants for Manifold type
template<typename T>
BOOST_CONCEPT_REQUIRES(((Testable<traits_x<T> >)),(bool)) //
BOOST_CONCEPT_REQUIRES(((Testable<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);
@ -498,11 +463,6 @@ public:
// and the versions with Jacobians.
//v = traits_x<M>::Local(p,q,Hp,Hq);
//q = traits_x<M>::Retract(p,v,Hp,Hv);
traits_x<M>::Print(p);
traits_x<M>::Print(p, "p");
b = traits_x<M>::Equals(p,q);
b = traits_x<M>::Equals(p,q,1e-9);
}
private:
ManifoldType p,q;
@ -531,11 +491,6 @@ public:
e = traits_x<G>::Inverse(g);
operator_usage(flavor);
// todo: how do we test the act concept? or do we even need to?
traits_x<G>::Print(g);
traits_x<G>::Print(g, "g");
b = traits_x<G>::Equals(g,h);
b = traits_x<G>::Equals(g,h,1e-9);
}
private:

View File

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

View File

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

View File

@ -130,6 +130,9 @@ public:
};
// DiscreteConditional
// traits
template<> struct traits_x<DiscreteConditional> : public Testable<DiscreteConditional> {};
/* ************************************************************************* */
template<typename ITERATOR>
DiscreteConditional::shared_ptr DiscreteConditional::Combine(

View File

@ -20,6 +20,7 @@
#include <gtsam/discrete/Assignment.h>
#include <gtsam/inference/Factor.h>
#include <gtsam/base/Testable.h>
namespace gtsam {
@ -101,4 +102,8 @@ public:
};
// DiscreteFactor
// traits
template<> struct traits_x<DiscreteFactor> : public Testable<DiscreteFactor> {};
template<> struct traits_x<DiscreteFactor::Values> : public Testable<DiscreteFactor::Values> {};
}// namespace gtsam

View File

@ -144,7 +144,10 @@ public:
//
// /** Apply a reduction, which is a remapping of variable indices. */
// GTSAM_EXPORT void reduceWithInverse(const internal::Reduction& inverseReduction);
};
// DiscreteFactorGraph
} // namespace gtsam
}; // \ DiscreteFactorGraph
/// traits
template<> struct traits_x<DiscreteFactorGraph> : public Testable<DiscreteFactorGraph> {};
} // \ namespace gtsam

View File

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

View File

@ -40,6 +40,11 @@ using namespace gtsam;
/* ******************************************************************************** */
typedef AlgebraicDecisionTree<Key> ADT;
// traits
namespace gtsam {
template<> struct traits_x<ADT> : public Testable<ADT> {};
}
#define DISABLE_DOT
template<typename T>

View File

@ -44,12 +44,22 @@ void dot(const T&f, const string& filename) {
struct Crazy { int a; double b; };
typedef DecisionTree<string,Crazy> CrazyDecisionTree; // check that DecisionTree is actually generic (as it pretends to be)
// traits
namespace gtsam {
template<> struct traits_x<CrazyDecisionTree> : public Testable<CrazyDecisionTree> {};
}
/* ******************************************************************************** */
// Test string labels and int range
/* ******************************************************************************** */
typedef DecisionTree<string, int> DT;
// traits
namespace gtsam {
template<> struct traits_x<DT> : public Testable<DT> {};
}
struct Ring {
static inline int zero() {
return 0;

View File

@ -130,5 +130,8 @@ inline unsigned char mrsymbolLabel(Key key) { return LabeledSymbol(key).label();
/** Return the index portion of a symbol key. */
inline size_t mrsymbolIndex(Key key) { return LabeledSymbol(key).index(); }
/// traits
template<> struct traits_x<LabeledSymbol> : public Testable<LabeledSymbol> {};
} // \namespace gtsam

View File

@ -191,5 +191,9 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
}
};
/// traits
template<> struct traits_x<Ordering> : public Testable<Ordering> {};
}

View File

@ -18,9 +18,9 @@
#pragma once
#include <boost/serialization/nvp.hpp>
#include <gtsam/inference/Key.h>
#include <gtsam/base/Testable.h>
#include <boost/serialization/nvp.hpp>
namespace gtsam {
@ -161,5 +161,8 @@ inline Key Y(size_t j) { return Symbol('y', j); }
inline Key Z(size_t j) { return Symbol('z', j); }
}
} // namespace gtsam
/// traits
template<> struct traits_x<Symbol> : public Testable<Symbol> {};
} // \ namespace gtsam

View File

@ -17,16 +17,18 @@
#pragma once
#include <gtsam/inference/Key.h>
#include <gtsam/base/FastList.h>
#include <gtsam/base/FastMap.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/types.h>
#include <gtsam/base/timing.h>
#include <boost/foreach.hpp>
#include <vector>
#include <deque>
#include <stdexcept>
#include <boost/foreach.hpp>
#include <gtsam/base/FastList.h>
#include <gtsam/base/FastMap.h>
#include <gtsam/base/types.h>
#include <gtsam/base/timing.h>
#include <gtsam/inference/Key.h>
namespace gtsam {
@ -175,6 +177,11 @@ protected:
/// @}
};
}
/// traits
template<>
struct traits_x<VariableIndex> : public Testable<VariableIndex> {
};
} //\ namespace gtsam
#include <gtsam/inference/VariableIndex-inl.h>

View File

@ -22,12 +22,12 @@
#include <gtsam/base/FastMap.h>
#include <gtsam/base/FastVector.h>
#include <gtsam/base/timing.h>
#include <iostream>
#include <gtsam/base/Testable.h>
#include <boost/foreach.hpp>
#include <boost/tuple/tuple.hpp>
#include <iostream>
#include <string>
namespace gtsam {
@ -82,6 +82,9 @@ public:
/// @}
};
/// traits
template<> struct traits_x<VariableSlots> : public Testable<VariableSlots> {};
/* ************************************************************************* */
template<class FG>
VariableSlots::VariableSlots(const FG& factorGraph)

View File

@ -21,6 +21,7 @@
#include <gtsam/base/FastList.h>
#include <gtsam/base/Vector.h>
#include <gtsam/base/Testable.h>
#include <string>
@ -70,4 +71,9 @@ namespace gtsam {
/** print with optional string */
GTSAM_EXPORT void print(const Errors& a, const std::string& s = "Error");
} // gtsam
/// traits
template<>
struct traits_x<Errors> : public Testable<Errors> {
};
} //\ namespace gtsam

View File

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

View File

@ -128,4 +128,9 @@ namespace gtsam {
Matrix marginalCovariance(Key key) const;
};
}
/// traits
template<>
struct traits_x<GaussianBayesTree> : public Testable<GaussianBayesTree> {
};
} //\ namespace gtsam

View File

@ -141,7 +141,11 @@ namespace gtsam {
}
}; // GaussianConditional
} // gtsam
/// traits
template<>
struct traits_x<GaussianConditional> : public Testable<GaussianConditional> {};
} // \ namespace gtsam
#include <gtsam/linear/GaussianConditional-inl.h>

View File

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

View File

@ -344,4 +344,9 @@ namespace gtsam {
//GTSAM_EXPORT void residual(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
//GTSAM_EXPORT void multiply(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
} // namespace gtsam
/// traits
template<>
struct traits_x<GaussianFactorGraph> : public Testable<GaussianFactorGraph> {
};
} // \ namespace gtsam

View File

@ -443,6 +443,11 @@ namespace gtsam {
}
};
}
/// traits
template<>
struct traits_x<HessianFactor> : public Testable<HessianFactor> {};
} // \ namespace gtsam
#include <gtsam/linear/HessianFactor-inl.h>

View File

@ -360,7 +360,12 @@ namespace gtsam {
}
}; // JacobianFactor
} // gtsam
/// traits
template<>
struct traits_x<JacobianFactor> : public Testable<JacobianFactor> {
};
} // \ namespace gtsam
#include <gtsam/linear/JacobianFactor-inl.h>

View File

@ -885,6 +885,13 @@ namespace gtsam {
typedef noiseModel::Diagonal::shared_ptr SharedDiagonal;
typedef noiseModel::Constrained::shared_ptr SharedConstrained;
} // namespace gtsam
/// 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> {};
} //\ namespace gtsam

View File

@ -381,4 +381,9 @@ namespace gtsam {
}
}; // VectorValues definition
/// traits
template<>
struct traits_x<VectorValues> : public Testable<VectorValues> {
};
} // \namespace gtsam

View File

@ -131,6 +131,9 @@ private:
}
};
/// traits
template<> struct traits_x<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFactor> {};
/**
* Version of AttitudeFactor for Pose3
* @addtogroup Navigation
@ -212,5 +215,8 @@ private:
}
};
/// traits
template<> struct traits_x<Pose3AttitudeFactor> : public Testable<Pose3AttitudeFactor> {};
} /// namespace gtsam

View File

@ -633,6 +633,9 @@ protected:
}; // ISAM2
/// traits
template<> struct traits_x<ISAM2> : public Testable<ISAM2> {};
/// Optimize the BayesTree, starting from the root.
/// @param replaced Needs to contain
/// all variables that are contained in the top of the Bayes tree that has been

View File

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

View File

@ -195,6 +195,10 @@ private:
};
// \class NonlinearEquality
template<typename VALUE>
struct traits_x<NonlinearEquality<VALUE> > : Testable<NonlinearEquality<VALUE> > {
};
/* ************************************************************************* */
/**
* Simple unary equality constraint - fixes a value for a variable
@ -276,6 +280,10 @@ private:
};
// \NonlinearEquality1
template<typename VALUE>
struct traits_x<NonlinearEquality1<VALUE> > : Testable<NonlinearEquality1<VALUE> > {
};
/* ************************************************************************* */
/**
* Simple binary equality constraint - this constraint forces two factors to
@ -337,5 +345,10 @@ private:
};
// \NonlinearEquality2
template<typename VALUE>
struct traits_x<NonlinearEquality2<VALUE> > : Testable<NonlinearEquality2<VALUE> > {
};
}// namespace gtsam

View File

@ -144,6 +144,10 @@ public:
}; // \class NonlinearFactor
/// traits
template<> struct traits_x<NonlinearFactor> : public Testable<NonlinearFactor> {
};
/* ************************************************************************* */
/**
* A nonlinear sum-of-squares factor with a zero-mean noise model

View File

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

View File

@ -24,8 +24,11 @@
#pragma once
#include <gtsam/base/ChartValue.h>
#include <gtsam/base/FastMap.h>
#include <gtsam/inference/Key.h>
#include <boost/optional.hpp>
#include <boost/pool/pool_alloc.hpp>
#include <boost/ptr_container/ptr_map.hpp>
#include <boost/iterator/transform_iterator.hpp>
#include <boost/iterator/filter_iterator.hpp>
@ -44,10 +47,6 @@
#include <string>
#include <utility>
#include <gtsam/base/ChartValue.h>
#include <gtsam/base/FastMap.h>
#include <gtsam/inference/Key.h>
namespace gtsam {
// Forward declarations / utilities
@ -523,6 +522,12 @@ namespace gtsam {
}
};
}
/// traits
template<>
struct traits_x<Values> : public Testable<Values> {
};
} //\ namespace gtsam
#include <gtsam/nonlinear/Values-inl.h>

View File

@ -123,6 +123,10 @@ namespace gtsam {
}
}; // \class BetweenFactor
/// traits
template<class VALUE>
struct traits_x<BetweenFactor<VALUE> > : public Testable<BetweenFactor<VALUE> > {};
/**
* Binary between constraint - forces between to a given value
* This constraint requires the underlying type to a Lie type
@ -150,4 +154,8 @@ namespace gtsam {
}
}; // \class BetweenConstraint
/// traits
template<class VALUE>
struct traits_x<BetweenConstraint<VALUE> > : public Testable<BetweenConstraint<VALUE> > {};
} /// namespace gtsam

View File

@ -121,6 +121,11 @@ namespace gtsam {
}
};
template<class CAMERA, class LANDMARK>
struct traits_x<GeneralSFMFactor<CAMERA, LANDMARK> > : Testable<
GeneralSFMFactor<CAMERA, LANDMARK> > {
};
/**
* Non-linear factor for a constraint derived from a 2D measurement.
* Compared to GeneralSFMFactor, it is a ternary-factor because the calibration is isolated from camera..
@ -214,6 +219,9 @@ namespace gtsam {
}
};
template<class CALIBRATION>
struct traits_x<GeneralSFMFactor2<CALIBRATION> > : Testable<
GeneralSFMFactor2<CALIBRATION> > {
};
} //namespace

View File

@ -187,4 +187,11 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
}
};
/// traits
template<class POSE, class LANDMARK, class CALIBRATION>
struct traits_x<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > :
public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
};
} // \ namespace gtsam

View File

@ -96,8 +96,11 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_);
}
};
// RangeFactor
}; // \ RangeFactor
/// traits
template<class T1, class T2>
struct traits_x<RangeFactor<T1,T2> > : public Testable<RangeFactor<T1,T2> > {};
/**
* Binary factor for a range measurement, with a transform applied
@ -185,7 +188,10 @@ private:
ar & BOOST_SERIALIZATION_NVP(measured_);
ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
}
};
// RangeFactor
}; // \ RangeFactorWithTransform
}// namespace gtsam
/// traits
template<class T1, class T2>
struct traits_x<RangeFactorWithTransform<T1, T2> > : public Testable<RangeFactorWithTransform<T1, T2> > {};
} // \ namespace gtsam

View File

@ -130,4 +130,8 @@ private:
}
};
/// traits
template<class T1, class T2>
struct traits_x<ReferenceFrameFactor<T1, T2> > : public Testable<ReferenceFrameFactor<T1, T2> > {};
} // \namespace gtsam

View File

@ -215,4 +215,8 @@ private:
}; // end of class declaration
/// traits
template<class T1, class T2>
struct traits_x<SmartProjectionPoseFactor<T1, T2> > : public Testable<SmartProjectionPoseFactor<T1, T2> > {};
} // \ namespace gtsam

View File

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

View File

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

View File

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

View File

@ -17,9 +17,10 @@
#pragma once
#include <gtsam/base/types.h>
#include <gtsam/inference/Conditional.h>
#include <gtsam/symbolic/SymbolicFactor.h>
#include <gtsam/inference/Conditional.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/types.h>
namespace gtsam {
@ -121,4 +122,9 @@ namespace gtsam {
}
};
}
/// traits
template<>
struct traits_x<SymbolicConditional> : public Testable<SymbolicConditional> {
};
} //\ namespace gtsam

View File

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

View File

@ -17,13 +17,15 @@
#pragma once
#include <utility>
#include <gtsam/inference/Factor.h>
#include <gtsam/inference/Key.h>
#include <gtsam/base/Testable.h>
#include <boost/shared_ptr.hpp>
#include <boost/assign/list_of.hpp>
#include <boost/make_shared.hpp>
#include <gtsam/inference/Factor.h>
#include <gtsam/inference/Key.h>
#include <utility>
namespace gtsam {
@ -158,4 +160,10 @@ namespace gtsam {
GTSAM_EXPORT std::pair<boost::shared_ptr<SymbolicConditional>, boost::shared_ptr<SymbolicFactor> >
EliminateSymbolic(const SymbolicFactorGraph& factors, const Ordering& keys);
}
/// traits
template<>
struct traits_x<SymbolicFactor> : public Testable<SymbolicFactor> {
};
} //\ namespace gtsam

View File

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

View File

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

View File

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

View File

@ -113,8 +113,11 @@ public:
return 0.0;
}
};
// LinearEquality
}; // \ LinearEquality
}// gtsam
/// traits
template<> struct traits_x<LinearEquality> : public Testable<LinearEquality> {};
} // \ namespace gtsam

View File

@ -28,5 +28,10 @@ public:
typedef boost::shared_ptr<LinearEqualityFactorGraph> shared_ptr;
};
} // namespace gtsam
/// traits
template<> struct traits_x<LinearEqualityFactorGraph> : public Testable<
LinearEqualityFactorGraph> {
};
} // \ namespace gtsam

View File

@ -136,8 +136,10 @@ public:
return aTp;
}
};
// LinearInequality
}; // \ LinearInequality
}// gtsam
/// traits
template<> struct traits_x<LinearInequality> : public Testable<LinearInequality> {};
} // \ namespace gtsam

View File

@ -43,5 +43,10 @@ public:
}
};
} // namespace gtsam
/// traits
template<> struct traits_x<LinearInequalityFactorGraph> : public Testable<
LinearInequalityFactorGraph> {
};
} // \ namespace gtsam

View File

@ -253,4 +253,9 @@ void ConcurrentBatchFilter::PrintKeys(const Container& keys, const std::string&
/// Typedef for Matlab wrapping
typedef ConcurrentBatchFilter::Result ConcurrentBatchFilterResult;
}/// namespace gtsam
/// traits
template<>
struct traits_x<ConcurrentBatchFilter> : public Testable<ConcurrentBatchFilter> {
};
} // \ namespace gtsam

View File

@ -204,4 +204,9 @@ private:
/// Typedef for Matlab wrapping
typedef ConcurrentBatchSmoother::Result ConcurrentBatchSmootherResult;
}/// namespace gtsam
/// traits
template<>
struct traits_x<ConcurrentBatchSmoother> : public Testable<ConcurrentBatchSmoother> {
};
} //\ namespace gtsam

View File

@ -198,4 +198,9 @@ private:
/// Typedef for Matlab wrapping
typedef ConcurrentIncrementalFilter::Result ConcurrentIncrementalFilterResult;
}/// namespace gtsam
/// traits
template<>
struct traits_x<ConcurrentIncrementalFilter> : public Testable<ConcurrentIncrementalFilter> {
};
} //\ namespace gtsam

View File

@ -168,4 +168,9 @@ private:
/// Typedef for Matlab wrapping
typedef ConcurrentIncrementalSmoother::Result ConcurrentIncrementalSmootherResult;
}/// namespace gtsam
/// traits
template<>
struct traits_x<ConcurrentIncrementalSmoother> : public Testable<ConcurrentIncrementalSmoother> {
};
} // \ namespace gtsam

View File

@ -156,8 +156,10 @@ private:
}
};
/// traits
template<>
struct traits_x<LinearizedJacobianFactor> : public Testable<LinearizedJacobianFactor> {
};
/**
* A factor that takes a linear, Hessian factor and inserts it into
@ -269,6 +271,9 @@ private:
}
};
/// traits
template<>
struct traits_x<LinearizedHessianFactor> : public Testable<LinearizedHessianFactor> {
};
} // \namespace aspn

View File

@ -19,12 +19,11 @@
*/
#include <gtsam_unstable/nonlinear/CallRecord.h>
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h>
#include <CppUnitLite/TestHarness.h>
using namespace std;
using namespace gtsam;
@ -70,6 +69,11 @@ struct CallConfig {
}
};
/// traits
namespace gtsam {
template<> struct traits_x<CallConfig> : public Testable<CallConfig> {};
}
struct Record: public internal::CallRecordImplementor<Record, Cols> {
Record() : cc(0, 0) {}
virtual ~Record() {

View File

@ -16,13 +16,13 @@
**/
#pragma once
#include <ostream>
#include <gtsam/base/Testable.h>
#include <gtsam/base/Lie.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/linear/GaussianFactor.h>
#include <gtsam/linear/NoiseModel.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/Lie.h>
#include <ostream>
namespace gtsam {
@ -132,4 +132,9 @@ private:
}; // \class GaussMarkov1stOrderFactor
/// traits
template<class VALUE> struct traits_x<GaussMarkov1stOrderFactor<VALUE> > :
public Testable<GaussMarkov1stOrderFactor<VALUE> > {
};
} /// namespace gtsam

View File

@ -391,7 +391,12 @@ private:
boost::serialization::base_object<Base>(*this));
}
}; // \class GaussMarkov1stOrderFactor
}; // \class InertialNavFactor_GlobalVelocity
/// traits
template<class POSE, class VELOCITY, class IMUBIAS>
struct traits_x<InertialNavFactor_GlobalVelocity<POSE, VELOCITY, IMUBIAS> > :
public Testable<InertialNavFactor_GlobalVelocity<POSE, VELOCITY, IMUBIAS> > {
};
} /// namespace aspn

View File

@ -178,4 +178,11 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
}
};
/// traits
template<class POSE, class LANDMARK, class CALIBRATION>
struct traits_x<ProjectionFactorPPP<POSE, LANDMARK, CALIBRATION> > :
public Testable<ProjectionFactorPPP<POSE, LANDMARK, CALIBRATION> > {
};
} // \ namespace gtsam

View File

@ -168,4 +168,11 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
}
};
/// traits
template<class POSE, class LANDMARK, class CALIBRATION>
struct traits_x<ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> > :
public Testable<ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> > {
};
} // \ namespace gtsam

View File

@ -745,4 +745,10 @@ private:
}
};
/// traits
template<class POSE, class LANDMARK, class CALIBRATION, size_t D>
struct traits_x<SmartStereoProjectionFactor<POSE, LANDMARK, CALIBRATION, D> > :
public Testable<SmartStereoProjectionFactor<POSE, LANDMARK, CALIBRATION, D> > {
};
} // \ namespace gtsam

View File

@ -215,4 +215,10 @@ private:
}; // end of class declaration
/// traits
template<class POSE, class LANDMARK, class CALIBRATION>
struct traits_x<SmartStereoProjectionPoseFactor<POSE, LANDMARK, CALIBRATION> > :
public Testable<SmartStereoProjectionPoseFactor<POSE, LANDMARK, CALIBRATION> > {
};
} // \ namespace gtsam

View File

@ -16,13 +16,13 @@
**/
#pragma once
#include <ostream>
#include <gtsam/base/Testable.h>
#include <gtsam/base/Lie.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/linear/GaussianFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/Lie.h>
#include <ostream>
namespace gtsam {
@ -224,4 +224,10 @@ namespace gtsam {
}
}; // \class TransformBtwRobotsUnaryFactor
/// traits
template<class VALUE>
struct traits_x<TransformBtwRobotsUnaryFactor<VALUE> > :
public Testable<TransformBtwRobotsUnaryFactor<VALUE> > {
};
} /// namespace gtsam

View File

@ -16,15 +16,15 @@
**/
#pragma once
#include <ostream>
#include <gtsam/base/Testable.h>
#include <gtsam/base/Lie.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Marginals.h>
#include <gtsam/linear/GaussianFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/Lie.h>
#include <ostream>
namespace gtsam {
@ -422,4 +422,10 @@ namespace gtsam {
}
}; // \class TransformBtwRobotsUnaryFactorEM
/// traits
template<class VALUE>
struct traits_x<TransformBtwRobotsUnaryFactorEM<VALUE> > :
public Testable<TransformBtwRobotsUnaryFactorEM<VALUE> > {
};
} /// namespace gtsam

View File

@ -28,6 +28,13 @@ using namespace gtsam;
typedef PoseBetweenFactor<Pose3> TestPoseBetweenFactor;
/// traits
namespace gtsam {
template<>
struct traits_x<TestPoseBetweenFactor> : public Testable<TestPoseBetweenFactor> {
};
}
/* ************************************************************************* */
TEST( PoseBetweenFactor, Constructor) {
Key poseKey1(1);

View File

@ -28,6 +28,13 @@ using namespace gtsam;
typedef PosePriorFactor<Pose3> TestPosePriorFactor;
/// traits
namespace gtsam {
template<>
struct traits_x<TestPosePriorFactor> : public Testable<TestPosePriorFactor> {
};
}
/* ************************************************************************* */
TEST( PosePriorFactor, Constructor) {
Key poseKey(1);

View File

@ -48,6 +48,13 @@ using symbol_shorthand::T;
typedef ProjectionFactorPPP<Pose3, Point3> TestProjectionFactor;
/// traits
namespace gtsam {
template<>
struct traits_x<TestProjectionFactor> : public Testable<TestProjectionFactor> {
};
}
/* ************************************************************************* */
TEST( ProjectionFactorPPP, nonStandard ) {
ProjectionFactorPPP<Pose3, Point3, Cal3DS2> f;

View File

@ -18,9 +18,9 @@
// \callgraph
#pragma once
#include <gtsam/geometry/Point2.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/geometry/Point2.h>
// \namespace
@ -270,3 +270,16 @@ namespace simulated2D {
};
} // namespace simulated2D
/// traits
namespace gtsam {
template<class POSE, class LANDMARK>
struct traits_x<simulated2D::GenericMeasurement<POSE, LANDMARK> > : Testable<
simulated2D::GenericMeasurement<POSE, LANDMARK> > {
};
template<>
struct traits_x<simulated2D::Values> : public Testable<simulated2D::Values> {
};
}