Merge branch 'master' into measurement_concepts
Conflicts: gtsam/slam/BearingRangeFactor.hrelease/4.3a0
parent
49f4c911f6
commit
eeacef81b6
|
|
@ -17,7 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -25,7 +24,7 @@ namespace gtsam {
|
|||
/**
|
||||
* LieScalar is a wrapper around double to allow it to be a Lie type
|
||||
*/
|
||||
struct LieScalar : public Lie<LieScalar>, Testable<LieScalar> {
|
||||
struct LieScalar : public Lie<LieScalar> {
|
||||
|
||||
/** default constructor - should be unnecessary */
|
||||
LieScalar() {}
|
||||
|
|
|
|||
|
|
@ -17,7 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
#include <gtsam/base/Vector.h>
|
||||
|
||||
|
|
@ -26,7 +25,7 @@ namespace gtsam {
|
|||
/**
|
||||
* LieVector is a wrapper around vector to allow it to be a Lie type
|
||||
*/
|
||||
struct LieVector : public Vector, public Lie<LieVector>, Testable<LieVector> {
|
||||
struct LieVector : public Vector, public Lie<LieVector> {
|
||||
|
||||
/** default constructor - should be unnecessary */
|
||||
LieVector() {}
|
||||
|
|
|
|||
|
|
@ -65,6 +65,25 @@ namespace gtsam {
|
|||
|
||||
}; // Testable class
|
||||
|
||||
/**
|
||||
* A testable concept check to be placed in unit tests, rather than subclassing
|
||||
*
|
||||
*/
|
||||
template <class T>
|
||||
class TestableConcept {
|
||||
static bool checkTestableConcept(const T& d) {
|
||||
// check print function, with optional string
|
||||
d.print(std::string());
|
||||
d.print();
|
||||
|
||||
// check print, with optional threshold
|
||||
double tol = 1.0;
|
||||
bool r1 = d.equals(d, tol);
|
||||
bool r2 = d.equals(d);
|
||||
return r1 && r2;
|
||||
}
|
||||
}; // Testable class
|
||||
|
||||
/**
|
||||
* This template works for any type with equals
|
||||
*/
|
||||
|
|
@ -104,3 +123,11 @@ namespace gtsam {
|
|||
};
|
||||
|
||||
} // gtsam
|
||||
|
||||
/**
|
||||
* Macros for using the TestableConcept
|
||||
* - An instantiation for use inside unit tests
|
||||
* - A typedef for use inside generic algorithms
|
||||
*/
|
||||
#define GTSAM_CONCEPT_TESTABLE_INST(T) template class gtsam::TestableConcept<T>;
|
||||
#define GTSAM_CONCEPT_TESTABLE_TYPE(T) typedef gtsam::TestableConcept<T> _gtsam_TestableConcept_##T;
|
||||
|
|
|
|||
|
|
@ -16,10 +16,13 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/LieScalar.h>
|
||||
|
||||
using namespace gtsam;
|
||||
|
||||
GTSAM_CONCEPT_TESTABLE_INST(LieScalar)
|
||||
|
||||
const double tol=1e-9;
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
|||
|
|
@ -16,10 +16,13 @@
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/LieVector.h>
|
||||
|
||||
using namespace gtsam;
|
||||
|
||||
GTSAM_CONCEPT_TESTABLE_INST(LieVector)
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( testLieVector, construction ) {
|
||||
Vector v = Vector_(3, 1.0, 2.0, 3.0);
|
||||
|
|
|
|||
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
|||
* @brief Calibration used by Bundler
|
||||
* @ingroup geometry
|
||||
*/
|
||||
class Cal3Bundler: public Testable<Cal3Bundler> {
|
||||
class Cal3Bundler {
|
||||
|
||||
private:
|
||||
double f_, k1_, k2_ ;
|
||||
|
|
|
|||
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
|||
* @brief Calibration of a camera with radial distortion
|
||||
* @ingroup geometry
|
||||
*/
|
||||
class Cal3DS2 : Testable<Cal3DS2> {
|
||||
class Cal3DS2 {
|
||||
private:
|
||||
double fx_, fy_, s_, u0_, v0_ ; // focal length, skew and principal point
|
||||
double k1_, k2_ ; // radial 2nd-order and 4th-order
|
||||
|
|
|
|||
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
|||
* @brief The most common 5DOF 3D->2D calibration
|
||||
* @ingroup geometry
|
||||
*/
|
||||
class Cal3_S2: Testable<Cal3_S2> {
|
||||
class Cal3_S2 {
|
||||
private:
|
||||
double fx_, fy_, s_, u0_, v0_;
|
||||
|
||||
|
|
|
|||
|
|
@ -19,18 +19,17 @@
|
|||
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <gtsam/base/Matrix.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* A 2D point
|
||||
* Derived from testable so has standard print and equals, and assert_equals works
|
||||
* Complies with the Testable Concept
|
||||
* Functional, so no set functions: once created, a point is constant.
|
||||
* @ingroup geometry
|
||||
*/
|
||||
class Point2: Testable<Point2>, public Lie<Point2> {
|
||||
class Point2: public Lie<Point2> {
|
||||
public:
|
||||
/// dimension of the variable - used to autodetect sizes
|
||||
static const size_t dimension = 2;
|
||||
|
|
|
|||
|
|
@ -31,7 +31,7 @@ namespace gtsam {
|
|||
* A 2D pose (Point2,Rot2)
|
||||
* @ingroup geometry
|
||||
*/
|
||||
class Pose2: Testable<Pose2>, public Lie<Pose2> {
|
||||
class Pose2: public Lie<Pose2> {
|
||||
|
||||
public:
|
||||
static const size_t dimension = 3;
|
||||
|
|
|
|||
|
|
@ -28,7 +28,7 @@ namespace gtsam {
|
|||
* NOTE: the angle theta is in radians unless explicitly stated
|
||||
* @ingroup geometry
|
||||
*/
|
||||
class Rot2: Testable<Rot2>, public Lie<Rot2> {
|
||||
class Rot2: public Lie<Rot2> {
|
||||
|
||||
public:
|
||||
/** get the dimension by the type */
|
||||
|
|
|
|||
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
|||
* A 2D stereo point, v will be same for rectified images
|
||||
* @ingroup geometry
|
||||
*/
|
||||
class StereoPoint2: Testable<StereoPoint2>, Lie<StereoPoint2> {
|
||||
class StereoPoint2: Lie<StereoPoint2> {
|
||||
public:
|
||||
static const size_t dimension = 3;
|
||||
private:
|
||||
|
|
|
|||
|
|
@ -16,6 +16,7 @@
|
|||
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/geometry/Cal3Bundler.h>
|
||||
|
||||
|
|
|
|||
|
|
@ -16,6 +16,7 @@
|
|||
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/geometry/Cal3DS2.h>
|
||||
|
||||
|
|
|
|||
|
|
@ -15,11 +15,14 @@
|
|||
*/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/geometry/Cal3_S2.h>
|
||||
|
||||
using namespace gtsam;
|
||||
|
||||
GTSAM_CONCEPT_TESTABLE_INST(Cal3_S2)
|
||||
|
||||
Cal3_S2 K(500, 500, 0.1, 640 / 2, 480 / 2);
|
||||
Point2 p(1, -2);
|
||||
|
||||
|
|
|
|||
|
|
@ -16,6 +16,7 @@
|
|||
**/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
|
||||
using namespace std;
|
||||
|
|
|
|||
|
|
@ -23,6 +23,7 @@
|
|||
using namespace boost::assign;
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/lieProxies.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
|
|
@ -34,6 +35,12 @@ using namespace std;
|
|||
|
||||
// #define SLOW_BUT_CORRECT_EXPMAP
|
||||
|
||||
// concept checks for testable
|
||||
GTSAM_CONCEPT_TESTABLE_INST(Pose2)
|
||||
GTSAM_CONCEPT_TESTABLE_INST(Point2)
|
||||
GTSAM_CONCEPT_TESTABLE_INST(Rot2)
|
||||
GTSAM_CONCEPT_TESTABLE_INST(LieVector)
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(Pose2, constructors) {
|
||||
Point2 p;
|
||||
|
|
|
|||
|
|
@ -16,6 +16,7 @@
|
|||
*/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/geometry/Rot2.h>
|
||||
|
||||
|
|
|
|||
|
|
@ -16,6 +16,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -35,6 +36,10 @@ namespace gtsam {
|
|||
typedef NonlinearFactor2<VALUES, POSEKEY, POINTKEY> Base;
|
||||
|
||||
Rot z_; /** measurement */
|
||||
|
||||
/** concept check by type */
|
||||
GTSAM_CONCEPT_TESTABLE_TYPE(Rot)
|
||||
|
||||
public:
|
||||
|
||||
/** default constructor for serialization/testing only */
|
||||
|
|
|
|||
|
|
@ -19,6 +19,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <gtsam/geometry/concepts.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -41,7 +42,8 @@ namespace gtsam {
|
|||
Rot bearing_;
|
||||
double range_;
|
||||
|
||||
// Concept requirements for this factor
|
||||
/** concept check by type */
|
||||
GTSAM_CONCEPT_TESTABLE_TYPE(Rot)
|
||||
GTSAM_CONCEPT_RANGE_MEASUREMENT(Pose, Point)
|
||||
|
||||
public:
|
||||
|
|
|
|||
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/nonlinear/NonlinearConstraint.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -35,6 +36,9 @@ namespace gtsam {
|
|||
|
||||
X measured_; /// fixed between value
|
||||
|
||||
/** concept check by type */
|
||||
GTSAM_CONCEPT_TESTABLE_TYPE(X)
|
||||
|
||||
public:
|
||||
|
||||
typedef boost::shared_ptr<BetweenConstraint<VALUES, KEY> > shared_ptr;
|
||||
|
|
|
|||
|
|
@ -17,9 +17,10 @@
|
|||
|
||||
#include <ostream>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam/linear/GaussianFactor.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
|
@ -38,6 +39,9 @@ namespace gtsam {
|
|||
|
||||
T measured_; /** The measurement */
|
||||
|
||||
/** concept check by type */
|
||||
GTSAM_CONCEPT_TESTABLE_TYPE(T)
|
||||
|
||||
public:
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
|
|
|
|||
|
|
@ -42,6 +42,8 @@ struct BoundingConstraint1: public NonlinearConstraint1<VALUES, KEY> {
|
|||
Base(key, 1, mu), threshold_(threshold), isGreaterThan_(isGreaterThan) {
|
||||
}
|
||||
|
||||
virtual ~BoundingConstraint1() {}
|
||||
|
||||
inline double threshold() const { return threshold_; }
|
||||
inline bool isGreaterThan() const { return isGreaterThan_; }
|
||||
|
||||
|
|
@ -107,6 +109,8 @@ struct BoundingConstraint2: public NonlinearConstraint2<VALUES, KEY1, KEY2> {
|
|||
bool isGreaterThan, double mu = 1000.0)
|
||||
: Base(key1, key2, 1, mu), threshold_(threshold), isGreaterThan_(isGreaterThan) {}
|
||||
|
||||
virtual ~BoundingConstraint2() {}
|
||||
|
||||
inline double threshold() const { return threshold_; }
|
||||
inline bool isGreaterThan() const { return isGreaterThan_; }
|
||||
|
||||
|
|
|
|||
|
|
@ -15,6 +15,7 @@
|
|||
**/
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
@ -39,6 +40,9 @@ namespace gtsam {
|
|||
|
||||
T prior_; /** The measurement */
|
||||
|
||||
/** concept check by type */
|
||||
GTSAM_CONCEPT_TESTABLE_TYPE(T)
|
||||
|
||||
public:
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
|
|
|
|||
Loading…
Reference in New Issue