diff --git a/.cproject b/.cproject index 11d2ab33e..075558734 100644 --- a/.cproject +++ b/.cproject @@ -281,6 +281,7 @@ + @@ -1011,6 +1012,14 @@ true true + + make + -j5 + all + true + true + true + make -j2 @@ -2166,6 +2175,38 @@ true true + + make + -j5 + wrap_gtsam_clean + true + true + true + + + make + -j5 + wrap_gtsam_unstable_clean + true + true + true + + + make + -j5 + wrap_gtsam_distclean + true + true + true + + + make + -j5 + wrap_gtsam_unstable_distclean + true + true + true + make -j2 diff --git a/CMakeLists.txt b/CMakeLists.txt index 96efa97dd..675e7c80b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -63,6 +63,7 @@ option(GTSAM_INSTALL_MATLAB_TESTS "Enable/Disable installation of matlab option(GTSAM_INSTALL_WRAP "Enable/Disable installation of wrap utility" ON) set(GTSAM_TOOLBOX_INSTALL_PATH ${CMAKE_INSTALL_PREFIX}/borg/toolbox CACHE DOCSTRING "Path to install matlab toolbox") +set(GTSAM_WRAP_HEADER_PATH ${PROJECT_SOURCE_DIR}/wrap CACHE DOCSTRING "Path to directory of matlab.h") # TODO: Check for matlab mex binary before handling building of binaries diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 7467ad0cf..50ec1d4de 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -138,6 +138,5 @@ if (GTSAM_BUILD_WRAP) # Macro to handle details of setting up targets # FIXME: issue with dependency between wrap_gtsam and wrap_gtsam_build, only shows up on CMake 2.8.3 - # FIXME: rework install commands to specify only certain filetypes/folders to avoid installing temp files wrap_library(gtsam "${mexFlags}" "../") endif () diff --git a/gtsam_unstable/base/Dummy.h b/gtsam_unstable/base/Dummy.h index ccf23af5d..995186cd6 100644 --- a/gtsam_unstable/base/Dummy.h +++ b/gtsam_unstable/base/Dummy.h @@ -33,6 +33,10 @@ namespace gtsam { std::cout << s << "Dummy " << id << std::endl; } + unsigned char dummyTwoVar(unsigned char a) const { + return a; + } + }; } // namespace gtsam diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index fda6ff8c4..c9d114d58 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -14,6 +14,7 @@ namespace gtsam { class Dummy { Dummy(); void print(string s) const; + unsigned char dummyTwoVar(unsigned char a) const; }; #include diff --git a/matlab/examples/OdometryExample.m b/matlab/examples/OdometryExample.m index f203c858e..b3cbff6a2 100644 --- a/matlab/examples/OdometryExample.m +++ b/matlab/examples/OdometryExample.m @@ -56,4 +56,4 @@ for i=1:result.size() end axis([-0.6 4.8 -1 1]) axis equal -view(2) \ No newline at end of file +view(2) diff --git a/matlab/tests/testOdometryExample.m b/matlab/tests/testOdometryExample.m index 0056a43e8..634c52799 100644 --- a/matlab/tests/testOdometryExample.m +++ b/matlab/tests/testOdometryExample.m @@ -33,8 +33,8 @@ initialEstimate.insertPose(3, gtsamPose2(4.1, 0.1, 0.1)); %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd result = graph.optimize(initialEstimate,0); marginals = graph.marginals(result); -marginals.marginalCovariance(i); +marginals.marginalCovariance(1); %% Check first pose equality -pose_i = result.pose(1); -CHECK('pose_1.equals(gtsamPose2,1e-4)',pose_1.equals(gtsamPose2,1e-4)); \ No newline at end of file +pose_1 = result.pose(1); +CHECK('pose_1.equals(gtsamPose2,1e-4)',pose_1.equals(gtsamPose2,1e-4)); diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp index f51b86864..e2073ac8c 100644 --- a/wrap/Argument.cpp +++ b/wrap/Argument.cpp @@ -12,6 +12,7 @@ /** * @file Argument.ccp * @author Frank Dellaert + * @author Andrew Melim **/ #include @@ -53,14 +54,14 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const { file.oss << "boost::shared_ptr<" << cppType << "> " << name << " = unwrap_shared_ptr< "; else if (is_ref) // A reference: emit an "unwrap_shared_ptr" call and de-reference the pointer - file.oss << cppType << "& " << name << " = *unwrap_shared_ptr< "; + file.oss << " " << cppType << "& " << name << " = *unwrap_shared_ptr< "; else // Not a pointer or a reference: emit an "unwrap" call // unwrap is specified in matlab.h as a series of template specializations // that know how to unpack the expected MATLAB object // example: double tol = unwrap< double >(in[2]); // example: Vector v = unwrap< Vector >(in[1]); - file.oss << cppType << " " << name << " = unwrap< "; + file.oss << " " << cppType << " " << name << " = unwrap< "; file.oss << cppType << " >(" << matlabName; if (is_ptr || is_ref) file.oss << ", \"" << matlabType << "\""; @@ -126,3 +127,4 @@ void ArgumentList::matlab_unwrap(FileWriter& file, int start) const { } /* ************************************************************************* */ + diff --git a/wrap/Argument.h b/wrap/Argument.h index 000e3079a..b4c3fe4a7 100644 --- a/wrap/Argument.h +++ b/wrap/Argument.h @@ -13,6 +13,7 @@ * @file Argument.h * @brief arguments to constructors and methods * @author Frank Dellaert + * @author Andrew Melim **/ #pragma once @@ -65,6 +66,7 @@ struct ArgumentList: public std::vector { * @param start initial index for input array, set to 1 for method */ void matlab_unwrap(FileWriter& file, int start = 0) const; // MATLAB to C++ + }; } // \namespace wrap diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 6f6f91b0a..e57a85884 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -10,8 +10,9 @@ * -------------------------------------------------------------------------- */ /** - * @file Class.ccp + * @file Class.cpp * @author Frank Dellaert + * @author Andrew Melim **/ #include @@ -22,6 +23,7 @@ #include "Class.h" #include "utilities.h" +#include "Argument.h" using namespace std; using namespace wrap; @@ -43,13 +45,25 @@ void Class::matlab_proxy(const string& classFile) const { file.oss << " methods" << endl; // constructor file.oss << " function obj = " << matlabName << "(varargin)" << endl; - BOOST_FOREACH(Constructor c, constructors) - c.matlab_proxy_fragment(file,matlabName); - file.oss << " if nargin ~= 13 && obj.self == 0, error('" << matlabName << " constructor failed'); end" << endl; + //i is constructor id + int id = 0; + BOOST_FOREACH(ArgumentList a, constructor.args_list) + { + constructor.matlab_proxy_fragment(file,matlabName, id, a); + id++; + } + //Static constructor collect call + file.oss << " if nargin ==14, new_" << matlabName << "_(varargin{1},0); end" << endl; + file.oss << " if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('" << matlabName << " constructor failed'); end" << endl; file.oss << " end" << endl; // deconstructor file.oss << " function delete(obj)" << endl; - file.oss << " delete_" << matlabName << "(obj);" << endl; + file.oss << " if obj.self ~= 0" << endl; + //TODO: Add verbosity flag + //file.oss << " fprintf(1,'MATLAB class deleting %x',obj.self);" << endl; + file.oss << " new_" << matlabName << "_(obj.self);" << endl; + file.oss << " obj.self = 0;" << endl; + file.oss << " end" << endl; file.oss << " end" << endl; file.oss << " function display(obj), obj.print(''); end" << endl; file.oss << " function disp(obj), obj.display; end" << endl; @@ -61,18 +75,19 @@ void Class::matlab_proxy(const string& classFile) const { } /* ************************************************************************* */ +//TODO: Consolidate into single file void Class::matlab_constructors(const string& toolboxPath) const { - BOOST_FOREACH(Constructor c, constructors) { - c.matlab_mfile (toolboxPath, qualifiedName()); - c.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), using_namespaces, includes); + /*BOOST_FOREACH(Constructor c, constructors) { + args_list.push_back(c.args); + }*/ + + BOOST_FOREACH(ArgumentList a, constructor.args_list) { + constructor.matlab_mfile(toolboxPath, qualifiedName(), a); } + constructor.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), + using_namespaces, includes); } -/* ************************************************************************* */ -void Class::matlab_deconstructor(const string& toolboxPath) const { - d.matlab_mfile (toolboxPath, qualifiedName()); - d.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), using_namespaces, includes); -} /* ************************************************************************* */ void Class::matlab_methods(const string& classPath) const { string matlabName = qualifiedName(), cppName = qualifiedName("::"); @@ -97,9 +112,7 @@ void Class::matlab_make_fragment(FileWriter& file, const string& mexFlags) const { string mex = "mex " + mexFlags + " "; string matlabClassName = qualifiedName(); - BOOST_FOREACH(Constructor c, constructors) - file.oss << mex << c.matlab_wrapper_name(matlabClassName) << ".cpp" << endl; - file.oss << mex << d.matlab_wrapper_name(matlabClassName) << ".cpp" << endl; + file.oss << mex << constructor.matlab_wrapper_name(matlabClassName) << ".cpp" << endl; BOOST_FOREACH(StaticMethod sm, static_methods) file.oss << mex << matlabClassName + "_" + sm.name << ".cpp" << endl; file.oss << endl << "cd @" << matlabClassName << endl; @@ -123,15 +136,12 @@ void Class::makefile_fragment(FileWriter& file) const { // // Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) - string matlabName = qualifiedName(); + string matlabName = qualifiedName(); - // collect names - vector file_names; - BOOST_FOREACH(Constructor c, constructors) { - string file_base = c.matlab_wrapper_name(matlabName); - file_names.push_back(file_base); - } - file_names.push_back(d.matlab_wrapper_name(matlabName)); + // collect names + vector file_names; + string file_base = constructor.matlab_wrapper_name(matlabName); + file_names.push_back(file_base); BOOST_FOREACH(StaticMethod c, static_methods) { string file_base = matlabName + "_" + c.name; file_names.push_back(file_base); @@ -142,7 +152,8 @@ void Class::makefile_fragment(FileWriter& file) const { } BOOST_FOREACH(const string& file_base, file_names) { - file.oss << file_base << ".$(MEXENDING): " << file_base << ".cpp" << endl; + file.oss << file_base << ".$(MEXENDING): " << file_base << ".cpp"; + file.oss << " $(PATH_TO_WRAP)/matlab.h" << endl; file.oss << "\t$(MEX) $(mex_flags) " << file_base << ".cpp -output " << file_base << endl; } diff --git a/wrap/Class.h b/wrap/Class.h index 875b3203e..fb9906716 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -13,6 +13,7 @@ * @file Class.h * @brief describe the C++ class that is being wrapped * @author Frank Dellaert + * @author Andrew Melim **/ #pragma once @@ -33,19 +34,17 @@ struct Class { // Then the instance variables are set directly by the Module constructor std::string name; ///< Class name - std::vector constructors; ///< Class constructors std::vector methods; ///< Class methods std::vector static_methods; ///< Static methods std::vector namespaces; ///< Stack of namespaces std::vector using_namespaces; ///< default namespaces std::vector includes; ///< header include overrides - Deconstructor d; + Constructor constructor; ///< Class constructors 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; ///< emit proxy class void matlab_constructors(const std::string& toolboxPath) const; ///< emit constructor wrappers - void matlab_deconstructor(const std::string& toolboxPath) const; void matlab_methods(const std::string& classPath) const; ///< emit method wrappers void matlab_static_methods(const std::string& classPath) const; ///< emit static method wrappers void matlab_make_fragment(FileWriter& file, diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp index fda7db1b4..7785de08f 100644 --- a/wrap/Constructor.cpp +++ b/wrap/Constructor.cpp @@ -12,10 +12,12 @@ /** * @file Constructor.ccp * @author Frank Dellaert + * @author Andrew Melim **/ #include #include +#include #include @@ -25,14 +27,16 @@ using namespace std; using namespace wrap; + /* ************************************************************************* */ string Constructor::matlab_wrapper_name(const string& className) const { - string str = "new_" + className + "_" + args.signature(); + string str = "new_" + className + "_"; return str; } /* ************************************************************************* */ -void Constructor::matlab_proxy_fragment(FileWriter& file, const string& className) const { +void Constructor::matlab_proxy_fragment(FileWriter& file, + const string& className, const int id, const ArgumentList args) const { size_t nrArgs = args.size(); // check for number of arguments... file.oss << " if (nargin == " << nrArgs; @@ -45,19 +49,17 @@ void Constructor::matlab_proxy_fragment(FileWriter& file, const string& classNam first=false; } // emit code for calling constructor - file.oss << "), obj.self = " << matlab_wrapper_name(className) << "("; + file.oss << "), obj.self = " << matlab_wrapper_name(className) << "(" << "0," << id; // emit constructor arguments - first = true; for(size_t i=0;i& using_namespaces, const vector& includes) const { + const vector& using_namespaces, + const vector& includes) const { string matlabName = matlab_wrapper_name(matlabClassName); // open destination wrapperFile @@ -91,12 +94,66 @@ void Constructor::matlab_wrapper(const string& toolboxPath, generateIncludes(file, name, includes); generateUsingNamespace(file, using_namespaces); + //Typedef boost::shared_ptr + file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; + file.oss << endl; + + //Generate collector + file.oss << "static std::set collector;" << endl; + file.oss << endl; + + //Generate the destructor function + file.oss << "struct Destruct" << endl; + file.oss << "{" << endl; + file.oss << " void operator() (Shared* p)" << endl; + file.oss << " {" << endl; + file.oss << " collector.erase(p);" << endl; + file.oss << " }" << endl; + file.oss << "};" << endl; + file.oss << endl; + + //Generate cleanup function + file.oss << "void cleanup(void) {" << endl; + file.oss << " std::for_each( collector.begin(), collector.end(), Destruct() );" << endl; + file.oss << "}" << endl; + file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; file.oss << "{" << endl; - file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << args.size() << ");" << endl; - args.matlab_unwrap(file); // unwrap arguments - file.oss << " " << cppClassName << "* self = new " << cppClassName << "(" << args.names() << ");" << endl; // need qualified name, delim: "::" - file.oss << " out[0] = wrap_constructed(self,\"" << matlabClassName << "\");" << endl; // need matlab qualified name + //Cleanup function callback + file.oss << " mexAtExit(cleanup);" << endl; + file.oss << endl; + file.oss << " const mxArray* input = in[0];" << endl; + file.oss << " Shared* self = *(Shared**) mxGetData(input);" << endl; + file.oss << endl; + file.oss << " if(self) {" << endl; + file.oss << " if(nargin > 1) {" << endl; + file.oss << " collector.insert(self);" << endl; + if(verbose_) + file.oss << " std::cout << \"Collected\" << collector.size() << std::endl;" << endl; + file.oss << " }" << endl; + file.oss << " else if(collector.erase(self))" << endl; + file.oss << " delete self;" << endl; + file.oss << " } else {" << endl; + file.oss << " int nc = unwrap(in[1]);" << endl; + + int i = 0; + BOOST_FOREACH(ArgumentList al, args_list) + { + file.oss << " if(nc == " << i <<") {" << endl; + al.matlab_unwrap(file, 2); // unwrap arguments, start at 1 + file.oss << " self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl; + file.oss << " }" << endl; + i++; + } + + //file.oss << " self = construct(nc, in);" << endl; + file.oss << " collector.insert(self);" << endl; + if(verbose_) + file.oss << " std::cout << \"constructed \" << self << \", size=\" << collector.size() << std::endl;" << endl; + file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl; + file.oss << " *reinterpret_cast (mxGetPr(out[0])) = self;" << endl; + file.oss << " }" << endl; + file.oss << "}" << endl; // close file diff --git a/wrap/Constructor.h b/wrap/Constructor.h index 4aba5b984..467ff3b22 100644 --- a/wrap/Constructor.h +++ b/wrap/Constructor.h @@ -28,12 +28,12 @@ namespace wrap { struct Constructor { /// Constructor creates an empty class - Constructor(bool verbose = true) : + Constructor(bool verbose = false) : verbose_(verbose) { } // Then the instance variables are set directly by the Module constructor - ArgumentList args; + std::vector args_list; std::string name; bool verbose_; @@ -48,11 +48,14 @@ struct Constructor { * Create fragment to select constructor in proxy class, e.g., * if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end */ - void matlab_proxy_fragment(FileWriter& file, const std::string& className) const; + void matlab_proxy_fragment(FileWriter& file, + const std::string& className, const int i, + const ArgumentList args) const; /// m-file void matlab_mfile(const std::string& toolboxPath, - const std::string& qualifiedMatlabName) const; + const std::string& qualifiedMatlabName, + const ArgumentList args) const; /// cpp wrapper void matlab_wrapper(const std::string& toolboxPath, @@ -60,7 +63,12 @@ struct Constructor { const std::string& matlabClassName, const std::vector& using_namespaces, const std::vector& includes) const; + + /// constructor function + void generate_construct(FileWriter& file, const std::string& cppClassName, + std::vector& args_list) const; + }; -} // \namespace wrap +} // \namespace wrap diff --git a/wrap/FileWriter.cpp b/wrap/FileWriter.cpp index ae474be0a..38abf2488 100644 --- a/wrap/FileWriter.cpp +++ b/wrap/FileWriter.cpp @@ -46,6 +46,10 @@ void FileWriter::emit(bool add_header, bool force_overwrite) const { ofs << new_contents; ofs.close(); if (verbose_) cerr << " ...complete" << endl; + + // Add small message whenever writing a new file and not running in full verbose mode + if (!verbose_) + cout << "wrap: generating " << filename_ << endl; } else { if (verbose_) cerr << " ...no update" << endl; } diff --git a/wrap/Method.cpp b/wrap/Method.cpp index 7686ecd2d..f5da0d370 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -61,6 +61,18 @@ void Method::matlab_wrapper(const string& classPath, generateIncludes(file, className, includes); generateUsingNamespace(file, using_namespaces); + if(returnVal.isPair) + { + if(returnVal.category1 == ReturnValue::CLASS) + file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + if(returnVal.category2 == ReturnValue::CLASS) + file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl; + } + else + if(returnVal.category1 == ReturnValue::CLASS) + file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + + file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; // call file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; // start @@ -73,9 +85,9 @@ void Method::matlab_wrapper(const string& classPath, // get class pointer // example: shared_ptr = unwrap_shared_ptr< Test >(in[0], "Test"); - file.oss << " boost::shared_ptr<" << cppClassName << "> self = unwrap_shared_ptr< " << cppClassName - << " >(in[0],\"" << matlabClassName << "\");" << endl; - + file.oss << " mxArray* mxh = mxGetProperty(in[0],0,\"self\");" << endl; + file.oss << " Shared* self = *reinterpret_cast (mxGetPr(mxh));" << endl; + file.oss << " Shared obj = *self;" << endl; // unwrap arguments, see Argument.cpp args.matlab_unwrap(file,1); @@ -84,7 +96,7 @@ void Method::matlab_wrapper(const string& classPath, file.oss << " "; if (returnVal.type1!="void") file.oss << returnVal.return_type(true,ReturnValue::pair) << " result = "; - file.oss << "self->" << name << "(" << args.names() << ");\n"; + file.oss << "obj->" << name << "(" << args.names() << ");\n"; // wrap result // example: out[0]=wrap(result); diff --git a/wrap/Module.cpp b/wrap/Module.cpp index e0771351a..0adf1cda0 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -26,8 +26,10 @@ #include #include #include +#include #include +#include using namespace std; using namespace wrap; @@ -52,8 +54,9 @@ Module::Module(const string& interfacePath, ReturnValue retVal0, retVal; Argument arg0, arg; ArgumentList args0, args; + vector arg_dup; ///keep track of duplicates Constructor constructor0(enable_verbose), constructor(enable_verbose); - Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); + //Deconstructor deconstructor0(enable_verbose), deconstructor(enable_verbose); Method method0(enable_verbose), method(enable_verbose); StaticMethod static_method0(enable_verbose), static_method(enable_verbose); Class cls0(enable_verbose),cls(enable_verbose); @@ -118,11 +121,12 @@ Module::Module(const string& interfacePath, Rule constructor_p = (className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p) - [assign_a(constructor.args,args)] - [assign_a(constructor.name,cls.name)] - [assign_a(args,args0)] - [push_back_a(cls.constructors, constructor)] - [assign_a(constructor,constructor0)]; + [push_back_a(constructor.args_list, args)] + [assign_a(args,args0)]; + //[assign_a(constructor.args,args)] + //[assign_a(constructor.name,cls.name)] + //[push_back_a(cls.constructors, constructor)] + //[assign_a(constructor,constructor0)]; Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::"); @@ -184,13 +188,16 @@ Module::Module(const string& interfacePath, >> '{' >> *(functions_p | comments_p) >> str_p("};")) + [assign_a(constructor.name, cls.name)] + [assign_a(cls.constructor, constructor)] [assign_a(cls.namespaces, namespaces)] [assign_a(cls.using_namespaces, using_namespace_current)] [append_a(cls.includes, namespace_includes)] - [assign_a(deconstructor.name,cls.name)] - [assign_a(cls.d, deconstructor)] + //[assign_a(deconstructor.name,cls.name)] + //[assign_a(cls.d, deconstructor)] [push_back_a(classes,cls)] - [assign_a(deconstructor,deconstructor0)] + //[assign_a(deconstructor,deconstructor0)] + [assign_a(constructor, constructor0)] [assign_a(cls,cls0)]; Rule namespace_def_p = @@ -280,7 +287,7 @@ void verifyReturnTypes(const vector& validtypes, const vector& vt) { /* ************************************************************************* */ void Module::matlab_code(const string& mexCommand, const string& toolboxPath, - const string& mexExt, const string& mexFlags) const { + const string& mexExt, const string& headerPath,const string& mexFlags) const { fs::create_directories(toolboxPath); @@ -301,6 +308,7 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath, makeModuleMakefile.oss << "\nMEX = " << mexCommand << "\n"; makeModuleMakefile.oss << "MEXENDING = " << mexExt << "\n"; + makeModuleMakefile.oss << "PATH_TO_WRAP = " << headerPath << "\n"; makeModuleMakefile.oss << "mex_flags = " << mexFlags << "\n\n"; // Dependency check list @@ -336,7 +344,7 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath, cls.matlab_proxy(classFile); // verify all of the function arguments - verifyArguments(validTypes, cls.constructors); + //TODO:verifyArguments(validTypes, cls.constructor.args_list); verifyArguments(validTypes, cls.static_methods); verifyArguments(validTypes, cls.methods); @@ -350,7 +358,7 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath, cls.matlab_methods(classPath); // create deconstructor - cls.matlab_deconstructor(toolboxPath); + //cls.matlab_deconstructor(toolboxPath); // add lines to make m-file makeModuleMfile.oss << "%% " << cls.qualifiedName() << endl; diff --git a/wrap/Module.h b/wrap/Module.h index 4b650728d..239aa20b0 100644 --- a/wrap/Module.h +++ b/wrap/Module.h @@ -44,6 +44,7 @@ struct Module { const std::string& mexCommand, const std::string& path, const std::string& mexExt, + const std::string& headerPath, const std::string& mexFlags) const; }; diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index ace1159ec..087a1c6ef 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -3,6 +3,7 @@ * * @date Dec 1, 2011 * @author Alex Cunningham + * @author Andrew Melim */ #include @@ -17,11 +18,11 @@ using namespace wrap; string ReturnValue::return_type(bool add_ptr, pairing p) const { if (p==pair && isPair) { string str = "pair< " + - maybe_shared_ptr(add_ptr && isPtr1, qualifiedType1("::")) + ", " + - maybe_shared_ptr(add_ptr && isPtr2, qualifiedType2("::")) + " >"; + maybe_shared_ptr(add_ptr && isPtr1, qualifiedType1("::"), type1) + ", " + + maybe_shared_ptr(add_ptr && isPtr2, qualifiedType2("::"), type2) + " >"; return str; } else - return maybe_shared_ptr(add_ptr && isPtr1, (p==arg2)? qualifiedType2("::") : qualifiedType1("::")); + return maybe_shared_ptr(add_ptr && isPtr1, (p==arg2)? qualifiedType2("::") : qualifiedType1("::"), (p==arg2)? type2 : type1); } /* ************************************************************************* */ @@ -44,31 +45,44 @@ string ReturnValue::qualifiedType2(const string& delim) const { } /* ************************************************************************* */ +//TODO:Fix this void ReturnValue::wrap_result(FileWriter& file) 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 << " out[0] = wrap_shared_ptr(result.first,\"" << matlabType1 << "\");\n"; - else if (category1 == ReturnValue::CLASS) // if we are going to make one - file.oss << " out[0] = wrap_shared_ptr(boost::make_shared< " << cppType1 << " >(result.first),\"" << matlabType1 << "\");\n"; + if (isPtr1) {// if we already have a pointer + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result.first);" << endl; + file.oss << " out[0] = wrap_collect_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"; + file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; + } else // if basis type 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 << " out[1] = wrap_shared_ptr(result.second,\"" << matlabType2 << "\");\n"; - else if (category2 == ReturnValue::CLASS) // if we are going to make one - file.oss << " out[1] = wrap_shared_ptr(boost::make_shared< " << cppType2 << " >(result.second),\"" << matlabType2 << "\");\n"; + if (isPtr2) {// if we already have a pointer + file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(result.second);" << endl; + file.oss << " out[1] = wrap_collect_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"; + file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType2 << "\");\n"; + } else file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n"; } - else if (isPtr1) - file.oss << " out[0] = wrap_shared_ptr(result,\"" << matlabType1 << "\");\n"; - else if (category1 == ReturnValue::CLASS) - file.oss << " out[0] = wrap_shared_ptr(boost::make_shared< " << cppType1 << " >(result),\"" << matlabType1 << "\");\n"; + else if (isPtr1){ + file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result);" << endl; + file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; + } + else if (category1 == ReturnValue::CLASS){ + file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result));\n"; + file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; + } else if (matlabType1!="void") file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n"; } diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index 7bdba650b..a4fb3fbe8 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -10,8 +10,9 @@ * -------------------------------------------------------------------------- */ /** - * @file Method.ccp + * @file StaticMethod.ccp * @author Frank Dellaert + * @author Andrew Melim **/ #include @@ -62,6 +63,15 @@ void StaticMethod::matlab_wrapper(const string& toolboxPath, const string& class generateIncludes(file, className, includes); generateUsingNamespace(file, using_namespaces); + if(returnVal.isPair) + { + file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl; + } + else + file.oss << "typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; + + file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; // call file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; // start diff --git a/wrap/matlab.h b/wrap/matlab.h index 313cfaa9f..3cfebdfe7 100644 --- a/wrap/matlab.h +++ b/wrap/matlab.h @@ -41,6 +41,8 @@ extern "C" { #include #include #include +#include +#include using namespace std; using namespace boost; // not usual, but for conciseness of generated code @@ -311,113 +313,6 @@ gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) { return A; } -//***************************************************************************** -// Shared Pointer Handle -// inspired by mexhandle, but using shared_ptr -//***************************************************************************** - -template -class ObjectHandle { -private: - ObjectHandle* signature; // use 'this' as a unique object signature - const std::type_info* type; // type checking information - boost::shared_ptr t; // object pointer - -public: - // Constructor for free-store allocated objects. - // Creates shared pointer, will delete if is last one to hold pointer - ObjectHandle(T* ptr) : - type(&typeid(T)), t(ptr) { - signature = this; - } - - // Constructor for shared pointers - // Creates shared pointer, will delete if is last one to hold pointer - ObjectHandle(boost::shared_ptr shared_ptr) : - /*type(&typeid(T)),*/ t(shared_ptr) { - signature = this; - } - - ~ObjectHandle() { - // object is in shared_ptr, will be automatically deleted - signature = 0; // destroy signature - // std::cout << "ObjectHandle destructor" << std::endl; - } - - // Get the actual object contained by handle - boost::shared_ptr get_object() const { - return t; - } - - // Print the mexhandle for debugging - void print(const char* str) { - mexPrintf("mexhandle %s:\n", str); - mexPrintf(" signature = %d:\n", signature); - mexPrintf(" pointer = %d:\n", t.get()); - } - - // Convert ObjectHandle to a mxArray handle (to pass back from mex-function). - // Create a numeric array as handle for an ObjectHandle. - // We ASSUME we can store object pointer in the mxUINT32 element of mxArray. - mxArray* to_mex_handle() { - mxArray* handle = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast**> (mxGetPr(handle)) = this; - return handle; - } - - string type_name() const { - return type->name(); - } - - // Convert mxArray (passed to mex-function) to an ObjectHandle. - // Import a handle from MatLab as a mxArray of UINT32. Check that - // it is actually a pointer to an ObjectHandle. - static ObjectHandle* from_mex_handle(const mxArray* handle) { - if (mxGetClassID(handle) != mxUINT32OR64_CLASS || mxIsComplex(handle) - || mxGetM(handle) != 1 || mxGetN(handle) != 1) error( - "Parameter is not an ObjectHandle type."); - - // We *assume* we can store ObjectHandle pointer in the mxUINT32 of handle - ObjectHandle* obj = *reinterpret_cast (mxGetPr(handle)); - - if (!obj) // gross check to see we don't have an invalid pointer - error("Parameter is NULL. It does not represent an ObjectHandle object."); - // TODO: change this for max-min check for pointer values - - if (obj->signature != obj) // check memory has correct signature - error("Parameter does not represent an ObjectHandle object."); - - /* - if (*(obj->type) != typeid(T)) { // check type - mexPrintf("Given: <%s>, Required: <%s>.\n", obj->type_name(), typeid(T).name()); - error("Given ObjectHandle does not represent the correct type."); - } - */ - - return obj; - } - -}; - -//***************************************************************************** -// wrapping C++ objects in a MATLAB proxy class -//***************************************************************************** - -/* - For every C++ class Class, a matlab proxy class @Class/Class.m object - is created. Its constructor will check which of the C++ constructors - needs to be called, based on nr of arguments. It then calls the - corresponding mex function new_Class_signature, which will create a - C++ object using new, and pass the pointer to wrap_constructed - (below). This creates a mexhandle and returns it to the proxy class - constructor, which assigns it to self. Matlab owns this handle now. -*/ -template -mxArray* wrap_constructed(Class* pointer, const char *classname) { - ObjectHandle* handle = new ObjectHandle(pointer); - return handle->to_mex_handle(); -} - /* [create_object] creates a MATLAB proxy class object with a mexhandle in the self property. Matlab does not allow the creation of matlab @@ -435,138 +330,49 @@ mxArray* create_object(const char *classname, mxArray* h) { return result; } +/* + * Similar to create object, this also collects the shared_ptr in addition + * to creating the dummy object. Mainly used for static constructor methods + * which don't have direct access to the function. + */ +mxArray* create_collect_object(const char *classname, mxArray* h){ + mxArray *result; + //First arg is a flag to collect + mxArray* dummy[14] = {h,h,h,h,h, h,h,h,h,h, h,h,h,h}; + mexCallMATLAB(1,&result,14,dummy,classname); + mxSetProperty(result, 0, "self", h); + return result; +} + /* When the user calls a method that returns a shared pointer, we create an ObjectHandle from the shared_pointer and return it as a proxy class to matlab. */ template -mxArray* wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const char *classname) { - ObjectHandle* handle = new ObjectHandle(shared_ptr); - return create_object(classname,handle->to_mex_handle()); +mxArray* wrap_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) { + mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast**> (mxGetPr(mxh)) = shared_ptr; + //return mxh; + return create_object(classname, mxh); } -//***************************************************************************** -// unwrapping a MATLAB proxy class to a C++ object reference -//***************************************************************************** +template +mxArray* wrap_collect_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) { + mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast**> (mxGetPr(mxh)) = shared_ptr; + //return mxh; + return create_collect_object(classname, mxh); +} -/* - Besides the basis types, the only other argument type allowed is a - shared pointer to a C++ object. In this case, matlab needs to pass a - proxy class object to the mex function. [unwrap_shared_ptr] extracts - the ObjectHandle from the self property, and returns a shared pointer - to the object. -*/ template boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& className) { - #ifndef UNSAFE_WRAP - // Useful code to check argument type - // Problem, does not support inheritance - bool isClass = mxIsClass(obj, className.c_str()); - if (!isClass) { - mexPrintf("Expected %s, got %s\n", className.c_str(), mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif + mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - return handle->get_object(); + if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh) + || mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error( + "Parameter is not an Shared type."); + + boost::shared_ptr* spp = *reinterpret_cast**> (mxGetPr(mxh)); + return *spp; } - -/* - * Specialized template for noise model. Checking their derived types properly - */ -// Isotropic -template <> -boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& className) { -#ifndef UNSAFE_WRAP - bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic"); - bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit"); - if (!isIsotropic && !isUnit) { - mexPrintf("Expected gtsamnoiseModelIsotropic or derived classes, got %s\n", mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - return handle->get_object(); -} - -// Diagonal -template <> -boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& className) { -#ifndef UNSAFE_WRAP - bool isDiagonal = mxIsClass(obj, "gtsamnoiseModelDiagonal"); - bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic"); - bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit"); - if (!isDiagonal && !isIsotropic && !isUnit ) { - mexPrintf("Expected gtsamnoiseModelDiagonal or derived classes, got %s\n", mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - return handle->get_object(); -} - -// Gaussian -template <> -boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& className) { -#ifndef UNSAFE_WRAP - bool isGaussian = mxIsClass(obj, "gtsamnoiseModelGaussian"); - bool isDiagonal = mxIsClass(obj, "gtsamnoiseModelDiagonal"); - bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic"); - bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit"); - if (!isGaussian && !isDiagonal && !isIsotropic && !isUnit) { - mexPrintf("Expected gtsamnoiseModelGaussian or derived classes, got %s\n", mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - return handle->get_object(); -} - -// Base -template <> -boost::shared_ptr unwrap_shared_ptr(const mxArray* obj, const string& className) { -#ifndef UNSAFE_WRAP - bool isBase = mxIsClass(obj, "gtsamnoiseModelBase"); - bool isGaussian = mxIsClass(obj, "gtsamnoiseModelGaussian"); - bool isDiagonal = mxIsClass(obj, "gtsamnoiseModelDiagonal"); - bool isIsotropic = mxIsClass(obj, "gtsamnoiseModelIsotropic"); - bool isUnit = mxIsClass(obj, "gtsamnoiseModelUnit"); - if (!isBase && !isGaussian && !isDiagonal && !isIsotropic && !isUnit) { - mexPrintf("Expected gtsamnoiseModelBase or derived classes, got %s\n", mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - return handle->get_object(); -} - -//end specialized templates - -template -void delete_shared_ptr(const mxArray* obj, const string& className) { - //Why is this here? -#ifndef UNSAFE_WRAP - bool isClass = true;//mxIsClass(obj, className.c_str()); - if (!isClass) { - mexPrintf("Expected %s, got %s\n", className.c_str(), mxGetClassName(obj)); - error("Argument has wrong type."); - } -#endif - mxArray* mxh = mxGetProperty(obj,0,"self"); - if (mxh==NULL) error("unwrap_reference: invalid wrap object"); - ObjectHandle* handle = ObjectHandle::from_mex_handle(mxh); - delete handle; -} - -//***************************************************************************** diff --git a/wrap/tests/expected/@Point2/Point2.m b/wrap/tests/expected/@Point2/Point2.m index 454d81399..68744ae00 100644 --- a/wrap/tests/expected/@Point2/Point2.m +++ b/wrap/tests/expected/@Point2/Point2.m @@ -5,12 +5,16 @@ classdef Point2 < handle end methods function obj = Point2(varargin) - if (nargin == 0), obj.self = new_Point2_(); end - if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Point2_dd(varargin{1},varargin{2}); end - if nargin ~= 13 && obj.self == 0, error('Point2 constructor failed'); end + if (nargin == 0), obj.self = new_Point2_(0,0); end + if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Point2_(0,1,varargin{1},varargin{2}); end + if nargin ==14, new_Point2_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Point2 constructor failed'); end end function delete(obj) - delete_Point2(obj); + if obj.self ~= 0 + new_Point2_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected/@Point2/argChar.cpp b/wrap/tests/expected/@Point2/argChar.cpp index 18548ee8f..e5fac45fe 100644 --- a/wrap/tests/expected/@Point2/argChar.cpp +++ b/wrap/tests/expected/@Point2/argChar.cpp @@ -1,10 +1,14 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("argChar",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - char a = unwrap< char >(in[1]); - self->argChar(a); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + char a = unwrap< char >(in[1]); + obj->argChar(a); } diff --git a/wrap/tests/expected/@Point2/argChar.m b/wrap/tests/expected/@Point2/argChar.m index 93880c5b1..6c935a1d6 100644 --- a/wrap/tests/expected/@Point2/argChar.m +++ b/wrap/tests/expected/@Point2/argChar.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.argChar(a) function result = argChar(obj,a) -% usage: obj.argChar(a) error('need to compile argChar.cpp'); end diff --git a/wrap/tests/expected/@Point2/argUChar.cpp b/wrap/tests/expected/@Point2/argUChar.cpp index bbaa65a8f..54c592915 100644 --- a/wrap/tests/expected/@Point2/argUChar.cpp +++ b/wrap/tests/expected/@Point2/argUChar.cpp @@ -1,10 +1,14 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("argUChar",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - unsigned char a = unwrap< unsigned char >(in[1]); - self->argUChar(a); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + unsigned char a = unwrap< unsigned char >(in[1]); + obj->argUChar(a); } diff --git a/wrap/tests/expected/@Point2/argUChar.m b/wrap/tests/expected/@Point2/argUChar.m index bb524b3f0..ea42a2b4f 100644 --- a/wrap/tests/expected/@Point2/argUChar.m +++ b/wrap/tests/expected/@Point2/argUChar.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.argUChar(a) function result = argUChar(obj,a) -% usage: obj.argUChar(a) error('need to compile argUChar.cpp'); end diff --git a/wrap/tests/expected/@Point2/dim.cpp b/wrap/tests/expected/@Point2/dim.cpp index 1349dc267..7e44ae075 100644 --- a/wrap/tests/expected/@Point2/dim.cpp +++ b/wrap/tests/expected/@Point2/dim.cpp @@ -1,10 +1,14 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("dim",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - int result = self->dim(); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + int result = obj->dim(); out[0] = wrap< int >(result); } diff --git a/wrap/tests/expected/@Point2/dim.m b/wrap/tests/expected/@Point2/dim.m index 84c368193..934e0b895 100644 --- a/wrap/tests/expected/@Point2/dim.m +++ b/wrap/tests/expected/@Point2/dim.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.dim() function result = dim(obj) -% usage: obj.dim() error('need to compile dim.cpp'); end diff --git a/wrap/tests/expected/@Point2/returnChar.cpp b/wrap/tests/expected/@Point2/returnChar.cpp index c5b67a018..43a537786 100644 --- a/wrap/tests/expected/@Point2/returnChar.cpp +++ b/wrap/tests/expected/@Point2/returnChar.cpp @@ -1,10 +1,14 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("returnChar",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - char result = self->returnChar(); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + char result = obj->returnChar(); out[0] = wrap< char >(result); } diff --git a/wrap/tests/expected/@Point2/returnChar.m b/wrap/tests/expected/@Point2/returnChar.m index a33718047..8c3ceee35 100644 --- a/wrap/tests/expected/@Point2/returnChar.m +++ b/wrap/tests/expected/@Point2/returnChar.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.returnChar() function result = returnChar(obj) -% usage: obj.returnChar() error('need to compile returnChar.cpp'); end diff --git a/wrap/tests/expected/@Point2/vectorConfusion.cpp b/wrap/tests/expected/@Point2/vectorConfusion.cpp index d992d1d94..e3aa4f0d6 100644 --- a/wrap/tests/expected/@Point2/vectorConfusion.cpp +++ b/wrap/tests/expected/@Point2/vectorConfusion.cpp @@ -1,10 +1,16 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr SharedVectorNotEigen; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("vectorConfusion",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - VectorNotEigen result = self->vectorConfusion(); - out[0] = wrap_shared_ptr(boost::make_shared< VectorNotEigen >(result),"VectorNotEigen"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + VectorNotEigen result = obj->vectorConfusion(); + SharedVectorNotEigen* ret = new SharedVectorNotEigen(new VectorNotEigen(result)); + out[0] = wrap_collect_shared_ptr(ret,"VectorNotEigen"); } diff --git a/wrap/tests/expected/@Point2/vectorConfusion.m b/wrap/tests/expected/@Point2/vectorConfusion.m index cc47b0dc7..9966c930d 100644 --- a/wrap/tests/expected/@Point2/vectorConfusion.m +++ b/wrap/tests/expected/@Point2/vectorConfusion.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.vectorConfusion() function result = vectorConfusion(obj) -% usage: obj.vectorConfusion() error('need to compile vectorConfusion.cpp'); end diff --git a/wrap/tests/expected/@Point2/x.cpp b/wrap/tests/expected/@Point2/x.cpp index 65e56cae5..8cebadb66 100644 --- a/wrap/tests/expected/@Point2/x.cpp +++ b/wrap/tests/expected/@Point2/x.cpp @@ -1,10 +1,14 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("x",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - double result = self->x(); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + double result = obj->x(); out[0] = wrap< double >(result); } diff --git a/wrap/tests/expected/@Point2/x.m b/wrap/tests/expected/@Point2/x.m index e1ebbd450..44f069872 100644 --- a/wrap/tests/expected/@Point2/x.m +++ b/wrap/tests/expected/@Point2/x.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.x() function result = x(obj) -% usage: obj.x() error('need to compile x.cpp'); end diff --git a/wrap/tests/expected/@Point2/y.cpp b/wrap/tests/expected/@Point2/y.cpp index f8e10dc5d..7e3650534 100644 --- a/wrap/tests/expected/@Point2/y.cpp +++ b/wrap/tests/expected/@Point2/y.cpp @@ -1,10 +1,14 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("y",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); - double result = self->y(); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + double result = obj->y(); out[0] = wrap< double >(result); } diff --git a/wrap/tests/expected/@Point2/y.m b/wrap/tests/expected/@Point2/y.m index d27fc8bf2..7971c1e33 100644 --- a/wrap/tests/expected/@Point2/y.m +++ b/wrap/tests/expected/@Point2/y.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.y() function result = y(obj) -% usage: obj.y() error('need to compile y.cpp'); end diff --git a/wrap/tests/expected/@Point3/Point3.m b/wrap/tests/expected/@Point3/Point3.m index 3e7a6fd65..b916293b7 100644 --- a/wrap/tests/expected/@Point3/Point3.m +++ b/wrap/tests/expected/@Point3/Point3.m @@ -5,11 +5,15 @@ classdef Point3 < handle end methods function obj = Point3(varargin) - if (nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')), obj.self = new_Point3_ddd(varargin{1},varargin{2},varargin{3}); end - if nargin ~= 13 && obj.self == 0, error('Point3 constructor failed'); end + if (nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')), obj.self = new_Point3_(0,0,varargin{1},varargin{2},varargin{3}); end + if nargin ==14, new_Point3_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Point3 constructor failed'); end end function delete(obj) - delete_Point3(obj); + if obj.self ~= 0 + new_Point3_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected/@Point3/norm.cpp b/wrap/tests/expected/@Point3/norm.cpp index 0c7ac2038..8f6a10b72 100644 --- a/wrap/tests/expected/@Point3/norm.cpp +++ b/wrap/tests/expected/@Point3/norm.cpp @@ -1,11 +1,15 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("norm",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Point3 >(in[0],"Point3"); - double result = self->norm(); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + double result = obj->norm(); out[0] = wrap< double >(result); } diff --git a/wrap/tests/expected/@Test/Test.m b/wrap/tests/expected/@Test/Test.m index b8e55381c..e4bd30221 100644 --- a/wrap/tests/expected/@Test/Test.m +++ b/wrap/tests/expected/@Test/Test.m @@ -5,12 +5,16 @@ classdef Test < handle end methods function obj = Test(varargin) - if (nargin == 0), obj.self = new_Test_(); end - if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Test_dM(varargin{1},varargin{2}); end - if nargin ~= 13 && obj.self == 0, error('Test constructor failed'); end + if (nargin == 0), obj.self = new_Test_(0,0); end + if (nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')), obj.self = new_Test_(0,1,varargin{1},varargin{2}); end + if nargin ==14, new_Test_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('Test constructor failed'); end end function delete(obj) - delete_Test(obj); + if obj.self ~= 0 + new_Test_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp b/wrap/tests/expected/@Test/arg_EigenConstRef.cpp index 09a5c6f62..848870d11 100644 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp +++ b/wrap/tests/expected/@Test/arg_EigenConstRef.cpp @@ -1,11 +1,15 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("arg_EigenConstRef",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix"); - self->arg_EigenConstRef(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + Matrix& value = *unwrap_shared_ptr< Matrix >(in[1], "Matrix"); + obj->arg_EigenConstRef(value); } diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.m b/wrap/tests/expected/@Test/arg_EigenConstRef.m index 9e6c04c5a..c348014c1 100644 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.m +++ b/wrap/tests/expected/@Test/arg_EigenConstRef.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.arg_EigenConstRef(value) function result = arg_EigenConstRef(obj,value) -% usage: obj.arg_EigenConstRef(value) error('need to compile arg_EigenConstRef.cpp'); end diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.cpp b/wrap/tests/expected/@Test/create_MixedPtrs.cpp index 81bcdc5d8..1776c855b 100644 --- a/wrap/tests/expected/@Test/create_MixedPtrs.cpp +++ b/wrap/tests/expected/@Test/create_MixedPtrs.cpp @@ -1,12 +1,20 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_MixedPtrs",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - pair< Test, boost::shared_ptr > result = self->create_MixedPtrs(); - out[0] = wrap_shared_ptr(boost::make_shared< Test >(result.first),"Test"); - out[1] = wrap_shared_ptr(result.second,"Test"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + pair< Test, SharedTest > result = obj->create_MixedPtrs(); + SharedTest* ret = new SharedTest(new Test(result.first)); + out[0] = wrap_collect_shared_ptr(ret,"Test"); + SharedTest* ret = new SharedTest(result.second); + out[1] = wrap_collect_shared_ptr(ret,"Test"); } diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.m b/wrap/tests/expected/@Test/create_MixedPtrs.m index bd1927fba..38a9f1d7e 100644 --- a/wrap/tests/expected/@Test/create_MixedPtrs.m +++ b/wrap/tests/expected/@Test/create_MixedPtrs.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% [first,second] = obj.create_MixedPtrs() function [first,second] = create_MixedPtrs(obj) -% usage: obj.create_MixedPtrs() error('need to compile create_MixedPtrs.cpp'); end diff --git a/wrap/tests/expected/@Test/create_ptrs.cpp b/wrap/tests/expected/@Test/create_ptrs.cpp index 830d62a12..ab4261d5c 100644 --- a/wrap/tests/expected/@Test/create_ptrs.cpp +++ b/wrap/tests/expected/@Test/create_ptrs.cpp @@ -1,12 +1,20 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_ptrs",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - pair< boost::shared_ptr, boost::shared_ptr > result = self->create_ptrs(); - out[0] = wrap_shared_ptr(result.first,"Test"); - out[1] = wrap_shared_ptr(result.second,"Test"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + pair< SharedTest, SharedTest > result = obj->create_ptrs(); + SharedTest* ret = new SharedTest(result.first); + out[0] = wrap_collect_shared_ptr(ret,"Test"); + SharedTest* ret = new SharedTest(result.second); + out[1] = wrap_collect_shared_ptr(ret,"Test"); } diff --git a/wrap/tests/expected/@Test/create_ptrs.m b/wrap/tests/expected/@Test/create_ptrs.m index e380f1829..80c6781dc 100644 --- a/wrap/tests/expected/@Test/create_ptrs.m +++ b/wrap/tests/expected/@Test/create_ptrs.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% [first,second] = obj.create_ptrs() function [first,second] = create_ptrs(obj) -% usage: obj.create_ptrs() error('need to compile create_ptrs.cpp'); end diff --git a/wrap/tests/expected/@Test/print.cpp b/wrap/tests/expected/@Test/print.cpp index 1d259f2e8..e3a758182 100644 --- a/wrap/tests/expected/@Test/print.cpp +++ b/wrap/tests/expected/@Test/print.cpp @@ -1,10 +1,14 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("print",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - self->print(); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + obj->print(); } diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.cpp b/wrap/tests/expected/@Test/return_Point2Ptr.cpp index e6990198e..b3e61d37a 100644 --- a/wrap/tests/expected/@Test/return_Point2Ptr.cpp +++ b/wrap/tests/expected/@Test/return_Point2Ptr.cpp @@ -1,12 +1,18 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr SharedPoint2; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Point2Ptr",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - bool value = unwrap< bool >(in[1]); - boost::shared_ptr result = self->return_Point2Ptr(value); - out[0] = wrap_shared_ptr(result,"Point2"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + bool value = unwrap< bool >(in[1]); + SharedPoint2 result = obj->return_Point2Ptr(value); + SharedPoint2* ret = new SharedPoint2(result); + out[0] = wrap_collect_shared_ptr(ret,"Point2"); } diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.m b/wrap/tests/expected/@Test/return_Point2Ptr.m index 26fd146a2..84e586bc7 100644 --- a/wrap/tests/expected/@Test/return_Point2Ptr.m +++ b/wrap/tests/expected/@Test/return_Point2Ptr.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_Point2Ptr(value) function result = return_Point2Ptr(obj,value) -% usage: obj.return_Point2Ptr(value) error('need to compile return_Point2Ptr.cpp'); end diff --git a/wrap/tests/expected/@Test/return_Test.cpp b/wrap/tests/expected/@Test/return_Test.cpp index 63e9f5a3b..cd0f1ef10 100644 --- a/wrap/tests/expected/@Test/return_Test.cpp +++ b/wrap/tests/expected/@Test/return_Test.cpp @@ -1,12 +1,18 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Test",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - Test result = self->return_Test(value); - out[0] = wrap_shared_ptr(boost::make_shared< Test >(result),"Test"); + Test result = obj->return_Test(value); + SharedTest* ret = new SharedTest(new Test(result)); + out[0] = wrap_collect_shared_ptr(ret,"Test"); } diff --git a/wrap/tests/expected/@Test/return_Test.m b/wrap/tests/expected/@Test/return_Test.m index f31dc3192..d1a2e440c 100644 --- a/wrap/tests/expected/@Test/return_Test.m +++ b/wrap/tests/expected/@Test/return_Test.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_Test(value) function result = return_Test(obj,value) -% usage: obj.return_Test(value) error('need to compile return_Test.cpp'); end diff --git a/wrap/tests/expected/@Test/return_TestPtr.cpp b/wrap/tests/expected/@Test/return_TestPtr.cpp index 3c053791d..2957de8f3 100644 --- a/wrap/tests/expected/@Test/return_TestPtr.cpp +++ b/wrap/tests/expected/@Test/return_TestPtr.cpp @@ -1,12 +1,18 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_TestPtr",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "Test"); - boost::shared_ptr result = self->return_TestPtr(value); - out[0] = wrap_shared_ptr(result,"Test"); + SharedTest result = obj->return_TestPtr(value); + SharedTest* ret = new SharedTest(result); + out[0] = wrap_collect_shared_ptr(ret,"Test"); } diff --git a/wrap/tests/expected/@Test/return_TestPtr.m b/wrap/tests/expected/@Test/return_TestPtr.m index e69149551..937c85fcc 100644 --- a/wrap/tests/expected/@Test/return_TestPtr.m +++ b/wrap/tests/expected/@Test/return_TestPtr.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_TestPtr(value) function result = return_TestPtr(obj,value) -% usage: obj.return_TestPtr(value) error('need to compile return_TestPtr.cpp'); end diff --git a/wrap/tests/expected/@Test/return_bool.cpp b/wrap/tests/expected/@Test/return_bool.cpp index 92612a279..c9c792934 100644 --- a/wrap/tests/expected/@Test/return_bool.cpp +++ b/wrap/tests/expected/@Test/return_bool.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_bool",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - bool value = unwrap< bool >(in[1]); - bool result = self->return_bool(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + bool value = unwrap< bool >(in[1]); + bool result = obj->return_bool(value); out[0] = wrap< bool >(result); } diff --git a/wrap/tests/expected/@Test/return_bool.m b/wrap/tests/expected/@Test/return_bool.m index a0c5a0b17..358cb9750 100644 --- a/wrap/tests/expected/@Test/return_bool.m +++ b/wrap/tests/expected/@Test/return_bool.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_bool(value) function result = return_bool(obj,value) -% usage: obj.return_bool(value) error('need to compile return_bool.cpp'); end diff --git a/wrap/tests/expected/@Test/return_double.cpp b/wrap/tests/expected/@Test/return_double.cpp index e167a16c0..4e6612278 100644 --- a/wrap/tests/expected/@Test/return_double.cpp +++ b/wrap/tests/expected/@Test/return_double.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_double",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - double value = unwrap< double >(in[1]); - double result = self->return_double(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + double value = unwrap< double >(in[1]); + double result = obj->return_double(value); out[0] = wrap< double >(result); } diff --git a/wrap/tests/expected/@Test/return_double.m b/wrap/tests/expected/@Test/return_double.m index dd181ff0b..681371f39 100644 --- a/wrap/tests/expected/@Test/return_double.m +++ b/wrap/tests/expected/@Test/return_double.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_double(value) function result = return_double(obj,value) -% usage: obj.return_double(value) error('need to compile return_double.cpp'); end diff --git a/wrap/tests/expected/@Test/return_field.cpp b/wrap/tests/expected/@Test/return_field.cpp index 838bab0a4..43507f4d7 100644 --- a/wrap/tests/expected/@Test/return_field.cpp +++ b/wrap/tests/expected/@Test/return_field.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_field",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Test& t = *unwrap_shared_ptr< Test >(in[1], "Test"); - bool result = self->return_field(t); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + Test& t = *unwrap_shared_ptr< Test >(in[1], "Test"); + bool result = obj->return_field(t); out[0] = wrap< bool >(result); } diff --git a/wrap/tests/expected/@Test/return_field.m b/wrap/tests/expected/@Test/return_field.m index bc4223671..e2894c381 100644 --- a/wrap/tests/expected/@Test/return_field.m +++ b/wrap/tests/expected/@Test/return_field.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_field(t) function result = return_field(obj,t) -% usage: obj.return_field(t) error('need to compile return_field.cpp'); end diff --git a/wrap/tests/expected/@Test/return_int.cpp b/wrap/tests/expected/@Test/return_int.cpp index 4cdaf5abc..2a27ac73a 100644 --- a/wrap/tests/expected/@Test/return_int.cpp +++ b/wrap/tests/expected/@Test/return_int.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_int",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - int value = unwrap< int >(in[1]); - int result = self->return_int(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + int value = unwrap< int >(in[1]); + int result = obj->return_int(value); out[0] = wrap< int >(result); } diff --git a/wrap/tests/expected/@Test/return_int.m b/wrap/tests/expected/@Test/return_int.m index 4984557e6..779e9feb2 100644 --- a/wrap/tests/expected/@Test/return_int.m +++ b/wrap/tests/expected/@Test/return_int.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_int(value) function result = return_int(obj,value) -% usage: obj.return_int(value) error('need to compile return_int.cpp'); end diff --git a/wrap/tests/expected/@Test/return_matrix1.cpp b/wrap/tests/expected/@Test/return_matrix1.cpp index f7fb72040..d4c66622b 100644 --- a/wrap/tests/expected/@Test/return_matrix1.cpp +++ b/wrap/tests/expected/@Test/return_matrix1.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_matrix1",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Matrix value = unwrap< Matrix >(in[1]); - Matrix result = self->return_matrix1(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + Matrix value = unwrap< Matrix >(in[1]); + Matrix result = obj->return_matrix1(value); out[0] = wrap< Matrix >(result); } diff --git a/wrap/tests/expected/@Test/return_matrix1.m b/wrap/tests/expected/@Test/return_matrix1.m index 66dd1886f..d6d9791f9 100644 --- a/wrap/tests/expected/@Test/return_matrix1.m +++ b/wrap/tests/expected/@Test/return_matrix1.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_matrix1(value) function result = return_matrix1(obj,value) -% usage: obj.return_matrix1(value) error('need to compile return_matrix1.cpp'); end diff --git a/wrap/tests/expected/@Test/return_matrix2.cpp b/wrap/tests/expected/@Test/return_matrix2.cpp index f8b6823fa..a40fa79cf 100644 --- a/wrap/tests/expected/@Test/return_matrix2.cpp +++ b/wrap/tests/expected/@Test/return_matrix2.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_matrix2",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Matrix value = unwrap< Matrix >(in[1]); - Matrix result = self->return_matrix2(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + Matrix value = unwrap< Matrix >(in[1]); + Matrix result = obj->return_matrix2(value); out[0] = wrap< Matrix >(result); } diff --git a/wrap/tests/expected/@Test/return_matrix2.m b/wrap/tests/expected/@Test/return_matrix2.m index 5a0359862..584b365b8 100644 --- a/wrap/tests/expected/@Test/return_matrix2.m +++ b/wrap/tests/expected/@Test/return_matrix2.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_matrix2(value) function result = return_matrix2(obj,value) -% usage: obj.return_matrix2(value) error('need to compile return_matrix2.cpp'); end diff --git a/wrap/tests/expected/@Test/return_pair.cpp b/wrap/tests/expected/@Test/return_pair.cpp index 54b3f6522..7d715644c 100644 --- a/wrap/tests/expected/@Test/return_pair.cpp +++ b/wrap/tests/expected/@Test/return_pair.cpp @@ -1,14 +1,18 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_pair",nargout,nargin-1,2); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Vector v = unwrap< Vector >(in[1]); - Matrix A = unwrap< Matrix >(in[2]); - pair< Vector, Matrix > result = self->return_pair(v,A); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + Vector v = unwrap< Vector >(in[1]); + Matrix A = unwrap< Matrix >(in[2]); + pair< Vector, Matrix > result = obj->return_pair(v,A); out[0] = wrap< Vector >(result.first); out[1] = wrap< Matrix >(result.second); } diff --git a/wrap/tests/expected/@Test/return_pair.m b/wrap/tests/expected/@Test/return_pair.m index 611dd3434..2e892210c 100644 --- a/wrap/tests/expected/@Test/return_pair.m +++ b/wrap/tests/expected/@Test/return_pair.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% [first,second] = obj.return_pair(v,A) function [first,second] = return_pair(obj,v,A) -% usage: obj.return_pair(v,A) error('need to compile return_pair.cpp'); end diff --git a/wrap/tests/expected/@Test/return_ptrs.cpp b/wrap/tests/expected/@Test/return_ptrs.cpp index eea94ca3c..8a5f9a0ce 100644 --- a/wrap/tests/expected/@Test/return_ptrs.cpp +++ b/wrap/tests/expected/@Test/return_ptrs.cpp @@ -1,14 +1,22 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr SharedTest; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_ptrs",nargout,nargin-1,2); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "Test"); boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "Test"); - pair< boost::shared_ptr, boost::shared_ptr > result = self->return_ptrs(p1,p2); - out[0] = wrap_shared_ptr(result.first,"Test"); - out[1] = wrap_shared_ptr(result.second,"Test"); + pair< SharedTest, SharedTest > result = obj->return_ptrs(p1,p2); + SharedTest* ret = new SharedTest(result.first); + out[0] = wrap_collect_shared_ptr(ret,"Test"); + SharedTest* ret = new SharedTest(result.second); + out[1] = wrap_collect_shared_ptr(ret,"Test"); } diff --git a/wrap/tests/expected/@Test/return_ptrs.m b/wrap/tests/expected/@Test/return_ptrs.m index 18d69ac92..a7af4b73c 100644 --- a/wrap/tests/expected/@Test/return_ptrs.m +++ b/wrap/tests/expected/@Test/return_ptrs.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% [first,second] = obj.return_ptrs(p1,p2) function [first,second] = return_ptrs(obj,p1,p2) -% usage: obj.return_ptrs(p1,p2) error('need to compile return_ptrs.cpp'); end diff --git a/wrap/tests/expected/@Test/return_size_t.cpp b/wrap/tests/expected/@Test/return_size_t.cpp index 901c5c9bd..f18680d0d 100644 --- a/wrap/tests/expected/@Test/return_size_t.cpp +++ b/wrap/tests/expected/@Test/return_size_t.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_size_t",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - size_t value = unwrap< size_t >(in[1]); - size_t result = self->return_size_t(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + size_t value = unwrap< size_t >(in[1]); + size_t result = obj->return_size_t(value); out[0] = wrap< size_t >(result); } diff --git a/wrap/tests/expected/@Test/return_size_t.m b/wrap/tests/expected/@Test/return_size_t.m index 143f04d24..2fae64028 100644 --- a/wrap/tests/expected/@Test/return_size_t.m +++ b/wrap/tests/expected/@Test/return_size_t.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_size_t(value) function result = return_size_t(obj,value) -% usage: obj.return_size_t(value) error('need to compile return_size_t.cpp'); end diff --git a/wrap/tests/expected/@Test/return_string.cpp b/wrap/tests/expected/@Test/return_string.cpp index 778e07522..013814241 100644 --- a/wrap/tests/expected/@Test/return_string.cpp +++ b/wrap/tests/expected/@Test/return_string.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_string",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - string value = unwrap< string >(in[1]); - string result = self->return_string(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + string value = unwrap< string >(in[1]); + string result = obj->return_string(value); out[0] = wrap< string >(result); } diff --git a/wrap/tests/expected/@Test/return_string.m b/wrap/tests/expected/@Test/return_string.m index f1eab8661..67fb5f10d 100644 --- a/wrap/tests/expected/@Test/return_string.m +++ b/wrap/tests/expected/@Test/return_string.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_string(value) function result = return_string(obj,value) -% usage: obj.return_string(value) error('need to compile return_string.cpp'); end diff --git a/wrap/tests/expected/@Test/return_vector1.cpp b/wrap/tests/expected/@Test/return_vector1.cpp index 5e8aed397..593cd20bd 100644 --- a/wrap/tests/expected/@Test/return_vector1.cpp +++ b/wrap/tests/expected/@Test/return_vector1.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_vector1",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Vector value = unwrap< Vector >(in[1]); - Vector result = self->return_vector1(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + Vector value = unwrap< Vector >(in[1]); + Vector result = obj->return_vector1(value); out[0] = wrap< Vector >(result); } diff --git a/wrap/tests/expected/@Test/return_vector1.m b/wrap/tests/expected/@Test/return_vector1.m index 316ca4cf2..461c51618 100644 --- a/wrap/tests/expected/@Test/return_vector1.m +++ b/wrap/tests/expected/@Test/return_vector1.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_vector1(value) function result = return_vector1(obj,value) -% usage: obj.return_vector1(value) error('need to compile return_vector1.cpp'); end diff --git a/wrap/tests/expected/@Test/return_vector2.cpp b/wrap/tests/expected/@Test/return_vector2.cpp index 4c3242f2e..1be4a614a 100644 --- a/wrap/tests/expected/@Test/return_vector2.cpp +++ b/wrap/tests/expected/@Test/return_vector2.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_vector2",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< Test >(in[0],"Test"); - Vector value = unwrap< Vector >(in[1]); - Vector result = self->return_vector2(value); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + Vector value = unwrap< Vector >(in[1]); + Vector result = obj->return_vector2(value); out[0] = wrap< Vector >(result); } diff --git a/wrap/tests/expected/@Test/return_vector2.m b/wrap/tests/expected/@Test/return_vector2.m index 6426e0ce9..f3c77dd85 100644 --- a/wrap/tests/expected/@Test/return_vector2.m +++ b/wrap/tests/expected/@Test/return_vector2.m @@ -1,5 +1,4 @@ -% automatically generated by wrap +% result = obj.return_vector2(value) function result = return_vector2(obj,value) -% usage: obj.return_vector2(value) error('need to compile return_vector2.cpp'); end diff --git a/wrap/tests/expected/Makefile b/wrap/tests/expected/Makefile index a8959757b..57a606790 100644 --- a/wrap/tests/expected/Makefile +++ b/wrap/tests/expected/Makefile @@ -2,95 +2,86 @@ MEX = mex MEXENDING = mexa64 +PATH_TO_WRAP = /not_really_a_real_path/borg/gtsam/wrap mex_flags = -O5 all: Point2 Point3 Test # Point2 -new_Point2_.$(MEXENDING): new_Point2_.cpp +new_Point2_.$(MEXENDING): new_Point2_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_Point2_.cpp -output new_Point2_ -new_Point2_dd.$(MEXENDING): new_Point2_dd.cpp - $(MEX) $(mex_flags) new_Point2_dd.cpp -output new_Point2_dd -delete_Point2.$(MEXENDING): delete_Point2.cpp - $(MEX) $(mex_flags) delete_Point2.cpp -output delete_Point2 -@Point2/x.$(MEXENDING): @Point2/x.cpp +@Point2/x.$(MEXENDING): @Point2/x.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point2/x.cpp -output @Point2/x -@Point2/y.$(MEXENDING): @Point2/y.cpp +@Point2/y.$(MEXENDING): @Point2/y.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point2/y.cpp -output @Point2/y -@Point2/dim.$(MEXENDING): @Point2/dim.cpp +@Point2/dim.$(MEXENDING): @Point2/dim.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point2/dim.cpp -output @Point2/dim -@Point2/returnChar.$(MEXENDING): @Point2/returnChar.cpp +@Point2/returnChar.$(MEXENDING): @Point2/returnChar.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point2/returnChar.cpp -output @Point2/returnChar -@Point2/argChar.$(MEXENDING): @Point2/argChar.cpp +@Point2/argChar.$(MEXENDING): @Point2/argChar.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point2/argChar.cpp -output @Point2/argChar -@Point2/argUChar.$(MEXENDING): @Point2/argUChar.cpp +@Point2/argUChar.$(MEXENDING): @Point2/argUChar.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point2/argUChar.cpp -output @Point2/argUChar -@Point2/vectorConfusion.$(MEXENDING): @Point2/vectorConfusion.cpp +@Point2/vectorConfusion.$(MEXENDING): @Point2/vectorConfusion.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point2/vectorConfusion.cpp -output @Point2/vectorConfusion -Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) delete_Point2.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) @Point2/returnChar.$(MEXENDING) @Point2/argChar.$(MEXENDING) @Point2/argUChar.$(MEXENDING) @Point2/vectorConfusion.$(MEXENDING) +Point2: new_Point2_.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING) @Point2/returnChar.$(MEXENDING) @Point2/argChar.$(MEXENDING) @Point2/argUChar.$(MEXENDING) @Point2/vectorConfusion.$(MEXENDING) # Point3 -new_Point3_ddd.$(MEXENDING): new_Point3_ddd.cpp - $(MEX) $(mex_flags) new_Point3_ddd.cpp -output new_Point3_ddd -delete_Point3.$(MEXENDING): delete_Point3.cpp - $(MEX) $(mex_flags) delete_Point3.cpp -output delete_Point3 -Point3_staticFunction.$(MEXENDING): Point3_staticFunction.cpp +new_Point3_.$(MEXENDING): new_Point3_.cpp $(PATH_TO_WRAP)/matlab.h + $(MEX) $(mex_flags) new_Point3_.cpp -output new_Point3_ +Point3_staticFunction.$(MEXENDING): Point3_staticFunction.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) Point3_staticFunction.cpp -output Point3_staticFunction -Point3_StaticFunctionRet.$(MEXENDING): Point3_StaticFunctionRet.cpp +Point3_StaticFunctionRet.$(MEXENDING): Point3_StaticFunctionRet.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) Point3_StaticFunctionRet.cpp -output Point3_StaticFunctionRet -@Point3/norm.$(MEXENDING): @Point3/norm.cpp +@Point3/norm.$(MEXENDING): @Point3/norm.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Point3/norm.cpp -output @Point3/norm -Point3: new_Point3_ddd.$(MEXENDING) delete_Point3.$(MEXENDING) Point3_staticFunction.$(MEXENDING) Point3_StaticFunctionRet.$(MEXENDING) @Point3/norm.$(MEXENDING) +Point3: new_Point3_.$(MEXENDING) Point3_staticFunction.$(MEXENDING) Point3_StaticFunctionRet.$(MEXENDING) @Point3/norm.$(MEXENDING) # Test -new_Test_.$(MEXENDING): new_Test_.cpp +new_Test_.$(MEXENDING): new_Test_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_Test_.cpp -output new_Test_ -new_Test_dM.$(MEXENDING): new_Test_dM.cpp - $(MEX) $(mex_flags) new_Test_dM.cpp -output new_Test_dM -delete_Test.$(MEXENDING): delete_Test.cpp - $(MEX) $(mex_flags) delete_Test.cpp -output delete_Test -@Test/return_pair.$(MEXENDING): @Test/return_pair.cpp +@Test/return_pair.$(MEXENDING): @Test/return_pair.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_pair.cpp -output @Test/return_pair -@Test/return_bool.$(MEXENDING): @Test/return_bool.cpp +@Test/return_bool.$(MEXENDING): @Test/return_bool.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_bool.cpp -output @Test/return_bool -@Test/return_size_t.$(MEXENDING): @Test/return_size_t.cpp +@Test/return_size_t.$(MEXENDING): @Test/return_size_t.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_size_t.cpp -output @Test/return_size_t -@Test/return_int.$(MEXENDING): @Test/return_int.cpp +@Test/return_int.$(MEXENDING): @Test/return_int.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_int.cpp -output @Test/return_int -@Test/return_double.$(MEXENDING): @Test/return_double.cpp +@Test/return_double.$(MEXENDING): @Test/return_double.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_double.cpp -output @Test/return_double -@Test/return_string.$(MEXENDING): @Test/return_string.cpp +@Test/return_string.$(MEXENDING): @Test/return_string.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_string.cpp -output @Test/return_string -@Test/return_vector1.$(MEXENDING): @Test/return_vector1.cpp +@Test/return_vector1.$(MEXENDING): @Test/return_vector1.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_vector1.cpp -output @Test/return_vector1 -@Test/return_matrix1.$(MEXENDING): @Test/return_matrix1.cpp +@Test/return_matrix1.$(MEXENDING): @Test/return_matrix1.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_matrix1.cpp -output @Test/return_matrix1 -@Test/return_vector2.$(MEXENDING): @Test/return_vector2.cpp +@Test/return_vector2.$(MEXENDING): @Test/return_vector2.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_vector2.cpp -output @Test/return_vector2 -@Test/return_matrix2.$(MEXENDING): @Test/return_matrix2.cpp +@Test/return_matrix2.$(MEXENDING): @Test/return_matrix2.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_matrix2.cpp -output @Test/return_matrix2 -@Test/arg_EigenConstRef.$(MEXENDING): @Test/arg_EigenConstRef.cpp +@Test/arg_EigenConstRef.$(MEXENDING): @Test/arg_EigenConstRef.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/arg_EigenConstRef.cpp -output @Test/arg_EigenConstRef -@Test/return_field.$(MEXENDING): @Test/return_field.cpp +@Test/return_field.$(MEXENDING): @Test/return_field.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_field.cpp -output @Test/return_field -@Test/return_TestPtr.$(MEXENDING): @Test/return_TestPtr.cpp +@Test/return_TestPtr.$(MEXENDING): @Test/return_TestPtr.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_TestPtr.cpp -output @Test/return_TestPtr -@Test/return_Test.$(MEXENDING): @Test/return_Test.cpp +@Test/return_Test.$(MEXENDING): @Test/return_Test.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_Test.cpp -output @Test/return_Test -@Test/return_Point2Ptr.$(MEXENDING): @Test/return_Point2Ptr.cpp +@Test/return_Point2Ptr.$(MEXENDING): @Test/return_Point2Ptr.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_Point2Ptr.cpp -output @Test/return_Point2Ptr -@Test/create_ptrs.$(MEXENDING): @Test/create_ptrs.cpp +@Test/create_ptrs.$(MEXENDING): @Test/create_ptrs.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/create_ptrs.cpp -output @Test/create_ptrs -@Test/create_MixedPtrs.$(MEXENDING): @Test/create_MixedPtrs.cpp +@Test/create_MixedPtrs.$(MEXENDING): @Test/create_MixedPtrs.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/create_MixedPtrs.cpp -output @Test/create_MixedPtrs -@Test/return_ptrs.$(MEXENDING): @Test/return_ptrs.cpp +@Test/return_ptrs.$(MEXENDING): @Test/return_ptrs.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/return_ptrs.cpp -output @Test/return_ptrs -@Test/print.$(MEXENDING): @Test/print.cpp +@Test/print.$(MEXENDING): @Test/print.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @Test/print.cpp -output @Test/print -Test: new_Test_.$(MEXENDING) new_Test_dM.$(MEXENDING) delete_Test.$(MEXENDING) @Test/return_pair.$(MEXENDING) @Test/return_bool.$(MEXENDING) @Test/return_size_t.$(MEXENDING) @Test/return_int.$(MEXENDING) @Test/return_double.$(MEXENDING) @Test/return_string.$(MEXENDING) @Test/return_vector1.$(MEXENDING) @Test/return_matrix1.$(MEXENDING) @Test/return_vector2.$(MEXENDING) @Test/return_matrix2.$(MEXENDING) @Test/arg_EigenConstRef.$(MEXENDING) @Test/return_field.$(MEXENDING) @Test/return_TestPtr.$(MEXENDING) @Test/return_Test.$(MEXENDING) @Test/return_Point2Ptr.$(MEXENDING) @Test/create_ptrs.$(MEXENDING) @Test/create_MixedPtrs.$(MEXENDING) @Test/return_ptrs.$(MEXENDING) @Test/print.$(MEXENDING) +Test: new_Test_.$(MEXENDING) @Test/return_pair.$(MEXENDING) @Test/return_bool.$(MEXENDING) @Test/return_size_t.$(MEXENDING) @Test/return_int.$(MEXENDING) @Test/return_double.$(MEXENDING) @Test/return_string.$(MEXENDING) @Test/return_vector1.$(MEXENDING) @Test/return_matrix1.$(MEXENDING) @Test/return_vector2.$(MEXENDING) @Test/return_matrix2.$(MEXENDING) @Test/arg_EigenConstRef.$(MEXENDING) @Test/return_field.$(MEXENDING) @Test/return_TestPtr.$(MEXENDING) @Test/return_Test.$(MEXENDING) @Test/return_Point2Ptr.$(MEXENDING) @Test/create_ptrs.$(MEXENDING) @Test/create_MixedPtrs.$(MEXENDING) @Test/return_ptrs.$(MEXENDING) @Test/print.$(MEXENDING) diff --git a/wrap/tests/expected/Point3_StaticFunctionRet.cpp b/wrap/tests/expected/Point3_StaticFunctionRet.cpp index 652d8713e..49d15f4fa 100644 --- a/wrap/tests/expected/Point3_StaticFunctionRet.cpp +++ b/wrap/tests/expected/Point3_StaticFunctionRet.cpp @@ -1,11 +1,15 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr SharedPoint3; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("Point3_StaticFunctionRet",nargout,nargin,1); - double z = unwrap< double >(in[0]); + double z = unwrap< double >(in[0]); Point3 result = Point3::StaticFunctionRet(z); - out[0] = wrap_shared_ptr(boost::make_shared< Point3 >(result),"Point3"); + SharedPoint3* ret = new SharedPoint3(new Point3(result)); + out[0] = wrap_collect_shared_ptr(ret,"Point3"); } diff --git a/wrap/tests/expected/Point3_staticFunction.cpp b/wrap/tests/expected/Point3_staticFunction.cpp index 6adfdbe5a..e29670b9a 100644 --- a/wrap/tests/expected/Point3_staticFunction.cpp +++ b/wrap/tests/expected/Point3_staticFunction.cpp @@ -1,7 +1,10 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shareddouble; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("Point3_staticFunction",nargout,nargin,0); diff --git a/wrap/tests/expected/delete_Point2.cpp b/wrap/tests/expected/delete_Point2.cpp deleted file mode 100644 index bd8bd12eb..000000000 --- a/wrap/tests/expected/delete_Point2.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_Point2",nargout,nargin,1); - delete_shared_ptr< Point2 >(in[0],"Point2"); -} diff --git a/wrap/tests/expected/delete_Point2.m b/wrap/tests/expected/delete_Point2.m deleted file mode 100644 index c6c623bec..000000000 --- a/wrap/tests/expected/delete_Point2.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_Point2(obj) - error('need to compile delete_Point2.cpp'); -end diff --git a/wrap/tests/expected/delete_Point3.cpp b/wrap/tests/expected/delete_Point3.cpp deleted file mode 100644 index 9836bb25e..000000000 --- a/wrap/tests/expected/delete_Point3.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_Point3",nargout,nargin,1); - delete_shared_ptr< Point3 >(in[0],"Point3"); -} diff --git a/wrap/tests/expected/delete_Point3.m b/wrap/tests/expected/delete_Point3.m deleted file mode 100644 index b52b898cf..000000000 --- a/wrap/tests/expected/delete_Point3.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_Point3(obj) - error('need to compile delete_Point3.cpp'); -end diff --git a/wrap/tests/expected/delete_Test.cpp b/wrap/tests/expected/delete_Test.cpp deleted file mode 100644 index 6a22cc327..000000000 --- a/wrap/tests/expected/delete_Test.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_Test",nargout,nargin,1); - delete_shared_ptr< Test >(in[0],"Test"); -} diff --git a/wrap/tests/expected/delete_Test.m b/wrap/tests/expected/delete_Test.m deleted file mode 100644 index 21ec790a3..000000000 --- a/wrap/tests/expected/delete_Test.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_Test(obj) - error('need to compile delete_Test.cpp'); -end diff --git a/wrap/tests/expected/make_geometry.m b/wrap/tests/expected/make_geometry.m index 2858f2994..32f81871d 100644 --- a/wrap/tests/expected/make_geometry.m +++ b/wrap/tests/expected/make_geometry.m @@ -10,8 +10,6 @@ addpath(toolboxpath); %% Point2 cd(toolboxpath) mex -O5 new_Point2_.cpp -mex -O5 new_Point2_dd.cpp -mex -O5 delete_Point2.cpp cd @Point2 mex -O5 x.cpp @@ -24,8 +22,7 @@ mex -O5 vectorConfusion.cpp %% Point3 cd(toolboxpath) -mex -O5 new_Point3_ddd.cpp -mex -O5 delete_Point3.cpp +mex -O5 new_Point3_.cpp mex -O5 Point3_staticFunction.cpp mex -O5 Point3_StaticFunctionRet.cpp @@ -35,8 +32,6 @@ mex -O5 norm.cpp %% Test cd(toolboxpath) mex -O5 new_Test_.cpp -mex -O5 new_Test_dM.cpp -mex -O5 delete_Test.cpp cd @Test mex -O5 return_pair.cpp diff --git a/wrap/tests/expected/new_Point2_.cpp b/wrap/tests/expected/new_Point2_.cpp index a88076efb..11b2821a3 100644 --- a/wrap/tests/expected/new_Point2_.cpp +++ b/wrap/tests/expected/new_Point2_.cpp @@ -1,9 +1,47 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_Point2_",nargout,nargin,0); - Point2* self = new Point2(); - out[0] = wrap_constructed(self,"Point2"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new Point2()); + } + if(nc == 1) { + double x = unwrap< double >(in[2]); + double y = unwrap< double >(in[3]); + self = new Shared(new Point2(x,y)); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected/new_Point2_.m b/wrap/tests/expected/new_Point2_.m index b0b655b5e..b5fdcff15 100644 --- a/wrap/tests/expected/new_Point2_.m +++ b/wrap/tests/expected/new_Point2_.m @@ -1,4 +1,4 @@ % automatically generated by wrap -function result = new_Point2_(obj) +function result = new_Point2_(obj,x,y) error('need to compile new_Point2_.cpp'); end diff --git a/wrap/tests/expected/new_Point2_dd.cpp b/wrap/tests/expected/new_Point2_dd.cpp deleted file mode 100644 index 7c7f062b7..000000000 --- a/wrap/tests/expected/new_Point2_dd.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Point2_dd",nargout,nargin,2); - double x = unwrap< double >(in[0]); - double y = unwrap< double >(in[1]); - Point2* self = new Point2(x,y); - out[0] = wrap_constructed(self,"Point2"); -} diff --git a/wrap/tests/expected/new_Point2_dd.m b/wrap/tests/expected/new_Point2_dd.m deleted file mode 100644 index 4a769ce30..000000000 --- a/wrap/tests/expected/new_Point2_dd.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Point2_dd(obj,x,y) - error('need to compile new_Point2_dd.cpp'); -end diff --git a/wrap/tests/expected/new_Point3_.cpp b/wrap/tests/expected/new_Point3_.cpp new file mode 100644 index 000000000..01316da5a --- /dev/null +++ b/wrap/tests/expected/new_Point3_.cpp @@ -0,0 +1,46 @@ +// automatically generated by wrap +#include +#include +#include +using namespace geometry; +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + double x = unwrap< double >(in[2]); + double y = unwrap< double >(in[3]); + double z = unwrap< double >(in[4]); + self = new Shared(new Point3(x,y,z)); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } +} diff --git a/wrap/tests/expected/new_Point3_.m b/wrap/tests/expected/new_Point3_.m new file mode 100644 index 000000000..f306af227 --- /dev/null +++ b/wrap/tests/expected/new_Point3_.m @@ -0,0 +1,4 @@ +% automatically generated by wrap +function result = new_Point3_(obj,x,y,z) + error('need to compile new_Point3_.cpp'); +end diff --git a/wrap/tests/expected/new_Point3_ddd.cpp b/wrap/tests/expected/new_Point3_ddd.cpp deleted file mode 100644 index aa45dc71c..000000000 --- a/wrap/tests/expected/new_Point3_ddd.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Point3_ddd",nargout,nargin,3); - double x = unwrap< double >(in[0]); - double y = unwrap< double >(in[1]); - double z = unwrap< double >(in[2]); - Point3* self = new Point3(x,y,z); - out[0] = wrap_constructed(self,"Point3"); -} diff --git a/wrap/tests/expected/new_Point3_ddd.m b/wrap/tests/expected/new_Point3_ddd.m deleted file mode 100644 index 154dda1d0..000000000 --- a/wrap/tests/expected/new_Point3_ddd.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Point3_ddd(obj,x,y,z) - error('need to compile new_Point3_ddd.cpp'); -end diff --git a/wrap/tests/expected/new_Test_.cpp b/wrap/tests/expected/new_Test_.cpp index 9c66706ae..e14e6b71d 100644 --- a/wrap/tests/expected/new_Test_.cpp +++ b/wrap/tests/expected/new_Test_.cpp @@ -1,10 +1,48 @@ // automatically generated by wrap #include +#include #include using namespace geometry; +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_Test_",nargout,nargin,0); - Test* self = new Test(); - out[0] = wrap_constructed(self,"Test"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new Test()); + } + if(nc == 1) { + double a = unwrap< double >(in[2]); + Matrix b = unwrap< Matrix >(in[3]); + self = new Shared(new Test(a,b)); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected/new_Test_.m b/wrap/tests/expected/new_Test_.m index 33c465f8b..82faf0fd6 100644 --- a/wrap/tests/expected/new_Test_.m +++ b/wrap/tests/expected/new_Test_.m @@ -1,4 +1,4 @@ % automatically generated by wrap -function result = new_Test_(obj) +function result = new_Test_(obj,a,b) error('need to compile new_Test_.cpp'); end diff --git a/wrap/tests/expected/new_Test_dM.cpp b/wrap/tests/expected/new_Test_dM.cpp deleted file mode 100644 index e8a7c8de1..000000000 --- a/wrap/tests/expected/new_Test_dM.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// automatically generated by wrap -#include -#include -using namespace geometry; -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Test_dM",nargout,nargin,2); - double a = unwrap< double >(in[0]); - Matrix b = unwrap< Matrix >(in[1]); - Test* self = new Test(a,b); - out[0] = wrap_constructed(self,"Test"); -} diff --git a/wrap/tests/expected/new_Test_dM.m b/wrap/tests/expected/new_Test_dM.m deleted file mode 100644 index c7009d6a9..000000000 --- a/wrap/tests/expected/new_Test_dM.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = new_Test_dM(obj,a,b) - error('need to compile new_Test_dM.cpp'); -end diff --git a/wrap/tests/expected_namespaces/@ClassD/ClassD.m b/wrap/tests/expected_namespaces/@ClassD/ClassD.m index 9e3ddf132..2a82b6bbf 100644 --- a/wrap/tests/expected_namespaces/@ClassD/ClassD.m +++ b/wrap/tests/expected_namespaces/@ClassD/ClassD.m @@ -5,11 +5,15 @@ classdef ClassD < handle end methods function obj = ClassD(varargin) - if (nargin == 0), obj.self = new_ClassD_(); end - if nargin ~= 13 && obj.self == 0, error('ClassD constructor failed'); end + if (nargin == 0), obj.self = new_ClassD_(0,0); end + if nargin ==14, new_ClassD_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ClassD constructor failed'); end end function delete(obj) - delete_ClassD(obj); + if obj.self ~= 0 + new_ClassD_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m b/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m index 806070a36..f1cc51eda 100644 --- a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m +++ b/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m @@ -5,11 +5,15 @@ classdef ns1ClassA < handle end methods function obj = ns1ClassA(varargin) - if (nargin == 0), obj.self = new_ns1ClassA_(); end - if nargin ~= 13 && obj.self == 0, error('ns1ClassA constructor failed'); end + if (nargin == 0), obj.self = new_ns1ClassA_(0,0); end + if nargin ==14, new_ns1ClassA_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns1ClassA constructor failed'); end end function delete(obj) - delete_ns1ClassA(obj); + if obj.self ~= 0 + new_ns1ClassA_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m b/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m index 13d5846ae..9403d5b7c 100644 --- a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m +++ b/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m @@ -5,11 +5,15 @@ classdef ns1ClassB < handle end methods function obj = ns1ClassB(varargin) - if (nargin == 0), obj.self = new_ns1ClassB_(); end - if nargin ~= 13 && obj.self == 0, error('ns1ClassB constructor failed'); end + if (nargin == 0), obj.self = new_ns1ClassB_(0,0); end + if nargin ==14, new_ns1ClassB_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns1ClassB constructor failed'); end end function delete(obj) - delete_ns1ClassB(obj); + if obj.self ~= 0 + new_ns1ClassB_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp index 514e5db08..668980943 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp +++ b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp @@ -1,11 +1,15 @@ // automatically generated by wrap #include +#include #include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("memberFunction",nargout,nargin-1,0); - boost::shared_ptr self = unwrap_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); - double result = self->memberFunction(); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + double result = obj->memberFunction(); out[0] = wrap< double >(result); } diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m b/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m index 188ac087d..b4c9de568 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m +++ b/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m @@ -5,11 +5,15 @@ classdef ns2ClassA < handle end methods function obj = ns2ClassA(varargin) - if (nargin == 0), obj.self = new_ns2ClassA_(); end - if nargin ~= 13 && obj.self == 0, error('ns2ClassA constructor failed'); end + if (nargin == 0), obj.self = new_ns2ClassA_(0,0); end + if nargin ==14, new_ns2ClassA_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns2ClassA constructor failed'); end end function delete(obj) - delete_ns2ClassA(obj); + if obj.self ~= 0 + new_ns2ClassA_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp index 789b0815e..a55fd5581 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp +++ b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp @@ -1,12 +1,16 @@ // automatically generated by wrap #include +#include #include #include +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("nsArg",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); - ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ns1ClassB"); - int result = self->nsArg(arg); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ns1ClassB"); + int result = obj->nsArg(arg); out[0] = wrap< int >(result); } diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp index dbeb42f60..334bc9928 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp +++ b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp @@ -1,12 +1,18 @@ // automatically generated by wrap #include +#include #include #include +typedef boost::shared_ptr SharedClassB; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("nsReturn",nargout,nargin-1,1); - boost::shared_ptr self = unwrap_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); - double q = unwrap< double >(in[1]); - ns2::ns3::ClassB result = self->nsReturn(q); - out[0] = wrap_shared_ptr(boost::make_shared< ns2::ns3::ClassB >(result),"ns2ns3ClassB"); + mxArray* mxh = mxGetProperty(in[0],0,"self"); + Shared* self = *reinterpret_cast (mxGetPr(mxh)); + Shared obj = *self; + double q = unwrap< double >(in[1]); + ns2::ns3::ClassB result = obj->nsReturn(q); + SharedClassB* ret = new SharedClassB(new ns2::ns3::ClassB(result)); + out[0] = wrap_collect_shared_ptr(ret,"ns2ns3ClassB"); } diff --git a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m b/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m index 793e73e64..13fbb49f3 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m +++ b/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m @@ -5,11 +5,15 @@ classdef ns2ClassC < handle end methods function obj = ns2ClassC(varargin) - if (nargin == 0), obj.self = new_ns2ClassC_(); end - if nargin ~= 13 && obj.self == 0, error('ns2ClassC constructor failed'); end + if (nargin == 0), obj.self = new_ns2ClassC_(0,0); end + if nargin ==14, new_ns2ClassC_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns2ClassC constructor failed'); end end function delete(obj) - delete_ns2ClassC(obj); + if obj.self ~= 0 + new_ns2ClassC_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m b/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m index 3997cd005..29e0721f0 100644 --- a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m +++ b/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m @@ -5,11 +5,15 @@ classdef ns2ns3ClassB < handle end methods function obj = ns2ns3ClassB(varargin) - if (nargin == 0), obj.self = new_ns2ns3ClassB_(); end - if nargin ~= 13 && obj.self == 0, error('ns2ns3ClassB constructor failed'); end + if (nargin == 0), obj.self = new_ns2ns3ClassB_(0,0); end + if nargin ==14, new_ns2ns3ClassB_(varargin{1},0); end + if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('ns2ns3ClassB constructor failed'); end end function delete(obj) - delete_ns2ns3ClassB(obj); + if obj.self ~= 0 + new_ns2ns3ClassB_(obj.self); + obj.self = 0; + end end function display(obj), obj.print(''); end function disp(obj), obj.display; end diff --git a/wrap/tests/expected_namespaces/Makefile b/wrap/tests/expected_namespaces/Makefile index c48a1b154..55866228b 100644 --- a/wrap/tests/expected_namespaces/Makefile +++ b/wrap/tests/expected_namespaces/Makefile @@ -2,65 +2,54 @@ MEX = mex MEXENDING = mexa64 +PATH_TO_WRAP = /not_really_a_real_path/borg/gtsam/wrap mex_flags = -O5 all: ns1ClassA ns1ClassB ns2ClassA ns2ns3ClassB ns2ClassC ClassD # ns1ClassA -new_ns1ClassA_.$(MEXENDING): new_ns1ClassA_.cpp +new_ns1ClassA_.$(MEXENDING): new_ns1ClassA_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_ns1ClassA_.cpp -output new_ns1ClassA_ -delete_ns1ClassA.$(MEXENDING): delete_ns1ClassA.cpp - $(MEX) $(mex_flags) delete_ns1ClassA.cpp -output delete_ns1ClassA -ns1ClassA: new_ns1ClassA_.$(MEXENDING) delete_ns1ClassA.$(MEXENDING) +ns1ClassA: new_ns1ClassA_.$(MEXENDING) # ns1ClassB -new_ns1ClassB_.$(MEXENDING): new_ns1ClassB_.cpp +new_ns1ClassB_.$(MEXENDING): new_ns1ClassB_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_ns1ClassB_.cpp -output new_ns1ClassB_ -delete_ns1ClassB.$(MEXENDING): delete_ns1ClassB.cpp - $(MEX) $(mex_flags) delete_ns1ClassB.cpp -output delete_ns1ClassB -ns1ClassB: new_ns1ClassB_.$(MEXENDING) delete_ns1ClassB.$(MEXENDING) +ns1ClassB: new_ns1ClassB_.$(MEXENDING) # ns2ClassA -new_ns2ClassA_.$(MEXENDING): new_ns2ClassA_.cpp +new_ns2ClassA_.$(MEXENDING): new_ns2ClassA_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_ns2ClassA_.cpp -output new_ns2ClassA_ -delete_ns2ClassA.$(MEXENDING): delete_ns2ClassA.cpp - $(MEX) $(mex_flags) delete_ns2ClassA.cpp -output delete_ns2ClassA -ns2ClassA_afunction.$(MEXENDING): ns2ClassA_afunction.cpp +ns2ClassA_afunction.$(MEXENDING): ns2ClassA_afunction.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) ns2ClassA_afunction.cpp -output ns2ClassA_afunction -@ns2ClassA/memberFunction.$(MEXENDING): @ns2ClassA/memberFunction.cpp +@ns2ClassA/memberFunction.$(MEXENDING): @ns2ClassA/memberFunction.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @ns2ClassA/memberFunction.cpp -output @ns2ClassA/memberFunction -@ns2ClassA/nsArg.$(MEXENDING): @ns2ClassA/nsArg.cpp +@ns2ClassA/nsArg.$(MEXENDING): @ns2ClassA/nsArg.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @ns2ClassA/nsArg.cpp -output @ns2ClassA/nsArg -@ns2ClassA/nsReturn.$(MEXENDING): @ns2ClassA/nsReturn.cpp +@ns2ClassA/nsReturn.$(MEXENDING): @ns2ClassA/nsReturn.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) @ns2ClassA/nsReturn.cpp -output @ns2ClassA/nsReturn -ns2ClassA: new_ns2ClassA_.$(MEXENDING) delete_ns2ClassA.$(MEXENDING) ns2ClassA_afunction.$(MEXENDING) @ns2ClassA/memberFunction.$(MEXENDING) @ns2ClassA/nsArg.$(MEXENDING) @ns2ClassA/nsReturn.$(MEXENDING) +ns2ClassA: new_ns2ClassA_.$(MEXENDING) ns2ClassA_afunction.$(MEXENDING) @ns2ClassA/memberFunction.$(MEXENDING) @ns2ClassA/nsArg.$(MEXENDING) @ns2ClassA/nsReturn.$(MEXENDING) # ns2ns3ClassB -new_ns2ns3ClassB_.$(MEXENDING): new_ns2ns3ClassB_.cpp +new_ns2ns3ClassB_.$(MEXENDING): new_ns2ns3ClassB_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_ns2ns3ClassB_.cpp -output new_ns2ns3ClassB_ -delete_ns2ns3ClassB.$(MEXENDING): delete_ns2ns3ClassB.cpp - $(MEX) $(mex_flags) delete_ns2ns3ClassB.cpp -output delete_ns2ns3ClassB -ns2ns3ClassB: new_ns2ns3ClassB_.$(MEXENDING) delete_ns2ns3ClassB.$(MEXENDING) +ns2ns3ClassB: new_ns2ns3ClassB_.$(MEXENDING) # ns2ClassC -new_ns2ClassC_.$(MEXENDING): new_ns2ClassC_.cpp +new_ns2ClassC_.$(MEXENDING): new_ns2ClassC_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_ns2ClassC_.cpp -output new_ns2ClassC_ -delete_ns2ClassC.$(MEXENDING): delete_ns2ClassC.cpp - $(MEX) $(mex_flags) delete_ns2ClassC.cpp -output delete_ns2ClassC -ns2ClassC: new_ns2ClassC_.$(MEXENDING) delete_ns2ClassC.$(MEXENDING) +ns2ClassC: new_ns2ClassC_.$(MEXENDING) # ClassD -new_ClassD_.$(MEXENDING): new_ClassD_.cpp +new_ClassD_.$(MEXENDING): new_ClassD_.cpp $(PATH_TO_WRAP)/matlab.h $(MEX) $(mex_flags) new_ClassD_.cpp -output new_ClassD_ -delete_ClassD.$(MEXENDING): delete_ClassD.cpp - $(MEX) $(mex_flags) delete_ClassD.cpp -output delete_ClassD -ClassD: new_ClassD_.$(MEXENDING) delete_ClassD.$(MEXENDING) +ClassD: new_ClassD_.$(MEXENDING) diff --git a/wrap/tests/expected_namespaces/delete_ClassD.cpp b/wrap/tests/expected_namespaces/delete_ClassD.cpp deleted file mode 100644 index 5284e33ba..000000000 --- a/wrap/tests/expected_namespaces/delete_ClassD.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ClassD",nargout,nargin,1); - delete_shared_ptr< ClassD >(in[0],"ClassD"); -} diff --git a/wrap/tests/expected_namespaces/delete_ClassD.m b/wrap/tests/expected_namespaces/delete_ClassD.m deleted file mode 100644 index aef8cb642..000000000 --- a/wrap/tests/expected_namespaces/delete_ClassD.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ClassD(obj) - error('need to compile delete_ClassD.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassA.cpp b/wrap/tests/expected_namespaces/delete_ns1ClassA.cpp deleted file mode 100644 index 17a25b523..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassA.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns1ClassA",nargout,nargin,1); - delete_shared_ptr< ns1::ClassA >(in[0],"ns1ClassA"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassA.m b/wrap/tests/expected_namespaces/delete_ns1ClassA.m deleted file mode 100644 index 343d5636a..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassA.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns1ClassA(obj) - error('need to compile delete_ns1ClassA.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassB.cpp b/wrap/tests/expected_namespaces/delete_ns1ClassB.cpp deleted file mode 100644 index 7302cc3d3..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassB.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns1ClassB",nargout,nargin,1); - delete_shared_ptr< ns1::ClassB >(in[0],"ns1ClassB"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns1ClassB.m b/wrap/tests/expected_namespaces/delete_ns1ClassB.m deleted file mode 100644 index ec50f3f06..000000000 --- a/wrap/tests/expected_namespaces/delete_ns1ClassB.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns1ClassB(obj) - error('need to compile delete_ns1ClassB.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassA.cpp b/wrap/tests/expected_namespaces/delete_ns2ClassA.cpp deleted file mode 100644 index 0562ee073..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassA.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns2ClassA",nargout,nargin,1); - delete_shared_ptr< ns2::ClassA >(in[0],"ns2ClassA"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassA.m b/wrap/tests/expected_namespaces/delete_ns2ClassA.m deleted file mode 100644 index 4f1b92aa5..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassA.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns2ClassA(obj) - error('need to compile delete_ns2ClassA.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassC.cpp b/wrap/tests/expected_namespaces/delete_ns2ClassC.cpp deleted file mode 100644 index ef57796b7..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassC.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// automatically generated by wrap -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns2ClassC",nargout,nargin,1); - delete_shared_ptr< ns2::ClassC >(in[0],"ns2ClassC"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns2ClassC.m b/wrap/tests/expected_namespaces/delete_ns2ClassC.m deleted file mode 100644 index 1db1ddc93..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ClassC.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns2ClassC(obj) - error('need to compile delete_ns2ClassC.cpp'); -end diff --git a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.cpp b/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.cpp deleted file mode 100644 index 0a6c4ce73..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.cpp +++ /dev/null @@ -1,9 +0,0 @@ -// automatically generated by wrap -#include -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("delete_ns2ns3ClassB",nargout,nargin,1); - delete_shared_ptr< ns2::ns3::ClassB >(in[0],"ns2ns3ClassB"); -} diff --git a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.m b/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.m deleted file mode 100644 index 427359eca..000000000 --- a/wrap/tests/expected_namespaces/delete_ns2ns3ClassB.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap -function result = delete_ns2ns3ClassB(obj) - error('need to compile delete_ns2ns3ClassB.cpp'); -end diff --git a/wrap/tests/expected_namespaces/make_testNamespaces.m b/wrap/tests/expected_namespaces/make_testNamespaces.m index d835a2da0..5ff13e5d4 100644 --- a/wrap/tests/expected_namespaces/make_testNamespaces.m +++ b/wrap/tests/expected_namespaces/make_testNamespaces.m @@ -10,21 +10,18 @@ addpath(toolboxpath); %% ns1ClassA cd(toolboxpath) mex -O5 new_ns1ClassA_.cpp -mex -O5 delete_ns1ClassA.cpp cd @ns1ClassA %% ns1ClassB cd(toolboxpath) mex -O5 new_ns1ClassB_.cpp -mex -O5 delete_ns1ClassB.cpp cd @ns1ClassB %% ns2ClassA cd(toolboxpath) mex -O5 new_ns2ClassA_.cpp -mex -O5 delete_ns2ClassA.cpp mex -O5 ns2ClassA_afunction.cpp cd @ns2ClassA @@ -35,21 +32,18 @@ mex -O5 nsReturn.cpp %% ns2ns3ClassB cd(toolboxpath) mex -O5 new_ns2ns3ClassB_.cpp -mex -O5 delete_ns2ns3ClassB.cpp cd @ns2ns3ClassB %% ns2ClassC cd(toolboxpath) mex -O5 new_ns2ClassC_.cpp -mex -O5 delete_ns2ClassC.cpp cd @ns2ClassC %% ClassD cd(toolboxpath) mex -O5 new_ClassD_.cpp -mex -O5 delete_ClassD.cpp cd @ClassD diff --git a/wrap/tests/expected_namespaces/new_ClassD_.cpp b/wrap/tests/expected_namespaces/new_ClassD_.cpp index 59ea4398b..6ebe46f2d 100644 --- a/wrap/tests/expected_namespaces/new_ClassD_.cpp +++ b/wrap/tests/expected_namespaces/new_ClassD_.cpp @@ -1,9 +1,42 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_ClassD_",nargout,nargin,0); - ClassD* self = new ClassD(); - out[0] = wrap_constructed(self,"ClassD"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new ClassD()); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp b/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp index cbb82eb70..eca52a3ea 100644 --- a/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp +++ b/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp @@ -1,9 +1,42 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_ns1ClassA_",nargout,nargin,0); - ns1::ClassA* self = new ns1::ClassA(); - out[0] = wrap_constructed(self,"ns1ClassA"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new ns1::ClassA()); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp b/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp index d50cede19..5eb90cae8 100644 --- a/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp +++ b/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp @@ -1,10 +1,43 @@ // automatically generated by wrap #include +#include #include #include +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_ns1ClassB_",nargout,nargin,0); - ns1::ClassB* self = new ns1::ClassB(); - out[0] = wrap_constructed(self,"ns1ClassB"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new ns1::ClassB()); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp b/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp index 81bae3198..f0e6c2036 100644 --- a/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp +++ b/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp @@ -1,10 +1,43 @@ // automatically generated by wrap #include +#include #include #include +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_ns2ClassA_",nargout,nargin,0); - ns2::ClassA* self = new ns2::ClassA(); - out[0] = wrap_constructed(self,"ns2ClassA"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new ns2::ClassA()); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp b/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp index fbee07926..ae6a88845 100644 --- a/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp +++ b/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp @@ -1,9 +1,42 @@ // automatically generated by wrap #include +#include #include +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_ns2ClassC_",nargout,nargin,0); - ns2::ClassC* self = new ns2::ClassC(); - out[0] = wrap_constructed(self,"ns2ClassC"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new ns2::ClassC()); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp index ca9d02df3..bf6e244a2 100644 --- a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp +++ b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp @@ -1,10 +1,43 @@ // automatically generated by wrap #include +#include #include #include +typedef boost::shared_ptr Shared; + +static std::set collector; + +struct Destruct +{ + void operator() (Shared* p) + { + collector.erase(p); + } +}; + +void cleanup(void) { + std::for_each( collector.begin(), collector.end(), Destruct() ); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("new_ns2ns3ClassB_",nargout,nargin,0); - ns2::ns3::ClassB* self = new ns2::ns3::ClassB(); - out[0] = wrap_constructed(self,"ns2ns3ClassB"); + mexAtExit(cleanup); + + const mxArray* input = in[0]; + Shared* self = *(Shared**) mxGetData(input); + + if(self) { + if(nargin > 1) { + collector.insert(self); + } + else if(collector.erase(self)) + delete self; + } else { + int nc = unwrap(in[1]); + if(nc == 0) { + self = new Shared(new ns2::ns3::ClassB()); + } + collector.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetPr(out[0])) = self; + } } diff --git a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp b/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp index 72559acf8..3e8d54a14 100644 --- a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp +++ b/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp @@ -1,7 +1,10 @@ // automatically generated by wrap #include +#include #include #include +typedef boost::shared_ptr Shareddouble; +typedef boost::shared_ptr Shared; void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("ns2ClassA_afunction",nargout,nargin,0); diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index db3ac8982..8fac80113 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -39,6 +39,10 @@ static string topdir = "TOPSRCDIR_NOT_CONFIGURED"; // If TOPSRCDIR is not define typedef vector strvec; +// NOTE: as this path is only used to generate makefiles, it is hardcoded here for testing +// In practice, this path will be an absolute system path, which makes testing it more annoying +static const std::string headerPath = "/not_really_a_real_path/borg/gtsam/wrap"; + /* ************************************************************************* */ TEST( wrap, ArgumentList ) { ArgumentList args; @@ -63,13 +67,13 @@ TEST( wrap, check_exception ) { string path = topdir + "/wrap/tests"; Module module(path.c_str(), "testDependencies",enable_verbose); - CHECK_EXCEPTION(module.matlab_code("mex", "actual_deps", "mexa64", "-O5"), DependencyMissing); + CHECK_EXCEPTION(module.matlab_code("mex", "actual_deps", "mexa64", headerPath, "-O5"), DependencyMissing); } /* ************************************************************************* */ TEST( wrap, parse ) { - string header_path = topdir + "/wrap/tests"; - Module module(header_path.c_str(), "geometry",enable_verbose); + string markup_header_path = topdir + "/wrap/tests"; + Module module(markup_header_path.c_str(), "geometry",enable_verbose); EXPECT_LONGS_EQUAL(3, module.classes.size()); // check using declarations @@ -83,7 +87,7 @@ TEST( wrap, parse ) { { Class cls = module.classes.at(0); EXPECT(assert_equal("Point2", cls.name)); - EXPECT_LONGS_EQUAL(2, cls.constructors.size()); + EXPECT_LONGS_EQUAL(2, cls.constructor.args_list.size()); EXPECT_LONGS_EQUAL(7, cls.methods.size()); EXPECT_LONGS_EQUAL(0, cls.static_methods.size()); EXPECT_LONGS_EQUAL(0, cls.namespaces.size()); @@ -94,18 +98,18 @@ TEST( wrap, parse ) { { Class cls = module.classes.at(1); EXPECT(assert_equal("Point3", cls.name)); - EXPECT_LONGS_EQUAL(1, cls.constructors.size()); + EXPECT_LONGS_EQUAL(1, cls.constructor.args_list.size()); EXPECT_LONGS_EQUAL(1, cls.methods.size()); EXPECT_LONGS_EQUAL(2, cls.static_methods.size()); EXPECT_LONGS_EQUAL(0, cls.namespaces.size()); EXPECT(assert_equal(exp_using2, cls.using_namespaces)); // first constructor takes 3 doubles - Constructor c1 = cls.constructors.front(); - EXPECT_LONGS_EQUAL(3, c1.args.size()); + ArgumentList c1 = cls.constructor.args_list.front(); + EXPECT_LONGS_EQUAL(3, c1.size()); // check first double argument - Argument a1 = c1.args.front(); + Argument a1 = c1.front(); EXPECT(!a1.is_const); EXPECT(assert_equal("double", a1.type)); EXPECT(!a1.is_ref); @@ -123,7 +127,7 @@ TEST( wrap, parse ) { { LONGS_EQUAL(3, module.classes.size()); Class testCls = module.classes.at(2); - EXPECT_LONGS_EQUAL( 2, testCls.constructors.size()); + EXPECT_LONGS_EQUAL( 2, testCls.constructor.args_list.size()); EXPECT_LONGS_EQUAL(19, testCls.methods.size()); EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size()); EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size()); @@ -214,7 +218,7 @@ TEST( wrap, matlab_code_namespaces ) { // emit MATLAB code string exp_path = path + "/tests/expected_namespaces/"; string act_path = "actual_namespaces/"; - module.matlab_code("mex", "actual_namespaces", "mexa64", "-O5"); + module.matlab_code("mex", "actual_namespaces", "mexa64", headerPath, "-O5"); EXPECT(files_equal(exp_path + "new_ClassD_.cpp" , act_path + "new_ClassD_.cpp" )); EXPECT(files_equal(exp_path + "new_ClassD_.m" , act_path + "new_ClassD_.m" )); @@ -228,18 +232,6 @@ TEST( wrap, matlab_code_namespaces ) { EXPECT(files_equal(exp_path + "new_ns2ClassC_.m" , act_path + "new_ns2ClassC_.m" )); EXPECT(files_equal(exp_path + "new_ns2ns3ClassB_.cpp" , act_path + "new_ns2ns3ClassB_.cpp" )); EXPECT(files_equal(exp_path + "new_ns2ns3ClassB_.m" , act_path + "new_ns2ns3ClassB_.m" )); - EXPECT(files_equal(exp_path + "delete_ClassD.cpp" , act_path + "delete_ClassD.cpp" )); - EXPECT(files_equal(exp_path + "delete_ClassD.m" , act_path + "delete_ClassD.m" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassA.cpp" , act_path + "delete_ns1ClassA.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassA.m" , act_path + "delete_ns1ClassA.m" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassB.cpp" , act_path + "delete_ns1ClassB.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns1ClassB.m" , act_path + "delete_ns1ClassB.m" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassA.cpp" , act_path + "delete_ns2ClassA.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassA.m" , act_path + "delete_ns2ClassA.m" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassC.cpp" , act_path + "delete_ns2ClassC.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns2ClassC.m" , act_path + "delete_ns2ClassC.m" )); - EXPECT(files_equal(exp_path + "delete_ns2ns3ClassB.cpp" , act_path + "delete_ns2ns3ClassB.cpp" )); - EXPECT(files_equal(exp_path + "delete_ns2ns3ClassB.m" , act_path + "delete_ns2ns3ClassB.m" )); EXPECT(files_equal(exp_path + "ns2ClassA_afunction.cpp" , act_path + "ns2ClassA_afunction.cpp" )); EXPECT(files_equal(exp_path + "ns2ClassA_afunction.m" , act_path + "ns2ClassA_afunction.m" )); @@ -267,35 +259,83 @@ TEST( wrap, matlab_code ) { // emit MATLAB code // make_geometry will not compile, use make testwrap to generate real make - module.matlab_code("mex", "actual", "mexa64", "-O5"); + module.matlab_code("mex", "actual", "mexa64", headerPath, "-O5"); + string epath = path + "/tests/expected/"; + string apath = "actual/"; - EXPECT(files_equal(path + "/tests/expected/@Point2/Point2.m" , "actual/@Point2/Point2.m" )); - EXPECT(files_equal(path + "/tests/expected/@Point2/x.cpp" , "actual/@Point2/x.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Point3/Point3.m" , "actual/@Point3/Point3.m" )); - EXPECT(files_equal(path + "/tests/expected/new_Point3_ddd.m" , "actual/new_Point3_ddd.m" )); - EXPECT(files_equal(path + "/tests/expected/new_Point3_ddd.cpp", "actual/new_Point3_ddd.cpp")); - EXPECT(files_equal(path + "/tests/expected/Point3_staticFunction.m" , "actual/Point3_staticFunction.m" )); - EXPECT(files_equal(path + "/tests/expected/Point3_staticFunction.cpp", "actual/Point3_staticFunction.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Point3/norm.m" , "actual/@Point3/norm.m" )); - EXPECT(files_equal(path + "/tests/expected/@Point3/norm.cpp" , "actual/@Point3/norm.cpp" )); + EXPECT(files_equal(epath + "Makefile" , apath + "Makefile" )); + EXPECT(files_equal(epath + "make_geometry.m" , apath + "make_geometry.m" )); + EXPECT(files_equal(epath + "new_Point2_.cpp" , apath + "new_Point2_.cpp" )); + EXPECT(files_equal(epath + "new_Point2_.m" , apath + "new_Point2_.m" )); + EXPECT(files_equal(epath + "new_Point3_.cpp" , apath + "new_Point3_.cpp" )); + EXPECT(files_equal(epath + "new_Point3_.m" , apath + "new_Point3_.m" )); + EXPECT(files_equal(epath + "new_Test_.cpp" , apath + "new_Test_.cpp" )); + EXPECT(files_equal(epath + "new_Test_.m" , apath + "new_Test_.m" )); - EXPECT(files_equal(path + "/tests/expected/new_Test_.cpp" , "actual/new_Test_.cpp" )); - EXPECT(files_equal(path + "/tests/expected/delete_Test.cpp" , "actual/delete_Test.cpp" )); - EXPECT(files_equal(path + "/tests/expected/delete_Test.m" , "actual/delete_Test.m" )); - EXPECT(files_equal(path + "/tests/expected/@Test/Test.m" , "actual/@Test/Test.m" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_string.cpp" , "actual/@Test/return_string.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_pair.cpp" , "actual/@Test/return_pair.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/create_MixedPtrs.cpp", "actual/@Test/create_MixedPtrs.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Test/return_field.cpp" , "actual/@Test/return_field.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_TestPtr.cpp", "actual/@Test/return_TestPtr.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Test/return_Test.cpp" , "actual/@Test/return_Test.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/return_Point2Ptr.cpp", "actual/@Test/return_Point2Ptr.cpp")); - EXPECT(files_equal(path + "/tests/expected/@Test/return_ptrs.cpp" , "actual/@Test/return_ptrs.cpp" )); - EXPECT(files_equal(path + "/tests/expected/@Test/print.m" , "actual/@Test/print.m" )); - EXPECT(files_equal(path + "/tests/expected/@Test/print.cpp" , "actual/@Test/print.cpp" )); + EXPECT(files_equal(epath + "Point3_staticFunction.cpp" , apath + "Point3_staticFunction.cpp" )); + EXPECT(files_equal(epath + "Point3_staticFunction.m" , apath + "Point3_staticFunction.m" )); + EXPECT(files_equal(epath + "Point3_StaticFunctionRet.cpp" , apath + "Point3_StaticFunctionRet.cpp" )); + EXPECT(files_equal(epath + "Point3_StaticFunctionRet.m" , apath + "Point3_StaticFunctionRet.m" )); + + EXPECT(files_equal(epath + "@Point2/argChar.cpp" , apath + "@Point2/argChar.cpp" )); + EXPECT(files_equal(epath + "@Point2/argChar.m" , apath + "@Point2/argChar.m" )); + EXPECT(files_equal(epath + "@Point2/argUChar.cpp" , apath + "@Point2/argUChar.cpp" )); + EXPECT(files_equal(epath + "@Point2/argUChar.m" , apath + "@Point2/argUChar.m" )); + EXPECT(files_equal(epath + "@Point2/dim.cpp" , apath + "@Point2/dim.cpp" )); + EXPECT(files_equal(epath + "@Point2/dim.m" , apath + "@Point2/dim.m" )); + EXPECT(files_equal(epath + "@Point2/Point2.m" , apath + "@Point2/Point2.m" )); + EXPECT(files_equal(epath + "@Point2/returnChar.cpp" , apath + "@Point2/returnChar.cpp" )); + EXPECT(files_equal(epath + "@Point2/returnChar.m" , apath + "@Point2/returnChar.m" )); + EXPECT(files_equal(epath + "@Point2/vectorConfusion.cpp" , apath + "@Point2/vectorConfusion.cpp" )); + EXPECT(files_equal(epath + "@Point2/vectorConfusion.m" , apath + "@Point2/vectorConfusion.m" )); + EXPECT(files_equal(epath + "@Point2/x.cpp" , apath + "@Point2/x.cpp" )); + EXPECT(files_equal(epath + "@Point2/x.m" , apath + "@Point2/x.m" )); + EXPECT(files_equal(epath + "@Point2/y.cpp" , apath + "@Point2/y.cpp" )); + EXPECT(files_equal(epath + "@Point2/y.m" , apath + "@Point2/y.m" )); + EXPECT(files_equal(epath + "@Point3/norm.cpp" , apath + "@Point3/norm.cpp" )); + EXPECT(files_equal(epath + "@Point3/norm.m" , apath + "@Point3/norm.m" )); + EXPECT(files_equal(epath + "@Point3/Point3.m" , apath + "@Point3/Point3.m" )); + + EXPECT(files_equal(epath + "@Test/arg_EigenConstRef.cpp" , apath + "@Test/arg_EigenConstRef.cpp" )); + EXPECT(files_equal(epath + "@Test/arg_EigenConstRef.m" , apath + "@Test/arg_EigenConstRef.m" )); + EXPECT(files_equal(epath + "@Test/create_MixedPtrs.cpp" , apath + "@Test/create_MixedPtrs.cpp" )); + EXPECT(files_equal(epath + "@Test/create_MixedPtrs.m" , apath + "@Test/create_MixedPtrs.m" )); + EXPECT(files_equal(epath + "@Test/create_ptrs.cpp" , apath + "@Test/create_ptrs.cpp" )); + EXPECT(files_equal(epath + "@Test/create_ptrs.m" , apath + "@Test/create_ptrs.m" )); + EXPECT(files_equal(epath + "@Test/print.cpp" , apath + "@Test/print.cpp" )); + EXPECT(files_equal(epath + "@Test/print.m" , apath + "@Test/print.m" )); + EXPECT(files_equal(epath + "@Test/return_bool.cpp" , apath + "@Test/return_bool.cpp" )); + EXPECT(files_equal(epath + "@Test/return_bool.m" , apath + "@Test/return_bool.m" )); + EXPECT(files_equal(epath + "@Test/return_double.cpp" , apath + "@Test/return_double.cpp" )); + EXPECT(files_equal(epath + "@Test/return_double.m" , apath + "@Test/return_double.m" )); + EXPECT(files_equal(epath + "@Test/return_field.cpp" , apath + "@Test/return_field.cpp" )); + EXPECT(files_equal(epath + "@Test/return_field.m" , apath + "@Test/return_field.m" )); + EXPECT(files_equal(epath + "@Test/return_int.cpp" , apath + "@Test/return_int.cpp" )); + EXPECT(files_equal(epath + "@Test/return_int.m" , apath + "@Test/return_int.m" )); + EXPECT(files_equal(epath + "@Test/return_matrix1.cpp" , apath + "@Test/return_matrix1.cpp" )); + EXPECT(files_equal(epath + "@Test/return_matrix1.m" , apath + "@Test/return_matrix1.m" )); + EXPECT(files_equal(epath + "@Test/return_matrix2.cpp" , apath + "@Test/return_matrix2.cpp" )); + EXPECT(files_equal(epath + "@Test/return_matrix2.m" , apath + "@Test/return_matrix2.m" )); + EXPECT(files_equal(epath + "@Test/return_pair.cpp" , apath + "@Test/return_pair.cpp" )); + EXPECT(files_equal(epath + "@Test/return_pair.m" , apath + "@Test/return_pair.m" )); + EXPECT(files_equal(epath + "@Test/return_Point2Ptr.cpp" , apath + "@Test/return_Point2Ptr.cpp" )); + EXPECT(files_equal(epath + "@Test/return_Point2Ptr.m" , apath + "@Test/return_Point2Ptr.m" )); + EXPECT(files_equal(epath + "@Test/return_ptrs.cpp" , apath + "@Test/return_ptrs.cpp" )); + EXPECT(files_equal(epath + "@Test/return_ptrs.m" , apath + "@Test/return_ptrs.m" )); + EXPECT(files_equal(epath + "@Test/return_size_t.cpp" , apath + "@Test/return_size_t.cpp" )); + EXPECT(files_equal(epath + "@Test/return_size_t.m" , apath + "@Test/return_size_t.m" )); + EXPECT(files_equal(epath + "@Test/return_string.cpp" , apath + "@Test/return_string.cpp" )); + EXPECT(files_equal(epath + "@Test/return_string.m" , apath + "@Test/return_string.m" )); + EXPECT(files_equal(epath + "@Test/return_Test.cpp" , apath + "@Test/return_Test.cpp" )); + EXPECT(files_equal(epath + "@Test/return_Test.m" , apath + "@Test/return_Test.m" )); + EXPECT(files_equal(epath + "@Test/return_TestPtr.cpp" , apath + "@Test/return_TestPtr.cpp" )); + EXPECT(files_equal(epath + "@Test/return_TestPtr.m" , apath + "@Test/return_TestPtr.m" )); + EXPECT(files_equal(epath + "@Test/return_vector1.cpp" , apath + "@Test/return_vector1.cpp" )); + EXPECT(files_equal(epath + "@Test/return_vector1.m" , apath + "@Test/return_vector1.m" )); + EXPECT(files_equal(epath + "@Test/return_vector2.cpp" , apath + "@Test/return_vector2.cpp" )); + EXPECT(files_equal(epath + "@Test/return_vector2.m" , apath + "@Test/return_vector2.m" )); + EXPECT(files_equal(epath + "@Test/Test.m" , apath + "@Test/Test.m" )); - EXPECT(files_equal(path + "/tests/expected/make_geometry.m", "actual/make_geometry.m")); - EXPECT(files_equal(path + "/tests/expected/Makefile" , "actual/Makefile" )); } /* ************************************************************************* */ diff --git a/wrap/utilities.cpp b/wrap/utilities.cpp index bfd1e77df..00606f930 100644 --- a/wrap/utilities.cpp +++ b/wrap/utilities.cpp @@ -12,6 +12,7 @@ /** * @file utilities.ccp * @author Frank Dellaert + * @author Andrew Melim **/ #include @@ -103,10 +104,12 @@ bool files_equal(const string& expected, const string& actual, bool skipheader) } /* ************************************************************************* */ -string maybe_shared_ptr(bool add, const string& type) { - string str = add? "boost::shared_ptr<" : ""; - str += type; - if (add) str += ">"; +string maybe_shared_ptr(bool add, const string& qtype, const string& type) { + string str = add? "Shared" : ""; + if (add) str += type; + else str += qtype; + + //if (add) str += ">"; return str; } @@ -121,6 +124,7 @@ void generateUsingNamespace(FileWriter& file, const vector& using_namesp void generateIncludes(FileWriter& file, const string& class_name, const vector& includes) { file.oss << "#include " << endl; + file.oss << "#include " << endl; bool added_include = false; BOOST_FOREACH(const string& s, includes) { if (!s.empty()) { @@ -134,4 +138,5 @@ void generateIncludes(FileWriter& file, const string& class_name, /* ************************************************************************* */ + } // \namespace wrap diff --git a/wrap/utilities.h b/wrap/utilities.h index 384ff3749..1eb0e249f 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -10,8 +10,9 @@ * -------------------------------------------------------------------------- */ /** - * @file utilities.ccp + * @file utilities.h * @author Frank Dellaert + * @author Andrew Melim **/ #pragma once @@ -84,7 +85,7 @@ bool assert_equal(const std::string& expected, const std::string& actual); bool assert_equal(const std::vector& expected, const std::vector& actual); // auxiliary function to wrap an argument into a shared_ptr template -std::string maybe_shared_ptr(bool add, const std::string& type); +std::string maybe_shared_ptr(bool add, const std::string& qtype, const std::string& type); /** * Creates the "using namespace [name];" declarations diff --git a/wrap/wrap.cpp b/wrap/wrap.cpp index eabba647e..f818094f7 100644 --- a/wrap/wrap.cpp +++ b/wrap/wrap.cpp @@ -29,7 +29,7 @@ using namespace std; * @param interfacePath path to where interface file lives, e.g., borg/gtsam * @param moduleName name of the module to be generated e.g. gtsam * @param toolboxPath path where the toolbox should be generated, e.g. borg/gtsam/build - * @param nameSpace e.g. gtsam + * @param headerPath is the path to matlab.h * @param mexFlags extra arguments for mex script, i.e., include flags etc... */ void generate_matlab_toolbox( @@ -38,14 +38,15 @@ void generate_matlab_toolbox( const string& interfacePath, const string& moduleName, const string& toolboxPath, - const string& mexFlags) + const string& headerPath, + const string& mexFlags) { // Parse interface file into class object // This recursively creates Class objects, Method objects, etc... - wrap::Module module(interfacePath, moduleName, true); + wrap::Module module(interfacePath, moduleName, false); // Then emit MATLAB code - module.matlab_code(mexCommand,toolboxPath,mexExt,mexFlags); + module.matlab_code(mexCommand,toolboxPath,mexExt,headerPath,mexFlags); } /** Displays usage information */ @@ -57,6 +58,7 @@ void usage() { cerr << " interfacePath : *absolute* path to directory of module interface file" << endl; cerr << " moduleName : the name of the module, interface file must be called moduleName.h" << endl; cerr << " toolboxPath : the directory in which to generate the wrappers" << endl; + cerr << " headerPath : path to matlab.h" << endl; cerr << " [mexFlags] : extra flags for the mex command" << endl; } @@ -73,6 +75,6 @@ int main(int argc, const char* argv[]) { usage(); } else - generate_matlab_toolbox(argv[1],argv[2],argv[3],argv[4],argv[5],argc==6 ? " " : argv[6]); + generate_matlab_toolbox(argv[1],argv[2],argv[3],argv[4],argv[5],argv[6],argc==7 ? " " : argv[7]); return 0; }