diff --git a/gtsam.h b/gtsam.h index 98382283f..fcf9e2343 100644 --- a/gtsam.h +++ b/gtsam.h @@ -13,12 +13,17 @@ * - void * - Any class with which be copied with boost::make_shared() * - boost::shared_ptr of any object type - * Limitations on methods - * - Parsing does not support overloading - * - There can only be one method (static or otherwise) with a given name + * Constructors + * - Overloads are supported + * - A class with no constructors can be returned from other functions but not allocated directly in MATLAB + * Methods * - Constness has no effect - * Methods must start with a lowercase letter - * Static methods must start with a letter (upper or lowercase) and use the "static" keyword + * - Must start with a lowercase letter + * - Overloads are supported + * Static methods + * - Must start with a letter (upper or lowercase) and use the "static" keyword + * - Static method names will be changed to start with an uppercase letter in the generated MATLAB interface + * - Overloads are supported * Arguments to functions any of * - Eigen types: Matrix, Vector * - Eigen types and classes as an optionally const reference @@ -44,17 +49,23 @@ * - To override, add a full include statement just before the class statement * - An override include can be added for a namespace by placing it just before the namespace statement * - Both classes and namespace accept exactly one namespace - * Overriding type dependency checks + * Using classes defined in other modules * - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error - * - Limitation: this only works if the class does not need a namespace specification + * Virtual inheritance + * - Specify fully-qualified base classes, i.e. "virtual class Derived : module::Base {" + * - Mark with 'virtual' keyword, e.g. "virtual class Base {", and also "virtual class Derived : module::Base {" + * - Forward declarations must also be marked virtual, e.g. "virtual class module::Base;" and + * also "virtual class module::Derived;" + * - Pure virtual (abstract) classes should list no constructors in this interface file + * - Virtual classes must have a clone() function in C++ (though it does not have to be included + * in the MATLAB interface). clone() will be called whenever an object copy is needed, instead + * of using the copy constructor (which is used for non-virtual objects). */ /** * Status: * - TODO: global functions * - TODO: default values for arguments - * - TODO: overloaded functions - * - TODO: signatures for constructors can be ambiguous if two types have the same first letter * - TODO: Handle gtsam::Rot3M conversions to quaternions */ @@ -64,8 +75,9 @@ namespace gtsam { // base //************************************************************************* -class Value { +virtual class Value { // No constructors because this is an abstract class + Value(const gtsam::Value& rhs); // Testable void print(string s) const; @@ -74,7 +86,7 @@ class Value { size_t dim() const; }; -class LieVector : gtsam::Value { +virtual class LieVector : gtsam::Value { // Standard constructors LieVector(); LieVector(Vector v); @@ -106,7 +118,7 @@ class LieVector : gtsam::Value { // geometry //************************************************************************* -class Point2 : gtsam::Value { +virtual class Point2 : gtsam::Value { // Standard Constructors Point2(); Point2(double x, double y); @@ -138,7 +150,7 @@ class Point2 : gtsam::Value { Vector vector() const; }; -class StereoPoint2 : gtsam::Value { +virtual class StereoPoint2 : gtsam::Value { // Standard Constructors StereoPoint2(); StereoPoint2(double uL, double uR, double v); @@ -167,7 +179,7 @@ class StereoPoint2 : gtsam::Value { Vector vector() const; }; -class Point3 : gtsam::Value { +virtual class Point3 : gtsam::Value { // Standard Constructors Point3(); Point3(double x, double y, double z); @@ -200,7 +212,7 @@ class Point3 : gtsam::Value { double z() const; }; -class Rot2 : gtsam::Value { +virtual class Rot2 : gtsam::Value { // Standard Constructors and Named Constructors Rot2(); Rot2(double theta); @@ -242,7 +254,7 @@ class Rot2 : gtsam::Value { Matrix matrix() const; }; -class Rot3 : gtsam::Value { +virtual class Rot3 : gtsam::Value { // Standard Constructors and Named Constructors Rot3(); Rot3(Matrix R); @@ -294,7 +306,7 @@ class Rot3 : gtsam::Value { // Vector toQuaternion() const; // FIXME: Can't cast to Vector properly }; -class Pose2 : gtsam::Value { +virtual class Pose2 : gtsam::Value { // Standard Constructor Pose2(); Pose2(double x, double y, double theta); @@ -340,7 +352,7 @@ class Pose2 : gtsam::Value { Matrix matrix() const; }; -class Pose3 : gtsam::Value { +virtual class Pose3 : gtsam::Value { // Standard Constructors Pose3(); Pose3(const gtsam::Pose3& pose); @@ -388,7 +400,7 @@ class Pose3 : gtsam::Value { double range(const gtsam::Pose3& pose); // FIXME: shadows other range }; -class Cal3_S2 : gtsam::Value { +virtual class Cal3_S2 : gtsam::Value { // Standard Constructors Cal3_S2(); Cal3_S2(double fx, double fy, double s, double u0, double v0); @@ -438,7 +450,7 @@ class Cal3_S2Stereo { double baseline() const; }; -class CalibratedCamera : gtsam::Value { +virtual class CalibratedCamera : gtsam::Value { // Standard Constructors and Named Constructors CalibratedCamera(); CalibratedCamera(const gtsam::Pose3& pose); @@ -468,7 +480,7 @@ class CalibratedCamera : gtsam::Value { double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods }; -class SimpleCamera : gtsam::Value { +virtual class SimpleCamera : gtsam::Value { // Standard Constructors and Named Constructors SimpleCamera(); SimpleCamera(const gtsam::Pose3& pose); @@ -943,6 +955,7 @@ class Values { void print(string s) const; void insert(size_t j, const gtsam::Value& value); bool exists(size_t j) const; + gtsam::Value at(size_t j) const; }; // Actually a FastList diff --git a/wrap/Class.cpp b/wrap/Class.cpp index ebaefc4a8..fa6a0c950 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -30,7 +30,9 @@ using namespace std; using namespace wrap; /* ************************************************************************* */ -void Class::matlab_proxy(const string& classFile, const string& wrapperName, FileWriter& wrapperFile, vector& functionNames) const { +void Class::matlab_proxy(const string& classFile, const string& wrapperName, + const ReturnValue::TypeAttributesTable& typeAttributes, + FileWriter& wrapperFile, vector& functionNames) const { // open destination classFile FileWriter proxyFile(classFile, verbose_, "%"); @@ -96,7 +98,7 @@ void Class::matlab_proxy(const string& classFile, const string& wrapperName, Fil // Methods BOOST_FOREACH(const Methods::value_type& name_m, methods) { const Method& m = name_m.second; - m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, functionNames); + m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames); proxyFile.oss << "\n"; wrapperFile.oss << "\n"; } @@ -108,7 +110,7 @@ void Class::matlab_proxy(const string& classFile, const string& wrapperName, Fil // Static methods BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) { const StaticMethod& m = name_m.second; - m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, functionNames); + m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabName, wrapperName, using_namespaces, typeAttributes, functionNames); proxyFile.oss << "\n"; wrapperFile.oss << "\n"; } diff --git a/wrap/Class.h b/wrap/Class.h index 4d31b4972..5703f8353 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -34,10 +34,11 @@ struct Class { typedef std::map StaticMethods; /// Constructor creates an empty class - Class(bool verbose=true) : verbose_(verbose) {} + Class(bool verbose=true) : verbose_(verbose), isVirtual(false) {} // Then the instance variables are set directly by the Module constructor std::string name; ///< Class name + bool isVirtual; ///< Whether the class is part of a virtual inheritance chain std::vector qualifiedParent; ///< The *single* parent - the last string is the parent class name, preceededing elements are a namespace stack Methods methods; ///< Class methods StaticMethods static_methods; ///< Static methods @@ -49,7 +50,7 @@ struct Class { bool verbose_; ///< verbose flag // And finally MATLAB code is emitted, methods below called by Module::matlab_code - void matlab_proxy(const std::string& classFile, const std::string& wrapperName, + void matlab_proxy(const std::string& classFile, const std::string& wrapperName, const ReturnValue::TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, std::vector& functionNames) const; ///< emit proxy class std::string qualifiedName(const std::string& delim = "") const; ///< creates a namespace-qualified name, optional delimiter diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 01bb80189..f44a08a73 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -41,6 +41,7 @@ void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperF const string& matlabClassName, const string& wrapperName, const vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes, vector& functionNames) const { proxyFile.oss << " function varargout = " << name << "(this, varargin)\n"; @@ -79,7 +80,7 @@ void Method::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperF // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment( - wrapperFile, cppClassName, matlabClassName, overload, id, using_namespaces); + wrapperFile, cppClassName, matlabClassName, overload, id, using_namespaces, typeAttributes); // Add to function list functionNames.push_back(wrapFunctionName); @@ -100,7 +101,8 @@ string Method::wrapper_fragment(FileWriter& file, const string& matlabClassName, int overload, int id, - const vector& using_namespaces) const { + const vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes) const { // generate code @@ -139,16 +141,12 @@ string Method::wrapper_fragment(FileWriter& file, // unwrap arguments, see Argument.cpp args.matlab_unwrap(file,1); - // call method - // example: bool result = self->return_field(t); - file.oss << " "; + // call method and wrap result + // example: out[0]=wrap(self->return_field(t)); if (returnVal.type1!="void") - file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = "; - file.oss << "obj->" << name << "(" << args.names() << ");\n"; - - // wrap result - // example: out[0]=wrap(result); - returnVal.wrap_result(file); + returnVal.wrap_result("obj->"+name+"("+args.names()+")", file, typeAttributes); + else + file.oss << " obj->"+name+"("+args.names()+");\n"; // finish file.oss << "}\n"; diff --git a/wrap/Method.h b/wrap/Method.h index 204e3002d..d9b1f09f1 100644 --- a/wrap/Method.h +++ b/wrap/Method.h @@ -50,6 +50,7 @@ struct Method { void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& cppClassName, const std::string& matlabClassName, const std::string& wrapperName, const std::vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes, std::vector& functionNames) const; private: @@ -58,7 +59,8 @@ private: const std::string& matlabClassname, int overload, int id, - const std::vector& using_namespaces) const; ///< cpp wrapper + const std::vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes) const; ///< cpp wrapper }; } // \namespace wrap diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 5482a19b1..006e38d4a 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -24,8 +24,10 @@ //#define BOOST_SPIRIT_DEBUG #include #include +#include #include #include +#include #include #include #include @@ -65,12 +67,12 @@ Module::Module(const string& interfacePath, //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 = ""; - string class_name = ""; const string null_str = ""; //---------------------------------------------------------------------------- @@ -200,6 +202,7 @@ Module::Module(const string& interfacePath, 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 @@ -212,7 +215,7 @@ Module::Module(const string& interfacePath, [append_a(cls.includes, namespace_includes)] [assign_a(deconstructor.name,cls.name)] [assign_a(cls.deconstructor, deconstructor)] - [push_back_a(classes,cls)] + [push_back_a(classes, cls)] [assign_a(deconstructor,deconstructor0)] [assign_a(constructor, constructor0)] [assign_a(cls,cls0)]; @@ -233,9 +236,12 @@ Module::Module(const string& interfacePath, >> namespace_name_p[push_back_a(using_namespace_current)] >> ch_p(';'); Rule forward_declaration_p = - str_p("class") >> - (*(namespace_name_p >> str_p("::")) >> className_p)[push_back_a(forward_declarations)] - >> ch_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 ; @@ -325,7 +331,10 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co wrapperFile.oss << "\n"; // Dependency check list - vector validTypes = forward_declarations; + 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"); @@ -337,18 +346,31 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co validTypes.push_back("Vector"); validTypes.push_back("Matrix"); //Create a list of parsed classes for dependency checking - BOOST_FOREACH(Class cls, classes) { + BOOST_FOREACH(const Class& cls, classes) { validTypes.push_back(cls.qualifiedName("::")); } + + // Create type attributes table + ReturnValue::TypeAttributesTable typeAttributes; + BOOST_FOREACH(const ForwardDeclaration& fwDec, forward_declarations) { + if(!typeAttributes.insert(make_pair(fwDec.name, ReturnValue::TypeAttributes(fwDec.isVirtual))).second) + throw DuplicateDefinition("class " + fwDec.name); + } + 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 - BOOST_FOREACH(Class cls, classes) { + BOOST_FOREACH(const Class& cls, classes) { generateIncludes(wrapperFile, cls.name, cls.includes); } wrapperFile.oss << "\n"; // Generate all collectors - BOOST_FOREACH(Class cls, classes) { + BOOST_FOREACH(const Class& cls, classes) { const string matlabName = cls.qualifiedName(), cppName = cls.qualifiedName("::"); wrapperFile.oss << "typedef std::set*> " << "Collector_" << matlabName << ";\n"; @@ -359,7 +381,7 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co // generate mexAtExit cleanup function wrapperFile.oss << "void _deleteAllObjects()\n"; wrapperFile.oss << "{\n"; - BOOST_FOREACH(Class cls, classes) { + BOOST_FOREACH(const Class& cls, classes) { const string matlabName = cls.qualifiedName(); const string cppName = cls.qualifiedName("::"); const string collectorType = "Collector_" + matlabName; @@ -373,10 +395,10 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co wrapperFile.oss << "}\n"; // generate proxy classes and wrappers - BOOST_FOREACH(Class cls, classes) { + BOOST_FOREACH(const Class& cls, classes) { // create proxy class and wrapper code string classFile = toolboxPath + "/" + cls.qualifiedName() + ".m"; - cls.matlab_proxy(classFile, wrapperName, wrapperFile, functionNames); + cls.matlab_proxy(classFile, wrapperName, typeAttributes, wrapperFile, functionNames); // verify all of the function arguments //TODO:verifyArguments(validTypes, cls.constructor.args_list); diff --git a/wrap/Module.h b/wrap/Module.h index a04a861c4..3cb23be25 100644 --- a/wrap/Module.h +++ b/wrap/Module.h @@ -19,6 +19,7 @@ #include #include +#include #include "Class.h" @@ -28,11 +29,18 @@ namespace wrap { * A module just has a name and a list of classes */ struct Module { + + struct ForwardDeclaration { + std::string name; + bool isVirtual; + ForwardDeclaration() : isVirtual(false) {} + }; + std::string name; ///< module name std::vector classes; ///< list of classes bool verbose; ///< verbose flag // std::vector using_namespaces; ///< all default namespaces - std::vector forward_declarations; + std::vector forward_declarations; /// constructor that parses interface file Module(const std::string& interfacePath, diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index 0c9dd5830..77bdeb746 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -46,45 +46,60 @@ string ReturnValue::qualifiedType2(const string& delim) const { /* ************************************************************************* */ //TODO:Fix this -void ReturnValue::wrap_result(FileWriter& file) const { +void ReturnValue::wrap_result(const string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const { string cppType1 = qualifiedType1("::"), matlabType1 = qualifiedType1(); string cppType2 = qualifiedType2("::"), matlabType2 = qualifiedType2(); if (isPair) { // first return value in pair if (isPtr1) {// if we already have a pointer - file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result.first);" << endl; + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(" << result << ".first);" << endl; file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n"; } else if (category1 == ReturnValue::CLASS) { // if we are going to make one - file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result.first));\n"; + string objCopy; + if(typeAttributes.at(cppType1).isVirtual) + objCopy = "boost::dynamic_pointer_cast<" + cppType1 + ">(" + result + ".first.clone())"; + else + objCopy = "new " + cppType1 + "(" + result + ".first)"; + file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(" << objCopy << ");\n"; file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n"; } else // if basis type - file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n"; + file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(" << result << ".first);\n"; // second return value in pair if (isPtr2) {// if we already have a pointer - file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(result.second);" << endl; + file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(" << result << ".second);" << endl; file.oss << " out[1] = wrap_shared_ptr(ret,\"" << matlabType2 << "\");\n"; } else if (category2 == ReturnValue::CLASS) { // if we are going to make one - file.oss << " Shared" << type2 << "* ret = new Shared" << type2 << "(new " << cppType2 << "(result.first));\n"; + string objCopy; + if(typeAttributes.at(cppType1).isVirtual) + objCopy = "boost::dynamic_pointer_cast<" + cppType2 + ">(" + result + ".second.clone())"; + else + objCopy = "new " + cppType1 + "(" + result + ".second)"; + file.oss << " Shared" << type2 << "* ret = new Shared" << type2 << "(" << objCopy << ");\n"; file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType2 << "\");\n"; } else - file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n"; + file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(" << result << ".second);\n"; } else if (isPtr1){ - file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result);" << endl; + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(" << result << ");" << endl; file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n"; } else if (category1 == ReturnValue::CLASS){ - file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result));\n"; + string objCopy; + if(typeAttributes.at(cppType1).isVirtual) + objCopy = "boost::dynamic_pointer_cast<" + cppType1 + ">(" + result + ".clone())"; + else + objCopy = "new " + cppType1 + "(" + result + ")"; + file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(" << objCopy << ");\n"; file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n"; } else if (matlabType1!="void") - file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n"; + file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(" << result << ");\n"; } /* ************************************************************************* */ diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index 859e00433..7d30578b2 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -8,6 +8,7 @@ */ #include +#include #include "FileWriter.h" @@ -17,6 +18,14 @@ namespace wrap { struct ReturnValue { + struct TypeAttributes { + bool isVirtual; + TypeAttributes() : isVirtual(false) {} + TypeAttributes(bool isVirtual) : isVirtual(isVirtual) {} + }; + + typedef std::map TypeAttributesTable; + typedef enum { CLASS, EIGEN, @@ -47,7 +56,7 @@ struct ReturnValue { std::string matlab_returnType() const; - void wrap_result(FileWriter& file) const; + void wrap_result(const std::string& result, FileWriter& file, const TypeAttributesTable& typeAttributes) const; }; diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index dd0c606b5..75456b6b7 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -42,6 +42,7 @@ void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wr const string& matlabClassName, const string& wrapperName, const vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes, vector& functionNames) const { string upperName = name; upperName[0] = std::toupper(upperName[0], std::locale()); @@ -82,7 +83,7 @@ void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wr // Output C++ wrapper code const string wrapFunctionName = wrapper_fragment( - wrapperFile, cppClassName, matlabClassName, overload, id, using_namespaces); + wrapperFile, cppClassName, matlabClassName, overload, id, using_namespaces, typeAttributes); // Add to function list functionNames.push_back(wrapFunctionName); @@ -103,7 +104,8 @@ string StaticMethod::wrapper_fragment(FileWriter& file, const string& matlabClassName, int overload, int id, - const vector& using_namespaces) const { + const vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes) const { // generate code @@ -140,14 +142,11 @@ string StaticMethod::wrapper_fragment(FileWriter& file, file.oss << " "; - // call method with default type + // call method with default type and wrap result if (returnVal.type1!="void") - file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = "; - file.oss << cppClassName << "::" << name << "(" << args.names() << ");\n"; - - // wrap result - // example: out[0]=wrap(result); - returnVal.wrap_result(file); + returnVal.wrap_result(cppClassName+"::"+name+"("+args.names()+")", file, typeAttributes); + else + file.oss << cppClassName+"::"+name+"("+args.names()+");\n"; // finish file.oss << "}\n"; diff --git a/wrap/StaticMethod.h b/wrap/StaticMethod.h index 5bc599ea5..8a739665d 100644 --- a/wrap/StaticMethod.h +++ b/wrap/StaticMethod.h @@ -50,6 +50,7 @@ struct StaticMethod { void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& cppClassName, const std::string& matlabClassName, const std::string& wrapperName, const std::vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes, std::vector& functionNames) const; private: @@ -58,7 +59,8 @@ private: const std::string& matlabClassname, int overload, int id, - const std::vector& using_namespaces) const; ///< cpp wrapper + const std::vector& using_namespaces, + const ReturnValue::TypeAttributesTable& typeAttributes) const; ///< cpp wrapper }; } // \namespace wrap diff --git a/wrap/matlab.h b/wrap/matlab.h index 4033844e4..05f7fffb5 100644 --- a/wrap/matlab.h +++ b/wrap/matlab.h @@ -119,7 +119,7 @@ void checkArguments(const string& name, int nargout, int nargin, int expected) { // default wrapping throws an error: only basis types are allowed in wrap template -mxArray* wrap(Class& value) { +mxArray* wrap(const Class& value) { error("wrap internal error: attempted wrap of invalid type"); return 0; } @@ -127,13 +127,13 @@ mxArray* wrap(Class& value) { // specialization to string // wraps into a character array template<> -mxArray* wrap(string& value) { +mxArray* wrap(const string& value) { return mxCreateString(value.c_str()); } // specialization to char template<> -mxArray* wrap(char& value) { +mxArray* wrap(const char& value) { mxArray *result = scalar(mxUINT32OR64_CLASS); *(char*)mxGetData(result) = value; return result; @@ -141,7 +141,7 @@ mxArray* wrap(char& value) { // specialization to unsigned char template<> -mxArray* wrap(unsigned char& value) { +mxArray* wrap(const unsigned char& value) { mxArray *result = scalar(mxUINT32OR64_CLASS); *(unsigned char*)mxGetData(result) = value; return result; @@ -149,7 +149,7 @@ mxArray* wrap(unsigned char& value) { // specialization to bool template<> -mxArray* wrap(bool& value) { +mxArray* wrap(const bool& value) { mxArray *result = scalar(mxUINT32OR64_CLASS); *(bool*)mxGetData(result) = value; return result; @@ -157,7 +157,7 @@ mxArray* wrap(bool& value) { // specialization to size_t template<> -mxArray* wrap(size_t& value) { +mxArray* wrap(const size_t& value) { mxArray *result = scalar(mxUINT32OR64_CLASS); *(size_t*)mxGetData(result) = value; return result; @@ -165,7 +165,7 @@ mxArray* wrap(size_t& value) { // specialization to int template<> -mxArray* wrap(int& value) { +mxArray* wrap(const int& value) { mxArray *result = scalar(mxUINT32OR64_CLASS); *(int*)mxGetData(result) = value; return result; @@ -173,7 +173,7 @@ mxArray* wrap(int& value) { // specialization to double -> just double template<> -mxArray* wrap(double& value) { +mxArray* wrap(const double& value) { return mxCreateDoubleScalar(value); } @@ -188,13 +188,7 @@ mxArray* wrap_Vector(const gtsam::Vector& v) { // specialization to Eigen vector -> double vector template<> -mxArray* wrap(gtsam::Vector& v) { - return wrap_Vector(v); -} - -// const version -template<> -mxArray* wrap(const gtsam::Vector& v) { +mxArray* wrap(const gtsam::Vector& v) { return wrap_Vector(v); } @@ -214,13 +208,7 @@ mxArray* wrap_Matrix(const gtsam::Matrix& A) { // specialization to Eigen MATRIX -> double matrix template<> -mxArray* wrap(gtsam::Matrix& A) { - return wrap_Matrix(A); -} - -// const version -template<> -mxArray* wrap(const gtsam::Matrix& A) { +mxArray* wrap(const gtsam::Matrix& A) { return wrap_Matrix(A); } diff --git a/wrap/utilities.h b/wrap/utilities.h index b0c9fb208..eeda3c68a 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -22,6 +22,8 @@ #include #include #include +#include +#include #include "FileWriter.h" @@ -29,42 +31,40 @@ namespace wrap { class CantOpenFile : public std::exception { private: - std::string filename_; + const std::string what_; public: - CantOpenFile(const std::string& filename) : filename_(filename) {} + CantOpenFile(const std::string& filename) : what_("Can't open file " + filename) {} ~CantOpenFile() throw() {} - virtual const char* what() const throw() { - return ("Can't open file " + filename_).c_str(); - } + virtual const char* what() const throw() { return what_.c_str(); } }; class ParseFailed : public std::exception { private: - int length_; + const std::string what_; public: - ParseFailed(int length) : length_(length) {} - ~ParseFailed() throw() {} - virtual const char* what() const throw() { - std::stringstream buf; - int len = length_+1; - buf << "Parse failed at character [" << len << "]"; - return buf.str().c_str(); - } + ParseFailed(int length) : what_((boost::format("Parse failed at character [%d]")%(length-1)).str()) {} + ~ParseFailed() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } }; class DependencyMissing : public std::exception { private: - std::string dependency_; - std::string location_; + const std::string what_; public: - DependencyMissing(const std::string& dep, const std::string& loc) { - dependency_ = dep; - location_ = loc; - } + DependencyMissing(const std::string& dep, const std::string& loc) : + what_("Missing dependency " + dep + " in " + loc) {} ~DependencyMissing() throw() {} - virtual const char* what() const throw() { - return ("Missing dependency " + dependency_ + " in " + location_).c_str(); - } + virtual const char* what() const throw() { return what_.c_str(); } +}; + +class DuplicateDefinition : public std::exception { +private: + const std::string what_; +public: + DuplicateDefinition(const std::string& name) : + what_("Duplicate definition of " + name) {} + ~DuplicateDefinition() throw() {} + virtual const char* what() const throw() { return what_.c_str(); } }; /** Special "magic number" passed into MATLAB constructor to indicate creating