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 diff --git a/wrap/Class.cpp b/wrap/Class.cpp index cfafd0ce5..bb8051093 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -29,24 +29,49 @@ #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; /* ************************************************************************* */ -Method& Class::method(Str key) { +void Class::assignParent(const Qualified& parent) { + parentClass.reset(parent); +} + +/* ************************************************************************* */ +boost::optional Class::qualifiedParent() const { + boost::optional result = boost::none; + if (parentClass) result = parentClass->qualifiedName("::"); + return result; +} + +/* ************************************************************************* */ +static void handleException(const out_of_range& oor, + const Class::Methods& methods) { + cerr << "Class::method: key not found: " << oor.what() << ", methods are:\n"; + using boost::adaptors::map_keys; + ostream_iterator out_it(cerr, "\n"); + boost::copy(methods | map_keys, out_it); +} + +/* ************************************************************************* */ +Method& Class::mutableMethod(Str key) { try { return methods_.at(key); } catch (const out_of_range& oor) { - cerr << "Class::method: key not found: " << oor.what() - << ", methods are:\n"; - using boost::adaptors::map_keys; - ostream_iterator out_it(cerr, "\n"); - boost::copy(methods_ | map_keys, out_it); + handleException(oor,methods_); + throw runtime_error("Internal error in wrap"); + } +} + +/* ************************************************************************* */ +const Method& Class::method(Str key) const { + try { + return methods_.at(key); + } catch (const out_of_range& oor) { + handleException(oor,methods_); throw runtime_error("Internal error in wrap"); } } @@ -67,12 +92,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 ? parentClass->qualifiedName(".") : "handle"; comment_fragment(proxyFile); proxyFile.oss << "classdef " << name() << " < " << parent << endl; proxyFile.oss << " properties\n"; @@ -94,11 +118,12 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName, wrapperFile.oss << "\n"; // Regular constructors + boost::optional cppBaseName = qualifiedParent(); 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 +133,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 +195,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 +231,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,9 +254,10 @@ 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()) { + boost::optional cppBaseName = qualifiedParent(); + if (cppBaseName) { wrapperFile.oss << "\n"; - wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName + wrapperFile.oss << " typedef boost::shared_ptr<" << *cppBaseName << "> SharedBase;\n"; wrapperFile.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; @@ -297,7 +322,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, name()); + const TemplateSubstitution ts(templateArgName, instName, *this); // substitute template in arguments ArgumentList expandedArgs = argumentList.expandTemplate(ts); // do the same for return type @@ -311,7 +336,7 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName, } else // just add overload methods_[methodName].addOverload(methodName, argumentList, returnValue, - is_const, Qualified(), verbose); + is_const, boost::none, verbose); } /* ************************************************************************* */ @@ -353,23 +378,23 @@ void Class::verifyAll(vector& validTypes, bool& hasSerialiable) const { verifyReturnTypes(validTypes, methods_); // verify parents - if (!qualifiedParent.empty() - && find(validTypes.begin(), validTypes.end(), - qualifiedParent.qualifiedName("::")) == validTypes.end()) - throw DependencyMissing(qualifiedParent.qualifiedName("::"), - qualifiedName("::")); + boost::optional parent = qualifiedParent(); + if (parent + && find(validTypes.begin(), validTypes.end(), *parent) + == validTypes.end()) + throw DependencyMissing(*parent, qualifiedName("::")); } /* ************************************************************************* */ 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 244bcbac6..449f3df4b 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -27,6 +27,7 @@ #include #include +#include #include #include @@ -36,15 +37,19 @@ namespace wrap { /// Class has name, constructors, methods class Class: public Qualified { +public: typedef const std::string& Str; - typedef std::map Methods; + typedef std::map StaticMethods; + +private: + + boost::optional parentClass; ///< The *single* parent Methods methods_; ///< Class methods + Method& mutableMethod(Str key); public: - - typedef std::map StaticMethods; StaticMethods static_methods; ///< Static methods // Then the instance variables are set directly by the Module constructor @@ -53,22 +58,25 @@ 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 Constructor constructor; ///< Class constructors Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object bool verbose_; ///< verbose flag /// Constructor creates an empty class Class(bool verbose = true) : - isVirtual(false), isSerializable(false), hasSerialization(false), deconstructor( - verbose), verbose_(verbose) { + parentClass(boost::none), isVirtual(false), isSerializable(false), hasSerialization( + false), deconstructor(verbose), verbose_(verbose) { } + void assignParent(const Qualified& parent); + + boost::optional qualifiedParent() const; + size_t nrMethods() const { return methods_.size(); } - Method& method(Str key); + const Method& method(Str key) const; bool exists(Str name) const { return methods_.find(name) != methods_.end(); 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/FullyOverloadedFunction.h b/wrap/FullyOverloadedFunction.h index ac22ec3a8..30e27764b 100644 --- a/wrap/FullyOverloadedFunction.h +++ b/wrap/FullyOverloadedFunction.h @@ -109,8 +109,8 @@ class FullyOverloadedFunction: public Function, public SignatureOverloads { public: bool addOverload(const std::string& name, const ArgumentList& args, - const ReturnValue& retVal, const Qualified& instName = Qualified(), - bool verbose = false) { + const ReturnValue& retVal, boost::optional instName = + boost::none, bool verbose = false) { bool first = initializeOrCheck(name, instName, verbose); SignatureOverloads::push_back(args, retVal); return first; diff --git a/wrap/Function.cpp b/wrap/Function.cpp index 63b561dfd..e46d40037 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 2f52f07c1..ad57a28c8 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,9 @@ 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 +52,10 @@ public: } std::string matlabName() const { - if (templateArgValue_.empty()) - return name_; + if (templateArgValue_) + return name_ + templateArgValue_->name(); else - return name_ + templateArgValue_.name(); + return name_; } /// Emit function call to MATLAB (no argument checking) diff --git a/wrap/GlobalFunction.cpp b/wrap/GlobalFunction.cpp index f31bb4a93..013ef6d28 100644 --- a/wrap/GlobalFunction.cpp +++ b/wrap/GlobalFunction.cpp @@ -18,7 +18,7 @@ using namespace std; /* ************************************************************************* */ void GlobalFunction::addOverload(const Qualified& overload, const ArgumentList& args, const ReturnValue& retVal, - const Qualified& instName, bool verbose) { + boost::optional instName, bool verbose) { FullyOverloadedFunction::addOverload(overload.name(), args, retVal, instName, verbose); overloads.push_back(overload); diff --git a/wrap/GlobalFunction.h b/wrap/GlobalFunction.h index 6a49fe5ce..4805231fb 100644 --- a/wrap/GlobalFunction.h +++ b/wrap/GlobalFunction.h @@ -19,8 +19,8 @@ struct GlobalFunction: public FullyOverloadedFunction { // adds an overloaded version of this function, void addOverload(const Qualified& overload, const ArgumentList& args, - const ReturnValue& retVal, const Qualified& instName = Qualified(), - bool verbose = false); + const ReturnValue& retVal, boost::optional instName = + boost::none, bool verbose = false); void verifyArguments(const std::vector& validArgs) const { SignatureOverloads::verifyArguments(validArgs, name_); diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 66707d7e4..2ad6e8259 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -30,8 +30,8 @@ using namespace wrap; /* ************************************************************************* */ bool Method::addOverload(Str name, const ArgumentList& args, - const ReturnValue& retVal, bool is_const, const Qualified& instName, - bool verbose) { + const ReturnValue& retVal, bool is_const, + boost::optional instName, bool verbose) { bool first = MethodBase::addOverload(name, args, retVal, instName, verbose); if (first) is_const_ = is_const; @@ -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..33ff7072e 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -32,8 +32,9 @@ public: typedef const std::string& Str; bool addOverload(Str name, const ArgumentList& args, - const ReturnValue& retVal, bool is_const, const Qualified& instName = - Qualified(), bool verbose = false); + const ReturnValue& retVal, bool is_const, + boost::optional instName = boost::none, bool verbose = + false); virtual bool isStatic() const { return false; @@ -55,8 +56,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 48513e4ac..9b5f7135f 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/Module.cpp b/wrap/Module.cpp index fac1f4f02..25a5a5cac 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -113,7 +113,6 @@ void Module::parseMarkup(const std::string& data) { // TODO, do we really need cls here? Non-local Class cls0(verbose),cls(verbose); - TypeGrammar classParent_p(cls.qualifiedParent); // parse "gtsam::Pose2" and add to templateArgValues Qualified templateArgValue; @@ -203,12 +202,15 @@ void Module::parseMarkup(const std::string& data) { '(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) [bl::bind(&StaticMethod::addOverload, bl::var(cls.static_methods)[bl::var(methodName)], - bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)] + bl::var(methodName), bl::var(args), bl::var(retVal), boost::none,verbose)] [assign_a(retVal,retVal0)] [clear_a(args)]; Rule functions_p = constructor_p | method_p | static_method_p; + Qualified possibleParent; + TypeGrammar classParent_p(possibleParent); + // parse a full class vector templateInstantiations; Rule class_p = @@ -221,11 +223,13 @@ void Module::parseMarkup(const std::string& data) { >> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) >> str_p("class") >> basic.className_p[assign_a(cls.name_)] - >> ((':' >> classParent_p >> '{') | '{') + >> ((':' >> classParent_p >> '{') + [bl::bind(&Class::assignParent, bl::var(cls), bl::var(possibleParent))] + [clear_a(possibleParent)] | '{') >> *(functions_p | basic.comments_p) >> str_p("};")) [bl::bind(&Constructor::initializeOrCheck, bl::var(constructor), - bl::var(cls.name_), Qualified(), verbose)] + bl::var(cls.name_), boost::none, verbose)] [assign_a(cls.constructor, constructor)] [assign_a(cls.namespaces_, namespaces)] [assign_a(cls.deconstructor.name,cls.name_)] @@ -243,7 +247,7 @@ void Module::parseMarkup(const std::string& data) { [assign_a(globalFunction.namespaces_,namespaces)] [bl::bind(&GlobalFunction::addOverload, bl::var(global_functions)[bl::var(globalFunction.name_)], - bl::var(globalFunction), bl::var(args), bl::var(retVal), Qualified(),verbose)] + bl::var(globalFunction), bl::var(args), bl::var(retVal), boost::none,verbose)] [assign_a(retVal,retVal0)] [clear_a(globalFunction)] [clear_a(args)]; diff --git a/wrap/OverloadedFunction.h b/wrap/OverloadedFunction.h index 47c418748..7718bc139 100644 --- a/wrap/OverloadedFunction.h +++ b/wrap/OverloadedFunction.h @@ -87,7 +87,8 @@ class OverloadedFunction: public Function, public ArgumentOverloads { public: bool addOverload(const std::string& name, const ArgumentList& args, - const Qualified& instName = Qualified(), bool verbose = false) { + boost::optional instName = boost::none, bool verbose = + false) { bool first = initializeOrCheck(name, instName, verbose); ArgumentOverloads::push_back(args); return first; diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 391cfa1fc..494d6b0ff 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -73,6 +73,10 @@ public: namespaces_.push_back(ns1); } + Qualified(std::vector ns, const std::string& name) : + namespaces_(ns), name_(name), category(CLASS) { + } + std::string name() const { return name_; } @@ -112,6 +116,26 @@ public: category = VOID; } +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); + } + + /// Return a qualified string using given delimiter std::string qualifiedName(const std::string& delimiter = "") const { std::string result; 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 061e09005..27de70d0e 100644 --- a/wrap/TypeAttributesTable.cpp +++ b/wrap/TypeAttributesTable.cpp @@ -64,17 +64,22 @@ 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) - 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("::"), - "Is the base class of " + cls.qualifiedName("::") - + ", so needs to be declared virtual"); + + boost::optional parent = cls.qualifiedParent(); + if (parent) { + + // Check that class is virtual if it has a parent + if (!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 (!table_.at(*parent).isVirtual) + throw AttributeError(*parent, + "Is the base class of " + cls.qualifiedName("::") + + ", so needs to be declared virtual"); + } } } diff --git a/wrap/tests/expected2/MyTemplatePoint2.m b/wrap/tests/expected2/MyTemplatePoint2.m index d7d84876b..18c841b5d 100644 --- a/wrap/tests/expected2/MyTemplatePoint2.m +++ b/wrap/tests/expected2/MyTemplatePoint2.m @@ -12,10 +12,10 @@ %return_T(Point2 value) : returns gtsam::Point2 %return_Tptr(Point2 value) : returns gtsam::Point2 %return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > -%templatedMethodMatrix(Matrix t) : returns void -%templatedMethodPoint2(Point2 t) : returns void -%templatedMethodPoint3(Point3 t) : returns void -%templatedMethodVector(Vector t) : returns void +%templatedMethodMatrix(Matrix t) : returns Matrix +%templatedMethodPoint2(Point2 t) : returns gtsam::Point2 +%templatedMethodPoint3(Point3 t) : returns gtsam::Point3 +%templatedMethodVector(Vector t) : returns Vector % classdef MyTemplatePoint2 < MyBase properties @@ -110,7 +110,7 @@ classdef MyTemplatePoint2 < MyBase end function varargout = templatedMethodMatrix(this, varargin) - % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'double') geometry_wrapper(55, this, varargin{:}); @@ -120,7 +120,7 @@ classdef MyTemplatePoint2 < MyBase end function varargout = templatedMethodPoint2(this, varargin) - % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void + % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') geometry_wrapper(56, this, varargin{:}); @@ -130,7 +130,7 @@ classdef MyTemplatePoint2 < MyBase end function varargout = templatedMethodPoint3(this, varargin) - % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void + % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') geometry_wrapper(57, this, varargin{:}); @@ -140,7 +140,7 @@ classdef MyTemplatePoint2 < MyBase end function varargout = templatedMethodVector(this, varargin) - % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 geometry_wrapper(58, this, varargin{:}); diff --git a/wrap/tests/expected2/MyTemplatePoint3.m b/wrap/tests/expected2/MyTemplatePoint3.m index 190b3eca0..fab352072 100644 --- a/wrap/tests/expected2/MyTemplatePoint3.m +++ b/wrap/tests/expected2/MyTemplatePoint3.m @@ -12,10 +12,10 @@ %return_T(Point3 value) : returns gtsam::Point3 %return_Tptr(Point3 value) : returns gtsam::Point3 %return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > -%templatedMethodMatrix(Matrix t) : returns void -%templatedMethodPoint2(Point2 t) : returns void -%templatedMethodPoint3(Point3 t) : returns void -%templatedMethodVector(Vector t) : returns void +%templatedMethodMatrix(Matrix t) : returns Matrix +%templatedMethodPoint2(Point2 t) : returns gtsam::Point2 +%templatedMethodPoint3(Point3 t) : returns gtsam::Point3 +%templatedMethodVector(Vector t) : returns Vector % classdef MyTemplatePoint3 < MyBase properties @@ -110,7 +110,7 @@ classdef MyTemplatePoint3 < MyBase end function varargout = templatedMethodMatrix(this, varargin) - % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void + % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'double') geometry_wrapper(70, this, varargin{:}); @@ -120,7 +120,7 @@ classdef MyTemplatePoint3 < MyBase end function varargout = templatedMethodPoint2(this, varargin) - % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void + % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') geometry_wrapper(71, this, varargin{:}); @@ -130,7 +130,7 @@ classdef MyTemplatePoint3 < MyBase end function varargout = templatedMethodPoint3(this, varargin) - % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void + % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') geometry_wrapper(72, this, varargin{:}); @@ -140,7 +140,7 @@ classdef MyTemplatePoint3 < MyBase end function varargout = templatedMethodVector(this, varargin) - % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void + % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 geometry_wrapper(73, this, varargin{:}); diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index c937a2f5d..2714f3584 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -678,7 +678,7 @@ void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodMatrix",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); - obj->templatedMethod(t); + out[0] = wrap< Matrix >(obj->templatedMethod(t)); } void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -687,7 +687,7 @@ void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodPoint2",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - obj->templatedMethod(t); + out[0] = wrap< gtsam::Point2 >(obj->templatedMethod(t)); } void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -696,7 +696,7 @@ void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodPoint3",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - obj->templatedMethod(t); + out[0] = wrap< gtsam::Point3 >(obj->templatedMethod(t)); } void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -705,7 +705,7 @@ void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodVector",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint2"); Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); - obj->templatedMethod(t); + out[0] = wrap< Vector >(obj->templatedMethod(t)); } void MyTemplatePoint3_collectorInsertAndMakeBase_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -838,7 +838,7 @@ void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodMatrix",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); - obj->templatedMethod(t); + out[0] = wrap< Matrix >(obj->templatedMethod(t)); } void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -847,7 +847,7 @@ void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodPoint2",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2"); - obj->templatedMethod(t); + out[0] = wrap< gtsam::Point2 >(obj->templatedMethod(t)); } void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -856,7 +856,7 @@ void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodPoint3",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); - obj->templatedMethod(t); + out[0] = wrap< gtsam::Point3 >(obj->templatedMethod(t)); } void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) @@ -865,7 +865,7 @@ void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin checkArguments("templatedMethodVector",nargout,nargin-1,1); Shared obj = unwrap_shared_ptr(in[0], "ptr_MyTemplatePoint3"); Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); - obj->templatedMethod(t); + out[0] = wrap< Vector >(obj->templatedMethod(t)); } void MyFactorPosePoint2_collectorInsertAndMakeBase_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) 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; diff --git a/wrap/tests/testClass.cpp b/wrap/tests/testClass.cpp index 6a59cd83a..98a210e47 100644 --- a/wrap/tests/testClass.cpp +++ b/wrap/tests/testClass.cpp @@ -45,7 +45,7 @@ TEST( Class, OverloadingMethod ) { templateArgValues); EXPECT_LONGS_EQUAL(1, cls.nrMethods()); EXPECT(cls.exists(name)); - Method& method = cls.method(name); + Method method = cls.method(name); EXPECT_LONGS_EQUAL(1, method.nrOverloads()); cls.addMethod(verbose, is_const, name, args, retVal, templateArgName,