Merge remote-tracking branch 'origin/develop' into feature/AHRSFactor

Conflicts:
	gtsam/navigation/tests/testMagFactor.cpp
release/4.3a0
krunalchande 2014-11-22 17:25:31 -05:00
commit 056aed4419
31 changed files with 1100 additions and 545 deletions

106
.cproject
View File

@ -600,6 +600,7 @@
</target>
<target name="tests/testBayesTree.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>tests/testBayesTree.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -607,6 +608,7 @@
</target>
<target name="testBinaryBayesNet.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testBinaryBayesNet.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -654,6 +656,7 @@
</target>
<target name="testSymbolicBayesNet.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testSymbolicBayesNet.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -661,6 +664,7 @@
</target>
<target name="tests/testSymbolicFactor.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>tests/testSymbolicFactor.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -668,6 +672,7 @@
</target>
<target name="testSymbolicFactorGraph.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testSymbolicFactorGraph.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -683,6 +688,7 @@
</target>
<target name="tests/testBayesTree" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>tests/testBayesTree</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1130,6 +1136,7 @@
</target>
<target name="testErrors.run" path="linear" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testErrors.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1359,6 +1366,46 @@
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testBTree.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testBTree.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testDSF.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testDSF.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testDSFMap.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testDSFMap.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testDSFVector.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testDSFVector.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testFixedVector.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testFixedVector.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="all" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j2</buildArguments>
@ -1441,7 +1488,6 @@
</target>
<target name="testSimulated2DOriented.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testSimulated2DOriented.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1481,7 +1527,6 @@
</target>
<target name="testSimulated2D.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testSimulated2D.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1489,7 +1534,6 @@
</target>
<target name="testSimulated3D.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testSimulated3D.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1503,46 +1547,6 @@
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testBTree.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testBTree.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testDSF.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testDSF.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testDSFMap.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testDSFMap.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testDSFVector.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testDSFVector.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testFixedVector.run" path="build/gtsam_unstable/base/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testFixedVector.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testEliminationTree.run" path="build/gtsam/inference/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
@ -1800,6 +1804,7 @@
</target>
<target name="Generate DEB Package" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>cpack</buildCommand>
<buildArguments/>
<buildTarget>-G DEB</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1807,6 +1812,7 @@
</target>
<target name="Generate RPM Package" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>cpack</buildCommand>
<buildArguments/>
<buildTarget>-G RPM</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1814,6 +1820,7 @@
</target>
<target name="Generate TGZ Package" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>cpack</buildCommand>
<buildArguments/>
<buildTarget>-G TGZ</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -1821,6 +1828,7 @@
</target>
<target name="Generate TGZ Source Package" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>cpack</buildCommand>
<buildArguments/>
<buildTarget>--config CPackSourceConfig.cmake</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -2651,6 +2659,7 @@
</target>
<target name="testGraph.run" path="build/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testGraph.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -2658,6 +2667,7 @@
</target>
<target name="testJunctionTree.run" path="build/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testJunctionTree.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -2665,6 +2675,7 @@
</target>
<target name="testSymbolicBayesNetB.run" path="build/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>testSymbolicBayesNetB.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>
@ -2774,6 +2785,14 @@
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testCallRecord.run" path="build/gtsam_unstable/nonlinear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>
<buildTarget>testCallRecord.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testGaussianFactor.run" path="build/linear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j2</buildArguments>
@ -3184,7 +3203,6 @@
</target>
<target name="tests/testGaussianISAM2" path="build/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>tests/testGaussianISAM2</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>false</useDefaultCommand>

View File

@ -48,7 +48,7 @@ Point3 bias(10, -10, 50);
Point3 scaled = scale * nM;
Point3 measured = nRb.inverse() * (scale * nM) + bias;
double s = (scale * nM.norm());
double s(scale * nM.norm());
Unit3 dir(nM);
SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25);

View File

@ -215,7 +215,7 @@ namespace gtsam {
Values::Values(const Values::ConstFiltered<ValueType>& view) {
BOOST_FOREACH(const typename ConstFiltered<ValueType>::KeyValuePair& key_value, view) {
Key key = key_value.key;
insert<ValueType>(key, key_value.value);
insert(key, static_cast<const ValueType&>(key_value.value));
}
}

View File

@ -383,6 +383,12 @@ TEST(Values, filter) {
expectedSubValues1.insert(3, pose3);
EXPECT(assert_equal(expectedSubValues1, actualSubValues1));
// ConstFilter by Key
Values::ConstFiltered<Value> constfiltered = values.filter(boost::bind(std::greater_equal<Key>(), _1, 2));
EXPECT_LONGS_EQUAL(2, (long)constfiltered.size());
Values fromconstfiltered(constfiltered);
EXPECT(assert_equal(expectedSubValues1, fromconstfiltered));
// Filter by type
i = 0;
Values::ConstFiltered<Pose3> pose_filtered = values.filter<Pose3>();

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file Pose2SLAMExample.cpp
* @file Pose2SLAMExampleExpressions.cpp
* @brief Expressions version of Pose2SLAMExample.cpp
* @date Oct 2, 2014
* @author Frank Dellaert

View File

@ -0,0 +1,190 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file CallRecord.h
* @date November 21, 2014
* @author Frank Dellaert
* @author Paul Furgale
* @author Hannes Sommer
* @brief Internals for Expression.h, not for general consumption
*/
#pragma once
#include <gtsam/base/VerticalBlockMatrix.h>
#include <gtsam/base/FastVector.h>
#include <gtsam/base/Matrix.h>
#include <boost/mpl/transform.hpp>
namespace gtsam {
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 {
/**
* ConvertToDynamicIf converts to a dense matrix with dynamic rows iff
* ConvertToDynamicRows (colums stay as they are) otherwise
* it just passes dense Eigen matrices through.
*/
template<bool ConvertToDynamicRows>
struct ConvertToDynamicRowsIf {
template<typename Derived>
static Eigen::Matrix<double, Eigen::Dynamic, Derived::ColsAtCompileTime> convert(
const Eigen::MatrixBase<Derived> & x) {
return x;
}
};
template<>
struct ConvertToDynamicRowsIf<false> {
template<int Rows, int Cols>
static const Eigen::Matrix<double, Rows, Cols> & convert(
const Eigen::Matrix<double, Rows, Cols> & x) {
return x;
}
};
/**
* Recursive definition of an interface having several purely
* virtual _reverseAD(const Eigen::Matrix<double, Rows, Cols> &, JacobianMap&)
* with Rows in 1..MaxSupportedStaticRows
*/
template<int MaxSupportedStaticRows, int Cols>
struct ReverseADInterface: ReverseADInterface<MaxSupportedStaticRows - 1, Cols> {
using ReverseADInterface<MaxSupportedStaticRows - 1, Cols>::_reverseAD;
virtual void _reverseAD(
const Eigen::Matrix<double, MaxSupportedStaticRows, Cols> & dFdT,
JacobianMap& jacobians) const = 0;
};
template<int Cols>
struct ReverseADInterface<0, Cols> {
virtual void _reverseAD(
const Eigen::Matrix<double, Eigen::Dynamic, Cols> & 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<typename Derived, int MaxSupportedStaticRows, int Cols>
struct ReverseADImplementor: ReverseADImplementor<Derived,
MaxSupportedStaticRows - 1, Cols> {
private:
using ReverseADImplementor<Derived, MaxSupportedStaticRows - 1, Cols>::_reverseAD;
virtual void _reverseAD(
const Eigen::Matrix<double, MaxSupportedStaticRows, Cols> & dFdT,
JacobianMap& jacobians) const {
static_cast<const Derived *>(this)->reverseAD(dFdT, jacobians);
}
friend struct internal::ReverseADImplementor<Derived,
MaxSupportedStaticRows + 1, Cols>;
};
template<typename Derived, int Cols>
struct ReverseADImplementor<Derived, 0, Cols> : virtual internal::ReverseADInterface<
MaxVirtualStaticRows, Cols> {
private:
using internal::ReverseADInterface<MaxVirtualStaticRows, Cols>::_reverseAD;
const Derived & derived() const {
return static_cast<const Derived&>(*this);
}
virtual void _reverseAD(
const Eigen::Matrix<double, Eigen::Dynamic, Cols> & 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<Derived, 1, Cols>;
};
} // 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.
*/
template<int Cols>
struct CallRecord: virtual private internal::ReverseADInterface<
MaxVirtualStaticRows, Cols> {
inline void print(const std::string& indent) const {
_print(indent);
}
inline void startReverseAD(JacobianMap& jacobians) const {
_startReverseAD(jacobians);
}
template<int Rows>
inline void reverseAD(const Eigen::Matrix<double, Rows, Cols> & dFdT,
JacobianMap& jacobians) const {
_reverseAD(
internal::ConvertToDynamicRowsIf<(Rows > MaxVirtualStaticRows)>::convert(
dFdT), jacobians);
}
inline void reverseAD(const Matrix & dFdT, JacobianMap& jacobians) const {
_reverseAD(dFdT, jacobians);
}
virtual ~CallRecord() {
}
private:
virtual void _print(const std::string& indent) const = 0;
virtual void _startReverseAD(JacobianMap& jacobians) const = 0;
using internal::ReverseADInterface<MaxVirtualStaticRows, Cols>::_reverseAD;
};
namespace internal {
/**
* The CallRecordImplementor implements the CallRecord interface for a Derived class by
* delegating to its corresponding (templated) non-virtual methods.
*/
template<typename Derived, int Cols>
struct CallRecordImplementor: public CallRecord<Cols>,
private ReverseADImplementor<Derived, MaxVirtualStaticRows, Cols> {
private:
const Derived & derived() const {
return static_cast<const Derived&>(*this);
}
virtual void _print(const std::string& indent) const {
derived().print(indent);
}
virtual void _startReverseAD(JacobianMap& jacobians) const {
derived().startReverseAD(jacobians);
}
template<typename D, int R, int C> friend struct ReverseADImplementor;
};
} // namespace internal
} // gtsam

View File

@ -19,29 +19,21 @@
#pragma once
#include <gtsam_unstable/nonlinear/CallRecord.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/Manifold.h>
#include <gtsam/base/VerticalBlockMatrix.h>
#include <boost/foreach.hpp>
#include <boost/tuple/tuple.hpp>
#include <boost/bind.hpp>
// template meta-programming headers
#include <boost/mpl/vector.hpp>
#include <boost/mpl/plus.hpp>
#include <boost/mpl/front.hpp>
#include <boost/mpl/pop_front.hpp>
#include <boost/mpl/fold.hpp>
#include <boost/mpl/empty_base.hpp>
#include <boost/mpl/placeholders.hpp>
#include <boost/mpl/transform.hpp>
#include <boost/mpl/at.hpp>
namespace MPL = boost::mpl::placeholders;
#include <new> // for placement new
#include <map>
class ExpressionFactorBinaryTest;
// Forward declare for testing
@ -71,29 +63,6 @@ public:
}
};
//-----------------------------------------------------------------------------
/**
* The CallRecord class stores the Jacobians of applying a function
* with respect to each of its arguments. It also stores an executation trace
* (defined below) for each of its arguments.
*
* It is sub-classed in the function-style ExpressionNode sub-classes below.
*/
template<int COLS>
struct CallRecord {
static size_t const N = 0;
virtual void print(const std::string& indent) const {
}
virtual void startReverseAD(JacobianMap& jacobians) const {
}
virtual void reverseAD(const Matrix& dFdT, JacobianMap& jacobians) const {
}
typedef Eigen::Matrix<double, 2, COLS> Jacobian2T;
virtual void reverseAD2(const Jacobian2T& dFdT,
JacobianMap& jacobians) const {
}
};
//-----------------------------------------------------------------------------
/// Handle Leaf Case: reverseAD ends here, by writing a matrix into Jacobians
template<int ROWS, int COLS>
@ -101,10 +70,10 @@ void handleLeafCase(const Eigen::Matrix<double, ROWS, COLS>& dTdA,
JacobianMap& jacobians, Key key) {
jacobians(key).block<ROWS, COLS>(0, 0) += dTdA; // block makes HUGE difference
}
/// Handle Leaf Case for Dynamic Matrix type (slower)
template<>
/// Handle Leaf Case for Dynamic ROWS Matrix type (slower)
template<int COLS>
inline void handleLeafCase(
const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>& dTdA,
const Eigen::Matrix<double, Eigen::Dynamic, COLS>& dTdA,
JacobianMap& jacobians, Key key) {
jacobians(key) += dTdA;
}
@ -193,45 +162,19 @@ public:
content.ptr->startReverseAD(jacobians);
}
// Either add to Jacobians (Leaf) or propagate (Function)
void reverseAD(const Matrix& dTdA, JacobianMap& jacobians) const {
template<typename DerivedMatrix>
void reverseAD(const Eigen::MatrixBase<DerivedMatrix> & dTdA,
JacobianMap& jacobians) const {
if (kind == Leaf)
handleLeafCase(dTdA, jacobians, content.key);
handleLeafCase(dTdA.eval(), jacobians, content.key);
else if (kind == Function)
content.ptr->reverseAD(dTdA, jacobians);
}
// Either add to Jacobians (Leaf) or propagate (Function)
typedef Eigen::Matrix<double, 2, Dim> Jacobian2T;
void reverseAD2(const Jacobian2T& dTdA, JacobianMap& jacobians) const {
if (kind == Leaf)
handleLeafCase(dTdA, jacobians, content.key);
else if (kind == Function)
content.ptr->reverseAD2(dTdA, jacobians);
content.ptr->reverseAD(dTdA.eval(), jacobians);
}
/// Define type so we can apply it as a meta-function
typedef ExecutionTrace<T> type;
};
/// Primary template calls the generic Matrix reverseAD pipeline
template<size_t ROWS, class A>
struct Select {
typedef Eigen::Matrix<double, ROWS, traits::dimension<A>::value> Jacobian;
static void reverseAD(const ExecutionTrace<A>& trace, const Jacobian& dTdA,
JacobianMap& jacobians) {
trace.reverseAD(dTdA, jacobians);
}
};
/// Partially specialized template calls the 2-dimensional output version
template<class A>
struct Select<2, A> {
typedef Eigen::Matrix<double, 2, traits::dimension<A>::value> Jacobian;
static void reverseAD(const ExecutionTrace<A>& trace, const Jacobian& dTdA,
JacobianMap& jacobians) {
trace.reverseAD2(dTdA, jacobians);
}
};
//-----------------------------------------------------------------------------
/**
* Expression node. The superclass for objects that do the heavy lifting
@ -479,8 +422,15 @@ template<class T>
struct FunctionalBase: ExpressionNode<T> {
static size_t const N = 0; // number of arguments
typedef CallRecord<traits::dimension<T>::value> Record;
struct Record {
void print(const std::string& indent) const {
}
void startReverseAD(JacobianMap& jacobians) const {
}
template<typename SomeMatrix>
void reverseAD(const SomeMatrix & dFdT, JacobianMap& jacobians) const {
}
};
/// Construct an execution trace for reverse AD
void trace(const Values& values, Record* record, char*& raw) const {
// base case: does not do anything
@ -539,7 +489,7 @@ struct GenerateFunctionalNode: Argument<T, A, Base::N + 1>, Base {
typedef JacobianTrace<T, A, N> This;
/// Print to std::cout
virtual void print(const std::string& indent) const {
void print(const std::string& indent) const {
Base::Record::print(indent);
static const Eigen::IOFormat matlab(0, 1, " ", "; ", "", "", "[", "]");
std::cout << This::dTdA.format(matlab) << std::endl;
@ -547,25 +497,18 @@ struct GenerateFunctionalNode: Argument<T, A, Base::N + 1>, Base {
}
/// Start the reverse AD process
virtual void startReverseAD(JacobianMap& jacobians) const {
void startReverseAD(JacobianMap& jacobians) const {
Base::Record::startReverseAD(jacobians);
Select<traits::dimension<T>::value, A>::reverseAD(This::trace, This::dTdA,
jacobians);
This::trace.reverseAD(This::dTdA, jacobians);
}
/// Given df/dT, multiply in dT/dA and continue reverse AD process
virtual void reverseAD(const Matrix& dFdT, JacobianMap& jacobians) const {
template<int Rows, int Cols>
void reverseAD(const Eigen::Matrix<double, Rows, Cols> & dFdT,
JacobianMap& jacobians) const {
Base::Record::reverseAD(dFdT, jacobians);
This::trace.reverseAD(dFdT * This::dTdA, jacobians);
}
/// Version specialized to 2-dimensional output
typedef Eigen::Matrix<double, 2, traits::dimension<T>::value> Jacobian2T;
virtual void reverseAD2(const Jacobian2T& dFdT,
JacobianMap& jacobians) const {
Base::Record::reverseAD2(dFdT, jacobians);
This::trace.reverseAD2(dFdT * This::dTdA, jacobians);
}
};
/// Construct an execution trace for reverse AD
@ -619,8 +562,16 @@ struct FunctionalNode {
return static_cast<Argument<T, A, N> const &>(*this).expression;
}
/// Provide convenience access to Record storage
struct Record: public Base::Record {
/// Provide convenience access to Record storage and implement
/// the virtual function based interface of CallRecord using the CallRecordImplementor
struct Record: public internal::CallRecordImplementor<Record,
traits::dimension<T>::value>, public Base::Record {
using Base::Record::print;
using Base::Record::startReverseAD;
using Base::Record::reverseAD;
virtual ~Record() {
}
/// Access Value
template<class A, size_t N>
@ -633,7 +584,6 @@ struct FunctionalNode {
typename Jacobian<T, A>::type& jacobian() {
return static_cast<JacobianTrace<T, A, N>&>(*this).dTdA;
}
};
/// Construct an execution trace for reverse AD

View File

@ -116,7 +116,7 @@ public:
return root_->traceSize();
}
/// trace execution, very unsafe, for testing purposes only
/// trace execution, very unsafe, for testing purposes only //TODO this is not only used for testing, but in value() below!
T traceExecution(const Values& values, ExecutionTrace<T>& trace,
char* raw) const {
return root_->traceExecution(values, trace, raw);

View File

@ -0,0 +1,165 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------1------------------------------------------- */
/**
* @file testCallRecord.cpp
* @date November 21, 2014
* @author Frank Dellaert
* @author Paul Furgale
* @author Hannes Sommer
* @brief unit tests for CallRecord class
*/
#include <gtsam_unstable/nonlinear/CallRecord.h>
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h>
using namespace std;
using namespace gtsam;
/* ************************************************************************* */
static const int Cols = 3;
int dynamicIfAboveMax(int i){
if(i > MaxVirtualStaticRows){
return Eigen::Dynamic;
}
else return i;
}
struct CallConfig {
int compTimeRows;
int compTimeCols;
int runTimeRows;
int runTimeCols;
CallConfig() {}
CallConfig(int rows, int cols):
compTimeRows(dynamicIfAboveMax(rows)),
compTimeCols(cols),
runTimeRows(rows),
runTimeCols(cols)
{
}
CallConfig(int compTimeRows, int compTimeCols, int runTimeRows, int runTimeCols):
compTimeRows(compTimeRows),
compTimeCols(compTimeCols),
runTimeRows(runTimeRows),
runTimeCols(runTimeCols)
{
}
bool equals(const CallConfig & c, double /*tol*/) const {
return
this->compTimeRows == c.compTimeRows &&
this->compTimeCols == c.compTimeCols &&
this->runTimeRows == c.runTimeRows &&
this->runTimeCols == c.runTimeCols;
}
void print(const std::string & prefix) const {
std::cout << prefix << "{" << compTimeRows << ", " << compTimeCols << ", " << runTimeRows << ", " << runTimeCols << "}\n" ;
}
};
struct Record: public internal::CallRecordImplementor<Record, Cols> {
virtual ~Record() {
}
void print(const std::string& indent) const {
}
void startReverseAD(JacobianMap& jacobians) const {
}
mutable CallConfig cc;
private:
template<typename SomeMatrix>
void reverseAD(const SomeMatrix & dFdT, JacobianMap& jacobians) const {
cc.compTimeRows = SomeMatrix::RowsAtCompileTime;
cc.compTimeCols = SomeMatrix::ColsAtCompileTime;
cc.runTimeRows = dFdT.rows();
cc.runTimeCols = dFdT.cols();
}
template<typename Derived, int Rows, int OtherCols>
friend struct internal::ReverseADImplementor;
};
JacobianMap & NJM= *static_cast<JacobianMap *>(NULL);
/* ************************************************************************* */
typedef Eigen::Matrix<double, Eigen::Dynamic, Cols> DynRowMat;
TEST(CallRecord, virtualReverseAdDispatching) {
Record record;
{
const int Rows = 1;
record.CallRecord::reverseAD(Eigen::Matrix<double, Rows, Cols>(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
record.CallRecord::reverseAD(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<double, Rows, Cols>(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
record.CallRecord::reverseAD(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<double, Rows, Cols>(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
record.CallRecord::reverseAD(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<double, Rows, Cols>(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
record.CallRecord::reverseAD(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<double, Rows, Cols>(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
record.CallRecord::reverseAD(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<double, Rows, Cols>(), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols))));
record.CallRecord::reverseAD(DynRowMat(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols))));
record.CallRecord::reverseAD(Eigen::MatrixXd(Rows, Cols), NJM);
EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Eigen::Dynamic, Rows, Cols))));
}
}
/* ************************************************************************* */
int main() {
TestResult tr;
return TestRegistry::runAllTests(tr);
}
/* ************************************************************************* */

View File

@ -38,7 +38,6 @@ template<class T> struct Incomplete;
typedef mpl::vector<Pose3, Point3> MyTypes;
typedef FunctionalNode<Point2, MyTypes>::type Generated;
//Incomplete<Generated> incomplete;
BOOST_MPL_ASSERT((boost::is_same< Matrix2, Generated::Record::Jacobian2T >));
// Try generating vectors of ExecutionTrace
typedef mpl::vector<ExecutionTrace<Pose3>, ExecutionTrace<Point3> > ExpectedTraces;

View File

@ -122,13 +122,5 @@ struct ArgumentList: public std::vector<Argument> {
};
template<class T>
inline void verifyArguments(const std::vector<std::string>& validArgs,
const std::map<std::string, T>& vt) {
typedef typename std::map<std::string, T>::value_type NamedMethod;
BOOST_FOREACH(const NamedMethod& namedMethod, vt)
namedMethod.second.verifyArguments(validArgs);
}
} // \namespace wrap

View File

@ -286,13 +286,13 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName,
// Now stick in new overload stack with expandedMethodName key
// but note we use the same, unexpanded methodName in overload
string expandedMethodName = methodName + instName.name;
methods[expandedMethodName].addOverload(verbose, is_const, methodName,
expandedArgs, expandedRetVal, instName);
methods[expandedMethodName].addOverload(methodName, expandedArgs,
expandedRetVal, is_const, instName, verbose);
}
} else
// just add overload
methods[methodName].addOverload(verbose, is_const, methodName, argumentList,
returnValue);
methods[methodName].addOverload(methodName, argumentList, returnValue,
is_const, Qualified(), verbose);
}
/* ************************************************************************* */
@ -583,4 +583,16 @@ string Class::getSerializationExport() const {
return "BOOST_CLASS_EXPORT_GUID(" + qualifiedName("::") + ", \""
+ qualifiedName() + "\");";
}
/* ************************************************************************* */
void Class::python_wrapper(FileWriter& wrapperFile) const {
wrapperFile.oss << "class_<" << name << ">(\"" << name << "\")\n";
constructor.python_wrapper(wrapperFile, name);
BOOST_FOREACH(const StaticMethod& m, static_methods | boost::adaptors::map_values)
m.python_wrapper(wrapperFile, name);
BOOST_FOREACH(const Method& m, methods | boost::adaptors::map_values)
m.python_wrapper(wrapperFile, name);
wrapperFile.oss << ";\n\n";
}
/* ************************************************************************* */

View File

@ -111,6 +111,9 @@ public:
void deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
Str wrapperName, std::vector<std::string>& functionNames) const;
// emit python wrapper
void python_wrapper(FileWriter& wrapperFile) const;
friend std::ostream& operator<<(std::ostream& os, const Class& cls) {
os << "class " << cls.name << "{\n";
os << cls.constructor << ";\n";

View File

@ -29,52 +29,55 @@
using namespace std;
using namespace wrap;
/* ************************************************************************* */
string Constructor::matlab_wrapper_name(const string& className) const {
string Constructor::matlab_wrapper_name(Str className) const {
string str = "new_" + className;
return str;
}
/* ************************************************************************* */
void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperName,
bool hasParent, const int id, const ArgumentList args) const {
void Constructor::proxy_fragment(FileWriter& file,
const std::string& wrapperName, bool hasParent, const int id,
const ArgumentList args) const {
size_t nrArgs = args.size();
// check for number of arguments...
file.oss << " elseif nargin == " << nrArgs;
if (nrArgs>0) file.oss << " && ";
if (nrArgs > 0)
file.oss << " && ";
// ...and their types
bool first = true;
for(size_t i=0;i<nrArgs;i++) {
if (!first) file.oss << " && ";
file.oss << "isa(varargin{" << i+1 << "},'" << args[i].matlabClass(".") << "')";
first=false;
for (size_t i = 0; i < nrArgs; i++) {
if (!first)
file.oss << " && ";
file.oss << "isa(varargin{" << i + 1 << "},'" << args[i].matlabClass(".")
<< "')";
first = false;
}
// emit code for calling constructor
if(hasParent)
if (hasParent)
file.oss << "\n [ my_ptr, base_ptr ] = ";
else
file.oss << "\n my_ptr = ";
file.oss << wrapperName << "(" << id;
// emit constructor arguments
for(size_t i=0;i<nrArgs;i++) {
for (size_t i = 0; i < nrArgs; i++) {
file.oss << ", ";
file.oss << "varargin{" << i+1 << "}";
file.oss << "varargin{" << i + 1 << "}";
}
file.oss << ");\n";
}
/* ************************************************************************* */
string Constructor::wrapper_fragment(FileWriter& file,
const string& cppClassName,
const string& matlabUniqueName,
const string& cppBaseClassName,
int id,
const ArgumentList& al) const {
string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName,
Str matlabUniqueName, Str cppBaseClassName, int id,
const ArgumentList& al) const {
const string wrapFunctionName = matlabUniqueName + "_constructor_" + boost::lexical_cast<string>(id);
const string wrapFunctionName = matlabUniqueName + "_constructor_"
+ boost::lexical_cast<string>(id);
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
file.oss << "void " << wrapFunctionName
<< "(int nargout, mxArray *out[], int nargin, const mxArray *in[])"
<< endl;
file.oss << "{\n";
file.oss << " mexAtExit(&_deleteAllObjects);\n";
//Typedef boost::shared_ptr
@ -82,22 +85,29 @@ string Constructor::wrapper_fragment(FileWriter& file,
file.oss << "\n";
//Check to see if there will be any arguments and remove {} for consiseness
if(al.size() > 0)
if (al.size() > 0)
al.matlab_unwrap(file); // unwrap arguments
file.oss << " Shared *self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl;
file.oss << " Shared *self = new Shared(new " << cppClassName << "("
<< al.names() << "));" << endl;
file.oss << " collector_" << matlabUniqueName << ".insert(self);\n";
if(verbose_)
if (verbose_)
file.oss << " std::cout << \"constructed \" << self << std::endl;" << endl;
file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl;
file.oss << " *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;" << endl;
file.oss
<< " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);"
<< endl;
file.oss << " *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;"
<< endl;
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
if(!cppBaseClassName.empty()) {
if (!cppBaseClassName.empty()) {
file.oss << "\n";
file.oss << " typedef boost::shared_ptr<" << cppBaseClassName << "> SharedBase;\n";
file.oss << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
file.oss << " *reinterpret_cast<SharedBase**>(mxGetData(out[1])) = new SharedBase(*self);\n";
file.oss << " typedef boost::shared_ptr<" << cppBaseClassName
<< "> SharedBase;\n";
file.oss
<< " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
file.oss
<< " *reinterpret_cast<SharedBase**>(mxGetData(out[1])) = new SharedBase(*self);\n";
}
file.oss << "}" << endl;
@ -106,3 +116,9 @@ string Constructor::wrapper_fragment(FileWriter& file,
}
/* ************************************************************************* */
void Constructor::python_wrapper(FileWriter& wrapperFile, Str className) const {
wrapperFile.oss << " .def(\"" << name_ << "\", &" << className << "::" << name_
<< ");\n";
}
/* ************************************************************************* */

View File

@ -18,7 +18,7 @@
#pragma once
#include "Function.h"
#include "OverloadedFunction.h"
#include <string>
#include <vector>
@ -26,21 +26,19 @@
namespace wrap {
// Constructor class
struct Constructor: public ArgumentOverloads {
struct Constructor: public OverloadedFunction {
typedef const std::string& Str;
/// Constructor creates an empty class
Constructor(bool verbose = false) :
verbose_(verbose) {
Constructor(bool verbose = false) {
verbose_ = verbose;
}
// Then the instance variables are set directly by the Module constructor
std::string name;
bool verbose_;
Constructor expandTemplate(const TemplateSubstitution& ts) const {
Constructor inst = *this;
inst.argLists_ = expandArgumentListsTemplate(ts);
inst.name = ts.expandedClassName();
inst.name_ = ts.expandedClassName();
return inst;
}
@ -49,14 +47,14 @@ struct Constructor: public ArgumentOverloads {
// classFile is class proxy file, e.g., ../matlab/@Point2/Point2.m
/// wrapper name
std::string matlab_wrapper_name(const std::string& className) const;
std::string matlab_wrapper_name(Str className) const;
void comment_fragment(FileWriter& proxyFile) const {
if (nrOverloads() > 0)
proxyFile.oss << "%\n%-------Constructors-------\n";
for (size_t i = 0; i < nrOverloads(); i++) {
proxyFile.oss << "%";
argumentList(i).emit_prototype(proxyFile, name);
argumentList(i).emit_prototype(proxyFile, name_);
proxyFile.oss << "\n";
}
}
@ -65,22 +63,24 @@ struct Constructor: public ArgumentOverloads {
* Create fragment to select constructor in proxy class, e.g.,
* if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end
*/
void proxy_fragment(FileWriter& file, const std::string& wrapperName,
bool hasParent, const int id, const ArgumentList args) const;
void proxy_fragment(FileWriter& file, Str wrapperName, bool hasParent,
const int id, const ArgumentList args) const;
/// cpp wrapper
std::string wrapper_fragment(FileWriter& file,
const std::string& cppClassName, const std::string& matlabUniqueName,
const std::string& cppBaseClassName, int id,
std::string wrapper_fragment(FileWriter& file, Str cppClassName,
Str matlabUniqueName, Str cppBaseClassName, int id,
const ArgumentList& al) const;
/// constructor function
void generate_construct(FileWriter& file, const std::string& cppClassName,
void generate_construct(FileWriter& file, Str cppClassName,
std::vector<ArgumentList>& args_list) const;
// emit python wrapper
void python_wrapper(FileWriter& wrapperFile, Str className) const;
friend std::ostream& operator<<(std::ostream& os, const Constructor& m) {
for (size_t i = 0; i < m.nrOverloads(); i++)
os << m.name << m.argLists_[i];
os << m.name_ << m.argLists_[i];
return os;
}

View File

@ -0,0 +1,133 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file FullyOverloadedFunction.h
* @brief Function that can be fully overloaded: arguments and return values
* @author Frank Dellaert
* @date Nov 13, 2014
**/
#pragma once
#include "OverloadedFunction.h"
namespace wrap {
/**
* Signature Overload (including return value)
*/
class SignatureOverloads: public ArgumentOverloads {
protected:
std::vector<ReturnValue> returnVals_;
public:
const ReturnValue& returnValue(size_t i) const {
return returnVals_.at(i);
}
void push_back(const ArgumentList& args, const ReturnValue& retVal) {
argLists_.push_back(args);
returnVals_.push_back(retVal);
}
void verifyReturnTypes(const std::vector<std::string>& validtypes,
const std::string& s) const {
BOOST_FOREACH(const ReturnValue& retval, returnVals_) {
retval.type1.verify(validtypes, s);
if (retval.isPair)
retval.type2.verify(validtypes, s);
}
}
// TODO use transform ?
std::vector<ReturnValue> expandReturnValuesTemplate(
const TemplateSubstitution& ts) const {
std::vector<ReturnValue> result;
BOOST_FOREACH(const ReturnValue& retVal, returnVals_) {
ReturnValue instRetVal = retVal.expandTemplate(ts);
result.push_back(instRetVal);
}
return result;
}
/// Expand templates, imperative !
void expandTemplate(const TemplateSubstitution& ts) {
// substitute template in arguments
argLists_ = expandArgumentListsTemplate(ts);
// do the same for return types
returnVals_ = expandReturnValuesTemplate(ts);
}
// emit a list of comments, one for each overload
void usage_fragment(FileWriter& proxyFile, const std::string& name) const {
unsigned int argLCount = 0;
BOOST_FOREACH(ArgumentList argList, argLists_) {
argList.emit_prototype(proxyFile, name);
if (argLCount != nrOverloads() - 1)
proxyFile.oss << ", ";
else
proxyFile.oss << " : returns " << returnValue(0).return_type(false)
<< std::endl;
argLCount++;
}
}
// emit a list of comments, one for each overload
void comment_fragment(FileWriter& proxyFile, const std::string& name) const {
size_t i = 0;
BOOST_FOREACH(ArgumentList argList, argLists_) {
proxyFile.oss << "%";
argList.emit_prototype(proxyFile, name);
proxyFile.oss << " : returns " << returnVals_[i++].return_type(false)
<< std::endl;
}
}
friend std::ostream& operator<<(std::ostream& os,
const SignatureOverloads& overloads) {
for (size_t i = 0; i < overloads.nrOverloads(); i++)
os << overloads.returnVals_[i] << overloads.argLists_[i] << std::endl;
return os;
}
};
class FullyOverloadedFunction: public Function, public SignatureOverloads {
public:
bool addOverload(const std::string& name, const ArgumentList& args,
const ReturnValue& retVal, const Qualified& instName = Qualified(),
bool verbose = false) {
bool first = initializeOrCheck(name, instName, verbose);
SignatureOverloads::push_back(args, retVal);
return first;
}
};
// Templated checking functions
// TODO: do this via polymorphism, use transform ?
template<class F>
inline void verifyReturnTypes(const std::vector<std::string>& validTypes,
const std::map<std::string, F>& vt) {
typedef typename std::map<std::string, F>::value_type NamedMethod;
BOOST_FOREACH(const NamedMethod& namedMethod, vt)
namedMethod.second.verifyReturnTypes(validTypes);
}
} // \namespace wrap

View File

@ -29,38 +29,29 @@ using namespace std;
using namespace wrap;
/* ************************************************************************* */
void Function::addOverload(bool verbose, const std::string& name,
const Qualified& instName) {
bool Function::initializeOrCheck(const std::string& name,
const Qualified& instName, bool verbose) {
if (name.empty())
throw std::runtime_error(
"Function::initializeOrCheck called with empty name");
// Check if this overload is give to the correct method
if (name_.empty())
if (name_.empty()) {
name_ = name;
else if (name_ != name)
throw std::runtime_error(
"Function::addOverload: tried to add overload with name " + name
+ " instead of expected " + name_);
// Check if this overload is give to the correct method
if (templateArgValue_.empty())
templateArgValue_ = instName;
else if (templateArgValue_ != instName)
throw std::runtime_error(
"Function::addOverload: tried to add overload with template argument "
+ instName.qualifiedName(":") + " instead of expected "
+ templateArgValue_.qualifiedName(":"));
verbose_ = verbose;
return true;
} else {
if (name_ != name || templateArgValue_ != instName || verbose_ != verbose)
throw std::runtime_error(
"Function::initializeOrCheck called with different arguments: with name "
+ name + " instead of expected " + name_
+ ", or with template argument " + instName.qualifiedName(":")
+ " instead of expected " + templateArgValue_.qualifiedName(":"));
verbose_ = verbose;
}
/* ************************************************************************* */
vector<ArgumentList> ArgumentOverloads::expandArgumentListsTemplate(
const TemplateSubstitution& ts) const {
vector<ArgumentList> result;
BOOST_FOREACH(const ArgumentList& argList, argLists_) {
ArgumentList instArgList = argList.expandTemplate(ts);
result.push_back(instArgList);
return false;
}
return result;
}
/* ************************************************************************* */

View File

@ -19,11 +19,6 @@
#pragma once
#include "Argument.h"
#include "ReturnValue.h"
#include "TypeAttributesTable.h"
#include <string>
#include <list>
namespace wrap {
@ -32,20 +27,18 @@ class Function {
protected:
bool verbose_;
std::string name_; ///< name of method
Qualified templateArgValue_; ///< value of template argument if applicable
bool verbose_;
public:
/// Constructor creates empty object
Function(bool verbose = true) :
verbose_(verbose) {
}
Function(const std::string& name, bool verbose = true) :
verbose_(verbose), name_(name) {
}
/**
* @brief first time, fill in instance variables, otherwise check if same
* @return true if first time, false thereafter
*/
bool initializeOrCheck(const std::string& name, const Qualified& instName =
Qualified(), bool verbose = false);
std::string name() const {
return name_;
@ -57,172 +50,7 @@ public:
else
return name_ + templateArgValue_.name;
}
// The first time this function is called, it initializes the class members
// with those in rhs, but in subsequent calls it adds additional argument
// lists as function overloads.
void addOverload(bool verbose, const std::string& name,
const Qualified& instName = Qualified());
};
/**
* ArgumentList Overloads
*/
class ArgumentOverloads {
protected:
std::vector<ArgumentList> argLists_;
public:
size_t nrOverloads() const {
return argLists_.size();
}
const ArgumentList& argumentList(size_t i) const {
return argLists_.at(i);
}
void addOverload(const ArgumentList& args) {
argLists_.push_back(args);
}
std::vector<ArgumentList> expandArgumentListsTemplate(
const TemplateSubstitution& ts) const;
/// Expand templates, imperative !
virtual void ExpandTemplate(const TemplateSubstitution& ts) {
argLists_ = expandArgumentListsTemplate(ts);
}
void verifyArguments(const std::vector<std::string>& validArgs,
const std::string s) const {
BOOST_FOREACH(const ArgumentList& argList, argLists_) {
BOOST_FOREACH(Argument arg, argList) {
std::string fullType = arg.type.qualifiedName("::");
if (find(validArgs.begin(), validArgs.end(), fullType)
== validArgs.end())
throw DependencyMissing(fullType, "checking argument of " + s);
}
}
}
friend std::ostream& operator<<(std::ostream& os,
const ArgumentOverloads& overloads) {
BOOST_FOREACH(const ArgumentList& argList, overloads.argLists_)
os << argList << std::endl;
return os;
}
};
/**
* Signature Overload (including return value)
*/
class SignatureOverloads: public ArgumentOverloads {
protected:
std::vector<ReturnValue> returnVals_;
public:
const ReturnValue& returnValue(size_t i) const {
return returnVals_.at(i);
}
void addOverload(const ArgumentList& args, const ReturnValue& retVal) {
argLists_.push_back(args);
returnVals_.push_back(retVal);
}
void verifyReturnTypes(const std::vector<std::string>& validtypes,
const std::string& s) const {
BOOST_FOREACH(const ReturnValue& retval, returnVals_) {
retval.type1.verify(validtypes, s);
if (retval.isPair)
retval.type2.verify(validtypes, s);
}
}
// TODO use transform ?
std::vector<ReturnValue> expandReturnValuesTemplate(
const TemplateSubstitution& ts) const {
std::vector<ReturnValue> result;
BOOST_FOREACH(const ReturnValue& retVal, returnVals_) {
ReturnValue instRetVal = retVal.expandTemplate(ts);
result.push_back(instRetVal);
}
return result;
}
/// Expand templates, imperative !
void expandTemplate(const TemplateSubstitution& ts) {
// substitute template in arguments
argLists_ = expandArgumentListsTemplate(ts);
// do the same for return types
returnVals_ = expandReturnValuesTemplate(ts);
}
// emit a list of comments, one for each overload
void usage_fragment(FileWriter& proxyFile, const std::string& name) const {
unsigned int argLCount = 0;
BOOST_FOREACH(ArgumentList argList, argLists_) {
argList.emit_prototype(proxyFile, name);
if (argLCount != nrOverloads() - 1)
proxyFile.oss << ", ";
else
proxyFile.oss << " : returns " << returnValue(0).return_type(false)
<< std::endl;
argLCount++;
}
}
// emit a list of comments, one for each overload
void comment_fragment(FileWriter& proxyFile, const std::string& name) const {
size_t i = 0;
BOOST_FOREACH(ArgumentList argList, argLists_) {
proxyFile.oss << "%";
argList.emit_prototype(proxyFile, name);
proxyFile.oss << " : returns " << returnVals_[i++].return_type(false)
<< std::endl;
}
}
friend std::ostream& operator<<(std::ostream& os,
const SignatureOverloads& overloads) {
for (size_t i = 0; i < overloads.nrOverloads(); i++)
os << overloads.returnVals_[i] << overloads.argLists_[i] << std::endl;
return os;
}
};
// Templated checking functions
// TODO: do this via polymorphism ?
// TODO use transform
template<class F>
static std::map<std::string, F> expandMethodTemplate(
const std::map<std::string, F>& methods, const TemplateSubstitution& ts) {
std::map<std::string, F> result;
typedef std::pair<const std::string, F> NamedMethod;
BOOST_FOREACH(NamedMethod namedMethod, methods) {
F instMethod = namedMethod.second;
instMethod.expandTemplate(ts);
namedMethod.second = instMethod;
result.insert(namedMethod);
}
return result;
}
template<class F>
inline void verifyReturnTypes(const std::vector<std::string>& validTypes,
const std::map<std::string, F>& vt) {
typedef typename std::map<std::string, F>::value_type NamedMethod;
BOOST_FOREACH(const NamedMethod& namedMethod, vt)
namedMethod.second.verifyReturnTypes(validTypes);
}
} // \namespace wrap

View File

@ -16,18 +16,18 @@ namespace wrap {
using namespace std;
/* ************************************************************************* */
void GlobalFunction::addOverload(bool verbose, const Qualified& overload,
void GlobalFunction::addOverload(const Qualified& overload,
const ArgumentList& args, const ReturnValue& retVal,
const Qualified& instName) {
Function::addOverload(verbose, overload.name, instName);
SignatureOverloads::addOverload(args, retVal);
const Qualified& instName, bool verbose) {
string name(overload.name);
FullyOverloadedFunction::addOverload(name, args, retVal, instName, verbose);
overloads.push_back(overload);
}
/* ************************************************************************* */
void GlobalFunction::matlab_proxy(const std::string& toolboxPath,
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
FileWriter& file, std::vector<std::string>& functionNames) const {
void GlobalFunction::matlab_proxy(const string& toolboxPath,
const string& wrapperName, const TypeAttributesTable& typeAttributes,
FileWriter& file, vector<string>& functionNames) const {
// cluster overloads with same namespace
// create new GlobalFunction structures around namespaces - same namespaces and names are overloads
@ -40,8 +40,7 @@ void GlobalFunction::matlab_proxy(const std::string& toolboxPath,
string str_ns = qualifiedName("", overload.namespaces);
const ReturnValue& ret = returnValue(i);
const ArgumentList& args = argumentList(i);
grouped_functions[str_ns].addOverload(verbose_, overload, args, ret,
templateArgValue_);
grouped_functions[str_ns].addOverload(overload, args, ret);
}
size_t lastcheck = grouped_functions.size();
@ -54,9 +53,9 @@ void GlobalFunction::matlab_proxy(const std::string& toolboxPath,
}
/* ************************************************************************* */
void GlobalFunction::generateSingleFunction(const std::string& toolboxPath,
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
FileWriter& file, std::vector<std::string>& functionNames) const {
void GlobalFunction::generateSingleFunction(const string& toolboxPath,
const string& wrapperName, const TypeAttributesTable& typeAttributes,
FileWriter& file, vector<string>& functionNames) const {
// create the folder for the namespace
const Qualified& overload1 = overloads.front();
@ -128,6 +127,11 @@ void GlobalFunction::generateSingleFunction(const std::string& toolboxPath,
mfunctionFile.emit(true);
}
/* ************************************************************************* */
void GlobalFunction::python_wrapper(FileWriter& wrapperFile) const {
wrapperFile.oss << "def(\"" << name_ << "\", " << name_ << ");\n";
}
/* ************************************************************************* */
} // \namespace wrap

View File

@ -9,23 +9,18 @@
#pragma once
#include "Function.h"
#include "FullyOverloadedFunction.h"
namespace wrap {
struct GlobalFunction: public Function, public SignatureOverloads {
struct GlobalFunction: public FullyOverloadedFunction {
std::vector<Qualified> overloads; ///< Stack of qualified names
// Constructor only used in Module
GlobalFunction(bool verbose = true) :
Function(verbose) {
}
// Used to reconstruct
GlobalFunction(const std::string& name, bool verbose = true) :
Function(name,verbose) {
}
// adds an overloaded version of this function,
void addOverload(const Qualified& overload, const ArgumentList& args,
const ReturnValue& retVal, const Qualified& instName = Qualified(),
bool verbose = false);
void verifyArguments(const std::vector<std::string>& validArgs) const {
SignatureOverloads::verifyArguments(validArgs, name_);
@ -35,16 +30,14 @@ struct GlobalFunction: public Function, public SignatureOverloads {
SignatureOverloads::verifyReturnTypes(validtypes, name_);
}
// adds an overloaded version of this function,
void addOverload(bool verbose, const Qualified& overload,
const ArgumentList& args, const ReturnValue& retVal,
const Qualified& instName = Qualified());
// codegen function called from Module to build the cpp and matlab versions of the function
void matlab_proxy(const std::string& toolboxPath,
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
FileWriter& file, std::vector<std::string>& functionNames) const;
// emit python wrapper
void python_wrapper(FileWriter& wrapperFile) const;
private:
// Creates a single global function - all in same namespace

View File

@ -29,17 +29,25 @@ using namespace std;
using namespace wrap;
/* ************************************************************************* */
void Method::addOverload(bool verbose, bool is_const, Str name,
const ArgumentList& args, const ReturnValue& retVal,
const Qualified& instName) {
StaticMethod::addOverload(verbose, name, args, retVal, instName);
is_const_ = is_const;
bool Method::addOverload(Str name, const ArgumentList& args,
const ReturnValue& retVal, bool is_const, const Qualified& instName,
bool verbose) {
bool first = StaticMethod::addOverload(name, args, retVal, instName, verbose);
if (first)
is_const_ = is_const;
else if (is_const && !is_const_)
throw std::runtime_error(
"Method::addOverload now designated as const whereas before it was not");
else if (!is_const && is_const_)
throw std::runtime_error(
"Method::addOverload now designated as non-const whereas before it was");
return first;
}
/* ************************************************************************* */
void Method::proxy_header(FileWriter& proxyFile) const {
proxyFile.oss << " function varargout = " << matlabName() << "(this, varargin)\n";
proxyFile.oss << " function varargout = " << matlabName()
<< "(this, varargin)\n";
}
/* ************************************************************************* */

View File

@ -31,14 +31,9 @@ public:
typedef const std::string& Str;
/// Constructor creates empty object
Method(bool verbose = true) :
StaticMethod(verbose), is_const_(false) {
}
Method(const std::string& name, bool verbose = true) :
StaticMethod(name,verbose), is_const_(false) {
}
bool addOverload(Str name, const ArgumentList& args,
const ReturnValue& retVal, bool is_const, const Qualified& instName =
Qualified(), bool verbose = false);
virtual bool isStatic() const {
return false;
@ -48,13 +43,6 @@ public:
return is_const_;
}
// The first time this function is called, it initializes the class members
// with those in rhs, but in subsequent calls it adds additional argument
// lists as function overloads.
void addOverload(bool verbose, bool is_const, Str name,
const ArgumentList& args, const ReturnValue& retVal,
const Qualified& instName = Qualified());
friend std::ostream& operator<<(std::ostream& os, const Method& m) {
for (size_t i = 0; i < m.nrOverloads(); i++)
os << m.returnVals_[i] << " " << m.name_ << m.argLists_[i];

View File

@ -217,7 +217,7 @@ void Module::parseMarkup(const std::string& data) {
Constructor constructor0(verbose), constructor(verbose);
Rule constructor_p =
(className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p)
[bl::bind(&Constructor::addOverload, bl::var(constructor), bl::var(args))]
[bl::bind(&Constructor::push_back, bl::var(constructor), bl::var(args))]
[clear_a(args)];
vector<string> namespaces_return; /// namespace for current return type
@ -274,7 +274,7 @@ void Module::parseMarkup(const std::string& data) {
'(' >> argumentList_p >> ')' >> ';' >> *comments_p)
[bl::bind(&StaticMethod::addOverload,
bl::var(cls.static_methods)[bl::var(methodName)],
verbose, bl::var(methodName), bl::var(args), bl::var(retVal), Qualified())]
bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)]
[assign_a(retVal,retVal0)]
[clear_a(args)];
@ -295,7 +295,8 @@ void Module::parseMarkup(const std::string& data) {
>> ((':' >> classParent_p >> '{') | '{')
>> *(functions_p | comments_p)
>> str_p("};"))
[assign_a(constructor.name, cls.name)]
[bl::bind(&Constructor::initializeOrCheck, bl::var(constructor),
bl::var(cls.name), Qualified(), verbose)]
[assign_a(cls.constructor, constructor)]
[assign_a(cls.namespaces, namespaces)]
[assign_a(cls.deconstructor.name,cls.name)]
@ -313,7 +314,7 @@ void Module::parseMarkup(const std::string& data) {
[assign_a(globalFunction.namespaces,namespaces)]
[bl::bind(&GlobalFunction::addOverload,
bl::var(global_functions)[bl::var(globalFunction.name)],
verbose, bl::var(globalFunction), bl::var(args), bl::var(retVal), Qualified())]
bl::var(globalFunction), bl::var(args), bl::var(retVal), Qualified(),verbose)]
[assign_a(retVal,retVal0)]
[clear_a(globalFunction)]
[clear_a(args)];
@ -393,51 +394,35 @@ void Module::parseMarkup(const std::string& data) {
// Explicitly add methods to the classes from parents so it shows in documentation
BOOST_FOREACH(Class& cls, classes)
cls.appendInheritedMethods(cls, classes);
}
/* ************************************************************************* */
void Module::generateIncludes(FileWriter& file) const {
// collect includes
vector<string> all_includes(includes);
// sort and remove duplicates
sort(all_includes.begin(), all_includes.end());
vector<string>::const_iterator last_include = unique(all_includes.begin(), all_includes.end());
vector<string>::const_iterator it = all_includes.begin();
// add includes to file
for (; it != last_include; ++it)
file.oss << "#include <" << *it << ">" << endl;
file.oss << "\n";
}
/* ************************************************************************* */
void Module::matlab_code(const string& toolboxPath, const string& headerPath) const {
fs::create_directories(toolboxPath);
// Expand templates - This is done first so that template instantiations are
// counted in the list of valid types, have their attributes and dependencies
// checked, etc.
vector<Class> expandedClasses = ExpandTypedefInstantiations(classes, templateInstantiationTypedefs);
expandedClasses = ExpandTypedefInstantiations(classes,
templateInstantiationTypedefs);
// Dependency check list
vector<string> validTypes = GenerateValidTypes(expandedClasses, forward_declarations);
vector<string> validTypes = GenerateValidTypes(expandedClasses,
forward_declarations);
// Check that all classes have been defined somewhere
verifyArguments<GlobalFunction>(validTypes, global_functions);
verifyReturnTypes<GlobalFunction>(validTypes, global_functions);
bool hasSerialiable = false;
hasSerialiable = false;
BOOST_FOREACH(const Class& cls, expandedClasses)
cls.verifyAll(validTypes,hasSerialiable);
// Create type attributes table and check validity
TypeAttributesTable typeAttributes;
typeAttributes.addClasses(expandedClasses);
typeAttributes.addForwardDeclarations(forward_declarations);
typeAttributes.checkValidity(expandedClasses);
}
/* ************************************************************************* */
void Module::matlab_code(const string& toolboxPath) const {
fs::create_directories(toolboxPath);
// create the unified .cpp switch file
const string wrapperName = name + "_wrapper";
@ -458,19 +443,18 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co
// Generate includes while avoiding redundant includes
generateIncludes(wrapperFile);
// create typedef classes - we put this at the top of the wrap file so that collectors and method arguments can use these typedefs
BOOST_FOREACH(const Class& cls, expandedClasses) {
// create typedef classes - we put this at the top of the wrap file so that
// collectors and method arguments can use these typedefs
BOOST_FOREACH(const Class& cls, expandedClasses)
if(!cls.typedefName.empty())
wrapperFile.oss << cls.getTypedef() << "\n";
}
wrapperFile.oss << "\n";
// Generate boost.serialization export flags (needs typedefs from above)
if (hasSerialiable) {
BOOST_FOREACH(const Class& cls, expandedClasses) {
BOOST_FOREACH(const Class& cls, expandedClasses)
if(cls.isSerializable)
wrapperFile.oss << cls.getSerializationExport() << "\n";
}
wrapperFile.oss << "\n";
}
@ -483,14 +467,12 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co
vector<string> functionNames; // Function names stored by index for switch
// create proxy class and wrapper code
BOOST_FOREACH(const Class& cls, expandedClasses) {
BOOST_FOREACH(const Class& cls, expandedClasses)
cls.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames);
}
// create matlab files and wrapper code for global functions
BOOST_FOREACH(const GlobalFunctions::value_type& p, global_functions) {
BOOST_FOREACH(const GlobalFunctions::value_type& p, global_functions)
p.second.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames);
}
// finish wrapper file
wrapperFile.oss << "\n";
@ -500,6 +482,23 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co
}
/* ************************************************************************* */
void Module::generateIncludes(FileWriter& file) const {
// collect includes
vector<string> all_includes(includes);
// sort and remove duplicates
sort(all_includes.begin(), all_includes.end());
vector<string>::const_iterator last_include = unique(all_includes.begin(), all_includes.end());
vector<string>::const_iterator it = all_includes.begin();
// add includes to file
for (; it != last_include; ++it)
file.oss << "#include <" << *it << ">" << endl;
file.oss << "\n";
}
/* ************************************************************************* */
void Module::finish_wrapper(FileWriter& file, const std::vector<std::string>& functionNames) const {
file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
file.oss << "{\n";
@ -651,3 +650,31 @@ void Module::WriteRTTIRegistry(FileWriter& wrapperFile, const std::string& modul
}
/* ************************************************************************* */
void Module::python_wrapper(const string& toolboxPath) const {
fs::create_directories(toolboxPath);
// create the unified .cpp switch file
const string wrapperName = name + "_python";
string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp";
FileWriter wrapperFile(wrapperFileName, verbose, "//");
wrapperFile.oss << "#include <boost/python.hpp>\n\n";
wrapperFile.oss << "using namespace boost::python;\n";
wrapperFile.oss << "BOOST_PYTHON_MODULE(" + name + ")\n";
wrapperFile.oss << "{\n";
// write out classes
BOOST_FOREACH(const Class& cls, expandedClasses)
cls.python_wrapper(wrapperFile);
// write out global functions
BOOST_FOREACH(const GlobalFunctions::value_type& p, global_functions)
p.second.python_wrapper(wrapperFile);
// finish wrapper file
wrapperFile.oss << "}\n";
wrapperFile.emit(true);
}
/* ************************************************************************* */

View File

@ -37,40 +37,53 @@ struct Module {
typedef std::map<std::string, GlobalFunction> GlobalFunctions;
typedef std::map<std::string, Method> Methods;
std::string name; ///< module name
bool verbose; ///< verbose flag
// Filled during parsing:
std::string name; ///< module name
bool verbose; ///< verbose flag
std::vector<Class> classes; ///< list of classes
std::vector<TemplateInstantiationTypedef> templateInstantiationTypedefs; ///< list of template instantiations
std::vector<ForwardDeclaration> forward_declarations;
std::vector<std::string> includes; ///< Include statements
std::vector<std::string> includes; ///< Include statements
GlobalFunctions global_functions;
// After parsing:
std::vector<Class> expandedClasses;
bool hasSerialiable;
TypeAttributesTable typeAttributes;
/// constructor that parses interface file
Module(const std::string& interfacePath,
const std::string& moduleName,
bool enable_verbose=true);
Module(const std::string& interfacePath, const std::string& moduleName,
bool enable_verbose = true);
/// Dummy constructor that does no parsing - use only for testing
Module(const std::string& moduleName, bool enable_verbose=true);
/// MATLAB code generation:
void matlab_code(
const std::string& path,
const std::string& headerPath) const; // FIXME: headerPath not actually used?
void finish_wrapper(FileWriter& file, const std::vector<std::string>& functionNames) const;
void generateIncludes(FileWriter& file) const;
Module(const std::string& moduleName, bool enable_verbose = true);
/// non-const function that performs parsing - typically called by constructor
/// Throws exception on failure
void parseMarkup(const std::string& data);
/// MATLAB code generation:
void matlab_code(const std::string& path) const;
void generateIncludes(FileWriter& file) const;
void finish_wrapper(FileWriter& file,
const std::vector<std::string>& functionNames) const;
/// Python code generation:
void python_wrapper(const std::string& path) const;
private:
static std::vector<Class> ExpandTypedefInstantiations(const std::vector<Class>& classes, const std::vector<TemplateInstantiationTypedef> instantiations);
static std::vector<std::string> GenerateValidTypes(const std::vector<Class>& classes, const std::vector<ForwardDeclaration> forwardDeclarations);
static void WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile, const std::string& moduleName, const std::vector<Class>& classes);
static void WriteRTTIRegistry(FileWriter& wrapperFile, const std::string& moduleName, const std::vector<Class>& classes);
static std::vector<Class> ExpandTypedefInstantiations(
const std::vector<Class>& classes,
const std::vector<TemplateInstantiationTypedef> instantiations);
static std::vector<std::string> GenerateValidTypes(
const std::vector<Class>& classes,
const std::vector<ForwardDeclaration> forwardDeclarations);
static void WriteCollectorsAndCleanupFcn(FileWriter& wrapperFile,
const std::string& moduleName, const std::vector<Class>& classes);
static void WriteRTTIRegistry(FileWriter& wrapperFile,
const std::string& moduleName, const std::vector<Class>& classes);
};
} // \namespace wrap

126
wrap/OverloadedFunction.h Normal file
View File

@ -0,0 +1,126 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file OverloadedFunction.h
* @brief Function that can overload its arguments only
* @author Frank Dellaert
* @date Nov 13, 2014
**/
#pragma once
#include "Function.h"
#include "Argument.h"
namespace wrap {
/**
* ArgumentList Overloads
*/
class ArgumentOverloads {
protected:
std::vector<ArgumentList> argLists_;
public:
size_t nrOverloads() const {
return argLists_.size();
}
const ArgumentList& argumentList(size_t i) const {
return argLists_.at(i);
}
void push_back(const ArgumentList& args) {
argLists_.push_back(args);
}
std::vector<ArgumentList> expandArgumentListsTemplate(
const TemplateSubstitution& ts) const {
std::vector<ArgumentList> result;
BOOST_FOREACH(const ArgumentList& argList, argLists_) {
ArgumentList instArgList = argList.expandTemplate(ts);
result.push_back(instArgList);
}
return result;
}
/// Expand templates, imperative !
virtual void ExpandTemplate(const TemplateSubstitution& ts) {
argLists_ = expandArgumentListsTemplate(ts);
}
void verifyArguments(const std::vector<std::string>& validArgs,
const std::string s) const {
BOOST_FOREACH(const ArgumentList& argList, argLists_) {
BOOST_FOREACH(Argument arg, argList) {
std::string fullType = arg.type.qualifiedName("::");
if (find(validArgs.begin(), validArgs.end(), fullType)
== validArgs.end())
throw DependencyMissing(fullType, "checking argument of " + s);
}
}
}
friend std::ostream& operator<<(std::ostream& os,
const ArgumentOverloads& overloads) {
BOOST_FOREACH(const ArgumentList& argList, overloads.argLists_)
os << argList << std::endl;
return os;
}
};
class OverloadedFunction: public Function, public ArgumentOverloads {
public:
bool addOverload(const std::string& name, const ArgumentList& args,
const Qualified& instName = Qualified(), bool verbose = false) {
bool first = initializeOrCheck(name, instName, verbose);
ArgumentOverloads::push_back(args);
return first;
}
private:
};
// Templated checking functions
// TODO: do this via polymorphism, use transform ?
template<class F>
static std::map<std::string, F> expandMethodTemplate(
const std::map<std::string, F>& methods, const TemplateSubstitution& ts) {
std::map<std::string, F> result;
typedef std::pair<const std::string, F> NamedMethod;
BOOST_FOREACH(NamedMethod namedMethod, methods) {
F instMethod = namedMethod.second;
instMethod.expandTemplate(ts);
namedMethod.second = instMethod;
result.insert(namedMethod);
}
return result;
}
template<class F>
inline void verifyArguments(const std::vector<std::string>& validArgs,
const std::map<std::string, F>& vt) {
typedef typename std::map<std::string, F>::value_type NamedMethod;
BOOST_FOREACH(const NamedMethod& namedMethod, vt)
namedMethod.second.verifyArguments(validArgs);
}
} // \namespace wrap

View File

@ -29,14 +29,6 @@
using namespace std;
using namespace wrap;
/* ************************************************************************* */
void StaticMethod::addOverload(bool verbose, Str name, const ArgumentList& args,
const ReturnValue& retVal, const Qualified& instName) {
Function::addOverload(verbose, name, instName);
SignatureOverloads::addOverload(args, retVal);
}
/* ************************************************************************* */
void StaticMethod::proxy_header(FileWriter& proxyFile) const {
string upperName = matlabName();
@ -173,3 +165,10 @@ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
}
/* ************************************************************************* */
void StaticMethod::python_wrapper(FileWriter& wrapperFile,
Str className) const {
wrapperFile.oss << " .def(\"" << name_ << "\", &" << className << "::" << name_
<< ");\n";
}
/* ************************************************************************* */

View File

@ -19,31 +19,19 @@
#pragma once
#include "Function.h"
#include "FullyOverloadedFunction.h"
namespace wrap {
/// StaticMethod class
struct StaticMethod: public Function, public SignatureOverloads {
struct StaticMethod: public FullyOverloadedFunction {
typedef const std::string& Str;
/// Constructor creates empty object
StaticMethod(bool verbosity = true) :
Function(verbosity) {
}
StaticMethod(const std::string& name, bool verbose = true) :
Function(name,verbose) {
}
virtual bool isStatic() const {
return true;
}
void addOverload(bool verbose, Str name, const ArgumentList& args,
const ReturnValue& retVal, const Qualified& instName);
// emit a list of comments, one for each overload
void comment_fragment(FileWriter& proxyFile) const {
SignatureOverloads::comment_fragment(proxyFile, matlabName());
@ -64,6 +52,9 @@ struct StaticMethod: public Function, public SignatureOverloads {
Str wrapperName, const TypeAttributesTable& typeAttributes,
std::vector<std::string>& functionNames) const;
// emit python wrapper
void python_wrapper(FileWriter& wrapperFile, Str className) const;
friend std::ostream& operator<<(std::ostream& os, const StaticMethod& m) {
for (size_t i = 0; i < m.nrOverloads(); i++)
os << "static " << m.returnVals_[i] << " " << m.name_ << m.argLists_[i];

View File

@ -0,0 +1,83 @@
#include <boost/python.hpp>
using namespace boost::python;
BOOST_PYTHON_MODULE(geometry)
{
class_<Point2>("Point2")
.def("Point2", &Point2::Point2);
.def("argChar", &Point2::argChar);
.def("argUChar", &Point2::argUChar);
.def("dim", &Point2::dim);
.def("returnChar", &Point2::returnChar);
.def("vectorConfusion", &Point2::vectorConfusion);
.def("x", &Point2::x);
.def("y", &Point2::y);
;
class_<Point3>("Point3")
.def("Point3", &Point3::Point3);
.def("StaticFunctionRet", &Point3::StaticFunctionRet);
.def("staticFunction", &Point3::staticFunction);
.def("norm", &Point3::norm);
;
class_<Test>("Test")
.def("Test", &Test::Test);
.def("arg_EigenConstRef", &Test::arg_EigenConstRef);
.def("create_MixedPtrs", &Test::create_MixedPtrs);
.def("create_ptrs", &Test::create_ptrs);
.def("print", &Test::print);
.def("return_Point2Ptr", &Test::return_Point2Ptr);
.def("return_Test", &Test::return_Test);
.def("return_TestPtr", &Test::return_TestPtr);
.def("return_bool", &Test::return_bool);
.def("return_double", &Test::return_double);
.def("return_field", &Test::return_field);
.def("return_int", &Test::return_int);
.def("return_matrix1", &Test::return_matrix1);
.def("return_matrix2", &Test::return_matrix2);
.def("return_pair", &Test::return_pair);
.def("return_ptrs", &Test::return_ptrs);
.def("return_size_t", &Test::return_size_t);
.def("return_string", &Test::return_string);
.def("return_vector1", &Test::return_vector1);
.def("return_vector2", &Test::return_vector2);
;
class_<MyBase>("MyBase")
.def("MyBase", &MyBase::MyBase);
;
class_<MyTemplatePoint2>("MyTemplatePoint2")
.def("MyTemplatePoint2", &MyTemplatePoint2::MyTemplatePoint2);
.def("accept_T", &MyTemplatePoint2::accept_T);
.def("accept_Tptr", &MyTemplatePoint2::accept_Tptr);
.def("create_MixedPtrs", &MyTemplatePoint2::create_MixedPtrs);
.def("create_ptrs", &MyTemplatePoint2::create_ptrs);
.def("return_T", &MyTemplatePoint2::return_T);
.def("return_Tptr", &MyTemplatePoint2::return_Tptr);
.def("return_ptrs", &MyTemplatePoint2::return_ptrs);
.def("templatedMethod", &MyTemplatePoint2::templatedMethod);
.def("templatedMethod", &MyTemplatePoint2::templatedMethod);
;
class_<MyTemplatePoint3>("MyTemplatePoint3")
.def("MyTemplatePoint3", &MyTemplatePoint3::MyTemplatePoint3);
.def("accept_T", &MyTemplatePoint3::accept_T);
.def("accept_Tptr", &MyTemplatePoint3::accept_Tptr);
.def("create_MixedPtrs", &MyTemplatePoint3::create_MixedPtrs);
.def("create_ptrs", &MyTemplatePoint3::create_ptrs);
.def("return_T", &MyTemplatePoint3::return_T);
.def("return_Tptr", &MyTemplatePoint3::return_Tptr);
.def("return_ptrs", &MyTemplatePoint3::return_ptrs);
.def("templatedMethod", &MyTemplatePoint3::templatedMethod);
.def("templatedMethod", &MyTemplatePoint3::templatedMethod);
;
class_<MyFactorPosePoint2>("MyFactorPosePoint2")
.def("MyFactorPosePoint2", &MyFactorPosePoint2::MyFactorPosePoint2);
;
def("aGlobalFunction", aGlobalFunction);
def("overloadedGlobalFunction", overloadedGlobalFunction);
}

View File

@ -32,12 +32,14 @@ TEST( Method, Constructor ) {
/* ************************************************************************* */
// addOverload
TEST( Method, addOverload ) {
Method method("myName");
bool verbose = true, is_const = true;
Method method;
ArgumentList args;
const ReturnValue retVal(ReturnType("return_type"));
method.addOverload(verbose, is_const, "myName", args, retVal);
EXPECT_LONGS_EQUAL(1,method.nrOverloads());
bool is_const = true;
const ReturnValue retVal1(ReturnType("return_type1"));
method.addOverload("myName", args, retVal1, is_const);
const ReturnValue retVal2(ReturnType("return_type2"));
method.addOverload("myName", args, retVal2, is_const);
EXPECT_LONGS_EQUAL(2, method.nrOverloads());
}
/* ************************************************************************* */

View File

@ -64,12 +64,11 @@ TEST( wrap, check_exception ) {
THROWS_EXCEPTION(Module("/notarealpath", "geometry",enable_verbose));
CHECK_EXCEPTION(Module("/alsonotarealpath", "geometry",enable_verbose), CantOpenFile);
// clean out previous generated code
fs::remove_all("actual_deps");
string path = topdir + "/wrap/tests";
Module module(path.c_str(), "testDependencies",enable_verbose);
CHECK_EXCEPTION(module.matlab_code("actual_deps", headerPath), DependencyMissing);
// // TODO: matlab_code does not throw this anymore, so check constructor
// fs::remove_all("actual_deps"); // clean out previous generated code
// string path = topdir + "/wrap/tests";
// Module module(path.c_str(), "testDependencies",enable_verbose);
// CHECK_EXCEPTION(module.matlab_code("actual_deps"), DependencyMissing);
}
/* ************************************************************************* */
@ -413,7 +412,7 @@ TEST( wrap, matlab_code_namespaces ) {
// emit MATLAB code
string exp_path = path + "/tests/expected_namespaces/";
string act_path = "actual_namespaces/";
module.matlab_code("actual_namespaces", headerPath);
module.matlab_code("actual_namespaces");
EXPECT(files_equal(exp_path + "ClassD.m", act_path + "ClassD.m" ));
@ -441,7 +440,7 @@ TEST( wrap, matlab_code_geometry ) {
// emit MATLAB code
// make_geometry will not compile, use make testwrap to generate real make
module.matlab_code("actual", headerPath);
module.matlab_code("actual");
#ifndef WRAP_DISABLE_SERIALIZE
string epath = path + "/tests/expected/";
#else
@ -461,6 +460,25 @@ TEST( wrap, matlab_code_geometry ) {
EXPECT(files_equal(epath + "overloadedGlobalFunction.m" , apath + "overloadedGlobalFunction.m" ));
}
/* ************************************************************************* */
TEST( wrap, python_code_geometry ) {
// Parse into class object
string header_path = topdir + "/wrap/tests";
Module module(header_path,"geometry",enable_verbose);
string path = topdir + "/wrap";
// clean out previous generated code
fs::remove_all("actual-python");
// emit MATLAB code
// make_geometry will not compile, use make testwrap to generate real make
module.python_wrapper("actual-python");
string epath = path + "/tests/expected-python/";
string apath = "actual-python/";
EXPECT(files_equal(epath + "geometry_python.cpp", apath + "geometry_python.cpp" ));
}
/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */

View File

@ -40,7 +40,7 @@ void generate_matlab_toolbox(
wrap::Module module(interfacePath, moduleName, false);
// Then emit MATLAB code
module.matlab_code(toolboxPath,headerPath);
module.matlab_code(toolboxPath);
}
/** Displays usage information */