From 3cffb731559df2c2f56b5750b8e4a7d8bdd78279 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 10:36:52 +0100 Subject: [PATCH 1/3] Added MATLAB tests --- gtsam.h | 11 ++++----- matlab/gtsam_tests/.gitignore | 1 + matlab/gtsam_tests/testValues.m | 40 +++++++++++++++++++++++++++++++++ matlab/gtsam_tests/test_gtsam.m | 3 +++ 4 files changed, 48 insertions(+), 7 deletions(-) create mode 100644 matlab/gtsam_tests/.gitignore create mode 100644 matlab/gtsam_tests/testValues.m diff --git a/gtsam.h b/gtsam.h index b40913229..96d51117a 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1739,7 +1739,7 @@ class Values { void insert(size_t j, const gtsam::EssentialMatrix& t); void insert(size_t j, const gtsam::imuBias::ConstantBias& t); void insert(size_t j, Vector t); - void insert(size_t j, Matrix t); //git/gtsam/gtsam/base/Manifold.h:254:1: error: invalid application of ‘sizeof’ to incomplete type ‘boost::STATIC_ASSERTION_FAILURE’ + void insert(size_t j, Matrix t); void update(size_t j, const gtsam::Point2& t); void update(size_t j, const gtsam::Point3& t); @@ -1755,8 +1755,7 @@ class Values { void update(size_t j, Vector t); void update(size_t j, Matrix t); - template // Parse Error + template T at(size_t j); }; @@ -2154,9 +2153,7 @@ class NonlinearISAM { #include #include -template // Parse Error +template virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; @@ -2167,7 +2164,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor { #include -template // Parse Error +template virtual class BetweenFactor : gtsam::NoiseModelFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); T measured() const; diff --git a/matlab/gtsam_tests/.gitignore b/matlab/gtsam_tests/.gitignore new file mode 100644 index 000000000..6d725d9bc --- /dev/null +++ b/matlab/gtsam_tests/.gitignore @@ -0,0 +1 @@ +*.m~ diff --git a/matlab/gtsam_tests/testValues.m b/matlab/gtsam_tests/testValues.m new file mode 100644 index 000000000..ce2ae9d7e --- /dev/null +++ b/matlab/gtsam_tests/testValues.m @@ -0,0 +1,40 @@ +% test wrapping of Values +import gtsam.*; + +values = Values; +E = EssentialMatrix(Rot3,Unit3); +tol = 1e-9; + +values.insert(0, Point2); +values.insert(1, Point3); +values.insert(2, Rot2); +values.insert(3, Pose2); +values.insert(4, Rot3); +values.insert(5, Pose3); +values.insert(6, Cal3_S2); +values.insert(7, Cal3DS2); +values.insert(8, Cal3Bundler); +values.insert(9, E); +values.insert(10, imuBias.ConstantBias); + +% special cases for Vector and Matrix: +values.insert(11, [1;2;3]); +values.insert(12, [1 2;3 4]); + +EXPECT('at',values.atPoint2(0).equals(Point2,tol)); +EXPECT('at',values.atPoint3(1).equals(Point3,tol)); +EXPECT('at',values.atRot2(2).equals(Rot2,tol)); +EXPECT('at',values.atPose2(3).equals(Pose2,tol)); +EXPECT('at',values.atRot3(4).equals(Rot3,tol)); +EXPECT('at',values.atPose3(5).equals(Pose3,tol)); +EXPECT('at',values.atCal3_S2(6).equals(Cal3_S2,tol)); +EXPECT('at',values.atCal3DS2(7).equals(Cal3DS2,tol)); +EXPECT('at',values.atCal3Bundler(8).equals(Cal3Bundler,tol)); +EXPECT('at',values.atEssentialMatrix(9).equals(E,tol)); +EXPECT('at',values.atConstantBias(10).equals(imuBias.ConstantBias,tol)); + +% special cases for Vector and Matrix: +actualVector = values.atVector(11); +EQUALITY('at',[1 2;3 4],actualVector,tol); +actualMatrix = values.atMatrix(12); +EQUALITY('at',[1 2;3 4],actualMatrix,tol); diff --git a/matlab/gtsam_tests/test_gtsam.m b/matlab/gtsam_tests/test_gtsam.m index e3705948d..e08019610 100644 --- a/matlab/gtsam_tests/test_gtsam.m +++ b/matlab/gtsam_tests/test_gtsam.m @@ -1,5 +1,8 @@ % Test runner script - runs each test +display 'Starting: testValues' +testValues + display 'Starting: testJacobianFactor' testJacobianFactor From 74361ce64acb688b0928cfb72bd88c525a767052 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 10:37:25 +0100 Subject: [PATCH 2/3] Test with argument templated --- wrap/tests/geometry.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 3fec21ab9..0646ff456 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -106,7 +106,7 @@ virtual class MyTemplate : MyBase { MyTemplate(); template - void templatedMethod(const ARG& t); + ARG templatedMethod(const ARG& t); // Stress test templates and pointer combinations void accept_T(const T& value) const; From 14ef786dfe23099e85482532df7aef6def0d1b7f Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 30 Nov 2014 10:38:24 +0100 Subject: [PATCH 3/3] Removing empty in favor of boost::optional --- wrap/Class.cpp | 38 +++++++++++++++--------------- wrap/Class.h | 3 ++- wrap/Constructor.cpp | 6 ++--- wrap/Constructor.h | 4 ++-- wrap/Function.cpp | 9 +++----- wrap/Function.h | 11 +++++---- wrap/Method.cpp | 7 +++--- wrap/Method.h | 3 +-- wrap/MethodBase.cpp | 10 ++++---- wrap/MethodBase.h | 6 ++--- wrap/Qualified.h | 45 ++++++++++++++++++++++++++++-------- wrap/ReturnType.cpp | 4 ++-- wrap/ReturnType.h | 12 +++------- wrap/ReturnValue.cpp | 2 +- wrap/ReturnValue.h | 2 +- wrap/StaticMethod.cpp | 7 +++--- wrap/StaticMethod.h | 3 +-- wrap/TypeAttributesTable.cpp | 8 +++---- wrap/tests/testWrap.cpp | 18 +++++++-------- 19 files changed, 105 insertions(+), 93 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 93135498f..d8b18a0b4 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -29,11 +29,9 @@ #include #include #include // std::ostream_iterator - //#include // on Linux GCC: fails with error regarding needing C++0x std flags //#include // same failure as above #include // works on Linux GCC - using namespace std; using namespace wrap; @@ -67,12 +65,11 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, const string matlabQualName = qualifiedName("."); const string matlabUniqueName = qualifiedName(); const string cppName = qualifiedName("::"); - const string matlabBaseName = qualifiedParent.qualifiedName("."); - const string cppBaseName = qualifiedParent.qualifiedName("::"); // emit class proxy code // we want our class to inherit the handle class for memory purposes - const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName; + const string parent = + parentClass ? "handle" : parentClass->qualifiedName("."); comment_fragment(proxyFile); proxyFile.oss << "classdef " << name << " < " << parent << endl; proxyFile.oss << " properties\n"; @@ -94,11 +91,14 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, wrapperFile.oss << "\n"; // Regular constructors + boost::optional cppBaseName; + if (parentClass) + cppBaseName = parentClass->qualifiedName("::"); for (size_t i = 0; i < constructor.nrOverloads(); i++) { ArgumentList args = constructor.argumentList(i); const int id = (int) functionNames.size(); - constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), - id, args); + constructor.proxy_fragment(proxyFile, wrapperName, (bool) parentClass, id, + args); const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, cppBaseName, id, args); wrapperFile.oss << "\n"; @@ -108,9 +108,9 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, proxyFile.oss << " error('Arguments do not match any overload of " << matlabQualName << " constructor');\n"; proxyFile.oss << " end\n"; - if (!qualifiedParent.empty()) - proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" - << ptr_constructor_key << "), base_ptr);\n"; + if (parentClass) + proxyFile.oss << " obj = obj@" << parentClass->qualifiedName(".") + << "(uint64(" << ptr_constructor_key << "), base_ptr);\n"; proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n"; proxyFile.oss << " end\n\n"; @@ -170,7 +170,6 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, const string matlabUniqueName = qualifiedName(); const string cppName = qualifiedName("::"); - const string baseCppName = qualifiedParent.qualifiedName("::"); const int collectorInsertId = (int) functionNames.size(); const string collectorInsertFunctionName = matlabUniqueName @@ -207,7 +206,7 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, } else { proxyFile.oss << " my_ptr = varargin{2};\n"; } - if (qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back + if (!parentClass) // If this class has a base class, we'll get a base class pointer back proxyFile.oss << " "; else proxyFile.oss << " base_ptr = "; @@ -230,7 +229,8 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile, // Add to collector wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n"; // If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy) - if (!qualifiedParent.empty()) { + if (parentClass) { + const string baseCppName = parentClass->qualifiedName("::"); wrapperFile.oss << "\n"; wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n"; @@ -297,7 +297,7 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName, // Create method to expand // For all values of the template argument, create a new method BOOST_FOREACH(const Qualified& instName, templateArgValues) { - const TemplateSubstitution ts(templateArgName, instName, this->name); + const TemplateSubstitution ts(templateArgName, instName, *this); // substitute template in arguments ArgumentList expandedArgs = argumentList.expandTemplate(ts); // do the same for return type @@ -353,10 +353,10 @@ void Class::verifyAll(vector& validTypes, bool& hasSerialiable) const { verifyReturnTypes(validTypes, methods_); // verify parents - if (!qualifiedParent.empty() + if (parentClass && find(validTypes.begin(), validTypes.end(), - qualifiedParent.qualifiedName("::")) == validTypes.end()) - throw DependencyMissing(qualifiedParent.qualifiedName("::"), + parentClass->qualifiedName("::")) == validTypes.end()) + throw DependencyMissing(parentClass->qualifiedName("::"), qualifiedName("::")); } @@ -364,12 +364,12 @@ void Class::verifyAll(vector& validTypes, bool& hasSerialiable) const { void Class::appendInheritedMethods(const Class& cls, const vector& classes) { - if (!cls.qualifiedParent.empty()) { + if (cls.parentClass) { // Find parent BOOST_FOREACH(const Class& parent, classes) { // We found a parent class for our parent, TODO improve ! - if (parent.name == cls.qualifiedParent.name) { + if (parent.name == cls.parentClass->name) { methods_.insert(parent.methods_.begin(), parent.methods_.end()); appendInheritedMethods(parent, classes); } diff --git a/wrap/Class.h b/wrap/Class.h index 9e4dff13d..f1b0ba55a 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -27,6 +27,7 @@ #include #include +#include #include #include @@ -53,7 +54,7 @@ public: bool isVirtual; ///< Whether the class is part of a virtual inheritance chain bool isSerializable; ///< Whether we can use boost.serialization to serialize the class - creates exports bool hasSerialization; ///< Whether we should create the serialization functions - Qualified qualifiedParent; ///< The *single* parent + boost::optional parentClass; ///< The *single* parent Constructor constructor; ///< Class constructors Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object bool verbose_; ///< verbose flag diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp index 782c0ca80..35cc0fa53 100644 --- a/wrap/Constructor.cpp +++ b/wrap/Constructor.cpp @@ -69,7 +69,7 @@ void Constructor::proxy_fragment(FileWriter& file, /* ************************************************************************* */ string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName, - Str matlabUniqueName, Str cppBaseClassName, int id, + Str matlabUniqueName, boost::optional cppBaseClassName, int id, const ArgumentList& al) const { const string wrapFunctionName = matlabUniqueName + "_constructor_" @@ -100,9 +100,9 @@ string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName, << endl; // If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy) - if (!cppBaseClassName.empty()) { + if (cppBaseClassName) { file.oss << "\n"; - file.oss << " typedef boost::shared_ptr<" << cppBaseClassName + file.oss << " typedef boost::shared_ptr<" << *cppBaseClassName << "> SharedBase;\n"; file.oss << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; diff --git a/wrap/Constructor.h b/wrap/Constructor.h index a026bf423..1e061d17c 100644 --- a/wrap/Constructor.h +++ b/wrap/Constructor.h @@ -19,7 +19,7 @@ #pragma once #include "OverloadedFunction.h" - +#include #include #include @@ -68,7 +68,7 @@ struct Constructor: public OverloadedFunction { /// cpp wrapper std::string wrapper_fragment(FileWriter& file, Str cppClassName, - Str matlabUniqueName, Str cppBaseClassName, int id, + Str matlabUniqueName, boost::optional cppBaseClassName, int id, const ArgumentList& al) const; /// constructor function diff --git a/wrap/Function.cpp b/wrap/Function.cpp index d045d2915..babfd712f 100644 --- a/wrap/Function.cpp +++ b/wrap/Function.cpp @@ -29,8 +29,8 @@ using namespace std; using namespace wrap; /* ************************************************************************* */ -bool Function::initializeOrCheck(const string& name, const Qualified& instName, - bool verbose) { +bool Function::initializeOrCheck(const string& name, + boost::optional instName, bool verbose) { if (name.empty()) throw runtime_error("Function::initializeOrCheck called with empty name"); @@ -44,10 +44,7 @@ bool Function::initializeOrCheck(const string& name, const Qualified& instName, } else { if (name_ != name || templateArgValue_ != instName || verbose_ != verbose) throw runtime_error( - "Function::initializeOrCheck called with different arguments: with name " - + name + " instead of expected " + name_ - + ", or with template argument " + instName.qualifiedName(":") - + " instead of expected " + templateArgValue_.qualifiedName(":")); + "Function::initializeOrCheck called with different arguments"); return false; } diff --git a/wrap/Function.h b/wrap/Function.h index 249cd42a7..692b1dd76 100644 --- a/wrap/Function.h +++ b/wrap/Function.h @@ -19,6 +19,7 @@ #pragma once #include "Argument.h" +#include namespace wrap { @@ -28,7 +29,7 @@ class Function { protected: std::string name_; ///< name of method - Qualified templateArgValue_; ///< value of template argument if applicable + boost::optional templateArgValue_; ///< value of template argument if applicable bool verbose_; public: @@ -37,8 +38,8 @@ public: * @brief first time, fill in instance variables, otherwise check if same * @return true if first time, false thereafter */ - bool initializeOrCheck(const std::string& name, const Qualified& instName = - Qualified(), bool verbose = false); + bool initializeOrCheck(const std::string& name, boost::optional instName = + boost::none, bool verbose = false); std::string name() const { return name_; @@ -50,10 +51,10 @@ public: } std::string matlabName() const { - if (templateArgValue_.empty()) + if (templateArgValue_) return name_; else - return name_ + templateArgValue_.name; + return name_ + templateArgValue_->name; } /// Emit function call to MATLAB (no argument checking) diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 66707d7e4..60d859ac3 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -52,8 +52,7 @@ void Method::proxy_header(FileWriter& proxyFile) const { /* ************************************************************************* */ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const { + Str matlabUniqueName, const ArgumentList& args) const { // check arguments // extra argument obj -> nargin-1 is passed ! // example: checkArguments("equals",nargout,nargin-1,2); @@ -71,8 +70,8 @@ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, // call method and wrap result // example: out[0]=wrap(obj->return_field(t)); string expanded = "obj->" + name_; - if (!instName.empty()) - expanded += ("<" + instName.qualifiedName("::") + ">"); + if (templateArgValue_) + expanded += ("<" + templateArgValue_->qualifiedName("::") + ">"); return expanded; } diff --git a/wrap/Method.h b/wrap/Method.h index 160a0f454..5eea00c21 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -55,8 +55,7 @@ private: void proxy_header(FileWriter& proxyFile) const; virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const; + Str matlabUniqueName, const ArgumentList& args) const; }; } // \namespace wrap diff --git a/wrap/MethodBase.cpp b/wrap/MethodBase.cpp index 643d8ceec..6b3d345be 100644 --- a/wrap/MethodBase.cpp +++ b/wrap/MethodBase.cpp @@ -59,7 +59,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName, - matlabUniqueName, 0, id, typeAttributes, templateArgValue_); + matlabUniqueName, 0, id, typeAttributes); // Add to function list functionNames.push_back(wrapFunctionName); @@ -75,8 +75,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment(wrapperFile, - cppClassName, matlabUniqueName, i, id, typeAttributes, - templateArgValue_); + cppClassName, matlabUniqueName, i, id, typeAttributes); // Add to function list functionNames.push_back(wrapFunctionName); @@ -94,8 +93,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile, /* ************************************************************************* */ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, int overload, int id, - const TypeAttributesTable& typeAttributes, - const Qualified& instName) const { + const TypeAttributesTable& typeAttributes) const { // generate code @@ -120,7 +118,7 @@ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, // for static methods: cppClassName::staticMethod // for instance methods: obj->instanceMethod string expanded = wrapper_call(wrapperFile, cppClassName, matlabUniqueName, - args, instName); + args); expanded += ("(" + args.names() + ")"); if (returnVal.type1.name != "void") diff --git a/wrap/MethodBase.h b/wrap/MethodBase.h index 0aabe819d..903b89569 100644 --- a/wrap/MethodBase.h +++ b/wrap/MethodBase.h @@ -57,12 +57,10 @@ protected: std::string wrapper_fragment(FileWriter& wrapperFile, Str cppClassName, Str matlabUniqueName, int overload, int id, - const TypeAttributesTable& typeAttributes, const Qualified& instName = - Qualified()) const; ///< cpp wrapper + const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const = 0; + Str matlabUniqueName, const ArgumentList& args) const = 0; }; } // \namespace wrap diff --git a/wrap/Qualified.h b/wrap/Qualified.h index b23e9020d..3e2782a66 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -26,26 +26,53 @@ namespace wrap { /** * Class to encapuslate a qualified name, i.e., with (nested) namespaces */ -struct Qualified { +class Qualified { + +public: std::vector namespaces; ///< Stack of namespaces std::string name; ///< type name - Qualified(const std::string& name_ = "") : - name(name_) { + /// the different supported return value categories + typedef enum { + CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4 + } Category; + Category category_; + + Qualified() : + category_(CLASS) { } - bool empty() const { - return namespaces.empty() && name.empty(); + Qualified(std::vector ns, const std::string& name) : + namespaces(ns), name(name), category_(CLASS) { } - void clear() { - namespaces.clear(); - name.clear(); + Qualified(const std::string& n, Category category) : + name(n), category_(category) { + } + +public: + + static Qualified MakeClass(std::vector namespaces, + const std::string& name) { + return Qualified(namespaces, name); + } + + static Qualified MakeEigen(const std::string& name) { + return Qualified(name, EIGEN); + } + + static Qualified MakeBasis(const std::string& name) { + return Qualified(name, BASIS); + } + + static Qualified MakeVoid() { + return Qualified("void", VOID); } bool operator!=(const Qualified& other) const { - return other.name != name || other.namespaces != namespaces; + return other.name != name || other.namespaces != namespaces + || other.category_ != category_; } /// Return a qualified string using given delimiter diff --git a/wrap/ReturnType.cpp b/wrap/ReturnType.cpp index 25147e59a..2a925b819 100644 --- a/wrap/ReturnType.cpp +++ b/wrap/ReturnType.cpp @@ -23,7 +23,7 @@ void ReturnType::wrap_result(const string& out, const string& result, string cppType = qualifiedName("::"), matlabType = qualifiedName("."); - if (category == CLASS) { + if (category_ == CLASS) { string objCopy, ptrType; ptrType = "Shared" + name; const bool isVirtual = typeAttributes.attributes(cppType).isVirtual; @@ -52,7 +52,7 @@ void ReturnType::wrap_result(const string& out, const string& result, /* ************************************************************************* */ void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const { - if (category == CLASS) + if (category_ == CLASS) wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedName("::") << "> Shared" << name << ";" << endl; } diff --git a/wrap/ReturnType.h b/wrap/ReturnType.h index 1829fbc81..52d5c7ad5 100644 --- a/wrap/ReturnType.h +++ b/wrap/ReturnType.h @@ -17,22 +17,16 @@ namespace wrap { /** * Encapsulates return value of a method or function */ -struct ReturnType: Qualified { - - /// the different supported return value categories - typedef enum { - CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4 - } return_category; +struct ReturnType: public Qualified { bool isPtr; - return_category category; ReturnType() : - isPtr(false), category(CLASS) { + isPtr(false) { } ReturnType(const std::string& name) : - isPtr(false), category(CLASS) { + isPtr(false) { Qualified::name = name; } diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index 596acb2c3..dbf6277a7 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -64,7 +64,7 @@ void ReturnValue::emit_matlab(FileWriter& proxyFile) const { string output; if (isPair) proxyFile.oss << "[ varargout{1} varargout{2} ] = "; - else if (type1.category != ReturnType::VOID) + else if (type1.category_ != ReturnType::VOID) proxyFile.oss << "varargout{1} = "; } diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index abfcec2b0..e2af5ddbb 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -50,7 +50,7 @@ struct ReturnValue { void emit_matlab(FileWriter& proxyFile) const; friend std::ostream& operator<<(std::ostream& os, const ReturnValue& r) { - if (!r.isPair && r.type1.category == ReturnType::VOID) + if (!r.isPair && r.type1.category_ == ReturnType::VOID) os << "void"; else os << r.return_type(true); diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index 6a2917eb2..e4e7c89ae 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -38,8 +38,7 @@ void StaticMethod::proxy_header(FileWriter& proxyFile) const { /* ************************************************************************* */ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const { + Str matlabUniqueName, const ArgumentList& args) const { // check arguments // NOTE: for static functions, there is no object passed wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << "." << name_ @@ -51,8 +50,8 @@ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName, // call method and wrap result // example: out[0]=wrap(staticMethod(t)); string expanded = cppClassName + "::" + name_; - if (!instName.empty()) - expanded += ("<" + instName.qualifiedName("::") + ">"); + if (templateArgValue_) + expanded += ("<" + templateArgValue_->qualifiedName("::") + ">"); return expanded; } diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index c3bf526dd..a01eeff62 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -39,8 +39,7 @@ protected: virtual void proxy_header(FileWriter& proxyFile) const; virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, - Str matlabUniqueName, const ArgumentList& args, - const Qualified& instName) const; + Str matlabUniqueName, const ArgumentList& args) const; }; } // \namespace wrap diff --git a/wrap/TypeAttributesTable.cpp b/wrap/TypeAttributesTable.cpp index a836f2005..4252c097d 100644 --- a/wrap/TypeAttributesTable.cpp +++ b/wrap/TypeAttributesTable.cpp @@ -65,14 +65,14 @@ void TypeAttributesTable::addForwardDeclarations( void TypeAttributesTable::checkValidity(const vector& classes) const { BOOST_FOREACH(const Class& cls, classes) { // Check that class is virtual if it has a parent - if (!cls.qualifiedParent.empty() && !cls.isVirtual) + if (cls.parentClass && !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 - Qualified parent = cls.qualifiedParent; - if (!parent.empty() && !table_.at(parent.qualifiedName("::")).isVirtual) - throw AttributeError(parent.qualifiedName("::"), + if (cls.parentClass + && !table_.at(cls.parentClass->qualifiedName("::")).isVirtual) + throw AttributeError(cls.parentClass->qualifiedName("::"), "Is the base class of " + cls.qualifiedName("::") + ", so needs to be declared virtual"); } diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index c1f6f091e..b0c59addc 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -104,7 +104,7 @@ TEST( wrap, Small ) { EXPECT(!rv1.isPair); EXPECT(!rv1.type1.isPtr); EXPECT(assert_equal("double", rv1.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category_); // Method 2 Method m2 = cls.method("returnMatrix"); @@ -116,7 +116,7 @@ TEST( wrap, Small ) { EXPECT(!rv2.isPair); EXPECT(!rv2.type1.isPtr); EXPECT(assert_equal("Matrix", rv2.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category_); // Method 3 Method m3 = cls.method("returnPoint2"); @@ -128,7 +128,7 @@ TEST( wrap, Small ) { EXPECT(!rv3.isPair); EXPECT(!rv3.type1.isPtr); EXPECT(assert_equal("Point2", rv3.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category_); // Static Method 1 // static Vector returnVector(); @@ -140,7 +140,7 @@ TEST( wrap, Small ) { EXPECT(!rv4.isPair); EXPECT(!rv4.type1.isPtr); EXPECT(assert_equal("Vector", rv4.type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category_); } @@ -192,7 +192,7 @@ TEST( wrap, Geometry ) { Method m1 = cls.method("returnChar"); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT(assert_equal("char", m1.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category_); EXPECT(!m1.returnValue(0).isPair); EXPECT(assert_equal("returnChar", m1.name())); LONGS_EQUAL(1, m1.nrOverloads()); @@ -206,7 +206,7 @@ TEST( wrap, Geometry ) { Method m1 = cls.method("vectorConfusion"); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category_); EXPECT(!m1.returnValue(0).isPair); EXPECT(assert_equal("vectorConfusion", m1.name())); LONGS_EQUAL(1, m1.nrOverloads()); @@ -249,7 +249,7 @@ TEST( wrap, Geometry ) { Method m1 = cls.method("norm"); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT(assert_equal("double", m1.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category_); EXPECT(assert_equal("norm", m1.name())); LONGS_EQUAL(1, m1.nrOverloads()); EXPECT_LONGS_EQUAL(0, m1.argumentList(0).size()); @@ -275,9 +275,9 @@ TEST( wrap, Geometry ) { Method m2 = testCls.method("return_pair"); LONGS_EQUAL(1, m2.nrOverloads()); EXPECT(m2.returnValue(0).isPair); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category_); EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name)); - EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category); + EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category_); EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name)); // checking pointer args and return values