diff --git a/.cproject b/.cproject
index 9c03c5b7d..241afea81 100644
--- a/.cproject
+++ b/.cproject
@@ -2393,6 +2393,38 @@
true
true
+
+ make
+ -j4
+ testType.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testArgument.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testReturnValue.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testTemplate.run
+ true
+ true
+ true
+
make
-j5
diff --git a/gtsam.h b/gtsam.h
index d63563028..96d51117a 100644
--- a/gtsam.h
+++ b/gtsam.h
@@ -1738,6 +1738,8 @@ class Values {
void insert(size_t j, const gtsam::Cal3Bundler& t);
void insert(size_t j, const gtsam::EssentialMatrix& t);
void insert(size_t j, const gtsam::imuBias::ConstantBias& t);
+ void insert(size_t j, Vector t);
+ void insert(size_t j, Matrix t);
void update(size_t j, const gtsam::Point2& t);
void update(size_t j, const gtsam::Point3& t);
@@ -1750,9 +1752,10 @@ class Values {
void update(size_t j, const gtsam::Cal3Bundler& t);
void update(size_t j, const gtsam::EssentialMatrix& t);
void update(size_t j, const gtsam::imuBias::ConstantBias& t);
+ void update(size_t j, Vector t);
+ void update(size_t j, Matrix t);
- template
+ template
T at(size_t j);
};
@@ -2150,7 +2153,7 @@ class NonlinearISAM {
#include
#include
-template
+template
virtual class PriorFactor : gtsam::NoiseModelFactor {
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
T prior() const;
diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h
index a3a5b029b..1190822ed 100644
--- a/gtsam/base/Manifold.h
+++ b/gtsam/base/Manifold.h
@@ -73,7 +73,6 @@ template
struct dimension: public Dynamic {
};
-
/**
* zero::value is intended to be the origin of a canonical coordinate system
* with canonical(t) == DefaultChart::local(zero::value, t)
@@ -111,14 +110,16 @@ struct is_group > : publi
};
template
-struct is_manifold > : public boost::true_type{
+struct is_manifold > : public boost::true_type {
};
template
-struct dimension > : public boost::integral_constant {
- //TODO after switch to c++11 : the above should should be extracted to a constexpr function
- // for readability and to reduce code duplication
+struct dimension > : public boost::integral_constant<
+ int,
+ M == Eigen::Dynamic ? Eigen::Dynamic :
+ (N == Eigen::Dynamic ? Eigen::Dynamic : M * N)> {
+ //TODO after switch to c++11 : the above should should be extracted to a constexpr function
+ // for readability and to reduce code duplication
};
template
@@ -131,10 +132,10 @@ struct zero > {
};
template
-struct identity > : public zero > {
+struct identity > : public zero<
+ Eigen::Matrix > {
};
-
template struct is_chart: public boost::false_type {
};
@@ -248,12 +249,16 @@ struct DefaultChart > {
* This chart for the vector space of M x N matrices (represented by Eigen matrices) chooses as basis the one with respect to which the coordinates are exactly the matrix entries as laid out in memory (as determined by Options).
* Computing coordinates for a matrix is then simply a reshape to the row vector of appropriate size.
*/
- typedef Eigen::Matrix type;
+ typedef Eigen::Matrix type;
typedef type T;
- typedef Eigen::Matrix::value, 1> vector;BOOST_STATIC_ASSERT_MSG((M!=Eigen::Dynamic && N!=Eigen::Dynamic),
- "DefaultChart has not been implemented yet for dynamically sized matrices");
+ typedef Eigen::Matrix::value, 1> vector;
+
+ BOOST_STATIC_ASSERT_MSG((M!=Eigen::Dynamic && N!=Eigen::Dynamic),
+ "Internal error: DefaultChart for Dynamic should be handled by template below");
+
static vector local(const T& origin, const T& other) {
- return reshape(other) - reshape(origin);
+ return reshape(other)
+ - reshape(origin);
}
static T retract(const T& origin, const vector& d) {
return origin + reshape(d);
@@ -266,20 +271,36 @@ struct DefaultChart > {
// Dynamically sized Vector
template<>
struct DefaultChart {
- typedef Vector T;
- typedef T type;
- typedef T vector;
- static vector local(const T& origin, const T& other) {
+ typedef Vector type;
+ typedef Vector vector;
+ static vector local(const Vector& origin, const Vector& other) {
return other - origin;
}
- static T retract(const T& origin, const vector& d) {
+ static Vector retract(const Vector& origin, const vector& d) {
return origin + d;
}
- static int getDimension(const T& origin) {
+ static int getDimension(const Vector& origin) {
return origin.size();
}
};
+// Dynamically sized Matrix
+template<>
+struct DefaultChart {
+ typedef Matrix type;
+ typedef Vector vector;
+ static vector local(const Matrix& origin, const Matrix& other) {
+ Matrix d = other - origin;
+ return Eigen::Map(d.data(),getDimension(d));
+ }
+ static Matrix retract(const Matrix& origin, const vector& d) {
+ return origin + Eigen::Map(d.data(),origin.rows(),origin.cols());
+ }
+ static int getDimension(const Matrix& m) {
+ return m.size();
+ }
+};
+
/**
* Old Concept check class for Manifold types
* Requires a mapping between a linear tangent space and the underlying
diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h
index 50bed2e3b..7299d7c8a 100644
--- a/gtsam/inference/MetisIndex-inl.h
+++ b/gtsam/inference/MetisIndex-inl.h
@@ -26,8 +26,8 @@ namespace gtsam {
/* ************************************************************************* */
template
void MetisIndex::augment(const FactorGraph& factors) {
- std::map > iAdjMap; // Stores a set of keys that are adjacent to key x, with adjMap.first
- std::map >::iterator iAdjMapIt;
+ std::map > iAdjMap; // Stores a set of keys that are adjacent to key x, with adjMap.first
+ std::map >::iterator iAdjMapIt;
std::set keySet;
/* ********** Convert to CSR format ********** */
@@ -36,7 +36,7 @@ void MetisIndex::augment(const FactorGraph& factors) {
// starting at index xadj[i] and ending at(but not including)
// index xadj[i + 1](i.e., adjncy[xadj[i]] through
// and including adjncy[xadj[i + 1] - 1]).
- idx_t keyCounter = 0;
+ int32_t keyCounter = 0;
// First: Record a copy of each key inside the factorgraph and create a
// key to integer mapping. This is referenced during the adjaceny step
@@ -58,7 +58,7 @@ void MetisIndex::augment(const FactorGraph& factors) {
BOOST_FOREACH(const Key& k1, *factors[i])
BOOST_FOREACH(const Key& k2, *factors[i])
if (k1 != k2) {
- // Store both in Key and idx_t format
+ // Store both in Key and int32_t format
int i = intKeyBMap_.left.at(k1);
int j = intKeyBMap_.left.at(k2);
iAdjMap[i].insert(iAdjMap[i].end(), j);
@@ -71,14 +71,14 @@ void MetisIndex::augment(const FactorGraph& factors) {
xadj_.push_back(0); // Always set the first index to zero
for (iAdjMapIt = iAdjMap.begin(); iAdjMapIt != iAdjMap.end(); ++iAdjMapIt) {
- std::vector temp;
+ std::vector temp;
// Copy from the FastSet into a temporary vector
std::copy(iAdjMapIt->second.begin(), iAdjMapIt->second.end(),
std::back_inserter(temp));
// Insert each index's set in order by appending them to the end of adj_
adj_.insert(adj_.end(), temp.begin(), temp.end());
//adj_.push_back(temp);
- xadj_.push_back((idx_t) adj_.size());
+ xadj_.push_back((int32_t) adj_.size());
}
}
diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h
index 51624e29e..22b03ee5d 100644
--- a/gtsam/inference/MetisIndex.h
+++ b/gtsam/inference/MetisIndex.h
@@ -22,7 +22,6 @@
#include
#include
#include
-#include
// Boost bimap generates many ugly warnings in CLANG
#ifdef __clang__
@@ -47,13 +46,13 @@ namespace gtsam {
class GTSAM_EXPORT MetisIndex {
public:
typedef boost::shared_ptr shared_ptr;
- typedef boost::bimap bm_type;
+ typedef boost::bimap bm_type;
private:
- FastVector xadj_; // Index of node's adjacency list in adj
- FastVector adj_; // Stores ajacency lists of all nodes, appended into a single vector
- FastVector iadj_; // Integer keys for passing into metis. One to one mapping with adj_;
- boost::bimap intKeyBMap_; // Stores Key <-> integer value relationship
+ FastVector xadj_; // Index of node's adjacency list in adj
+ FastVector adj_; // Stores ajacency lists of all nodes, appended into a single vector
+ FastVector iadj_; // Integer keys for passing into metis. One to one mapping with adj_;
+ boost::bimap intKeyBMap_; // Stores Key <-> integer value relationship
size_t nKeys_;
public:
@@ -84,16 +83,16 @@ public:
template
void augment(const FactorGraph& factors);
- std::vector xadj() const {
+ std::vector xadj() const {
return xadj_;
}
- std::vector adj() const {
+ std::vector adj() const {
return adj_;
}
size_t nValues() const {
return nKeys_;
}
- Key intToKey(idx_t value) const {
+ Key intToKey(int32_t value) const {
assert(value >= 0);
return intKeyBMap_.right.find(value)->second;
}
diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h
index 3c397c9e9..d6e1b6e98 100644
--- a/gtsam/linear/IterativeSolver.h
+++ b/gtsam/linear/IterativeSolver.h
@@ -106,9 +106,9 @@ namespace gtsam {
typedef boost::tuple Base;
KeyInfoEntry(){}
KeyInfoEntry(size_t idx, size_t d, Key start) : Base(idx, d, start) {}
- const size_t index() const { return this->get<0>(); }
- const size_t dim() const { return this->get<1>(); }
- const size_t colstart() const { return this->get<2>(); }
+ size_t index() const { return this->get<0>(); }
+ size_t dim() const { return this->get<1>(); }
+ size_t colstart() const { return this->get<2>(); }
};
/************************************************************************************/
diff --git a/gtsam/nonlinear/Expression-inl.h b/gtsam/nonlinear/Expression-inl.h
index 08dd18ee3..332c23ca7 100644
--- a/gtsam/nonlinear/Expression-inl.h
+++ b/gtsam/nonlinear/Expression-inl.h
@@ -106,7 +106,7 @@ struct UseBlockIf {
};
}
-/// Handle Leaf Case: reverseAD ends here, by writing a matrix into Jacobians
+/// Handle Leaf Case: reverse AD ends here, by writing a matrix into Jacobians
template
void handleLeafCase(const Eigen::MatrixBase& dTdA,
JacobianMap& jacobians, Key key) {
@@ -186,28 +186,28 @@ public:
}
}
/**
- * *** This is the main entry point for reverseAD, called from Expression ***
+ * *** This is the main entry point for reverse AD, called from Expression ***
* Called only once, either inserts I into Jacobians (Leaf) or starts AD (Function)
*/
typedef Eigen::Matrix JacobianTT;
- void startReverseAD(JacobianMap& jacobians) const {
+ void startReverseAD1(JacobianMap& jacobians) const {
if (kind == Leaf) {
// This branch will only be called on trivial Leaf expressions, i.e. Priors
static const JacobianTT I = JacobianTT::Identity();
handleLeafCase(I, jacobians, content.key);
} else if (kind == Function)
// This is the more typical entry point, starting the AD pipeline
- // Inside the startReverseAD that the correctly dimensioned pipeline is chosen.
- content.ptr->startReverseAD(jacobians);
+ // Inside startReverseAD2 the correctly dimensioned pipeline is chosen.
+ content.ptr->startReverseAD2(jacobians);
}
// Either add to Jacobians (Leaf) or propagate (Function)
template
- void reverseAD(const Eigen::MatrixBase & dTdA,
+ void reverseAD1(const Eigen::MatrixBase & dTdA,
JacobianMap& jacobians) const {
if (kind == Leaf)
handleLeafCase(dTdA, jacobians, content.key);
else if (kind == Function)
- content.ptr->reverseAD(dTdA, jacobians);
+ content.ptr->reverseAD2(dTdA, jacobians);
}
/// Define type so we can apply it as a meta-function
@@ -470,10 +470,10 @@ struct FunctionalBase: ExpressionNode {
struct Record {
void print(const std::string& indent) const {
}
- void startReverseAD(JacobianMap& jacobians) const {
+ void startReverseAD4(JacobianMap& jacobians) const {
}
template
- void reverseAD(const SomeMatrix & dFdT, JacobianMap& jacobians) const {
+ void reverseAD4(const SomeMatrix & dFdT, JacobianMap& jacobians) const {
}
};
/// Construct an execution trace for reverse AD
@@ -505,9 +505,9 @@ struct JacobianTrace {
typename Jacobian::type dTdA;
};
-/**
- * Recursive Definition of Functional ExpressionNode
- */
+// Recursive Definition of Functional ExpressionNode
+// The reason we inherit from Argument is because we can then
+// case to this unique signature to retrieve the expression at any level
template
struct GenerateFunctionalNode: Argument, Base {
@@ -528,7 +528,9 @@ struct GenerateFunctionalNode: Argument, Base {
This::expression->dims(map);
}
- /// Recursive Record Class for Functional Expressions
+ // Recursive Record Class for Functional Expressions
+ // The reason we inherit from JacobianTrace is because we can then
+ // case to this unique signature to retrieve the value/trace at any level
struct Record: JacobianTrace, Base::Record {
typedef T return_type;
@@ -543,17 +545,26 @@ struct GenerateFunctionalNode: Argument, Base {
}
/// Start the reverse AD process
- void startReverseAD(JacobianMap& jacobians) const {
- Base::Record::startReverseAD(jacobians);
- This::trace.reverseAD(This::dTdA, jacobians);
+ void startReverseAD4(JacobianMap& jacobians) const {
+ Base::Record::startReverseAD4(jacobians);
+ // This is the crucial point where the size of the AD pipeline is selected.
+ // One pipeline is started for each argument, but the number of rows in each
+ // pipeline is the same, namely the dimension of the output argument T.
+ // For example, if the entire expression is rooted by a binary function
+ // yielding a 2D result, then the matrix dTdA will have 2 rows.
+ // ExecutionTrace::reverseAD1 just passes this on to CallRecord::reverseAD2
+ // which calls the correctly sized CallRecord::reverseAD3, which in turn
+ // calls reverseAD4 below.
+ This::trace.reverseAD1(This::dTdA, jacobians);
}
/// Given df/dT, multiply in dT/dA and continue reverse AD process
+ // Cols is always known at compile time
template
- void reverseAD(const Eigen::Matrix & dFdT,
+ void reverseAD4(const Eigen::Matrix & dFdT,
JacobianMap& jacobians) const {
- Base::Record::reverseAD(dFdT, jacobians);
- This::trace.reverseAD(dFdT * This::dTdA, jacobians);
+ Base::Record::reverseAD4(dFdT, jacobians);
+ This::trace.reverseAD1(dFdT * This::dTdA, jacobians);
}
};
@@ -614,8 +625,8 @@ struct FunctionalNode {
struct Record: public internal::CallRecordImplementor::value>, public Base::Record {
using Base::Record::print;
- using Base::Record::startReverseAD;
- using Base::Record::reverseAD;
+ using Base::Record::startReverseAD4;
+ using Base::Record::reverseAD4;
virtual ~Record() {
}
diff --git a/gtsam/nonlinear/Expression.h b/gtsam/nonlinear/Expression.h
index d44d21cd7..c7f022724 100644
--- a/gtsam/nonlinear/Expression.h
+++ b/gtsam/nonlinear/Expression.h
@@ -209,7 +209,7 @@ private:
ExecutionTraceStorage traceStorage[size];
ExecutionTrace trace;
T value(traceExecution(values, trace, traceStorage));
- trace.startReverseAD(jacobians);
+ trace.startReverseAD1(jacobians);
return value;
}
diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp
index 09fe0f253..941728d8c 100644
--- a/gtsam/nonlinear/tests/testValues.cpp
+++ b/gtsam/nonlinear/tests/testValues.cpp
@@ -12,6 +12,8 @@
/**
* @file testValues.cpp
* @author Richard Roberts
+ * @author Frank Dellaert
+ * @author Mike Bosse
*/
#include
@@ -168,9 +170,9 @@ TEST(Values, basic_functions)
Values values;
const Values& values_c = values;
values.insert(2, Vector3());
- values.insert(4, Vector3());
- values.insert(6, Vector3());
- values.insert(8, Vector3());
+ values.insert(4, Vector(3));
+ values.insert(6, Matrix23());
+ values.insert(8, Matrix(2,3));
// find
EXPECT_LONGS_EQUAL(4, values.find(4)->key);
diff --git a/gtsam_unstable/nonlinear/CallRecord.h b/gtsam_unstable/nonlinear/CallRecord.h
index f1ac0b044..159a841e5 100644
--- a/gtsam_unstable/nonlinear/CallRecord.h
+++ b/gtsam_unstable/nonlinear/CallRecord.h
@@ -32,12 +32,6 @@ class JacobianMap;
// forward declaration
//-----------------------------------------------------------------------------
-/**
- * MaxVirtualStaticRows defines how many separate virtual reverseAD with specific
- * static rows (1..MaxVirtualStaticRows) methods will be part of the CallRecord interface.
- */
-const int MaxVirtualStaticRows = 4;
-
namespace internal {
/**
@@ -57,7 +51,8 @@ struct ConvertToVirtualFunctionSupportedMatrixType {
template<>
struct ConvertToVirtualFunctionSupportedMatrixType {
template
- static const Eigen::Matrix convert(
+ static const Eigen::Matrix convert(
const Eigen::MatrixBase & x) {
return x;
}
@@ -69,126 +64,132 @@ struct ConvertToVirtualFunctionSupportedMatrixType {
}
};
-/**
- * Recursive definition of an interface having several purely
- * virtual _reverseAD(const Eigen::Matrix &, JacobianMap&)
- * with Rows in 1..MaxSupportedStaticRows
- */
-template
-struct ReverseADInterface: ReverseADInterface {
- using ReverseADInterface::_reverseAD;
- virtual void _reverseAD(
- const Eigen::Matrix & dFdT,
- JacobianMap& jacobians) const = 0;
-};
-
-template
-struct ReverseADInterface<0, Cols> {
- virtual void _reverseAD(
- const Eigen::Matrix & dFdT,
- JacobianMap& jacobians) const = 0;
- virtual void _reverseAD(const Matrix & dFdT,
- JacobianMap& jacobians) const = 0;
-};
-
-/**
- * ReverseADImplementor is a utility class used by CallRecordImplementor to
- * implementing the recursive ReverseADInterface interface.
- */
-template
-struct ReverseADImplementor: ReverseADImplementor {
-private:
- using ReverseADImplementor::_reverseAD;
- virtual void _reverseAD(
- const Eigen::Matrix & dFdT,
- JacobianMap& jacobians) const {
- static_cast(this)->reverseAD(dFdT, jacobians);
- }
- friend struct internal::ReverseADImplementor;
-};
-
-template
-struct ReverseADImplementor : virtual internal::ReverseADInterface<
- MaxVirtualStaticRows, Cols> {
-private:
- using internal::ReverseADInterface::_reverseAD;
- const Derived & derived() const {
- return static_cast(*this);
- }
- virtual void _reverseAD(
- const Eigen::Matrix & dFdT,
- JacobianMap& jacobians) const {
- derived().reverseAD(dFdT, jacobians);
- }
- virtual void _reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const {
- derived().reverseAD(dFdT, jacobians);
- }
- friend struct internal::ReverseADImplementor;
-};
-
} // namespace internal
/**
- * The CallRecord class stores the Jacobians of applying a function
- * with respect to each of its arguments. It also stores an execution trace
- * (defined below) for each of its arguments.
- *
- * It is implemented in the function-style ExpressionNode's nested Record class below.
+ * The CallRecord is an abstract base class for the any class that stores
+ * the Jacobians of applying a function with respect to each of its arguments,
+ * as well as an execution trace for each of its arguments.
*/
template
-struct CallRecord: virtual private internal::ReverseADInterface<
- MaxVirtualStaticRows, Cols> {
+struct CallRecord {
+ // Print entire record, recursively
inline void print(const std::string& indent) const {
_print(indent);
}
- inline void startReverseAD(JacobianMap& jacobians) const {
- _startReverseAD(jacobians);
+ // Main entry point for the reverse AD process of a functional expression.
+ // Called *once* by the main AD entry point, ExecutionTrace::startReverseAD1
+ // This function then calls ExecutionTrace::reverseAD for every argument
+ // which will in turn call the reverseAD method below.
+ // This non-virtual function _startReverseAD3, implemented in derived
+ inline void startReverseAD2(JacobianMap& jacobians) const {
+ _startReverseAD3(jacobians);
}
+ // Dispatch the reverseAD2 calls issued by ExecutionTrace::reverseAD1
+ // Here we convert to dynamic if the
template
- inline void reverseAD(const Eigen::MatrixBase & dFdT,
+ inline void reverseAD2(const Eigen::MatrixBase & dFdT,
JacobianMap& jacobians) const {
- _reverseAD(
- internal::ConvertToVirtualFunctionSupportedMatrixType<(Derived::RowsAtCompileTime > MaxVirtualStaticRows)>::convert(
- dFdT), jacobians);
+ _reverseAD3(
+ internal::ConvertToVirtualFunctionSupportedMatrixType<
+ (Derived::RowsAtCompileTime > 5)>::convert(dFdT),
+ jacobians);
}
- inline void reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const {
- _reverseAD(dFdT, jacobians);
+ // This overload supports matrices with both rows and columns dynamically sized.
+ // The template version above would be slower by introducing an extra conversion
+ // to statically sized columns.
+ inline void reverseAD2(const Matrix & dFdT, JacobianMap& jacobians) const {
+ _reverseAD3(dFdT, jacobians);
}
virtual ~CallRecord() {
}
private:
+
virtual void _print(const std::string& indent) const = 0;
- virtual void _startReverseAD(JacobianMap& jacobians) const = 0;
- using internal::ReverseADInterface::_reverseAD;
+ virtual void _startReverseAD3(JacobianMap& jacobians) const = 0;
+
+ virtual void _reverseAD3(const Matrix & dFdT,
+ JacobianMap& jacobians) const = 0;
+
+ virtual void _reverseAD3(
+ const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const = 0;
+
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const = 0;
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const = 0;
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const = 0;
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const = 0;
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const = 0;
};
+/**
+ * CallRecordMaxVirtualStaticRows tells which separate virtual reverseAD with specific
+ * static rows (1..CallRecordMaxVirtualStaticRows) methods are part of the CallRecord
+ * interface. It is used to keep the testCallRecord unit test in sync.
+ */
+const int CallRecordMaxVirtualStaticRows = 5;
+
namespace internal {
/**
* The CallRecordImplementor implements the CallRecord interface for a Derived class by
* delegating to its corresponding (templated) non-virtual methods.
*/
template
-struct CallRecordImplementor: public CallRecord,
- private ReverseADImplementor {
+struct CallRecordImplementor: public CallRecord {
private:
+
const Derived & derived() const {
return static_cast(*this);
}
+
virtual void _print(const std::string& indent) const {
derived().print(indent);
}
- virtual void _startReverseAD(JacobianMap& jacobians) const {
- derived().startReverseAD(jacobians);
+
+ virtual void _startReverseAD3(JacobianMap& jacobians) const {
+ derived().startReverseAD4(jacobians);
+ }
+
+ virtual void _reverseAD3(const Matrix & dFdT, JacobianMap& jacobians) const {
+ derived().reverseAD4(dFdT, jacobians);
+ }
+
+ virtual void _reverseAD3(
+ const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const {
+ derived().reverseAD4(dFdT, jacobians);
+ }
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const {
+ derived().reverseAD4(dFdT, jacobians);
+ }
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const {
+ derived().reverseAD4(dFdT, jacobians);
+ }
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const {
+ derived().reverseAD4(dFdT, jacobians);
+ }
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const {
+ derived().reverseAD4(dFdT, jacobians);
+ }
+ virtual void _reverseAD3(const Eigen::Matrix & dFdT,
+ JacobianMap& jacobians) const {
+ derived().reverseAD4(dFdT, jacobians);
}
- template friend struct ReverseADImplementor;
};
} // namespace internal
diff --git a/gtsam_unstable/nonlinear/ExpressionFactor.h b/gtsam_unstable/nonlinear/ExpressionFactor.h
index 95c4d71a8..de6e4983a 100644
--- a/gtsam_unstable/nonlinear/ExpressionFactor.h
+++ b/gtsam_unstable/nonlinear/ExpressionFactor.h
@@ -35,7 +35,6 @@ class ExpressionFactor: public NoiseModelFactor {
T measurement_; ///< the measurement to be compared with the expression
Expression expression_; ///< the expression that is AD enabled
FastVector dims_; ///< dimensions of the Jacobian matrices
- size_t augmentedCols_; ///< total number of columns + 1 (for RHS)
static const int Dim = traits::dimension::value;
@@ -55,15 +54,6 @@ public:
// Get keys and dimensions for Jacobian matrices
// An Expression is assumed unmutable, so we do this now
boost::tie(keys_, dims_) = expression_.keysAndDims();
-
- // Add sizes to know how much memory to allocate on stack in linearize
- augmentedCols_ = std::accumulate(dims_.begin(), dims_.end(), 1);
-
-#ifdef DEBUG_ExpressionFactor
- BOOST_FOREACH(size_t d, dims_)
- std::cout << d << " ";
- std::cout << " -> " << Dim << "x" << augmentedCols_ << std::endl;
-#endif
}
/**
diff --git a/gtsam_unstable/nonlinear/ceres_rotation.h b/gtsam_unstable/nonlinear/ceres_rotation.h
index b02c10211..6ed3b88cb 100644
--- a/gtsam_unstable/nonlinear/ceres_rotation.h
+++ b/gtsam_unstable/nonlinear/ceres_rotation.h
@@ -47,6 +47,7 @@
#include
#include
+#include
#include
#define DCHECK assert
diff --git a/gtsam_unstable/nonlinear/tests/CMakeLists.txt b/gtsam_unstable/nonlinear/tests/CMakeLists.txt
index 5b1fd07d4..ad14fcd9b 100644
--- a/gtsam_unstable/nonlinear/tests/CMakeLists.txt
+++ b/gtsam_unstable/nonlinear/tests/CMakeLists.txt
@@ -1 +1 @@
-gtsamAddTestsGlob(nonlinear_unstable "test*.cpp" "" "gtsam_unstable")
+gtsamAddTestsGlob(nonlinear_unstable "test*.cpp" "testCustomChartExpression.cpp" "gtsam_unstable")
diff --git a/gtsam_unstable/nonlinear/tests/testBasisDecompositions.cpp b/gtsam_unstable/nonlinear/tests/testBasisDecompositions.cpp
index f113a4f64..5d6ea2168 100644
--- a/gtsam_unstable/nonlinear/tests/testBasisDecompositions.cpp
+++ b/gtsam_unstable/nonlinear/tests/testBasisDecompositions.cpp
@@ -16,22 +16,9 @@
* @brief unit tests for Basis Decompositions w Expressions
*/
-#include
-#include
-#include
-#include
-#include
-#include
+#include
-#include
-
-#include
-using boost::assign::list_of;
-
-using namespace std;
-using namespace gtsam;
-
-noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1);
+namespace gtsam {
/// Fourier
template
@@ -67,6 +54,80 @@ public:
}
};
+}
+
+#include
+#include
+#include
+#include
+
+namespace gtsam {
+
+/// For now, this is our sequence representation
+typedef std::map Sequence;
+
+/**
+ * Class that does Fourier Decomposition via least squares
+ */
+class FourierDecomposition {
+public:
+
+ typedef Vector3 Coefficients; ///< Fourier coefficients
+
+private:
+ Coefficients c_;
+
+public:
+
+ /// Create nonlinear FG from Sequence
+ static NonlinearFactorGraph NonlinearGraph(const Sequence& sequence,
+ const SharedNoiseModel& model) {
+ NonlinearFactorGraph graph;
+ Expression c(0);
+ typedef std::pair Sample;
+ BOOST_FOREACH(Sample sample, sequence) {
+ Expression expression(Fourier<3>(sample.first), c);
+ ExpressionFactor factor(model, sample.second, expression);
+ graph.add(factor);
+ }
+ return graph;
+ }
+
+ /// Create linear FG from Sequence
+ static GaussianFactorGraph::shared_ptr LinearGraph(const Sequence& sequence,
+ const SharedNoiseModel& model) {
+ NonlinearFactorGraph graph = NonlinearGraph(sequence, model);
+ Values values;
+ values.insert(0, Coefficients::Zero()); // does not matter
+ GaussianFactorGraph::shared_ptr gfg = graph.linearize(values);
+ return gfg;
+ }
+
+ /// Constructor
+ FourierDecomposition(const Sequence& sequence,
+ const SharedNoiseModel& model) {
+ GaussianFactorGraph::shared_ptr gfg = LinearGraph(sequence, model);
+ VectorValues solution = gfg->optimize();
+ c_ = solution.at(0);
+ }
+
+ /// Return Fourier coefficients
+ Coefficients coefficients() {
+ return c_;
+ }
+};
+
+}
+
+#include
+#include
+#include
+
+using namespace std;
+using namespace gtsam;
+
+noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1);
+
//******************************************************************************
TEST(BasisDecompositions, Fourier) {
Fourier<3> fx(0);
@@ -79,12 +140,14 @@ TEST(BasisDecompositions, Fourier) {
}
//******************************************************************************
-TEST(BasisDecompositions, FourierExpression) {
+TEST(BasisDecompositions, ManualFourier) {
// Create linear factor graph
GaussianFactorGraph g;
Key key(1);
- Vector3_ c(key);
+ Expression c(key);
+ Values values;
+ values.insert(key, Vector3::Zero()); // does not matter
for (size_t i = 0; i < 16; i++) {
double x = i * M_PI / 8, y = exp(sin(x) + cos(x));
@@ -93,13 +156,44 @@ TEST(BasisDecompositions, FourierExpression) {
A << 1, cos(x), sin(x);
Vector b(1);
b << y;
- JacobianFactor f1(key, A, b, model);
+ JacobianFactor f1(key, A, b);
+ g.add(f1);
// With ExpressionFactor
Expression expression(Fourier<3>(x), c);
- ExpressionFactor f2(model, y, expression);
-
- g.add(f1);
+ EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, 1e-5, 1e-9);
+ {
+ ExpressionFactor f2(model, y, expression);
+ boost::shared_ptr gf = f2.linearize(values);
+ boost::shared_ptr jf = //
+ boost::dynamic_pointer_cast(gf);
+ CHECK(jf);
+ EXPECT( assert_equal(f1, *jf, 1e-9));
+ }
+ {
+ ExpressionFactor f2(model, y, expression);
+ boost::shared_ptr gf = f2.linearize(values);
+ boost::shared_ptr jf = //
+ boost::dynamic_pointer_cast(gf);
+ CHECK(jf);
+ EXPECT( assert_equal(f1, *jf, 1e-9));
+ }
+ {
+ ExpressionFactor f2(model, y, expression);
+ boost::shared_ptr gf = f2.linearize(values);
+ boost::shared_ptr jf = //
+ boost::dynamic_pointer_cast(gf);
+ CHECK(jf);
+ EXPECT( assert_equal(f1, *jf, 1e-9));
+ }
+ {
+ ExpressionFactor f2(model, y, expression);
+ boost::shared_ptr gf = f2.linearize(values);
+ boost::shared_ptr jf = //
+ boost::dynamic_pointer_cast(gf);
+ CHECK(jf);
+ EXPECT( assert_equal(f1, *jf, 1e-9));
+ }
}
// Solve
@@ -110,6 +204,24 @@ TEST(BasisDecompositions, FourierExpression) {
EXPECT(assert_equal((Vector) expected, actual.at(key),1e-4));
}
+//******************************************************************************
+TEST(BasisDecompositions, FourierDecomposition) {
+
+ // Create example sequence
+ Sequence sequence;
+ for (size_t i = 0; i < 16; i++) {
+ double x = i * M_PI / 8, y = exp(sin(x) + cos(x));
+ sequence[x] = y;
+ }
+
+ // Do Fourier Decomposition
+ FourierDecomposition actual(sequence, model);
+
+ // Check
+ Vector3 expected(1.5661, 1.2717, 1.2717);
+ EXPECT(assert_equal((Vector) expected, actual.coefficients(),1e-4));
+}
+
//******************************************************************************
int main() {
TestResult tr;
diff --git a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp
index a4561b349..1cc674901 100644
--- a/gtsam_unstable/nonlinear/tests/testCallRecord.cpp
+++ b/gtsam_unstable/nonlinear/tests/testCallRecord.cpp
@@ -33,7 +33,7 @@ static const int Cols = 3;
int dynamicIfAboveMax(int i){
- if(i > MaxVirtualStaticRows){
+ if(i > CallRecordMaxVirtualStaticRows){
return Eigen::Dynamic;
}
else return i;
@@ -43,7 +43,6 @@ struct CallConfig {
int compTimeCols;
int runTimeRows;
int runTimeCols;
- CallConfig() {}
CallConfig(int rows, int cols):
compTimeRows(dynamicIfAboveMax(rows)),
compTimeCols(cols),
@@ -72,25 +71,26 @@ struct CallConfig {
};
struct Record: public internal::CallRecordImplementor {
+ Record() : cc(0, 0) {}
virtual ~Record() {
}
void print(const std::string& indent) const {
}
- void startReverseAD(JacobianMap& jacobians) const {
+ void startReverseAD4(JacobianMap& jacobians) const {
}
mutable CallConfig cc;
private:
template
- void reverseAD(const SomeMatrix & dFdT, JacobianMap& jacobians) const {
+ void reverseAD4(const SomeMatrix & dFdT, JacobianMap& jacobians) const {
cc.compTimeRows = SomeMatrix::RowsAtCompileTime;
cc.compTimeCols = SomeMatrix::ColsAtCompileTime;
cc.runTimeRows = dFdT.rows();
cc.runTimeCols = dFdT.cols();
}
- template
- friend struct internal::ReverseADImplementor;
+ template
+ friend struct internal::CallRecordImplementor;
};
JacobianMap & NJM= *static_cast(NULL);
@@ -102,56 +102,56 @@ TEST(CallRecord, virtualReverseAdDispatching) {
Record record;
{
const int Rows = 1;
- record.CallRecord::reverseAD(Eigen::Matrix(), NJM);
+ record.CallRecord::reverseAD2(Eigen::Matrix(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
- record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
- record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols))));
}
{
const int Rows = 2;
- record.CallRecord::reverseAD(Eigen::Matrix(), NJM);
+ record.CallRecord::reverseAD2(Eigen::Matrix(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
- record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
- record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols))));
}
{
const int Rows = 3;
- record.CallRecord::reverseAD(Eigen::Matrix(), NJM);
+ record.CallRecord::reverseAD2(Eigen::Matrix(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
- record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
- record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols))));
}
{
- const int Rows = MaxVirtualStaticRows;
- record.CallRecord::reverseAD(Eigen::Matrix(), NJM);
+ const int Rows = 4;
+ record.CallRecord::reverseAD2(Eigen::Matrix(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
- record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
- record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols))));
}
{
- const int Rows = MaxVirtualStaticRows + 1;
- record.CallRecord::reverseAD(Eigen::Matrix(), NJM);
+ const int Rows = 5;
+ record.CallRecord::reverseAD2(Eigen::Matrix(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
- record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
- record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols))));
}
{
- const int Rows = MaxVirtualStaticRows + 2;
- record.CallRecord::reverseAD(Eigen::Matrix(), NJM);
+ const int Rows = 6;
+ record.CallRecord::reverseAD2(Eigen::Matrix(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
- record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
- record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM);
+ record.CallRecord::reverseAD2(Eigen::MatrixXd(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols))));
}
}
diff --git a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp
index d146ea945..09cad558a 100644
--- a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp
+++ b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp
@@ -76,10 +76,13 @@ TEST(ExpressionFactor, Model) {
// Concise version
ExpressionFactor f(model, Point2(0, 0), p);
+
+ // Check values and derivatives
EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9);
EXPECT_LONGS_EQUAL(2, f.dim());
boost::shared_ptr gf2 = f.linearize(values);
EXPECT( assert_equal(*old.linearize(values), *gf2, 1e-9));
+ EXPECT_CORRECT_FACTOR_JACOBIANS(f, values, 1e-5, 1e-5); // another way
}
/* ************************************************************************* */
@@ -124,6 +127,38 @@ TEST(ExpressionFactor, Unary) {
EXPECT( assert_equal(expected, *jf, 1e-9));
}
+/* ************************************************************************* */
+// Unary(Leaf)) and Unary(Unary(Leaf)))
+// wide version (not handled in fixed-size pipeline)
+typedef Eigen::Matrix Matrix93;
+Vector9 wide(const Point3& p, boost::optional H) {
+ Vector9 v;
+ v << p.vector(), p.vector(), p.vector();
+ if (H) *H << eye(3), eye(3), eye(3);
+ return v;
+}
+typedef Eigen::Matrix Matrix9;
+Vector9 id9(const Vector9& v, boost::optional H) {
+ if (H) *H = Matrix9::Identity();
+ return v;
+}
+TEST(ExpressionFactor, Wide) {
+ // Create some values
+ Values values;
+ values.insert(2, Point3(0, 0, 1));
+ Point3_ point(2);
+ Vector9 measured;
+ Expression expression(wide,point);
+ SharedNoiseModel model = noiseModel::Unit::Create(9);
+
+ ExpressionFactor f1(model, measured, expression);
+ EXPECT_CORRECT_FACTOR_JACOBIANS(f1, values, 1e-5, 1e-9);
+
+ Expression expression2(id9,expression);
+ ExpressionFactor f2(model, measured, expression2);
+ EXPECT_CORRECT_FACTOR_JACOBIANS(f2, values, 1e-5, 1e-9);
+}
+
/* ************************************************************************* */
static Point2 myUncal(const Cal3_S2& K, const Point2& p,
boost::optional Dcal, boost::optional Dp) {
diff --git a/matlab/gtsam_tests/.gitignore b/matlab/gtsam_tests/.gitignore
new file mode 100644
index 000000000..6d725d9bc
--- /dev/null
+++ b/matlab/gtsam_tests/.gitignore
@@ -0,0 +1 @@
+*.m~
diff --git a/matlab/gtsam_tests/testValues.m b/matlab/gtsam_tests/testValues.m
new file mode 100644
index 000000000..fe2cd30fe
--- /dev/null
+++ b/matlab/gtsam_tests/testValues.m
@@ -0,0 +1,40 @@
+% test wrapping of Values
+import gtsam.*;
+
+values = Values;
+E = EssentialMatrix(Rot3,Unit3);
+tol = 1e-9;
+
+values.insert(0, Point2);
+values.insert(1, Point3);
+values.insert(2, Rot2);
+values.insert(3, Pose2);
+values.insert(4, Rot3);
+values.insert(5, Pose3);
+values.insert(6, Cal3_S2);
+values.insert(7, Cal3DS2);
+values.insert(8, Cal3Bundler);
+values.insert(9, E);
+values.insert(10, imuBias.ConstantBias);
+
+% special cases for Vector and Matrix:
+values.insert(11, [1;2;3]);
+values.insert(12, [1 2;3 4]);
+
+EXPECT('at',values.atPoint2(0).equals(Point2,tol));
+EXPECT('at',values.atPoint3(1).equals(Point3,tol));
+EXPECT('at',values.atRot2(2).equals(Rot2,tol));
+EXPECT('at',values.atPose2(3).equals(Pose2,tol));
+EXPECT('at',values.atRot3(4).equals(Rot3,tol));
+EXPECT('at',values.atPose3(5).equals(Pose3,tol));
+EXPECT('at',values.atCal3_S2(6).equals(Cal3_S2,tol));
+EXPECT('at',values.atCal3DS2(7).equals(Cal3DS2,tol));
+EXPECT('at',values.atCal3Bundler(8).equals(Cal3Bundler,tol));
+EXPECT('at',values.atEssentialMatrix(9).equals(E,tol));
+EXPECT('at',values.atConstantBias(10).equals(imuBias.ConstantBias,tol));
+
+% special cases for Vector and Matrix:
+actualVector = values.atVector(11);
+EQUALITY('at',[1;2;3],actualVector,tol);
+actualMatrix = values.atMatrix(12);
+EQUALITY('at',[1 2;3 4],actualMatrix,tol);
diff --git a/matlab/gtsam_tests/test_gtsam.m b/matlab/gtsam_tests/test_gtsam.m
index e3705948d..e08019610 100644
--- a/matlab/gtsam_tests/test_gtsam.m
+++ b/matlab/gtsam_tests/test_gtsam.m
@@ -1,5 +1,8 @@
% Test runner script - runs each test
+display 'Starting: testValues'
+testValues
+
display 'Starting: testJacobianFactor'
testJacobianFactor
diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp
index 4989afb0d..1f57917d8 100644
--- a/wrap/Argument.cpp
+++ b/wrap/Argument.cpp
@@ -20,6 +20,7 @@
#include
#include
+#include
#include
#include
@@ -31,12 +32,13 @@ using namespace wrap;
/* ************************************************************************* */
Argument Argument::expandTemplate(const TemplateSubstitution& ts) const {
Argument instArg = *this;
- instArg.type = ts(type);
+ instArg.type = ts.tryToSubstitite(type);
return instArg;
}
/* ************************************************************************* */
-ArgumentList ArgumentList::expandTemplate(const TemplateSubstitution& ts) const {
+ArgumentList ArgumentList::expandTemplate(
+ const TemplateSubstitution& ts) const {
ArgumentList instArgList;
BOOST_FOREACH(const Argument& arg, *this) {
Argument instArg = arg.expandTemplate(ts);
@@ -48,25 +50,25 @@ ArgumentList ArgumentList::expandTemplate(const TemplateSubstitution& ts) const
/* ************************************************************************* */
string Argument::matlabClass(const string& delim) const {
string result;
- BOOST_FOREACH(const string& ns, type.namespaces)
+ BOOST_FOREACH(const string& ns, type.namespaces())
result += ns + delim;
- if (type.name == "string" || type.name == "unsigned char"
- || type.name == "char")
+ if (type.name() == "string" || type.name() == "unsigned char"
+ || type.name() == "char")
return result + "char";
- if (type.name == "Vector" || type.name == "Matrix")
+ if (type.name() == "Vector" || type.name() == "Matrix")
return result + "double";
- if (type.name == "int" || type.name == "size_t")
+ if (type.name() == "int" || type.name() == "size_t")
return result + "numeric";
- if (type.name == "bool")
+ if (type.name() == "bool")
return result + "logical";
- return result + type.name;
+ return result + type.name();
}
/* ************************************************************************* */
bool Argument::isScalar() const {
- return (type.name == "bool" || type.name == "char"
- || type.name == "unsigned char" || type.name == "int"
- || type.name == "size_t" || type.name == "double");
+ return (type.name() == "bool" || type.name() == "char"
+ || type.name() == "unsigned char" || type.name() == "int"
+ || type.name() == "size_t" || type.name() == "double");
}
/* ************************************************************************* */
@@ -97,6 +99,13 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const {
file.oss << ");" << endl;
}
+/* ************************************************************************* */
+void Argument::proxy_check(FileWriter& proxyFile, const string& s) const {
+ proxyFile.oss << "isa(" << s << ",'" << matlabClass(".") << "')";
+ if (type.name() == "Vector")
+ proxyFile.oss << " && size(" << s << ",2)==1";
+}
+
/* ************************************************************************* */
string ArgumentList::types() const {
string str;
@@ -104,7 +113,7 @@ string ArgumentList::types() const {
BOOST_FOREACH(Argument arg, *this) {
if (!first)
str += ",";
- str += arg.type.name;
+ str += arg.type.name();
first = false;
}
return str;
@@ -116,14 +125,14 @@ string ArgumentList::signature() const {
bool cap = false;
BOOST_FOREACH(Argument arg, *this) {
- BOOST_FOREACH(char ch, arg.type.name)
+ BOOST_FOREACH(char ch, arg.type.name())
if (isupper(ch)) {
sig += ch;
//If there is a capital letter, we don't want to read it below
cap = true;
}
if (!cap)
- sig += arg.type.name[0];
+ sig += arg.type.name()[0];
//Reset to default
cap = false;
}
@@ -170,25 +179,14 @@ void ArgumentList::emit_prototype(FileWriter& file, const string& name) const {
BOOST_FOREACH(Argument arg, *this) {
if (!first)
file.oss << ", ";
- file.oss << arg.type.name << " " << arg.name;
+ file.oss << arg.type.name() << " " << arg.name;
first = false;
}
file.oss << ")";
}
+
/* ************************************************************************* */
-void ArgumentList::emit_call(FileWriter& proxyFile,
- const ReturnValue& returnVal, const string& wrapperName, int id,
- bool staticMethod) const {
- returnVal.emit_matlab(proxyFile);
- proxyFile.oss << wrapperName << "(" << id;
- if (!staticMethod)
- proxyFile.oss << ", this";
- proxyFile.oss << ", varargin{:});\n";
-}
-/* ************************************************************************* */
-void ArgumentList::emit_conditional_call(FileWriter& proxyFile,
- const ReturnValue& returnVal, const string& wrapperName, int id,
- bool staticMethod) const {
+void ArgumentList::proxy_check(FileWriter& proxyFile) const {
// Check nr of arguments
proxyFile.oss << "if length(varargin) == " << size();
if (size() > 0)
@@ -198,15 +196,12 @@ void ArgumentList::emit_conditional_call(FileWriter& proxyFile,
for (size_t i = 0; i < size(); i++) {
if (!first)
proxyFile.oss << " && ";
- proxyFile.oss << "isa(varargin{" << i + 1 << "},'"
- << (*this)[i].matlabClass(".") << "')";
+ string s = "varargin{" + boost::lexical_cast(i + 1) + "}";
+ (*this)[i].proxy_check(proxyFile, s);
first = false;
}
proxyFile.oss << "\n";
-
- // output call to C++ wrapper
- proxyFile.oss << " ";
- emit_call(proxyFile, returnVal, wrapperName, id, staticMethod);
}
+
/* ************************************************************************* */
diff --git a/wrap/Argument.h b/wrap/Argument.h
index 3d8d7288f..3b7a13ee3 100644
--- a/wrap/Argument.h
+++ b/wrap/Argument.h
@@ -28,13 +28,23 @@ namespace wrap {
/// Argument class
struct Argument {
Qualified type;
- bool is_const, is_ref, is_ptr;
std::string name;
+ bool is_const, is_ref, is_ptr;
Argument() :
is_const(false), is_ref(false), is_ptr(false) {
}
+ Argument(const Qualified& t, const std::string& n) :
+ type(t), name(n), is_const(false), is_ref(false), is_ptr(false) {
+ }
+
+ bool operator==(const Argument& other) const {
+ return type == other.type && name == other.name
+ && is_const == other.is_const && is_ref == other.is_ref
+ && is_ptr == other.is_ptr;
+ }
+
Argument expandTemplate(const TemplateSubstitution& ts) const;
/// return MATLAB class for use in isa(x,class)
@@ -46,6 +56,12 @@ struct Argument {
/// MATLAB code generation, MATLAB to C++
void matlab_unwrap(FileWriter& file, const std::string& matlabName) const;
+ /**
+ * emit checking argument to MATLAB proxy
+ * @param proxyFile output stream
+ */
+ void proxy_check(FileWriter& proxyFile, const std::string& s) const;
+
friend std::ostream& operator<<(std::ostream& os, const Argument& arg) {
os << (arg.is_const ? "const " : "") << arg.type << (arg.is_ptr ? "*" : "")
<< (arg.is_ref ? "&" : "");
@@ -88,26 +104,12 @@ struct ArgumentList: public std::vector {
void emit_prototype(FileWriter& file, const std::string& name) const;
/**
- * emit emit MATLAB call to proxy
+ * emit checking arguments to MATLAB proxy
* @param proxyFile output stream
- * @param returnVal the return value
- * @param wrapperName of method or function
- * @param staticMethod flag to emit "this" in call
*/
- void emit_call(FileWriter& proxyFile, const ReturnValue& returnVal,
- const std::string& wrapperName, int id, bool staticMethod = false) const;
-
- /**
- * emit conditional MATLAB call to proxy (checking arguments first)
- * @param proxyFile output stream
- * @param returnVal the return value
- * @param wrapperName of method or function
- * @param staticMethod flag to emit "this" in call
- */
- void emit_conditional_call(FileWriter& proxyFile,
- const ReturnValue& returnVal, const std::string& wrapperName, int id,
- bool staticMethod = false) const;
+ void proxy_check(FileWriter& proxyFile) const;
+ /// Output stream operator
friend std::ostream& operator<<(std::ostream& os,
const ArgumentList& argList) {
os << "(";
@@ -122,5 +124,87 @@ struct ArgumentList: public std::vector {
};
-} // \namespace wrap
+/* ************************************************************************* */
+// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html
+struct ArgumentGrammar: public classic::grammar {
+
+ wrap::Argument& result_; ///< successful parse will be placed in here
+ TypeGrammar argument_type_g; ///< Type parser for Argument::type
+
+ /// Construct type grammar and specify where result is placed
+ ArgumentGrammar(wrap::Argument& result) :
+ result_(result), argument_type_g(result.type) {
+ }
+
+ /// Definition of type grammar
+ template
+ struct definition: BasicRules {
+
+ typedef classic::rule Rule;
+
+ Rule argument_p;
+
+ definition(ArgumentGrammar const& self) {
+ using namespace classic;
+
+ // NOTE: allows for pointers to all types
+ // Slightly more permissive than before on basis/eigen type qualification
+ // Also, currently parses Point2*&, can't make it work otherwise :-(
+ argument_p = !str_p("const")[assign_a(self.result_.is_const, T)] //
+ >> self.argument_type_g //
+ >> !ch_p('*')[assign_a(self.result_.is_ptr, T)]
+ >> !ch_p('&')[assign_a(self.result_.is_ref, T)]
+ >> BasicRules::name_p[assign_a(self.result_.name)];
+ }
+
+ Rule const& start() const {
+ return argument_p;
+ }
+
+ };
+};
+// ArgumentGrammar
+
+/* ************************************************************************* */
+// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html
+struct ArgumentListGrammar: public classic::grammar {
+
+ wrap::ArgumentList& result_; ///< successful parse will be placed in here
+
+ const Argument arg0; ///< used to reset arg
+ mutable Argument arg; ///< temporary argument for use during parsing
+ ArgumentGrammar argument_g; ///< single Argument parser
+
+ /// Construct type grammar and specify where result is placed
+ ArgumentListGrammar(wrap::ArgumentList& result) :
+ result_(result), argument_g(arg) {
+ }
+
+ /// Definition of type grammar
+ template
+ struct definition {
+
+ classic::rule argument_p, argumentList_p;
+
+ definition(ArgumentListGrammar const& self) {
+ using namespace classic;
+
+ argument_p = self.argument_g //
+ [classic::push_back_a(self.result_, self.arg)] //
+ [assign_a(self.arg, self.arg0)];
+
+ argumentList_p = '(' >> !argument_p >> *(',' >> argument_p) >> ')';
+ }
+
+ classic::rule const& start() const {
+ return argumentList_p;
+ }
+
+ };
+};
+// ArgumentListGrammar
+
+/* ************************************************************************* */
+
+}// \namespace wrap
diff --git a/wrap/Class.cpp b/wrap/Class.cpp
index 0e480f0fd..6e415065d 100644
--- a/wrap/Class.cpp
+++ b/wrap/Class.cpp
@@ -22,23 +22,68 @@
#include
#include
+#include
+#include
#include
#include
#include
+#include // std::ostream_iterator
//#include // on Linux GCC: fails with error regarding needing C++0x std flags
//#include // same failure as above
#include // works on Linux GCC
using namespace std;
using namespace wrap;
+/* ************************************************************************* */
+void Class::assignParent(const Qualified& parent) {
+ parentClass.reset(parent);
+}
+
+/* ************************************************************************* */
+boost::optional