diff --git a/.cproject b/.cproject index 075558734..b31515394 100644 --- a/.cproject +++ b/.cproject @@ -308,6 +308,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -334,7 +342,6 @@ make - tests/testBayesTree.run true false @@ -342,7 +349,6 @@ make - testBinaryBayesNet.run true false @@ -390,7 +396,6 @@ make - testSymbolicBayesNet.run true false @@ -398,7 +403,6 @@ make - tests/testSymbolicFactor.run true false @@ -406,7 +410,6 @@ make - testSymbolicFactorGraph.run true false @@ -422,20 +425,11 @@ make - tests/testBayesTree true false true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j5 @@ -524,22 +518,6 @@ false true - - make - -j2 - tests/testPose2.run - true - true - true - - - make - -j2 - tests/testPose3.run - true - true - true - make -j2 @@ -556,6 +534,22 @@ true true + + make + -j2 + tests/testPose2.run + true + true + true + + + make + -j2 + tests/testPose3.run + true + true + true + make -j2 @@ -580,26 +574,26 @@ true true - + make - -j2 - all + -j5 + testValues.run true true true - + make - -j2 - check + -j5 + testOrdering.run true true true - + make - -j2 - clean + -j5 + testKey.run true true true @@ -684,26 +678,26 @@ true true - + make - -j5 - testValues.run + -j2 + all true true true - + make - -j5 - testOrdering.run + -j2 + check true true true - + make - -j5 - testKey.run + -j2 + clean true true true @@ -958,7 +952,6 @@ make - testGraph.run true false @@ -966,7 +959,6 @@ make - testJunctionTree.run true false @@ -974,7 +966,6 @@ make - testSymbolicBayesNetB.run true false @@ -1110,7 +1101,6 @@ make - testErrors.run true false @@ -1574,6 +1564,7 @@ make + testSimulated2DOriented.run true false @@ -1613,6 +1604,7 @@ make + testSimulated2D.run true false @@ -1620,6 +1612,7 @@ make + testSimulated3D.run true false @@ -1835,6 +1828,7 @@ make + tests/testGaussianISAM2 true false @@ -1856,6 +1850,102 @@ true true + + make + -j2 + testRot3.run + true + true + true + + + make + -j2 + testRot2.run + true + true + true + + + make + -j2 + testPose3.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testCal3_S2.run + true + true + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run + true + true + true + make -j2 @@ -2057,7 +2147,6 @@ cpack - -G DEB true false @@ -2065,7 +2154,6 @@ cpack - -G RPM true false @@ -2073,7 +2161,6 @@ cpack - -G TGZ true false @@ -2081,7 +2168,6 @@ cpack - --config CPackSourceConfig.cmake true false @@ -2207,98 +2293,34 @@ true true - + make - -j2 - testRot3.run + -j5 + testSpirit.run true true true - + make - -j2 - testRot2.run + -j5 + testWrap.run true true true - + make - -j2 - testPose3.run + -j5 + check.wrap true true true - + make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - testPose2.run - true - true - true - - - make - -j2 - testCal3_S2.run - true - true - true - - - make - -j2 - testSimpleCamera.run - true - true - true - - - make - -j2 - testHomography2.run - true - true - true - - - make - -j2 - testCalibratedCamera.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testPoint2.run + -j5 + wrap true true true @@ -2342,46 +2364,7 @@ false true - - make - -j5 - testSpirit.run - true - true - true - - - make - -j5 - testWrap.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - wrap_gtsam - true - true - true - - - make - -j5 - wrap - true - true - true - + diff --git a/gtsam.h b/gtsam.h index 46ea37241..73f73389c 100644 --- a/gtsam.h +++ b/gtsam.h @@ -702,17 +702,17 @@ class VariableIndex { #include namespace noiseModel { -class Base { +virtual class Base { }; -class Gaussian : gtsam::noiseModel::Base { +virtual class Gaussian : gtsam::noiseModel::Base { static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R); static gtsam::noiseModel::Gaussian* Covariance(Matrix R); // Matrix R() const; // FIXME: cannot parse!!! void print(string s) const; }; -class Diagonal : gtsam::noiseModel::Gaussian { +virtual class Diagonal : gtsam::noiseModel::Gaussian { static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas); static gtsam::noiseModel::Diagonal* Variances(Vector variances); static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); @@ -720,14 +720,14 @@ class Diagonal : gtsam::noiseModel::Gaussian { void print(string s) const; }; -class Isotropic : gtsam::noiseModel::Gaussian { +virtual class Isotropic : gtsam::noiseModel::Gaussian { static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma); static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace); static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision); void print(string s) const; }; -class Unit : gtsam::noiseModel::Gaussian { +virtual class Unit : gtsam::noiseModel::Gaussian { static gtsam::noiseModel::Unit* Create(size_t dim); void print(string s) const; }; diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index a9bd195ba..8c470f1aa 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -86,9 +86,6 @@ ISAM2& ISAM2::operator=(const ISAM2& rhs) { params_ = rhs.params_; doglegDelta_ = rhs.doglegDelta_; -#ifndef NDEBUG - lastRelinVariables_ = rhs.lastRelinVariables_; -#endif lastAffectedVariableCount = rhs.lastAffectedVariableCount; lastAffectedFactorCount = rhs.lastAffectedFactorCount; lastAffectedCliqueCount = rhs.lastAffectedCliqueCount; @@ -661,15 +658,8 @@ ISAM2Result ISAM2::update( toc(7,"expmap"); result.variablesRelinearized = markedKeys.size(); - -#ifndef NDEBUG - lastRelinVariables_ = markedRelinMask; -#endif } else { result.variablesRelinearized = 0; -#ifndef NDEBUG - lastRelinVariables_ = vector(ordering_.nVars(), false); -#endif } tic(8,"linearize new"); diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 34fc7b46f..0d540a729 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -403,11 +403,6 @@ protected: /** The inverse ordering, only used for creating ISAM2Result::DetailedResults */ boost::optional inverseOrdering_; -private: -#ifndef NDEBUG - std::vector lastRelinVariables_; -#endif - public: typedef ISAM2 This; ///< This class diff --git a/gtsam/slam/visualSLAM.cpp b/gtsam/slam/visualSLAM.cpp index 5b04b92c6..2133c0ee8 100644 --- a/gtsam/slam/visualSLAM.cpp +++ b/gtsam/slam/visualSLAM.cpp @@ -31,7 +31,7 @@ namespace visualSLAM { if (Z.rows() != 2) throw std::invalid_argument("insertBackProjections: Z must be 2*K"); if (Z.cols() != J.size()) throw std::invalid_argument( "insertBackProjections: J and Z must have same number of entries"); - for(size_t k=0;k + +#include + +namespace gtsam { + +/* ************************************************************************* */ +void LinearContainerFactor::rekeyFactor(const Ordering& ordering) { + Ordering::InvertedMap invOrdering = ordering.invert(); // TODO: inefficient - make more selective ordering invert + rekeyFactor(invOrdering); +} + +/* ************************************************************************* */ +void LinearContainerFactor::rekeyFactor(const Ordering::InvertedMap& invOrdering) { + BOOST_FOREACH(Index& idx, factor_->keys()) { + Key fullKey = invOrdering.find(idx)->second; + idx = fullKey; + keys_.push_back(fullKey); + } +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const JacobianFactor& factor, const Ordering& ordering) +: factor_(factor.clone()) { + rekeyFactor(ordering); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const HessianFactor& factor, const Ordering& ordering) +: factor_(factor.clone()) { + rekeyFactor(ordering); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const GaussianFactor::shared_ptr& factor, const Ordering& ordering) +: factor_(factor->clone()) { + rekeyFactor(ordering); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const GaussianFactor::shared_ptr& factor) +: factor_(factor->clone()) +{ +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor(const JacobianFactor& factor, + const Ordering::InvertedMap& inverted_ordering) +: factor_(factor.clone()) { + rekeyFactor(inverted_ordering); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor(const HessianFactor& factor, + const Ordering::InvertedMap& inverted_ordering) +: factor_(factor.clone()) { + rekeyFactor(inverted_ordering); +} + +/* ************************************************************************* */ +LinearContainerFactor::LinearContainerFactor( + const GaussianFactor::shared_ptr& factor, + const Ordering::InvertedMap& ordering) +: factor_(factor->clone()) { + rekeyFactor(ordering); +} + +/* ************************************************************************* */ +void LinearContainerFactor::print(const std::string& s, const KeyFormatter& keyFormatter) const { + Base::print(s+"LinearContainerFactor", keyFormatter); + if (factor_) + factor_->print(" Stored Factor", keyFormatter); +} + +/* ************************************************************************* */ +bool LinearContainerFactor::equals(const NonlinearFactor& f, double tol) const { + const LinearContainerFactor* jcf = dynamic_cast(&f); + return jcf && factor_->equals(*jcf->factor_, tol) && NonlinearFactor::equals(f); +} + +/* ************************************************************************* */ +double LinearContainerFactor::error(const Values& c) const { + // VectorValues vecvalues; + // // FIXME: add values correctly here + // return factor_.error(vecvalues); + return 0; // FIXME: placeholder +} + +/* ************************************************************************* */ +size_t LinearContainerFactor::dim() const { + if (isJacobian()) + return toJacobian()->get_model()->dim(); + else + return 1; // Hessians don't have true dimension +} + +/* ************************************************************************* */ +boost::shared_ptr +LinearContainerFactor::linearize(const Values& c, const Ordering& ordering) const { + // clone factor + boost::shared_ptr result = factor_->clone(); + + // rekey + BOOST_FOREACH(Index& key, result->keys()) + key = ordering[key]; + + return result; +} + +/* ************************************************************************* */ +bool LinearContainerFactor::isJacobian() const { + return boost::shared_dynamic_cast(factor_); +} + +/* ************************************************************************* */ +JacobianFactor::shared_ptr LinearContainerFactor::toJacobian() const { + return boost::shared_dynamic_cast(factor_); +} + +/* ************************************************************************* */ +HessianFactor::shared_ptr LinearContainerFactor::toHessian() const { + return boost::shared_dynamic_cast(factor_); +} + +/* ************************************************************************* */ +GaussianFactor::shared_ptr LinearContainerFactor::negate(const Ordering& ordering) const { + GaussianFactor::shared_ptr result = factor_->negate(); + BOOST_FOREACH(Key& key, result->keys()) + key = ordering[key]; + return result; +} + +/* ************************************************************************* */ +} // \namespace gtsam + + + diff --git a/gtsam_unstable/nonlinear/LinearContainerFactor.h b/gtsam_unstable/nonlinear/LinearContainerFactor.h new file mode 100644 index 000000000..23705f96e --- /dev/null +++ b/gtsam_unstable/nonlinear/LinearContainerFactor.h @@ -0,0 +1,113 @@ +/** + * @file LinearContainerFactor.h + * + * @brief Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph + * + * @date Jul 6, 2012 + * @author Alex Cunningham + */ + +#pragma once + +#include +#include + +namespace gtsam { + +/** + * Dummy version of a generic linear factor to be injected into a nonlinear factor graph + */ +class LinearContainerFactor : public NonlinearFactor { +protected: + + GaussianFactor::shared_ptr factor_; + +public: + + /** Primary constructor: store a linear factor and decode the ordering */ + LinearContainerFactor(const JacobianFactor& factor, const Ordering& ordering); + + /** Primary constructor: store a linear factor and decode the ordering */ + LinearContainerFactor(const HessianFactor& factor, const Ordering& ordering); + + /** Constructor from shared_ptr */ + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Ordering& ordering); + + /** Constructor from re-keyed factor: all indices assumed replaced with Key */ + LinearContainerFactor(const GaussianFactor::shared_ptr& factor); + + /** Alternate constructor: store a linear factor and decode keys with inverted ordering*/ + LinearContainerFactor(const JacobianFactor& factor, + const Ordering::InvertedMap& inverted_ordering); + + /** Alternate constructor: store a linear factor and decode keys with inverted ordering*/ + LinearContainerFactor(const HessianFactor& factor, + const Ordering::InvertedMap& inverted_ordering); + + /** Constructor from shared_ptr with inverted ordering*/ + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, + const Ordering::InvertedMap& ordering); + + // Access + + const GaussianFactor::shared_ptr& factor() const { return factor_; } + + // Testable + + /** print */ + void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; + + /** Check if two factors are equal */ + bool equals(const NonlinearFactor& f, double tol = 1e-9) const; + + // NonlinearFactor + + /** + * Calculate the error of the factor: uses the underlying linear factor to compute ordering + */ + double error(const Values& c) const; + + /** get the dimension of the factor: rows of linear factor */ + size_t dim() const; + + /** linearize to a GaussianFactor: values has no effect, just clones/rekeys underlying factor */ + boost::shared_ptr + linearize(const Values& c, const Ordering& ordering) const; + + /** + * Creates an anti-factor directly and performs rekeying due to ordering + */ + GaussianFactor::shared_ptr negate(const Ordering& ordering) const; + + /** + * Creates a shared_ptr clone of the factor - needs to be specialized to allow + * for subclasses + * + * Clones the underlying linear factor + */ + NonlinearFactor::shared_ptr clone() const { + return NonlinearFactor::shared_ptr(new LinearContainerFactor(factor_)); + } + + // casting syntactic sugar + + /** + * Simple check whether this is a Jacobian or Hessian factor + */ + bool isJacobian() const; + + /** Casts to JacobianFactor */ + JacobianFactor::shared_ptr toJacobian() const; + + /** Casts to HessianFactor */ + HessianFactor::shared_ptr toHessian() const; + +protected: + void rekeyFactor(const Ordering& ordering); + void rekeyFactor(const Ordering::InvertedMap& invOrdering); + +}; // \class LinearContainerFactor + +} // \namespace gtsam + + diff --git a/gtsam_unstable/nonlinear/tests/testLinearContainerFactor.cpp b/gtsam_unstable/nonlinear/tests/testLinearContainerFactor.cpp new file mode 100644 index 000000000..e85b880e8 --- /dev/null +++ b/gtsam_unstable/nonlinear/tests/testLinearContainerFactor.cpp @@ -0,0 +1,113 @@ +/** + * @file testLinearContainerFactor.cpp + * + * @date Jul 6, 2012 + * @author Alex Cunningham + */ + +#include + +#include + +#include + +using namespace gtsam; + +const gtsam::noiseModel::Diagonal::shared_ptr diag_model2 = noiseModel::Diagonal::Sigmas(Vector_(2, 1.0, 1.0)); +const double tol = 1e-5; + +gtsam::Key l1 = 101, l2 = 102, x1 = 1, x2 = 2; + +Point2 landmark1(5.0, 1.5), landmark2(7.0, 1.5); +Pose2 poseA1(0.0, 0.0, 0.0), poseA2(2.0, 0.0, 0.0); + +/* ************************************************************************* */ +TEST( testLinearContainerFactor, generic_jacobian_factor ) { + + Ordering initOrdering; initOrdering += x1, x2, l1, l2; + + JacobianFactor expLinFactor1( + initOrdering[l1], + Matrix_(2,2, + 2.74222, -0.0067457, + 0.0, 2.63624), + initOrdering[l2], + Matrix_(2,2, + -0.0455167, -0.0443573, + -0.0222154, -0.102489), + Vector_(2, 0.0277052, + -0.0533393), + diag_model2); + + LinearContainerFactor actFactor1(expLinFactor1, initOrdering); + Values values; + values.insert(l1, landmark1); + values.insert(l2, landmark2); + values.insert(x1, poseA1); + values.insert(x2, poseA2); + + // Check reconstruction from same ordering + GaussianFactor::shared_ptr actLinearizationA = actFactor1.linearize(values, initOrdering); + EXPECT(assert_equal(*expLinFactor1.clone(), *actLinearizationA, tol)); + + // Check reconstruction from new ordering + Ordering newOrdering; newOrdering += x1, l1, x2, l2; + GaussianFactor::shared_ptr actLinearizationB = actFactor1.linearize(values, newOrdering); + + JacobianFactor expLinFactor2( + newOrdering[l1], + Matrix_(2,2, + 2.74222, -0.0067457, + 0.0, 2.63624), + newOrdering[l2], + Matrix_(2,2, + -0.0455167, -0.0443573, + -0.0222154, -0.102489), + Vector_(2, 0.0277052, + -0.0533393), + diag_model2); + + EXPECT(assert_equal(*expLinFactor2.clone(), *actLinearizationB, tol)); +} + +/* ************************************************************************* */ +TEST( testLinearContainerFactor, generic_hessian_factor ) { + Matrix G11 = Matrix_(1,1, 1.0); + Matrix G12 = Matrix_(1,2, 2.0, 4.0); + Matrix G13 = Matrix_(1,3, 3.0, 6.0, 9.0); + + Matrix G22 = Matrix_(2,2, 3.0, 5.0, 0.0, 6.0); + Matrix G23 = Matrix_(2,3, 4.0, 6.0, 8.0, 1.0, 2.0, 4.0); + + Matrix G33 = Matrix_(3,3, 1.0, 2.0, 3.0, 0.0, 5.0, 6.0, 0.0, 0.0, 9.0); + + Vector g1 = Vector_(1, -7.0); + Vector g2 = Vector_(2, -8.0, -9.0); + Vector g3 = Vector_(3, 1.0, 2.0, 3.0); + + double f = 10.0; + + Ordering initOrdering; initOrdering += x1, x2, l1, l2; + HessianFactor initFactor(initOrdering[x1], initOrdering[x2], initOrdering[l1], + G11, G12, G13, g1, G22, G23, g2, G33, g3, f); + + Values values; + values.insert(l1, landmark1); + values.insert(l2, landmark2); + values.insert(x1, poseA1); + values.insert(x2, poseA2); + + LinearContainerFactor actFactor(initFactor, initOrdering); + GaussianFactor::shared_ptr actLinearization1 = actFactor.linearize(values, initOrdering); + EXPECT(assert_equal(*initFactor.clone(), *actLinearization1, tol)); + + Ordering newOrdering; newOrdering += l1, x1, x2, l2; + HessianFactor expLinFactor(newOrdering[x1], newOrdering[x2], newOrdering[l1], + G11, G12, G13, g1, G22, G23, g2, G33, g3, f); + GaussianFactor::shared_ptr actLinearization2 = actFactor.linearize(values, newOrdering); + EXPECT(assert_equal(*expLinFactor.clone(), *actLinearization2, tol)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index f63d2add5..9fdd6512f 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -431,7 +431,7 @@ bool isam_check(const planarSLAM::Graph& fullgraph, const Values& fullinit, cons bool totalGradOk = assert_equal(expectedGradient, actualGradient); EXPECT(totalGradOk); - return nodeGradientsOk && expectedGradOk && totalGradOk; + return nodeGradientsOk && expectedGradOk && totalGradOk && isamEqual; } /* ************************************************************************* */ diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 803017e42..dd28a830a 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -18,7 +18,9 @@ #include #include #include -#include +//#include // on Linux GCC: fails with error regarding needing C++0x std flags +//#include // same failure as above +#include // works on Linux GCC #include #include diff --git a/wrap/Class.h b/wrap/Class.h index 5703f8353..78d779a1f 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -34,7 +34,7 @@ struct Class { typedef std::map StaticMethods; /// Constructor creates an empty class - Class(bool verbose=true) : verbose_(verbose), isVirtual(false) {} + Class(bool verbose=true) : isVirtual(false), verbose_(verbose) {} // Then the instance variables are set directly by the Module constructor std::string name; ///< Class name diff --git a/wrap/Method.h b/wrap/Method.h index d9b1f09f1..936b3812d 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -30,7 +30,7 @@ struct Method { /// Constructor creates empty object Method(bool verbose = true) : - verbose_(verbose) {} + verbose_(verbose), is_const_(false) {} // Then the instance variables are set directly by the Module constructor bool verbose_; diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 006e38d4a..413fc84b8 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -1,350 +1,350 @@ -/* ---------------------------------------------------------------------------- - - * 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 Module.ccp - * @author Frank Dellaert - * @author Alex Cunningham - * @author Andrew Melim - **/ - -#include "Module.h" -#include "FileWriter.h" -#include "utilities.h" -#include "spirit_actors.h" - -//#define BOOST_SPIRIT_DEBUG -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -using namespace std; -using namespace wrap; -using namespace BOOST_SPIRIT_CLASSIC_NS; -namespace bl = boost::lambda; -namespace fs = boost::filesystem; - -typedef rule Rule; - -/* ************************************************************************* */ -// We parse an interface file into a Module object. -// The grammar is defined using the boost/spirit combinatorial parser. -// For example, str_p("const") parses the string "const", and the >> -// operator creates a sequence parser. The grammar below, composed of rules -// and with start rule [class_p], doubles as the specs for our interface files. -/* ************************************************************************* */ - -Module::Module(const string& interfacePath, - const string& moduleName, bool enable_verbose) : name(moduleName), verbose(enable_verbose) -{ - // these variables will be imperatively updated to gradually build [cls] - // The one with postfix 0 are used to reset the variables after parse. - string methodName, methodName0; - bool isConst, isConst0 = false; - ReturnValue retVal0, retVal; - Argument arg0, arg; - ArgumentList args0, args; - vector arg_dup; ///keep track of duplicates - Constructor constructor0(enable_verbose), constructor(enable_verbose); - Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); - //Method method0(enable_verbose), method(enable_verbose); - StaticMethod static_method0(enable_verbose), static_method(enable_verbose); - Class cls0(enable_verbose),cls(enable_verbose); - ForwardDeclaration fwDec0, fwDec; - vector namespaces, /// current namespace tag - namespace_includes, /// current set of includes - namespaces_return, /// namespace for current return type - using_namespace_current; /// All namespaces from "using" declarations - string include_path = ""; - const string null_str = ""; - - //---------------------------------------------------------------------------- - // Grammar with actions that build the Class object. Actions are - // defined within the square brackets [] and are executed whenever a - // rule is successfully parsed. Define BOOST_SPIRIT_DEBUG to debug. - // The grammar is allows a very restricted C++ header - // lexeme_d turns off white space skipping - // http://www.boost.org/doc/libs/1_37_0/libs/spirit/classic/doc/directives.html - // ---------------------------------------------------------------------------- - - Rule comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); - - Rule basisType_p = - (str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char"); - - Rule keywords_p = - (str_p("const") | "static" | "namespace" | basisType_p); - - Rule eigenType_p = - (str_p("Vector") | "Matrix"); - - Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p); - - Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; - - Rule namespace_arg_p = namespace_name_p[push_back_a(arg.namespaces)] >> str_p("::"); - - Rule argEigenType_p = - eigenType_p[assign_a(arg.type)] >> - !ch_p('*')[assign_a(arg.is_ptr,true)]; - - Rule eigenRef_p = - !str_p("const") [assign_a(arg.is_const,true)] >> - eigenType_p [assign_a(arg.type)] >> - ch_p('&') [assign_a(arg.is_ref,true)]; - - Rule classArg_p = - !str_p("const") [assign_a(arg.is_const,true)] >> - *namespace_arg_p >> - className_p[assign_a(arg.type)] >> - (ch_p('*')[assign_a(arg.is_ptr,true)] | ch_p('&')[assign_a(arg.is_ref,true)]); - - Rule classParent_p = - *(namespace_name_p[push_back_a(cls.qualifiedParent)] >> str_p("::")) >> - className_p[push_back_a(cls.qualifiedParent)]; - - Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; - - Rule argument_p = - ((basisType_p[assign_a(arg.type)] | argEigenType_p | eigenRef_p | classArg_p) - >> name_p[assign_a(arg.name)]) - [push_back_a(args, arg)] - [assign_a(arg,arg0)]; - - Rule argumentList_p = !argument_p >> * (',' >> argument_p); - - Rule constructor_p = - (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) - [push_back_a(constructor.args_list, args)] - [assign_a(args,args0)]; - //[assign_a(constructor.args,args)] - //[assign_a(constructor.name,cls.name)] - //[push_back_a(cls.constructors, constructor)] - //[assign_a(constructor,constructor0)]; - - Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); - - Rule returnType1_p = - (basisType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::BASIS)]) | - ((*namespace_ret_p)[assign_a(retVal.namespaces1, namespaces_return)][clear_a(namespaces_return)] - >> (className_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::CLASS)]) >> - !ch_p('*')[assign_a(retVal.isPtr1,true)]) | - (eigenType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::EIGEN)]); - - Rule returnType2_p = - (basisType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::BASIS)]) | - ((*namespace_ret_p)[assign_a(retVal.namespaces2, namespaces_return)][clear_a(namespaces_return)] - >> (className_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::CLASS)]) >> - !ch_p('*') [assign_a(retVal.isPtr2,true)]) | - (eigenType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::EIGEN)]); - - Rule pair_p = - (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') - [assign_a(retVal.isPair,true)]; - - Rule void_p = str_p("void")[assign_a(retVal.type1)]; - - Rule returnType_p = void_p | returnType1_p | pair_p; - - Rule methodName_p = lexeme_d[lower_p >> *(alnum_p | '_')]; - - Rule method_p = - (returnType_p >> methodName_p[assign_a(methodName)] >> - '(' >> argumentList_p >> ')' >> - !str_p("const")[assign_a(isConst,true)] >> ';' >> *comments_p) - [bl::bind(&Method::addOverload, - bl::var(cls.methods)[bl::var(methodName)], - verbose, - bl::var(isConst), - bl::var(methodName), - bl::var(args), - bl::var(retVal))] - [assign_a(isConst,isConst0)] - [assign_a(methodName,methodName0)] - [assign_a(args,args0)] - [assign_a(retVal,retVal0)]; - - Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; - - Rule static_method_p = - (str_p("static") >> returnType_p >> staticMethodName_p[assign_a(methodName)] >> - '(' >> 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))] - [assign_a(methodName,methodName0)] - [assign_a(args,args0)] - [assign_a(retVal,retVal0)]; - - Rule functions_p = constructor_p | method_p | static_method_p; - - Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[assign_a(include_path)] >> ch_p('>'); - - Rule class_p = - (!*include_p - >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) - >> str_p("class")[push_back_a(cls.includes, include_path)][assign_a(include_path, null_str)] - >> className_p[assign_a(cls.name)] - >> ((':' >> classParent_p >> '{') | '{') // By having (parent >> '{' | '{') here instead of (!parent >> '{'), we trigger a parse error on a badly-formed parent spec - >> *(functions_p | comments_p) - >> str_p("};")) - [assign_a(constructor.name, cls.name)] - [assign_a(cls.constructor, constructor)] - [assign_a(cls.namespaces, namespaces)] - [assign_a(cls.using_namespaces, using_namespace_current)] - [append_a(cls.includes, namespace_includes)] - [assign_a(deconstructor.name,cls.name)] - [assign_a(cls.deconstructor, deconstructor)] - [push_back_a(classes, cls)] - [assign_a(deconstructor,deconstructor0)] - [assign_a(constructor, constructor0)] - [assign_a(cls,cls0)]; - - Rule namespace_def_p = - (!*include_p - >> str_p("namespace")[push_back_a(namespace_includes, include_path)][assign_a(include_path, null_str)] - >> namespace_name_p[push_back_a(namespaces)] - >> ch_p('{') - >> *(class_p | namespace_def_p | comments_p) - >> str_p("}///\\namespace") // end namespace, avoid confusion with classes - >> !namespace_name_p) - [pop_a(namespaces)] - [pop_a(namespace_includes)]; - - Rule using_namespace_p = - str_p("using") >> str_p("namespace") - >> namespace_name_p[push_back_a(using_namespace_current)] >> ch_p(';'); - - Rule forward_declaration_p = - !(str_p("virtual")[assign_a(fwDec.isVirtual, true)]) - >> str_p("class") - >> (*(namespace_name_p >> str_p("::")) >> className_p)[assign_a(fwDec.name)] - >> ch_p(';') - [push_back_a(forward_declarations, fwDec)] - [assign_a(fwDec, fwDec0)]; - - Rule module_content_p = comments_p | using_namespace_p | class_p | forward_declaration_p | namespace_def_p ; - - Rule module_p = *module_content_p >> !end_p; - - //---------------------------------------------------------------------------- - // for debugging, define BOOST_SPIRIT_DEBUG -# ifdef BOOST_SPIRIT_DEBUG - BOOST_SPIRIT_DEBUG_NODE(className_p); - BOOST_SPIRIT_DEBUG_NODE(classPtr_p); - BOOST_SPIRIT_DEBUG_NODE(classRef_p); - BOOST_SPIRIT_DEBUG_NODE(basisType_p); - BOOST_SPIRIT_DEBUG_NODE(name_p); - BOOST_SPIRIT_DEBUG_NODE(argument_p); - BOOST_SPIRIT_DEBUG_NODE(argumentList_p); - BOOST_SPIRIT_DEBUG_NODE(constructor_p); - BOOST_SPIRIT_DEBUG_NODE(returnType1_p); - BOOST_SPIRIT_DEBUG_NODE(returnType2_p); - BOOST_SPIRIT_DEBUG_NODE(pair_p); - BOOST_SPIRIT_DEBUG_NODE(void_p); - BOOST_SPIRIT_DEBUG_NODE(returnType_p); - BOOST_SPIRIT_DEBUG_NODE(methodName_p); - BOOST_SPIRIT_DEBUG_NODE(method_p); - BOOST_SPIRIT_DEBUG_NODE(class_p); - BOOST_SPIRIT_DEBUG_NODE(namespace_def_p); - BOOST_SPIRIT_DEBUG_NODE(module_p); -# endif - //---------------------------------------------------------------------------- - - // read interface file - string interfaceFile = interfacePath + "/" + moduleName + ".h"; - string contents = file_contents(interfaceFile); - - // and parse contents - parse_info info = parse(contents.c_str(), module_p, space_p); - if(!info.full) { - printf("parsing stopped at \n%.20s\n",info.stop); - throw ParseFailed(info.length); - } -} - -/* ************************************************************************* */ -template -void verifyArguments(const vector& validArgs, const map& vt) { - typedef typename map::value_type Name_Method; - BOOST_FOREACH(const Name_Method& name_method, vt) { - const T& t = name_method.second; - BOOST_FOREACH(const ArgumentList& argList, t.argLists) { - BOOST_FOREACH(Argument arg, argList) { - string fullType = arg.qualifiedType("::"); - if(find(validArgs.begin(), validArgs.end(), fullType) - == validArgs.end()) - throw DependencyMissing(fullType, t.name); - } - } - } -} - -/* ************************************************************************* */ -template -void verifyReturnTypes(const vector& validtypes, const map& vt) { - typedef typename map::value_type Name_Method; - BOOST_FOREACH(const Name_Method& name_method, vt) { - const T& t = name_method.second; - BOOST_FOREACH(const ReturnValue& retval, t.returnVals) { - if (find(validtypes.begin(), validtypes.end(), retval.qualifiedType1("::")) == validtypes.end()) - throw DependencyMissing(retval.qualifiedType1("::"), t.name); - if (retval.isPair && find(validtypes.begin(), validtypes.end(), retval.qualifiedType2("::")) == validtypes.end()) - throw DependencyMissing(retval.qualifiedType2("::"), t.name); - } - } -} - -/* ************************************************************************* */ -void Module::matlab_code(const string& toolboxPath, const string& headerPath) const { - - fs::create_directories(toolboxPath); - - // create the unified .cpp switch file - const string wrapperName = name + "_wrapper"; - string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; - FileWriter wrapperFile(wrapperFileName, verbose, "//"); - vector functionNames; // Function names stored by index for switch - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "\n"; - - // Dependency check list - vector validTypes; - BOOST_FOREACH(const ForwardDeclaration& fwDec, forward_declarations) { - validTypes.push_back(fwDec.name); - } - validTypes.push_back("void"); - validTypes.push_back("string"); - validTypes.push_back("int"); - validTypes.push_back("bool"); - validTypes.push_back("char"); - validTypes.push_back("unsigned char"); - validTypes.push_back("size_t"); - validTypes.push_back("double"); - validTypes.push_back("Vector"); - validTypes.push_back("Matrix"); +/* ---------------------------------------------------------------------------- + + * 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 Module.ccp + * @author Frank Dellaert + * @author Alex Cunningham + * @author Andrew Melim + **/ + +#include "Module.h" +#include "FileWriter.h" +#include "utilities.h" +#include "spirit_actors.h" + +//#define BOOST_SPIRIT_DEBUG +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace std; +using namespace wrap; +using namespace BOOST_SPIRIT_CLASSIC_NS; +namespace bl = boost::lambda; +namespace fs = boost::filesystem; + +typedef rule Rule; + +/* ************************************************************************* */ +// We parse an interface file into a Module object. +// The grammar is defined using the boost/spirit combinatorial parser. +// For example, str_p("const") parses the string "const", and the >> +// operator creates a sequence parser. The grammar below, composed of rules +// and with start rule [class_p], doubles as the specs for our interface files. +/* ************************************************************************* */ + +Module::Module(const string& interfacePath, + const string& moduleName, bool enable_verbose) : name(moduleName), verbose(enable_verbose) +{ + // these variables will be imperatively updated to gradually build [cls] + // The one with postfix 0 are used to reset the variables after parse. + string methodName, methodName0; + bool isConst, isConst0 = false; + ReturnValue retVal0, retVal; + Argument arg0, arg; + ArgumentList args0, args; + vector arg_dup; ///keep track of duplicates + Constructor constructor0(enable_verbose), constructor(enable_verbose); + Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); + //Method method0(enable_verbose), method(enable_verbose); + StaticMethod static_method0(enable_verbose), static_method(enable_verbose); + Class cls0(enable_verbose),cls(enable_verbose); + ForwardDeclaration fwDec0, fwDec; + vector namespaces, /// current namespace tag + namespace_includes, /// current set of includes + namespaces_return, /// namespace for current return type + using_namespace_current; /// All namespaces from "using" declarations + string include_path = ""; + const string null_str = ""; + + //---------------------------------------------------------------------------- + // Grammar with actions that build the Class object. Actions are + // defined within the square brackets [] and are executed whenever a + // rule is successfully parsed. Define BOOST_SPIRIT_DEBUG to debug. + // The grammar is allows a very restricted C++ header + // lexeme_d turns off white space skipping + // http://www.boost.org/doc/libs/1_37_0/libs/spirit/classic/doc/directives.html + // ---------------------------------------------------------------------------- + + Rule comments_p = comment_p("/*", "*/") | comment_p("//", eol_p); + + Rule basisType_p = + (str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char"); + + Rule keywords_p = + (str_p("const") | "static" | "namespace" | basisType_p); + + Rule eigenType_p = + (str_p("Vector") | "Matrix"); + + Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p); + + Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p; + + Rule namespace_arg_p = namespace_name_p[push_back_a(arg.namespaces)] >> str_p("::"); + + Rule argEigenType_p = + eigenType_p[assign_a(arg.type)] >> + !ch_p('*')[assign_a(arg.is_ptr,true)]; + + Rule eigenRef_p = + !str_p("const") [assign_a(arg.is_const,true)] >> + eigenType_p [assign_a(arg.type)] >> + ch_p('&') [assign_a(arg.is_ref,true)]; + + Rule classArg_p = + !str_p("const") [assign_a(arg.is_const,true)] >> + *namespace_arg_p >> + className_p[assign_a(arg.type)] >> + (ch_p('*')[assign_a(arg.is_ptr,true)] | ch_p('&')[assign_a(arg.is_ref,true)]); + + Rule classParent_p = + *(namespace_name_p[push_back_a(cls.qualifiedParent)] >> str_p("::")) >> + className_p[push_back_a(cls.qualifiedParent)]; + + Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')]; + + Rule argument_p = + ((basisType_p[assign_a(arg.type)] | argEigenType_p | eigenRef_p | classArg_p) + >> name_p[assign_a(arg.name)]) + [push_back_a(args, arg)] + [assign_a(arg,arg0)]; + + Rule argumentList_p = !argument_p >> * (',' >> argument_p); + + Rule constructor_p = + (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) + [push_back_a(constructor.args_list, args)] + [assign_a(args,args0)]; + //[assign_a(constructor.args,args)] + //[assign_a(constructor.name,cls.name)] + //[push_back_a(cls.constructors, constructor)] + //[assign_a(constructor,constructor0)]; + + Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); + + Rule returnType1_p = + (basisType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::BASIS)]) | + ((*namespace_ret_p)[assign_a(retVal.namespaces1, namespaces_return)][clear_a(namespaces_return)] + >> (className_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::CLASS)]) >> + !ch_p('*')[assign_a(retVal.isPtr1,true)]) | + (eigenType_p[assign_a(retVal.type1)][assign_a(retVal.category1, ReturnValue::EIGEN)]); + + Rule returnType2_p = + (basisType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::BASIS)]) | + ((*namespace_ret_p)[assign_a(retVal.namespaces2, namespaces_return)][clear_a(namespaces_return)] + >> (className_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::CLASS)]) >> + !ch_p('*') [assign_a(retVal.isPtr2,true)]) | + (eigenType_p[assign_a(retVal.type2)][assign_a(retVal.category2, ReturnValue::EIGEN)]); + + Rule pair_p = + (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>') + [assign_a(retVal.isPair,true)]; + + Rule void_p = str_p("void")[assign_a(retVal.type1)]; + + Rule returnType_p = void_p | returnType1_p | pair_p; + + Rule methodName_p = lexeme_d[lower_p >> *(alnum_p | '_')]; + + Rule method_p = + (returnType_p >> methodName_p[assign_a(methodName)] >> + '(' >> argumentList_p >> ')' >> + !str_p("const")[assign_a(isConst,true)] >> ';' >> *comments_p) + [bl::bind(&Method::addOverload, + bl::var(cls.methods)[bl::var(methodName)], + verbose, + bl::var(isConst), + bl::var(methodName), + bl::var(args), + bl::var(retVal))] + [assign_a(isConst,isConst0)] + [assign_a(methodName,methodName0)] + [assign_a(args,args0)] + [assign_a(retVal,retVal0)]; + + Rule staticMethodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')]; + + Rule static_method_p = + (str_p("static") >> returnType_p >> staticMethodName_p[assign_a(methodName)] >> + '(' >> 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))] + [assign_a(methodName,methodName0)] + [assign_a(args,args0)] + [assign_a(retVal,retVal0)]; + + Rule functions_p = constructor_p | method_p | static_method_p; + + Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[assign_a(include_path)] >> ch_p('>'); + + Rule class_p = + (!*include_p + >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) + >> str_p("class")[push_back_a(cls.includes, include_path)][assign_a(include_path, null_str)] + >> className_p[assign_a(cls.name)] + >> ((':' >> classParent_p >> '{') | '{') // By having (parent >> '{' | '{') here instead of (!parent >> '{'), we trigger a parse error on a badly-formed parent spec + >> *(functions_p | comments_p) + >> str_p("};")) + [assign_a(constructor.name, cls.name)] + [assign_a(cls.constructor, constructor)] + [assign_a(cls.namespaces, namespaces)] + [assign_a(cls.using_namespaces, using_namespace_current)] + [append_a(cls.includes, namespace_includes)] + [assign_a(deconstructor.name,cls.name)] + [assign_a(cls.deconstructor, deconstructor)] + [push_back_a(classes, cls)] + [assign_a(deconstructor,deconstructor0)] + [assign_a(constructor, constructor0)] + [assign_a(cls,cls0)]; + + Rule namespace_def_p = + (!*include_p + >> str_p("namespace")[push_back_a(namespace_includes, include_path)][assign_a(include_path, null_str)] + >> namespace_name_p[push_back_a(namespaces)] + >> ch_p('{') + >> *(class_p | namespace_def_p | comments_p) + >> str_p("}///\\namespace") // end namespace, avoid confusion with classes + >> !namespace_name_p) + [pop_a(namespaces)] + [pop_a(namespace_includes)]; + + Rule using_namespace_p = + str_p("using") >> str_p("namespace") + >> namespace_name_p[push_back_a(using_namespace_current)] >> ch_p(';'); + + Rule forward_declaration_p = + !(str_p("virtual")[assign_a(fwDec.isVirtual, true)]) + >> str_p("class") + >> (*(namespace_name_p >> str_p("::")) >> className_p)[assign_a(fwDec.name)] + >> ch_p(';') + [push_back_a(forward_declarations, fwDec)] + [assign_a(fwDec, fwDec0)]; + + Rule module_content_p = comments_p | using_namespace_p | class_p | forward_declaration_p | namespace_def_p ; + + Rule module_p = *module_content_p >> !end_p; + + //---------------------------------------------------------------------------- + // for debugging, define BOOST_SPIRIT_DEBUG +# ifdef BOOST_SPIRIT_DEBUG + BOOST_SPIRIT_DEBUG_NODE(className_p); + BOOST_SPIRIT_DEBUG_NODE(classPtr_p); + BOOST_SPIRIT_DEBUG_NODE(classRef_p); + BOOST_SPIRIT_DEBUG_NODE(basisType_p); + BOOST_SPIRIT_DEBUG_NODE(name_p); + BOOST_SPIRIT_DEBUG_NODE(argument_p); + BOOST_SPIRIT_DEBUG_NODE(argumentList_p); + BOOST_SPIRIT_DEBUG_NODE(constructor_p); + BOOST_SPIRIT_DEBUG_NODE(returnType1_p); + BOOST_SPIRIT_DEBUG_NODE(returnType2_p); + BOOST_SPIRIT_DEBUG_NODE(pair_p); + BOOST_SPIRIT_DEBUG_NODE(void_p); + BOOST_SPIRIT_DEBUG_NODE(returnType_p); + BOOST_SPIRIT_DEBUG_NODE(methodName_p); + BOOST_SPIRIT_DEBUG_NODE(method_p); + BOOST_SPIRIT_DEBUG_NODE(class_p); + BOOST_SPIRIT_DEBUG_NODE(namespace_def_p); + BOOST_SPIRIT_DEBUG_NODE(module_p); +# endif + //---------------------------------------------------------------------------- + + // read interface file + string interfaceFile = interfacePath + "/" + moduleName + ".h"; + string contents = file_contents(interfaceFile); + + // and parse contents + parse_info info = parse(contents.c_str(), module_p, space_p); + if(!info.full) { + printf("parsing stopped at \n%.20s\n",info.stop); + throw ParseFailed(info.length); + } +} + +/* ************************************************************************* */ +template +void verifyArguments(const vector& validArgs, const map& vt) { + typedef typename map::value_type Name_Method; + BOOST_FOREACH(const Name_Method& name_method, vt) { + const T& t = name_method.second; + BOOST_FOREACH(const ArgumentList& argList, t.argLists) { + BOOST_FOREACH(Argument arg, argList) { + string fullType = arg.qualifiedType("::"); + if(find(validArgs.begin(), validArgs.end(), fullType) + == validArgs.end()) + throw DependencyMissing(fullType, t.name); + } + } + } +} + +/* ************************************************************************* */ +template +void verifyReturnTypes(const vector& validtypes, const map& vt) { + typedef typename map::value_type Name_Method; + BOOST_FOREACH(const Name_Method& name_method, vt) { + const T& t = name_method.second; + BOOST_FOREACH(const ReturnValue& retval, t.returnVals) { + if (find(validtypes.begin(), validtypes.end(), retval.qualifiedType1("::")) == validtypes.end()) + throw DependencyMissing(retval.qualifiedType1("::"), t.name); + if (retval.isPair && find(validtypes.begin(), validtypes.end(), retval.qualifiedType2("::")) == validtypes.end()) + throw DependencyMissing(retval.qualifiedType2("::"), t.name); + } + } +} + +/* ************************************************************************* */ +void Module::matlab_code(const string& toolboxPath, const string& headerPath) const { + + fs::create_directories(toolboxPath); + + // create the unified .cpp switch file + const string wrapperName = name + "_wrapper"; + string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; + FileWriter wrapperFile(wrapperFileName, verbose, "//"); + vector functionNames; // Function names stored by index for switch + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "\n"; + + // Dependency check list + vector validTypes; + BOOST_FOREACH(const ForwardDeclaration& fwDec, forward_declarations) { + validTypes.push_back(fwDec.name); + } + validTypes.push_back("void"); + validTypes.push_back("string"); + validTypes.push_back("int"); + validTypes.push_back("bool"); + validTypes.push_back("char"); + validTypes.push_back("unsigned char"); + validTypes.push_back("size_t"); + validTypes.push_back("double"); + validTypes.push_back("Vector"); + validTypes.push_back("Matrix"); //Create a list of parsed classes for dependency checking BOOST_FOREACH(const Class& cls, classes) { validTypes.push_back(cls.qualifiedName("::")); @@ -359,69 +359,80 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co BOOST_FOREACH(const Class& cls, classes) { if(!typeAttributes.insert(make_pair(cls.qualifiedName("::"), ReturnValue::TypeAttributes(cls.isVirtual))).second) throw DuplicateDefinition("class " + cls.qualifiedName("::")); - - // Check that class is virtual if it has a parent } - - // Generate all includes + // Check attributes BOOST_FOREACH(const Class& cls, classes) { - generateIncludes(wrapperFile, cls.name, cls.includes); - } - wrapperFile.oss << "\n"; - - // Generate all collectors + // Check that class is virtual if it has a parent + if(!cls.qualifiedParent.empty() && !cls.isVirtual) + throw AttributeError(cls.qualifiedName("::"), "Has a base class so needs to be declared virtual, change to 'virtual class "+cls.name+" ...'"); + // Check that parent is virtual as well + if(!cls.qualifiedParent.empty() && !typeAttributes.at(wrap::qualifiedName("::", cls.qualifiedParent)).isVirtual) + throw AttributeError(wrap::qualifiedName("::", cls.qualifiedParent), + "Is the base class of " + cls.qualifiedName("::") + ", so needs to be declared virtual"); + } + + // Check that all classes have been defined somewhere BOOST_FOREACH(const Class& cls, classes) { - const string matlabName = cls.qualifiedName(), cppName = cls.qualifiedName("::"); - wrapperFile.oss << "typedef std::set*> " - << "Collector_" << matlabName << ";\n"; - wrapperFile.oss << "static Collector_" << matlabName << - " collector_" << matlabName << ";\n"; - } - - // generate mexAtExit cleanup function - wrapperFile.oss << "void _deleteAllObjects()\n"; - wrapperFile.oss << "{\n"; + // verify all of the function arguments + //TODO:verifyArguments(validTypes, cls.constructor.args_list); + verifyArguments(validTypes, cls.static_methods); + verifyArguments(validTypes, cls.methods); + + // verify function return types + verifyReturnTypes(validTypes, cls.static_methods); + verifyReturnTypes(validTypes, cls.methods); + } + + // Generate all includes BOOST_FOREACH(const Class& cls, classes) { - const string matlabName = cls.qualifiedName(); - const string cppName = cls.qualifiedName("::"); - const string collectorType = "Collector_" + matlabName; - const string collectorName = "collector_" + matlabName; - wrapperFile.oss << " for(" << collectorType << "::iterator iter = " << collectorName << ".begin();\n"; - wrapperFile.oss << " iter != " << collectorName << ".end(); ) {\n"; - wrapperFile.oss << " delete *iter;\n"; - wrapperFile.oss << " " << collectorName << ".erase(iter++);\n"; - wrapperFile.oss << " }\n"; - } - wrapperFile.oss << "}\n"; - - // generate proxy classes and wrappers + generateIncludes(wrapperFile, cls.name, cls.includes); + } + wrapperFile.oss << "\n"; + + // Generate all collectors BOOST_FOREACH(const Class& cls, classes) { - // create proxy class and wrapper code - string classFile = toolboxPath + "/" + cls.qualifiedName() + ".m"; - cls.matlab_proxy(classFile, wrapperName, typeAttributes, wrapperFile, functionNames); - - // verify all of the function arguments - //TODO:verifyArguments(validTypes, cls.constructor.args_list); - verifyArguments(validTypes, cls.static_methods); - verifyArguments(validTypes, cls.methods); - - // verify function return types - verifyReturnTypes(validTypes, cls.static_methods); - verifyReturnTypes(validTypes, cls.methods); - } - - // finish wrapper file - finish_wrapper(wrapperFile, functionNames); - - wrapperFile.emit(true); - } - -/* ************************************************************************* */ - void Module::finish_wrapper(FileWriter& file, const std::vector& functionNames) const { - file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - file.oss << "{\n"; + const string matlabName = cls.qualifiedName(), cppName = cls.qualifiedName("::"); + wrapperFile.oss << "typedef std::set*> " + << "Collector_" << matlabName << ";\n"; + wrapperFile.oss << "static Collector_" << matlabName << + " collector_" << matlabName << ";\n"; + } + + // generate mexAtExit cleanup function + wrapperFile.oss << "\nvoid _deleteAllObjects()\n"; + wrapperFile.oss << "{\n"; + BOOST_FOREACH(const Class& cls, classes) { + const string matlabName = cls.qualifiedName(); + const string cppName = cls.qualifiedName("::"); + const string collectorType = "Collector_" + matlabName; + const string collectorName = "collector_" + matlabName; + wrapperFile.oss << " for(" << collectorType << "::iterator iter = " << collectorName << ".begin();\n"; + wrapperFile.oss << " iter != " << collectorName << ".end(); ) {\n"; + wrapperFile.oss << " delete *iter;\n"; + wrapperFile.oss << " " << collectorName << ".erase(iter++);\n"; + wrapperFile.oss << " }\n"; + } + wrapperFile.oss << "}\n"; + + // create proxy class and wrapper code + BOOST_FOREACH(const Class& cls, classes) { + string classFile = toolboxPath + "/" + cls.qualifiedName() + ".m"; + cls.matlab_proxy(classFile, wrapperName, typeAttributes, wrapperFile, functionNames); + } + + // finish wrapper file + wrapperFile.oss << "\n"; + finish_wrapper(wrapperFile, functionNames); + + wrapperFile.emit(true); + } + +/* ************************************************************************* */ + void Module::finish_wrapper(FileWriter& file, const std::vector& functionNames) const { + file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + file.oss << "{\n"; file.oss << " mstream mout;\n"; // Send stdout to MATLAB console, see matlab.h - file.oss << " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n"; + file.oss << " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n"; file.oss << " int id = unwrap(in[0]);\n\n"; file.oss << " switch(id) {\n"; for(size_t id = 0; id < functionNames.size(); ++id) { @@ -431,8 +442,8 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co } file.oss << " }\n"; file.oss << "\n"; - file.oss << " std::cout.rdbuf(outbuf);\n"; // Restore cout, see matlab.h + file.oss << " std::cout.rdbuf(outbuf);\n"; // Restore cout, see matlab.h file.oss << "}\n"; - } - -/* ************************************************************************* */ + } + +/* ************************************************************************* */ diff --git a/wrap/tests/expected/Point2.m b/wrap/tests/expected/Point2.m index 95f46a2dd..f23e15eb4 100644 --- a/wrap/tests/expected/Point2.m +++ b/wrap/tests/expected/Point2.m @@ -1,81 +1,82 @@ % automatically generated by wrap classdef Point2 < handle properties - self = 0 + ptr_Point2 = 0 end methods function obj = Point2(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - geometry_wrapper(obj.self); + my_ptr = varargin{2}; + geometry_wrapper(0, my_ptr); elseif nargin == 0 - obj.self = geometry_wrapper(1); + my_ptr = geometry_wrapper(1); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - obj.self = geometry_wrapper(2,varargin{1},varargin{2}); + my_ptr = geometry_wrapper(2, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Point2 constructor'); end + obj.ptr_Point2 = my_ptr; end function delete(obj) - geometry_wrapper(3, obj.self); + geometry_wrapper(3, obj.ptr_Point2); end function display(obj), obj.print(''); end function disp(obj), obj.display; end - function varargout = argChar(self, varargin) + function varargout = argChar(this, varargin) if length(varargin) == 1 && isa(varargin{1},'char') - geometry_wrapper(4, self, varargin{:}); + geometry_wrapper(4, this, varargin{:}); else error('Arguments do not match any overload of function Point2.argChar'); end end - function varargout = argUChar(self, varargin) + function varargout = argUChar(this, varargin) if length(varargin) == 1 && isa(varargin{1},'char') - geometry_wrapper(5, self, varargin{:}); + geometry_wrapper(5, this, varargin{:}); else error('Arguments do not match any overload of function Point2.argUChar'); end end - function varargout = dim(self, varargin) + function varargout = dim(this, varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(6, self, varargin{:}); + varargout{1} = geometry_wrapper(6, this, varargin{:}); else error('Arguments do not match any overload of function Point2.dim'); end end - function varargout = returnChar(self, varargin) + function varargout = returnChar(this, varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(7, self, varargin{:}); + varargout{1} = geometry_wrapper(7, this, varargin{:}); else error('Arguments do not match any overload of function Point2.returnChar'); end end - function varargout = vectorConfusion(self, varargin) + function varargout = vectorConfusion(this, varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(8, self, varargin{:}); + varargout{1} = geometry_wrapper(8, this, varargin{:}); else error('Arguments do not match any overload of function Point2.vectorConfusion'); end end - function varargout = x(self, varargin) + function varargout = x(this, varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(9, self, varargin{:}); + varargout{1} = geometry_wrapper(9, this, varargin{:}); else error('Arguments do not match any overload of function Point2.x'); end end - function varargout = y(self, varargin) + function varargout = y(this, varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(10, self, varargin{:}); + varargout{1} = geometry_wrapper(10, this, varargin{:}); else error('Arguments do not match any overload of function Point2.y'); end diff --git a/wrap/tests/expected/Point3.m b/wrap/tests/expected/Point3.m index 7a1045a86..773ebefc0 100644 --- a/wrap/tests/expected/Point3.m +++ b/wrap/tests/expected/Point3.m @@ -1,31 +1,32 @@ % automatically generated by wrap classdef Point3 < handle properties - self = 0 + ptr_Point3 = 0 end methods function obj = Point3(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - geometry_wrapper(obj.self); + my_ptr = varargin{2}; + geometry_wrapper(11, my_ptr); elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double') - obj.self = geometry_wrapper(12,varargin{1},varargin{2},varargin{3}); + my_ptr = geometry_wrapper(12, varargin{1}, varargin{2}, varargin{3}); else error('Arguments do not match any overload of Point3 constructor'); end + obj.ptr_Point3 = my_ptr; end function delete(obj) - geometry_wrapper(13, obj.self); + geometry_wrapper(13, obj.ptr_Point3); end function display(obj), obj.print(''); end function disp(obj), obj.display; end - function varargout = norm(self, varargin) + function varargout = norm(this, varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(14, self, varargin{:}); + varargout{1} = geometry_wrapper(14, this, varargin{:}); else error('Arguments do not match any overload of function Point3.norm'); end diff --git a/wrap/tests/expected/Test.m b/wrap/tests/expected/Test.m index 2c914502a..f36c8eb30 100644 --- a/wrap/tests/expected/Test.m +++ b/wrap/tests/expected/Test.m @@ -1,177 +1,178 @@ % automatically generated by wrap classdef Test < handle properties - self = 0 + ptr_Test = 0 end methods function obj = Test(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - geometry_wrapper(obj.self); + my_ptr = varargin{2}; + geometry_wrapper(17, my_ptr); elseif nargin == 0 - obj.self = geometry_wrapper(18); + my_ptr = geometry_wrapper(18); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - obj.self = geometry_wrapper(19,varargin{1},varargin{2}); + my_ptr = geometry_wrapper(19, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Test constructor'); end + obj.ptr_Test = my_ptr; end function delete(obj) - geometry_wrapper(20, obj.self); + geometry_wrapper(20, obj.ptr_Test); end function display(obj), obj.print(''); end function disp(obj), obj.display; end - function varargout = arg_EigenConstRef(self, varargin) + function varargout = arg_EigenConstRef(this, varargin) if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(21, self, varargin{:}); + geometry_wrapper(21, this, varargin{:}); else error('Arguments do not match any overload of function Test.arg_EigenConstRef'); end end - function varargout = create_MixedPtrs(self, varargin) + function varargout = create_MixedPtrs(this, varargin) if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(22, self, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(22, this, varargin{:}); else error('Arguments do not match any overload of function Test.create_MixedPtrs'); end end - function varargout = create_ptrs(self, varargin) + function varargout = create_ptrs(this, varargin) if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(23, self, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(23, this, varargin{:}); else error('Arguments do not match any overload of function Test.create_ptrs'); end end - function varargout = print(self, varargin) + function varargout = print(this, varargin) if length(varargin) == 0 - geometry_wrapper(24, self, varargin{:}); + geometry_wrapper(24, this, varargin{:}); else error('Arguments do not match any overload of function Test.print'); end end - function varargout = return_Point2Ptr(self, varargin) + function varargout = return_Point2Ptr(this, varargin) if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(25, self, varargin{:}); + varargout{1} = geometry_wrapper(25, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_Point2Ptr'); end end - function varargout = return_Test(self, varargin) + function varargout = return_Test(this, varargin) if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(26, self, varargin{:}); + varargout{1} = geometry_wrapper(26, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_Test'); end end - function varargout = return_TestPtr(self, varargin) + function varargout = return_TestPtr(this, varargin) if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(27, self, varargin{:}); + varargout{1} = geometry_wrapper(27, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_TestPtr'); end end - function varargout = return_bool(self, varargin) + function varargout = return_bool(this, varargin) if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(28, self, varargin{:}); + varargout{1} = geometry_wrapper(28, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_bool'); end end - function varargout = return_double(self, varargin) + function varargout = return_double(this, varargin) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(29, self, varargin{:}); + varargout{1} = geometry_wrapper(29, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_double'); end end - function varargout = return_field(self, varargin) + function varargout = return_field(this, varargin) if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(30, self, varargin{:}); + varargout{1} = geometry_wrapper(30, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_field'); end end - function varargout = return_int(self, varargin) + function varargout = return_int(this, varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(31, self, varargin{:}); + varargout{1} = geometry_wrapper(31, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_int'); end end - function varargout = return_matrix1(self, varargin) + function varargout = return_matrix1(this, varargin) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(32, self, varargin{:}); + varargout{1} = geometry_wrapper(32, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix1'); end end - function varargout = return_matrix2(self, varargin) + function varargout = return_matrix2(this, varargin) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(33, self, varargin{:}); + varargout{1} = geometry_wrapper(33, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix2'); end end - function varargout = return_pair(self, varargin) + function varargout = return_pair(this, varargin) if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(34, self, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(34, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_pair'); end end - function varargout = return_ptrs(self, varargin) + function varargout = return_ptrs(this, varargin) if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') - [ varargout{1} varargout{2} ] = geometry_wrapper(35, self, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(35, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_ptrs'); end end - function varargout = return_size_t(self, varargin) + function varargout = return_size_t(this, varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(36, self, varargin{:}); + varargout{1} = geometry_wrapper(36, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_size_t'); end end - function varargout = return_string(self, varargin) + function varargout = return_string(this, varargin) if length(varargin) == 1 && isa(varargin{1},'char') - varargout{1} = geometry_wrapper(37, self, varargin{:}); + varargout{1} = geometry_wrapper(37, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_string'); end end - function varargout = return_vector1(self, varargin) + function varargout = return_vector1(this, varargin) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(38, self, varargin{:}); + varargout{1} = geometry_wrapper(38, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector1'); end end - function varargout = return_vector2(self, varargin) + function varargout = return_vector2(this, varargin) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(39, self, varargin{:}); + varargout{1} = geometry_wrapper(39, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector2'); end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index e2c866083..aad0c258a 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -31,7 +31,7 @@ void _deleteAllObjects() collector_Test.erase(iter++); } } -void Point2_constructor_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Point2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -80,7 +80,7 @@ void Point2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in { typedef boost::shared_ptr Shared; checkArguments("argChar",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); char a = unwrap< char >(in[1]); obj->argChar(a); } @@ -89,7 +89,7 @@ void Point2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *i { typedef boost::shared_ptr Shared; checkArguments("argUChar",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); unsigned char a = unwrap< unsigned char >(in[1]); obj->argUChar(a); } @@ -98,18 +98,16 @@ void Point2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("dim",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - int result = obj->dim(); - out[0] = wrap< int >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< int >(obj->dim()); } void Point2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("returnChar",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - char result = obj->returnChar(); - out[0] = wrap< char >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< char >(obj->returnChar()); } void Point2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -117,9 +115,8 @@ void Point2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxA typedef boost::shared_ptr SharedVectorNotEigen; typedef boost::shared_ptr Shared; checkArguments("vectorConfusion",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - VectorNotEigen result = obj->vectorConfusion(); - SharedVectorNotEigen* ret = new SharedVectorNotEigen(new VectorNotEigen(result)); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + SharedVectorNotEigen* ret = new SharedVectorNotEigen(new VectorNotEigen(obj->vectorConfusion())); out[0] = wrap_shared_ptr(ret,"VectorNotEigen"); } @@ -127,21 +124,19 @@ void Point2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("x",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - double result = obj->x(); - out[0] = wrap< double >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< double >(obj->x()); } void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("y",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point2"); - double result = obj->y(); - out[0] = wrap< double >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point2"); + out[0] = wrap< double >(obj->y()); } -void Point3_constructor_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); using namespace geometry; @@ -184,9 +179,8 @@ void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[] using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("norm",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Point3"); - double result = obj->norm(); - out[0] = wrap< double >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); + out[0] = wrap< double >(obj->norm()); } void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -196,8 +190,7 @@ using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("Point3.StaticFunctionRet",nargout,nargin,1); double z = unwrap< double >(in[0]); - Point3 result = Point3::StaticFunctionRet(z); - SharedPoint3* ret = new SharedPoint3(new Point3(result)); + SharedPoint3* ret = new SharedPoint3(new Point3(Point3::StaticFunctionRet(z))); out[0] = wrap_shared_ptr(ret,"Point3"); } @@ -206,11 +199,10 @@ void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxA using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("Point3.staticFunction",nargout,nargin,0); - double result = Point3::staticFunction(); - out[0] = wrap< double >(result); + out[0] = wrap< double >(Point3::staticFunction()); } -void Test_constructor_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); using namespace geometry; @@ -264,8 +256,8 @@ void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mx using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("arg_EigenConstRef",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); obj->arg_EigenConstRef(value); } @@ -276,11 +268,10 @@ using namespace geometry; typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; checkArguments("create_MixedPtrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - pair< Test, SharedTest > result = obj->create_MixedPtrs(); - SharedTest* ret = new SharedTest(new Test(result.first)); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + SharedTest* ret = new SharedTest(new Test(obj->create_MixedPtrs().first)); out[0] = wrap_shared_ptr(ret,"Test"); - SharedTest* ret = new SharedTest(result.second); + SharedTest* ret = new SharedTest(obj->create_MixedPtrs().second); out[1] = wrap_shared_ptr(ret,"Test"); } @@ -291,11 +282,10 @@ using namespace geometry; typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; checkArguments("create_ptrs",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - pair< SharedTest, SharedTest > result = obj->create_ptrs(); - SharedTest* ret = new SharedTest(result.first); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + SharedTest* ret = new SharedTest(obj->create_ptrs().first); out[0] = wrap_shared_ptr(ret,"Test"); - SharedTest* ret = new SharedTest(result.second); + SharedTest* ret = new SharedTest(obj->create_ptrs().second); out[1] = wrap_shared_ptr(ret,"Test"); } @@ -304,7 +294,7 @@ void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("print",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); obj->print(); } @@ -314,10 +304,9 @@ using namespace geometry; typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; checkArguments("return_Point2Ptr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); bool value = unwrap< bool >(in[1]); - SharedPoint2 result = obj->return_Point2Ptr(value); - SharedPoint2* ret = new SharedPoint2(result); + SharedPoint2* ret = new SharedPoint2(obj->return_Point2Ptr(value)); out[0] = wrap_shared_ptr(ret,"Point2"); } @@ -327,10 +316,9 @@ using namespace geometry; typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; checkArguments("return_Test",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - Test result = obj->return_Test(value); - SharedTest* ret = new SharedTest(new Test(result)); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + SharedTest* ret = new SharedTest(new Test(obj->return_Test(value))); out[0] = wrap_shared_ptr(ret,"Test"); } @@ -340,10 +328,9 @@ using namespace geometry; typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; checkArguments("return_TestPtr",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - SharedTest result = obj->return_TestPtr(value); - SharedTest* ret = new SharedTest(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + SharedTest* ret = new SharedTest(obj->return_TestPtr(value)); out[0] = wrap_shared_ptr(ret,"Test"); } @@ -352,10 +339,9 @@ void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_bool",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); bool value = unwrap< bool >(in[1]); - bool result = obj->return_bool(value); - out[0] = wrap< bool >(result); + out[0] = wrap< bool >(obj->return_bool(value)); } void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -363,10 +349,9 @@ void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArra using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_double",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); double value = unwrap< double >(in[1]); - double result = obj->return_double(value); - out[0] = wrap< double >(result); + out[0] = wrap< double >(obj->return_double(value)); } void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -374,10 +359,9 @@ void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_field",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - Test& t = *unwrap_shared_ptr< Test >(in[1], "Test"); - bool result = obj->return_field(t); - out[0] = wrap< bool >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Test& t = *unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap< bool >(obj->return_field(t)); } void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -385,10 +369,9 @@ void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray * using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_int",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); int value = unwrap< int >(in[1]); - int result = obj->return_int(value); - out[0] = wrap< int >(result); + out[0] = wrap< int >(obj->return_int(value)); } void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -396,10 +379,9 @@ void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArr using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_matrix1",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); Matrix value = unwrap< Matrix >(in[1]); - Matrix result = obj->return_matrix1(value); - out[0] = wrap< Matrix >(result); + out[0] = wrap< Matrix >(obj->return_matrix1(value)); } void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -407,10 +389,9 @@ void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArr using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_matrix2",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); Matrix value = unwrap< Matrix >(in[1]); - Matrix result = obj->return_matrix2(value); - out[0] = wrap< Matrix >(result); + out[0] = wrap< Matrix >(obj->return_matrix2(value)); } void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -418,12 +399,11 @@ void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_pair",nargout,nargin-1,2); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); Vector v = unwrap< Vector >(in[1]); Matrix A = unwrap< Matrix >(in[2]); - pair< Vector, Matrix > result = obj->return_pair(v,A); - out[0] = wrap< Vector >(result.first); - out[1] = wrap< Matrix >(result.second); + out[0] = wrap< Vector >(obj->return_pair(v,A).first); + out[1] = wrap< Matrix >(obj->return_pair(v,A).second); } void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -433,13 +413,12 @@ using namespace geometry; typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; checkArguments("return_ptrs",nargout,nargin-1,2); - Shared obj = unwrap_shared_ptr(in[0], "Test"); - boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "Test"); - boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "Test"); - pair< SharedTest, SharedTest > result = obj->return_ptrs(p1,p2); - SharedTest* ret = new SharedTest(result.first); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "ptr_Test"); + SharedTest* ret = new SharedTest(obj->return_ptrs(p1,p2).first); out[0] = wrap_shared_ptr(ret,"Test"); - SharedTest* ret = new SharedTest(result.second); + SharedTest* ret = new SharedTest(obj->return_ptrs(p1,p2).second); out[1] = wrap_shared_ptr(ret,"Test"); } @@ -448,10 +427,9 @@ void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArra using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_size_t",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); size_t value = unwrap< size_t >(in[1]); - size_t result = obj->return_size_t(value); - out[0] = wrap< size_t >(result); + out[0] = wrap< size_t >(obj->return_size_t(value)); } void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -459,10 +437,9 @@ void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArra using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_string",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); string value = unwrap< string >(in[1]); - string result = obj->return_string(value); - out[0] = wrap< string >(result); + out[0] = wrap< string >(obj->return_string(value)); } void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -470,10 +447,9 @@ void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArr using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_vector1",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); Vector value = unwrap< Vector >(in[1]); - Vector result = obj->return_vector1(value); - out[0] = wrap< Vector >(result); + out[0] = wrap< Vector >(obj->return_vector1(value)); } void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -481,10 +457,9 @@ void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArr using namespace geometry; typedef boost::shared_ptr Shared; checkArguments("return_vector2",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "Test"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Test"); Vector value = unwrap< Vector >(in[1]); - Vector result = obj->return_vector2(value); - out[0] = wrap< Vector >(result); + out[0] = wrap< Vector >(obj->return_vector2(value)); } void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -496,7 +471,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) switch(id) { case 0: - Point2_constructor_0(nargout, out, nargin-1, in+1); + Point2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); break; case 1: Point2_constructor_1(nargout, out, nargin-1, in+1); @@ -529,7 +504,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) Point2_y_10(nargout, out, nargin-1, in+1); break; case 11: - Point3_constructor_11(nargout, out, nargin-1, in+1); + Point3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); break; case 12: Point3_constructor_12(nargout, out, nargin-1, in+1); @@ -547,7 +522,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) Point3_staticFunction_16(nargout, out, nargin-1, in+1); break; case 17: - Test_constructor_17(nargout, out, nargin-1, in+1); + Test_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1); break; case 18: Test_constructor_18(nargout, out, nargin-1, in+1); diff --git a/wrap/tests/expected_namespaces/ClassD.m b/wrap/tests/expected_namespaces/ClassD.m index fcedbdc1c..3fb8d4837 100644 --- a/wrap/tests/expected_namespaces/ClassD.m +++ b/wrap/tests/expected_namespaces/ClassD.m @@ -1,22 +1,23 @@ % automatically generated by wrap classdef ClassD < handle properties - self = 0 + ptr_ClassD = 0 end methods function obj = ClassD(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - testNamespaces_wrapper(obj.self); + my_ptr = varargin{2}; + testNamespaces_wrapper(19, my_ptr); elseif nargin == 0 - obj.self = testNamespaces_wrapper(20); + my_ptr = testNamespaces_wrapper(20); else error('Arguments do not match any overload of ClassD constructor'); end + obj.ptr_ClassD = my_ptr; end function delete(obj) - testNamespaces_wrapper(21, obj.self); + testNamespaces_wrapper(21, obj.ptr_ClassD); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected_namespaces/ns1ClassA.m b/wrap/tests/expected_namespaces/ns1ClassA.m index 5ee717612..29f48ab4e 100644 --- a/wrap/tests/expected_namespaces/ns1ClassA.m +++ b/wrap/tests/expected_namespaces/ns1ClassA.m @@ -1,22 +1,23 @@ % automatically generated by wrap classdef ns1ClassA < handle properties - self = 0 + ptr_ns1ClassA = 0 end methods function obj = ns1ClassA(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - testNamespaces_wrapper(obj.self); + my_ptr = varargin{2}; + testNamespaces_wrapper(0, my_ptr); elseif nargin == 0 - obj.self = testNamespaces_wrapper(1); + my_ptr = testNamespaces_wrapper(1); else error('Arguments do not match any overload of ns1ClassA constructor'); end + obj.ptr_ns1ClassA = my_ptr; end function delete(obj) - testNamespaces_wrapper(2, obj.self); + testNamespaces_wrapper(2, obj.ptr_ns1ClassA); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected_namespaces/ns1ClassB.m b/wrap/tests/expected_namespaces/ns1ClassB.m index bc6dc0198..a1e9bc9a5 100644 --- a/wrap/tests/expected_namespaces/ns1ClassB.m +++ b/wrap/tests/expected_namespaces/ns1ClassB.m @@ -1,22 +1,23 @@ % automatically generated by wrap classdef ns1ClassB < handle properties - self = 0 + ptr_ns1ClassB = 0 end methods function obj = ns1ClassB(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - testNamespaces_wrapper(obj.self); + my_ptr = varargin{2}; + testNamespaces_wrapper(3, my_ptr); elseif nargin == 0 - obj.self = testNamespaces_wrapper(4); + my_ptr = testNamespaces_wrapper(4); else error('Arguments do not match any overload of ns1ClassB constructor'); end + obj.ptr_ns1ClassB = my_ptr; end function delete(obj) - testNamespaces_wrapper(5, obj.self); + testNamespaces_wrapper(5, obj.ptr_ns1ClassB); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected_namespaces/ns2ClassA.m b/wrap/tests/expected_namespaces/ns2ClassA.m index 38a161f07..7b3df9ed6 100644 --- a/wrap/tests/expected_namespaces/ns2ClassA.m +++ b/wrap/tests/expected_namespaces/ns2ClassA.m @@ -1,47 +1,48 @@ % automatically generated by wrap classdef ns2ClassA < handle properties - self = 0 + ptr_ns2ClassA = 0 end methods function obj = ns2ClassA(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - testNamespaces_wrapper(obj.self); + my_ptr = varargin{2}; + testNamespaces_wrapper(6, my_ptr); elseif nargin == 0 - obj.self = testNamespaces_wrapper(7); + my_ptr = testNamespaces_wrapper(7); else error('Arguments do not match any overload of ns2ClassA constructor'); end + obj.ptr_ns2ClassA = my_ptr; end function delete(obj) - testNamespaces_wrapper(8, obj.self); + testNamespaces_wrapper(8, obj.ptr_ns2ClassA); end function display(obj), obj.print(''); end function disp(obj), obj.display; end - function varargout = memberFunction(self, varargin) + function varargout = memberFunction(this, varargin) if length(varargin) == 0 - varargout{1} = testNamespaces_wrapper(9, self, varargin{:}); + varargout{1} = testNamespaces_wrapper(9, this, varargin{:}); else error('Arguments do not match any overload of function ns2ClassA.memberFunction'); end end - function varargout = nsArg(self, varargin) + function varargout = nsArg(this, varargin) if length(varargin) == 1 && isa(varargin{1},'ns1ClassB') - varargout{1} = testNamespaces_wrapper(10, self, varargin{:}); + varargout{1} = testNamespaces_wrapper(10, this, varargin{:}); else error('Arguments do not match any overload of function ns2ClassA.nsArg'); end end - function varargout = nsReturn(self, varargin) + function varargout = nsReturn(this, varargin) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = testNamespaces_wrapper(11, self, varargin{:}); + varargout{1} = testNamespaces_wrapper(11, this, varargin{:}); else error('Arguments do not match any overload of function ns2ClassA.nsReturn'); end diff --git a/wrap/tests/expected_namespaces/ns2ClassC.m b/wrap/tests/expected_namespaces/ns2ClassC.m index 647351e2f..5ba6e7125 100644 --- a/wrap/tests/expected_namespaces/ns2ClassC.m +++ b/wrap/tests/expected_namespaces/ns2ClassC.m @@ -1,22 +1,23 @@ % automatically generated by wrap classdef ns2ClassC < handle properties - self = 0 + ptr_ns2ClassC = 0 end methods function obj = ns2ClassC(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - testNamespaces_wrapper(obj.self); + my_ptr = varargin{2}; + testNamespaces_wrapper(16, my_ptr); elseif nargin == 0 - obj.self = testNamespaces_wrapper(17); + my_ptr = testNamespaces_wrapper(17); else error('Arguments do not match any overload of ns2ClassC constructor'); end + obj.ptr_ns2ClassC = my_ptr; end function delete(obj) - testNamespaces_wrapper(18, obj.self); + testNamespaces_wrapper(18, obj.ptr_ns2ClassC); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected_namespaces/ns2ns3ClassB.m b/wrap/tests/expected_namespaces/ns2ns3ClassB.m index 3df2f52e1..b5e57ea19 100644 --- a/wrap/tests/expected_namespaces/ns2ns3ClassB.m +++ b/wrap/tests/expected_namespaces/ns2ns3ClassB.m @@ -1,22 +1,23 @@ % automatically generated by wrap classdef ns2ns3ClassB < handle properties - self = 0 + ptr_ns2ns3ClassB = 0 end methods function obj = ns2ns3ClassB(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - obj.self = varargin{2}; - testNamespaces_wrapper(obj.self); + my_ptr = varargin{2}; + testNamespaces_wrapper(13, my_ptr); elseif nargin == 0 - obj.self = testNamespaces_wrapper(14); + my_ptr = testNamespaces_wrapper(14); else error('Arguments do not match any overload of ns2ns3ClassB constructor'); end + obj.ptr_ns2ns3ClassB = my_ptr; end function delete(obj) - testNamespaces_wrapper(15, obj.self); + testNamespaces_wrapper(15, obj.ptr_ns2ns3ClassB); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp b/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp index 7d910c9cc..3633e38c8 100644 --- a/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp +++ b/wrap/tests/expected_namespaces/testNamespaces_wrapper.cpp @@ -58,7 +58,7 @@ void _deleteAllObjects() collector_ClassD.erase(iter++); } } -void ns1ClassA_constructor_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void ns1ClassA_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -90,7 +90,7 @@ void ns1ClassA_deconstructor_2(int nargout, mxArray *out[], int nargin, const mx } } -void ns1ClassB_constructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void ns1ClassB_collectorInsertAndMakeBase_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -122,7 +122,7 @@ void ns1ClassB_deconstructor_5(int nargout, mxArray *out[], int nargin, const mx } } -void ns2ClassA_constructor_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void ns2ClassA_collectorInsertAndMakeBase_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -158,19 +158,17 @@ void ns2ClassA_memberFunction_9(int nargout, mxArray *out[], int nargin, const m { typedef boost::shared_ptr Shared; checkArguments("memberFunction",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ns2::ClassA"); - double result = obj->memberFunction(); - out[0] = wrap< double >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + out[0] = wrap< double >(obj->memberFunction()); } void ns2ClassA_nsArg_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("nsArg",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ns2::ClassA"); - ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ns1ClassB"); - int result = obj->nsArg(arg); - out[0] = wrap< int >(result); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ptr_ns1ClassB"); + out[0] = wrap< int >(obj->nsArg(arg)); } void ns2ClassA_nsReturn_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -178,10 +176,9 @@ void ns2ClassA_nsReturn_11(int nargout, mxArray *out[], int nargin, const mxArra typedef boost::shared_ptr SharedClassB; typedef boost::shared_ptr Shared; checkArguments("nsReturn",nargout,nargin-1,1); - Shared obj = unwrap_shared_ptr(in[0], "ns2::ClassA"); + Shared obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); double q = unwrap< double >(in[1]); - ns2::ns3::ClassB result = obj->nsReturn(q); - SharedClassB* ret = new SharedClassB(new ns2::ns3::ClassB(result)); + SharedClassB* ret = new SharedClassB(new ns2::ns3::ClassB(obj->nsReturn(q))); out[0] = wrap_shared_ptr(ret,"ns2ns3ClassB"); } @@ -189,11 +186,10 @@ void ns2ClassA_afunction_12(int nargout, mxArray *out[], int nargin, const mxArr { typedef boost::shared_ptr Shared; checkArguments("ns2ClassA.afunction",nargout,nargin,0); - double result = ns2::ClassA::afunction(); - out[0] = wrap< double >(result); + out[0] = wrap< double >(ns2::ClassA::afunction()); } -void ns2ns3ClassB_constructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void ns2ns3ClassB_collectorInsertAndMakeBase_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -225,7 +221,7 @@ void ns2ns3ClassB_deconstructor_15(int nargout, mxArray *out[], int nargin, cons } } -void ns2ClassC_constructor_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void ns2ClassC_collectorInsertAndMakeBase_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -257,7 +253,7 @@ void ns2ClassC_deconstructor_18(int nargout, mxArray *out[], int nargin, const m } } -void ClassD_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void ClassD_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -298,7 +294,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) switch(id) { case 0: - ns1ClassA_constructor_0(nargout, out, nargin-1, in+1); + ns1ClassA_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); break; case 1: ns1ClassA_constructor_1(nargout, out, nargin-1, in+1); @@ -307,7 +303,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) ns1ClassA_deconstructor_2(nargout, out, nargin-1, in+1); break; case 3: - ns1ClassB_constructor_3(nargout, out, nargin-1, in+1); + ns1ClassB_collectorInsertAndMakeBase_3(nargout, out, nargin-1, in+1); break; case 4: ns1ClassB_constructor_4(nargout, out, nargin-1, in+1); @@ -316,7 +312,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) ns1ClassB_deconstructor_5(nargout, out, nargin-1, in+1); break; case 6: - ns2ClassA_constructor_6(nargout, out, nargin-1, in+1); + ns2ClassA_collectorInsertAndMakeBase_6(nargout, out, nargin-1, in+1); break; case 7: ns2ClassA_constructor_7(nargout, out, nargin-1, in+1); @@ -337,7 +333,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) ns2ClassA_afunction_12(nargout, out, nargin-1, in+1); break; case 13: - ns2ns3ClassB_constructor_13(nargout, out, nargin-1, in+1); + ns2ns3ClassB_collectorInsertAndMakeBase_13(nargout, out, nargin-1, in+1); break; case 14: ns2ns3ClassB_constructor_14(nargout, out, nargin-1, in+1); @@ -346,7 +342,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) ns2ns3ClassB_deconstructor_15(nargout, out, nargin-1, in+1); break; case 16: - ns2ClassC_constructor_16(nargout, out, nargin-1, in+1); + ns2ClassC_collectorInsertAndMakeBase_16(nargout, out, nargin-1, in+1); break; case 17: ns2ClassC_constructor_17(nargout, out, nargin-1, in+1); @@ -355,7 +351,7 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) ns2ClassC_deconstructor_18(nargout, out, nargin-1, in+1); break; case 19: - ClassD_constructor_19(nargout, out, nargin-1, in+1); + ClassD_collectorInsertAndMakeBase_19(nargout, out, nargin-1, in+1); break; case 20: ClassD_constructor_20(nargout, out, nargin-1, in+1); diff --git a/wrap/tests/testDependencies.h b/wrap/tests/testDependencies.h index 429bb5a2a..34a8056b8 100644 --- a/wrap/tests/testDependencies.h +++ b/wrap/tests/testDependencies.h @@ -1,24 +1,8 @@ //Header file to test dependency checking // class Pose3 { - Pose3(); - Pose3(const Rot3& r, const Point3& t);//What is Rot3? Throw here - Pose3(Vector v); - Pose3(Matrix t); - static Pose3 Expmap(Vector v); - static Vector Logmap(const Pose3& p); - static Rot3 testStaticDep(Rot3& r);//What is Rot3? Throw here - void print(string s) const; - bool equals(const Pose3& pose, double tol) const; - double x() const; - double y() const; - double z() const; - Rot3 testReturnType() const; // Throw here - Matrix matrix() const; - Matrix adjointMap() const; - Pose3 compose(const Pose3& p2); - Pose3 between(const Pose3& p2); - Pose3 retract(Vector v); - Point3 translation() const; - Rot3 rotation() const; //What is Rot3? Throw here + Pose3(const Rot3& r, const Point3& t); //What is Rot3? Throw here + static Rot3 testStaticDep(Rot3& r); //What is Rot3? Throw here + Rot3 testReturnType() const; // Throw here + void testMethodArg(const Rot3& r) const; }; diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index 9f9f29688..b8e9effc1 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -58,7 +58,7 @@ TEST( wrap, ArgumentList ) { } /* ************************************************************************* */ -TEST( wrap, check_exception ) { +TEST_UNSAFE( wrap, check_exception ) { THROWS_EXCEPTION(Module("/notarealpath", "geometry",enable_verbose)); CHECK_EXCEPTION(Module("/alsonotarealpath", "geometry",enable_verbose), CantOpenFile); @@ -80,8 +80,9 @@ TEST( wrap, parse ) { strvec exp_using1, exp_using2; exp_using2 += "geometry"; // forward declarations - strvec exp_forward; exp_forward += "VectorNotEigen", "ns::OtherClass"; - EXPECT(assert_equal(exp_forward, module.forward_declarations)); + LONGS_EQUAL(2, module.forward_declarations.size()); + EXPECT(assert_equal("VectorNotEigen", module.forward_declarations[0].name)); + EXPECT(assert_equal("ns::OtherClass", module.forward_declarations[1].name)); // check first class, Point2 { diff --git a/wrap/utilities.h b/wrap/utilities.h index eeda3c68a..99e19a755 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -21,7 +21,9 @@ #include #include #include -#include +//#include // on Linux GCC: fails with error regarding needing C++0x std flags +//#include // same failure as above +#include // works on Linux GCC #include #include @@ -66,6 +68,16 @@ public: ~DuplicateDefinition() throw() {} virtual const char* what() const throw() { return what_.c_str(); } }; + +class AttributeError : public std::exception { +private: + const std::string what_; +public: + AttributeError(const std::string& name, const std::string& problem) : + what_("Class " + name + ": " + problem) {} + ~AttributeError() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } +}; /** Special "magic number" passed into MATLAB constructor to indicate creating * a MATLAB object from a shared_ptr allocated in C++