Modified wrap to generate a single cpp wrapper file containing all wrapped functions, and one .m file per class and static method.

release/4.3a0
Richard Roberts 2012-07-05 14:04:36 +00:00
parent 11911e8940
commit b5937ce35d
15 changed files with 690 additions and 682 deletions

View File

@ -28,81 +28,96 @@
using namespace std; using namespace std;
using namespace wrap; using namespace wrap;
static const uint64_t ptr_constructor_key =
(uint64_t('G') << 56) |
(uint64_t('T') << 48) |
(uint64_t('S') << 40) |
(uint64_t('A') << 32) |
(uint64_t('M') << 24) |
(uint64_t('p') << 16) |
(uint64_t('t') << 8) |
(uint64_t('r'));
/* ************************************************************************* */ /* ************************************************************************* */
void Class::matlab_proxy(const string& classFile) const { void Class::matlab_proxy(const string& classFile, const string& wrapperName, FileWriter& wrapperFile, vector<string>& functionNames) const {
// open destination classFile // open destination classFile
FileWriter file(classFile, verbose_, "%"); FileWriter proxyFile(classFile, verbose_, "%");
// get the name of actual matlab object // get the name of actual matlab object
string matlabName = qualifiedName(); string matlabName = qualifiedName(), cppName = qualifiedName("::");
// emit class proxy code // emit class proxy code
// we want our class to inherit the handle class for memory purposes // we want our class to inherit the handle class for memory purposes
file.oss << "classdef " << matlabName << " < handle" << endl; proxyFile.oss << "classdef " << matlabName << " < handle" << endl;
file.oss << " properties" << endl; proxyFile.oss << " properties" << endl;
file.oss << " self = 0" << endl; proxyFile.oss << " self = 0" << endl;
file.oss << " end" << endl; proxyFile.oss << " end" << endl;
file.oss << " methods" << endl; proxyFile.oss << " methods" << endl;
// constructor
file.oss << " function obj = " << matlabName << "(varargin)" << endl; // Constructor
//i is constructor id proxyFile.oss << " function obj = " << matlabName << "(varargin)" << endl;
int id = 0; // Special pointer constructor
{
const int id = functionNames.size();
proxyFile.oss << " if nargin == 2 && isa(varargin{1}, 'uint64') && ";
proxyFile.oss << "varargin{1} == uint64(" << ptr_constructor_key << ")\n";
proxyFile.oss << " obj.self = varargin{2};\n";
}
// Regular constructors
BOOST_FOREACH(ArgumentList a, constructor.args_list) BOOST_FOREACH(ArgumentList a, constructor.args_list)
{ {
constructor.matlab_proxy_fragment(file,matlabName, id, a); const int id = functionNames.size();
id++; constructor.proxy_fragment(proxyFile, wrapperName, matlabName, id, a);
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
cppName, matlabName, id, using_namespaces, includes, a);
wrapperFile.oss << "\n";
functionNames.push_back(wrapFunctionName);
} }
//Static constructor collect call proxyFile.oss << " else\n";
file.oss << " if nargin ==14, new_" << matlabName << "(varargin{1},0); end" << endl; proxyFile.oss << " error('" << matlabName << " constructor failed');" << endl;
file.oss << " if nargin ~= 13 && nargin ~= 14 && obj.self == 0, error('" << matlabName << " constructor failed'); end" << endl; proxyFile.oss << " end\n";
file.oss << " end" << endl; proxyFile.oss << " end\n\n";
// deconstructor
file.oss << " function delete(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;
file.oss << " end" << endl;
file.oss << "end" << endl;
// close file // Deconstructor
file.emit(true); {
const int id = functionNames.size();
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabName, id);
proxyFile.oss << "\n";
const string functionName = deconstructor.wrapper_fragment(wrapperFile,
cppName, matlabName, id, using_namespaces, includes);
wrapperFile.oss << "\n";
functionNames.push_back(functionName);
} }
proxyFile.oss << " function display(obj), obj.print(''); end\n\n";
proxyFile.oss << " function disp(obj), obj.display; end\n\n";
/* ************************************************************************* */ // Methods
//TODO: Consolidate into single file
void Class::matlab_constructors(const string& toolboxPath) const {
/*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_methods(const string& classPath) const {
string matlabName = qualifiedName(), cppName = qualifiedName("::");
BOOST_FOREACH(Method m, methods) { BOOST_FOREACH(Method m, methods) {
m.matlab_mfile (classPath); const int id = functionNames.size();
m.matlab_wrapper(classPath, name, cppName, matlabName, using_namespaces, includes); m.proxy_fragment(proxyFile, wrapperName, id);
proxyFile.oss << "\n";
const string wrapFunctionName = m.wrapper_fragment(wrapperFile,
cppName, matlabName, id, using_namespaces);
wrapperFile.oss << "\n";
functionNames.push_back(wrapFunctionName);
} }
proxyFile.oss << " end" << endl;
proxyFile.oss << "end" << endl;
// Close file
proxyFile.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Class::matlab_static_methods(const string& toolboxPath) const { void Class::matlab_static_methods(const string& toolboxPath, const string& wrapperName,
FileWriter& wrapperFile, vector<string>& functionNames) const {
string matlabName = qualifiedName(), cppName = qualifiedName("::"); string matlabName = qualifiedName(), cppName = qualifiedName("::");
BOOST_FOREACH(const StaticMethod& m, static_methods) { BOOST_FOREACH(const StaticMethod& m, static_methods) {
m.matlab_mfile (toolboxPath, qualifiedName()); const int id = functionNames.size();
m.matlab_wrapper(toolboxPath, name, matlabName, cppName, using_namespaces, includes); m.proxy_fragment(toolboxPath, matlabName, wrapperName, id);
const string wrapFunction = m.wrapper_fragment(wrapperFile, matlabName, cppName, id, using_namespaces);
functionNames.push_back(wrapFunction);
} }
} }

View File

@ -19,6 +19,7 @@
#pragma once #pragma once
#include <string> #include <string>
#include <boost/bimap.hpp>
#include "Constructor.h" #include "Constructor.h"
#include "Deconstructor.h" #include "Deconstructor.h"
@ -40,13 +41,14 @@ struct Class {
std::vector<std::string> using_namespaces;///< default namespaces std::vector<std::string> using_namespaces;///< default namespaces
std::vector<std::string> includes; ///< header include overrides std::vector<std::string> includes; ///< header include overrides
Constructor constructor; ///< Class constructors Constructor constructor; ///< Class constructors
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
bool verbose_; ///< verbose flag bool verbose_; ///< verbose flag
// And finally MATLAB code is emitted, methods below called by Module::matlab_code // 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_proxy(const std::string& classFile, const std::string& wrapperName,
void matlab_constructors(const std::string& toolboxPath) const; ///< emit constructor wrappers FileWriter& wrapperFile, std::vector<std::string>& functionNames) const; ///< emit proxy class
void matlab_methods(const std::string& classPath) const; ///< emit method wrappers void matlab_static_methods(const std::string& toolboxPath, const std::string& wrapperName,
void matlab_static_methods(const std::string& classPath) const; ///< emit static method wrappers FileWriter& wrapperFile, std::vector<std::string>& functionNames) const; ///< emit static method wrappers
void matlab_make_fragment(FileWriter& file, void matlab_make_fragment(FileWriter& file,
const std::string& toolboxPath, const std::string& toolboxPath,
const std::string& mexFlags) const; ///< emit make fragment for global make script const std::string& mexFlags) const; ///< emit make fragment for global make script

View File

@ -20,6 +20,7 @@
#include <algorithm> #include <algorithm>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <boost/lexical_cast.hpp>
#include "utilities.h" #include "utilities.h"
#include "Constructor.h" #include "Constructor.h"
@ -35,11 +36,11 @@ string Constructor::matlab_wrapper_name(const string& className) const {
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Constructor::matlab_proxy_fragment(FileWriter& file, void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperName,
const string& className, const int id, const ArgumentList args) const { const string& className, const int id, const ArgumentList args) const {
size_t nrArgs = args.size(); size_t nrArgs = args.size();
// check for number of arguments... // check for number of arguments...
file.oss << " if (nargin == " << nrArgs; file.oss << " elseif nargin == " << nrArgs;
if (nrArgs>0) file.oss << " && "; if (nrArgs>0) file.oss << " && ";
// ...and their types // ...and their types
bool first = true; bool first = true;
@ -49,117 +50,48 @@ void Constructor::matlab_proxy_fragment(FileWriter& file,
first=false; first=false;
} }
// emit code for calling constructor // emit code for calling constructor
file.oss << "), obj.self = " << matlab_wrapper_name(className) << "(" << "0," << id; file.oss << "\n obj.self = " << wrapperName << "(" << id;
// emit constructor arguments // emit constructor arguments
for(size_t i=0;i<nrArgs;i++) { for(size_t i=0;i<nrArgs;i++) {
file.oss << ","; file.oss << ",";
file.oss << "varargin{" << i+1 << "}"; file.oss << "varargin{" << i+1 << "}";
} }
file.oss << "); end" << endl; file.oss << ");\n";
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Constructor::matlab_mfile(const string& toolboxPath, const string& qualifiedMatlabName, const ArgumentList args) const { string Constructor::wrapper_fragment(FileWriter& file,
string matlabName = matlab_wrapper_name(qualifiedMatlabName);
// open destination m-file
string wrapperFile = toolboxPath + "/" + matlabName + ".m";
FileWriter file(wrapperFile, verbose_, "%");
// generate code
file.oss << "function result = " << matlabName << "(obj";
if (args.size()) file.oss << "," << args.names();
file.oss << ")" << endl;
file.oss << " error('need to compile " << matlabName << ".cpp');" << endl;
file.oss << "end" << endl;
// close file
file.emit(true);
}
/* ************************************************************************* */
void Constructor::matlab_wrapper(const string& toolboxPath,
const string& cppClassName, const string& cppClassName,
const string& matlabClassName, const string& matlabClassName,
int id,
const vector<string>& using_namespaces, const vector<string>& using_namespaces,
const vector<string>& includes) const { const vector<string>& includes,
string matlabName = matlab_wrapper_name(matlabClassName); const ArgumentList& al) const {
const string matlabName = matlab_wrapper_name(matlabClassName);
const string wrapFunctionName = matlabClassName + "_constructor_" + boost::lexical_cast<string>(id);
// open destination wrapperFile file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
string wrapperFile = toolboxPath + "/" + matlabName + ".cpp"; file.oss << "{\n";
FileWriter file(wrapperFile, verbose_, "//"); file.oss << " mexAtExit(&_deleteAllObjects);\n";
// generate code
generateIncludes(file, name, includes);
generateUsingNamespace(file, using_namespaces); generateUsingNamespace(file, using_namespaces);
//Typedef boost::shared_ptr //Typedef boost::shared_ptr
file.oss << "typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;\n";
file.oss << endl; file.oss << "\n";
//Generate collector
file.oss << "static std::set<Shared*> collector;" << endl;
file.oss << endl;
//Generate cleanup function
file.oss << "void cleanup(void) {" << endl;
file.oss << " for(std::set<Shared*>::iterator iter = collector.begin(); iter != collector.end(); ) {\n";
file.oss << " delete *iter;\n";
file.oss << " collector.erase(iter++);\n";
file.oss << " }\n";
file.oss << "}" << endl;
file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
file.oss << "{" << endl;
//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<int>(in[1]);" << endl << endl;
int i = 0;
BOOST_FOREACH(ArgumentList al, args_list)
{
//Check to see if there will be any arguments and remove {} for consiseness //Check to see if there will be any arguments and remove {} for consiseness
if(al.size()) if(al.size() > 0)
{ al.matlab_unwrap(file); // unwrap arguments
file.oss << " if(nc == " << i <<") {" << endl; file.oss << " Shared *self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl;
al.matlab_unwrap(file, 2); // unwrap arguments, start at 1 file.oss << " collector_" << matlabClassName << ".insert(self);\n";
file.oss << " self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl;
file.oss << " }" << endl;
}
else
{
file.oss << " if(nc == " << i <<")" << endl;
file.oss << " self = new Shared(new " << cppClassName << "(" << al.names() << "));" << endl;
}
i++;
}
//file.oss << " self = construct(nc, in);" << endl;
file.oss << " collector.insert(self);" << endl;
if(verbose_) if(verbose_)
file.oss << " std::cout << \"constructed \" << self << \", size=\" << collector.size() << std::endl;" << endl; file.oss << " std::cout << \"constructed \" << self << \" << std::endl;" << endl;
file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl; file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl;
file.oss << " *reinterpret_cast<Shared**> (mxGetPr(out[0])) = self;" << endl; file.oss << " *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;" << endl;
file.oss << " }" << endl;
file.oss << "}" << endl; file.oss << "}" << endl;
// close file return wrapFunctionName;
file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -48,21 +48,18 @@ struct Constructor {
* Create fragment to select constructor in proxy class, e.g., * Create fragment to select constructor in proxy class, e.g.,
* if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end * if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end
*/ */
void matlab_proxy_fragment(FileWriter& file, void proxy_fragment(FileWriter& file, const std::string& wrapperName,
const std::string& className, const int i, const std::string& className, const int id,
const ArgumentList args) const;
/// m-file
void matlab_mfile(const std::string& toolboxPath,
const std::string& qualifiedMatlabName,
const ArgumentList args) const; const ArgumentList args) const;
/// cpp wrapper /// cpp wrapper
void matlab_wrapper(const std::string& toolboxPath, std::string wrapper_fragment(FileWriter& file,
const std::string& cppClassName, const std::string& cppClassName,
const std::string& matlabClassName, const std::string& matlabClassName,
int id,
const std::vector<std::string>& using_namespaces, const std::vector<std::string>& using_namespaces,
const std::vector<std::string>& includes) const; const std::vector<std::string>& includes,
const ArgumentList& al) const;
/// constructor function /// constructor function
void generate_construct(FileWriter& file, const std::string& cppClassName, void generate_construct(FileWriter& file, const std::string& cppClassName,

View File

@ -19,6 +19,7 @@
#include <fstream> #include <fstream>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <boost/lexical_cast.hpp>
#include "utilities.h" #include "utilities.h"
#include "Deconstructor.h" #include "Deconstructor.h"
@ -33,51 +34,42 @@ string Deconstructor::matlab_wrapper_name(const string& className) const {
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Deconstructor::matlab_mfile(const string& toolboxPath, const string& qualifiedMatlabName) const { void Deconstructor::proxy_fragment(FileWriter& file,
const std::string& wrapperName,
const std::string& qualifiedMatlabName, int id) const {
string matlabName = matlab_wrapper_name(qualifiedMatlabName); file.oss << " function delete(obj)\n";
file.oss << " " << wrapperName << "(" << id << ", obj.self);\n";
// open destination m-file file.oss << " end\n";
string wrapperFile = toolboxPath + "/" + matlabName + ".m";
FileWriter file(wrapperFile, verbose_, "%");
// generate code
file.oss << "function result = " << matlabName << "(obj";
if (args.size()) file.oss << "," << args.names();
file.oss << ")" << endl;
file.oss << " error('need to compile " << matlabName << ".cpp');" << endl;
file.oss << "end" << endl;
// close file
file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Deconstructor::matlab_wrapper(const string& toolboxPath, string Deconstructor::wrapper_fragment(FileWriter& file,
const string& cppClassName, const string& cppClassName,
const string& matlabClassName, const string& matlabClassName,
int id,
const vector<string>& using_namespaces, const vector<string>& includes) const { const vector<string>& using_namespaces, const vector<string>& includes) const {
string matlabName = matlab_wrapper_name(matlabClassName);
// open destination wrapperFile const string matlabName = matlab_wrapper_name(matlabClassName);
string wrapperFile = toolboxPath + "/" + matlabName + ".cpp";
FileWriter file(wrapperFile, verbose_, "//");
// generate code const string wrapFunctionName = matlabClassName + "_deconstructor_" + boost::lexical_cast<string>(id);
//
generateIncludes(file, name, includes);
cout << "Generate includes " << name << endl;
generateUsingNamespace(file, using_namespaces);
file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl; file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
file.oss << "{" << endl; file.oss << "{" << endl;
generateUsingNamespace(file, using_namespaces);
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl;
//Deconstructor takes 1 arg, the mxArray obj //Deconstructor takes 1 arg, the mxArray obj
file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << "1" << ");" << endl; file.oss << " checkArguments(\"" << matlabName << "\",nargout,nargin," << "1" << ");" << endl;
file.oss << " delete_shared_ptr< " << cppClassName << " >(in[0],\"" << matlabClassName << "\");" << endl; file.oss << " Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));\n";
file.oss << " Collector_" << matlabClassName << "::iterator item;\n";
file.oss << " item = collector_" << matlabClassName << ".find(self);\n";
file.oss << " if(item != collector_" << matlabClassName << ".end()) {\n";
file.oss << " delete self;\n";
file.oss << " collector_" << matlabClassName << ".erase(item);\n";
file.oss << " }\n";
file.oss << "}" << endl; file.oss << "}" << endl;
// close file return wrapFunctionName;
file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -46,13 +46,15 @@ struct Deconstructor {
std::string matlab_wrapper_name(const std::string& className) const; std::string matlab_wrapper_name(const std::string& className) const;
/// m-file /// m-file
void matlab_mfile(const std::string& toolboxPath, void proxy_fragment(FileWriter& file,
const std::string& qualifiedMatlabName) const; const std::string& wrapperName,
const std::string& qualifiedMatlabName, int id) const;
/// cpp wrapper /// cpp wrapper
void matlab_wrapper(const std::string& toolboxPath, std::string wrapper_fragment(FileWriter& file,
const std::string& cppClassName, const std::string& cppClassName,
const std::string& matlabClassName, const std::string& matlabClassName,
int id,
const std::vector<std::string>& using_namespaces, const std::vector<std::string>& using_namespaces,
const std::vector<std::string>& includes) const; const std::vector<std::string>& includes) const;
}; };

View File

@ -18,6 +18,7 @@
#include <fstream> #include <fstream>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <boost/lexical_cast.hpp>
#include "Method.h" #include "Method.h"
#include "utilities.h" #include "utilities.h"
@ -26,39 +27,35 @@ using namespace std;
using namespace wrap; using namespace wrap;
/* ************************************************************************* */ /* ************************************************************************* */
void Method::matlab_mfile(const string& classPath) const { void Method::proxy_fragment(FileWriter& file, const std::string& wrapperName, const int id) const {
// open destination m-file string output;
string wrapperFile = classPath + "/" + name + ".m"; if(returnVal.isPair)
FileWriter file(wrapperFile, verbose_, "%"); output = "[ r1 r2 ] = ";
else if(returnVal.category1 == ReturnValue::VOID)
// generate code output = "";
string returnType = returnVal.matlab_returnType(); else
file.oss << "% " << returnType << " = obj." << name << "(" << args.names() << ")" << endl; output = "r = ";
file.oss << "function " << returnType << " = " << name << "(obj"; file.oss << " function " << output << name << "(varargin)\n";
if (args.size()) file.oss << "," << args.names(); file.oss << " " << output << wrapperName << "(" << id << ", varargin{:});\n";
file.oss << ")" << endl; file.oss << " end\n";
file.oss << " error('need to compile " << name << ".cpp');" << endl;
file.oss << "end" << endl;
// close file
file.emit(false);
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Method::matlab_wrapper(const string& classPath, string Method::wrapper_fragment(FileWriter& file,
const string& className,
const string& cppClassName, const string& cppClassName,
const string& matlabClassName, const string& matlabClassName,
const vector<string>& using_namespaces, const std::vector<std::string>& includes) const { int id,
// open destination wrapperFile const vector<string>& using_namespaces) const {
string wrapperFile = classPath + "/" + name + ".cpp";
FileWriter file(wrapperFile, verbose_, "//");
// generate code // generate code
// header const string wrapFunctionName = matlabClassName + "_" + name + "_" + boost::lexical_cast<string>(id);
generateIncludes(file, className, includes);
// call
file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
// start
file.oss << "{\n";
generateUsingNamespace(file, using_namespaces); generateUsingNamespace(file, using_namespaces);
if(returnVal.isPair) if(returnVal.isPair)
@ -73,10 +70,6 @@ void Method::matlab_wrapper(const string& classPath,
file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl;
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << 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
file.oss << "{\n";
// check arguments // check arguments
// extra argument obj -> nargin-1 is passed ! // extra argument obj -> nargin-1 is passed !
@ -103,8 +96,7 @@ void Method::matlab_wrapper(const string& classPath,
// finish // finish
file.oss << "}\n"; file.oss << "}\n";
// close file return wrapFunctionName;
file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -42,13 +42,12 @@ struct Method {
// MATLAB code generation // MATLAB code generation
// classPath is class directory, e.g., ../matlab/@Point2 // classPath is class directory, e.g., ../matlab/@Point2
void matlab_mfile(const std::string& classPath) const; ///< m-file void proxy_fragment(FileWriter& file, const std::string& wrapperName, const int id) const;
void matlab_wrapper(const std::string& classPath, std::string wrapper_fragment(FileWriter& file,
const std::string& className,
const std::string& cppClassName, const std::string& cppClassName,
const std::string& matlabClassname, const std::string& matlabClassname,
const std::vector<std::string>& using_namespaces, int id,
const std::vector<std::string>& includes) const; ///< cpp wrapper const std::vector<std::string>& using_namespaces) const; ///< cpp wrapper
}; };
} // \namespace wrap } // \namespace wrap

View File

@ -56,7 +56,7 @@ Module::Module(const string& interfacePath,
ArgumentList args0, args; ArgumentList args0, args;
vector<string> arg_dup; ///keep track of duplicates vector<string> arg_dup; ///keep track of duplicates
Constructor constructor0(enable_verbose), constructor(enable_verbose); 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); Method method0(enable_verbose), method(enable_verbose);
StaticMethod static_method0(enable_verbose), static_method(enable_verbose); StaticMethod static_method0(enable_verbose), static_method(enable_verbose);
Class cls0(enable_verbose),cls(enable_verbose); Class cls0(enable_verbose),cls(enable_verbose);
@ -193,10 +193,10 @@ Module::Module(const string& interfacePath,
[assign_a(cls.namespaces, namespaces)] [assign_a(cls.namespaces, namespaces)]
[assign_a(cls.using_namespaces, using_namespace_current)] [assign_a(cls.using_namespaces, using_namespace_current)]
[append_a(cls.includes, namespace_includes)] [append_a(cls.includes, namespace_includes)]
//[assign_a(deconstructor.name,cls.name)] [assign_a(deconstructor.name,cls.name)]
//[assign_a(cls.d, deconstructor)] [assign_a(cls.deconstructor, deconstructor)]
[push_back_a(classes,cls)] [push_back_a(classes,cls)]
//[assign_a(deconstructor,deconstructor0)] [assign_a(deconstructor,deconstructor0)]
[assign_a(constructor, constructor0)] [assign_a(constructor, constructor0)]
[assign_a(cls,cls0)]; [assign_a(cls,cls0)];
@ -299,6 +299,16 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
string makeFileName = toolboxPath + "/Makefile"; string makeFileName = toolboxPath + "/Makefile";
FileWriter makeModuleMakefile(makeFileName, verbose, "#"); FileWriter makeModuleMakefile(makeFileName, verbose, "#");
// create the unified .cpp switch file
const string wrapperName = name + "_wrapper";
string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp";
FileWriter wrapperFile(wrapperFileName, verbose, "//");
vector<string> functionNames; // Function names stored by index for switch
wrapperFile.oss << "#include <wrap/matlab.h>\n";
wrapperFile.oss << "#include <map>\n";
wrapperFile.oss << "#include <boost/foreach.hpp>\n";
wrapperFile.oss << "\n";
makeModuleMfile.oss << "echo on" << endl << endl; makeModuleMfile.oss << "echo on" << endl << endl;
makeModuleMfile.oss << "toolboxpath = mfilename('fullpath');" << endl; makeModuleMfile.oss << "toolboxpath = mfilename('fullpath');" << endl;
makeModuleMfile.oss << "delims = find(toolboxpath == '/' | toolboxpath == '\\');" << endl; makeModuleMfile.oss << "delims = find(toolboxpath == '/' | toolboxpath == '\\');" << endl;
@ -333,15 +343,42 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
} }
makeModuleMakefile.oss << "\n\n"; makeModuleMakefile.oss << "\n\n";
// Generate all includes
BOOST_FOREACH(Class cls, classes) {
generateIncludes(wrapperFile, cls.name, cls.includes);
}
wrapperFile.oss << "\n";
// Generate all collectors
BOOST_FOREACH(Class cls, classes) {
const string matlabName = cls.qualifiedName(), cppName = cls.qualifiedName("::");
wrapperFile.oss << "typedef std::set<boost::shared_ptr<" << cppName << ">*> "
<< "Collector_" << matlabName << ";\n";
wrapperFile.oss << "static Collector_" << matlabName <<
" collector_" << matlabName << ";\n";
}
// generate mexAtExit cleanup function
wrapperFile.oss << "void _deleteAllObjects()\n";
wrapperFile.oss << "{\n";
BOOST_FOREACH(Class cls, classes) {
const string matlabName = cls.qualifiedName();
const string cppName = cls.qualifiedName("::");
const string collectorType = "Collector_" + matlabName;
const string collectorName = "collector_" + matlabName;
wrapperFile.oss << " for(" << collectorType << "::iterator iter = " << collectorName << ".begin();\n";
wrapperFile.oss << " iter != " << collectorName << ".end(); ) {\n";
wrapperFile.oss << " delete *iter;\n";
wrapperFile.oss << " " << collectorName << ".erase(iter++);\n";
wrapperFile.oss << " }\n";
}
wrapperFile.oss << "}\n";
// generate proxy classes and wrappers // generate proxy classes and wrappers
BOOST_FOREACH(Class cls, classes) { BOOST_FOREACH(Class cls, classes) {
// create directory if needed
string classPath = toolboxPath + "/@" + cls.qualifiedName();
fs::create_directories(classPath);
// create proxy class // create proxy class
string classFile = classPath + "/" + cls.qualifiedName() + ".m"; string classFile = toolboxPath + "/" + cls.qualifiedName() + ".m";
cls.matlab_proxy(classFile); cls.matlab_proxy(classFile, wrapperName, wrapperFile, functionNames);
// verify all of the function arguments // verify all of the function arguments
//TODO:verifyArguments<ArgumentList>(validTypes, cls.constructor.args_list); //TODO:verifyArguments<ArgumentList>(validTypes, cls.constructor.args_list);
@ -353,12 +390,7 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
verifyReturnTypes<Method>(validTypes, cls.methods); verifyReturnTypes<Method>(validTypes, cls.methods);
// create constructor and method wrappers // create constructor and method wrappers
cls.matlab_constructors(toolboxPath); cls.matlab_static_methods(toolboxPath, wrapperName, wrapperFile, functionNames);
cls.matlab_static_methods(toolboxPath);
cls.matlab_methods(classPath);
// create deconstructor
//cls.matlab_deconstructor(toolboxPath);
// add lines to make m-file // add lines to make m-file
makeModuleMfile.oss << "%% " << cls.qualifiedName() << endl; makeModuleMfile.oss << "%% " << cls.qualifiedName() << endl;
@ -384,6 +416,30 @@ void Module::matlab_code(const string& mexCommand, const string& toolboxPath,
// finish Makefile // finish Makefile
makeModuleMakefile.oss << "\n" << endl; makeModuleMakefile.oss << "\n" << endl;
makeModuleMakefile.emit(true); makeModuleMakefile.emit(true);
// finish wrapper file
finish_wrapper(wrapperFile, functionNames);
wrapperFile.emit(true);
}
/* ************************************************************************* */
void Module::finish_wrapper(FileWriter& file, const std::vector<std::string>& functionNames) const {
file.oss << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
file.oss << "{\n";
file.oss << " mstream mout;\n"; // Send stdout to MATLAB console, see matlab.h
file.oss << " std::streambuf *outbuf = std::cout.rdbuf(&mout);\n\n";
file.oss << " int id = unwrap<int>(in[0]);\n\n";
file.oss << " switch(id) {\n";
for(size_t id = 0; id < functionNames.size(); ++id) {
file.oss << " case " << id << ":\n";
file.oss << " " << functionNames[id] << "(nargout, out, nargin-1, in+1);\n";
file.oss << " break;\n";
}
file.oss << " }\n";
file.oss << "\n";
file.oss << " std::cout.rdbuf(outbuf);\n"; // Restore cout, see matlab.h
file.oss << "}\n";
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -46,6 +46,8 @@ struct Module {
const std::string& mexExt, const std::string& mexExt,
const std::string& headerPath, const std::string& headerPath,
const std::string& mexFlags) const; const std::string& mexFlags) const;
void finish_wrapper(FileWriter& file, const std::vector<std::string>& functionNames) const;
}; };
} // \namespace wrap } // \namespace wrap

View File

@ -49,16 +49,20 @@ string ReturnValue::qualifiedType2(const string& delim) const {
void ReturnValue::wrap_result(FileWriter& file) const { void ReturnValue::wrap_result(FileWriter& file) const {
string cppType1 = qualifiedType1("::"), matlabType1 = qualifiedType1(); string cppType1 = qualifiedType1("::"), matlabType1 = qualifiedType1();
string cppType2 = qualifiedType2("::"), matlabType2 = qualifiedType2(); string cppType2 = qualifiedType2("::"), matlabType2 = qualifiedType2();
const string collectorName1 = "collector_" + matlabType1;
const string collectorName2 = "collector_" + matlabType2;
if (isPair) { if (isPair) {
// first return value in pair // first return value in pair
if (isPtr1) {// if we already have a pointer if (isPtr1) {// if we already have a pointer
file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result.first);" << endl; file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result.first);" << endl;
file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; file.oss << " " << collectorName1 << ".insert(ret);\n";
file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n";
} }
else if (category1 == ReturnValue::CLASS) { // if we are going to make one 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 << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result.first));\n";
file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; file.oss << " " << collectorName1 << ".insert(ret);\n";
file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n";
} }
else // if basis type else // if basis type
file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n"; file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n";
@ -66,22 +70,26 @@ void ReturnValue::wrap_result(FileWriter& file) const {
// second return value in pair // second return value in pair
if (isPtr2) {// if we already have a pointer if (isPtr2) {// if we already have a pointer
file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(result.second);" << endl; file.oss << " Shared" << type2 <<"* ret = new Shared" << type2 << "(result.second);" << endl;
file.oss << " out[1] = wrap_collect_shared_ptr(ret,\"" << matlabType2 << "\");\n"; file.oss << " " << collectorName2 << ".insert(ret);\n";
file.oss << " out[1] = wrap_shared_ptr(ret,\"" << matlabType2 << "\");\n";
} }
else if (category2 == ReturnValue::CLASS) { // if we are going to make one 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 << " Shared" << type2 << "* ret = new Shared" << type2 << "(new " << cppType2 << "(result.first));\n";
file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType2 << "\");\n"; file.oss << " " << collectorName2 << ".insert(ret);\n";
file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType2 << "\");\n";
} }
else else
file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n"; file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n";
} }
else if (isPtr1){ else if (isPtr1){
file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result);" << endl; file.oss << " Shared" << type1 <<"* ret = new Shared" << type1 << "(result);" << endl;
file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; file.oss << " " << collectorName1 << ".insert(ret);\n";
file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n";
} }
else if (category1 == ReturnValue::CLASS){ else if (category1 == ReturnValue::CLASS){
file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result));\n"; file.oss << " Shared" << type1 << "* ret = new Shared" << type1 << "(new " << cppType1 << "(result));\n";
file.oss << " out[0] = wrap_collect_shared_ptr(ret,\"" << matlabType1 << "\");\n"; file.oss << " " << collectorName1 << ".insert(ret);\n";
file.oss << " out[0] = wrap_shared_ptr(ret,\"" << matlabType1 << "\");\n";
} }
else if (matlabType1!="void") else if (matlabType1!="void")
file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n"; file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n";

View File

@ -19,6 +19,7 @@
#include <fstream> #include <fstream>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <boost/lexical_cast.hpp>
#include "StaticMethod.h" #include "StaticMethod.h"
#include "utilities.h" #include "utilities.h"
@ -27,55 +28,51 @@ using namespace std;
using namespace wrap; using namespace wrap;
/* ************************************************************************* */ /* ************************************************************************* */
void StaticMethod::matlab_mfile(const string& toolboxPath, const string& className) const { void StaticMethod::proxy_fragment(const string& toolboxPath, const string& matlabClassName, const std::string& wrapperName, const int id) const {
// open destination m-file const string full_name = matlabClassName + "_" + name;
string full_name = className + "_" + name; FileWriter file(toolboxPath + "/" + full_name + ".m", verbose, "%");
string wrapperFile = toolboxPath + "/" + full_name + ".m";
FileWriter file(wrapperFile, verbose, "%");
// generate code string output;
string returnType = returnVal.matlab_returnType(); if(returnVal.isPair)
file.oss << "function " << returnType << " = " << full_name << "("; output = "[ r1 r2 ] = ";
if (args.size()) file.oss << args.names(); else if(returnVal.category1 == ReturnValue::VOID)
file.oss << ")" << endl; output = "";
file.oss << "% usage: x = " << full_name << "(" << args.names() << ")" << endl; else
file.oss << " error('need to compile " << full_name << ".cpp');" << endl; output = "r = ";
file.oss << "end" << endl; file.oss << "function " << output << full_name << "(varargin)\n";
file.oss << " " << output << wrapperName << "(" << id << ", varargin{:});\n";
file.oss << "end\n";
// close file
file.emit(true); file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */
void StaticMethod::matlab_wrapper(const string& toolboxPath, const string& className, string StaticMethod::wrapper_fragment(FileWriter& file,
const string& matlabClassName, const string& cppClassName, const string& matlabClassName, const string& cppClassName,
const vector<string>& using_namespaces, int id, const vector<string>& using_namespaces) const {
const vector<string>& includes) const {
// open destination wrapperFile
string full_name = matlabClassName + "_" + name;
string wrapperFile = toolboxPath + "/" + full_name + ".cpp";
FileWriter file(wrapperFile, verbose, "//");
// generate code const string full_name = matlabClassName + "_" + name;
const string wrapFunctionName = matlabClassName + "_" + name + "_" + boost::lexical_cast<string>(id);
// header // call
generateIncludes(file, className, includes); file.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
// start
file.oss << "{\n";
generateUsingNamespace(file, using_namespaces); generateUsingNamespace(file, using_namespaces);
if(returnVal.isPair) if(returnVal.isPair)
{ {
if(returnVal.category1 == ReturnValue::CLASS)
file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; 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; file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType2("::") << "> Shared" << returnVal.type2 << ";"<< endl;
} }
else else
if(returnVal.category1 == ReturnValue::CLASS)
file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl; file.oss << " typedef boost::shared_ptr<" << returnVal.qualifiedType1("::") << "> Shared" << returnVal.type1 << ";"<< endl;
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << 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
file.oss << "{\n";
// check arguments // check arguments
// NOTE: for static functions, there is no object passed // NOTE: for static functions, there is no object passed
@ -98,8 +95,7 @@ void StaticMethod::matlab_wrapper(const string& toolboxPath, const string& class
// finish // finish
file.oss << "}\n"; file.oss << "}\n";
// close file return wrapFunctionName;
file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -44,12 +44,13 @@ struct StaticMethod {
// NOTE: static functions are not inside the class, and // NOTE: static functions are not inside the class, and
// are created with [ClassName]_[FunctionName]() format // are created with [ClassName]_[FunctionName]() format
void matlab_mfile(const std::string& toolboxPath, const std::string& className) const; ///< m-file void proxy_fragment(const std::string& toolboxPath, const std::string& matlabClassName,
void matlab_wrapper(const std::string& toolboxPath, const std::string& wrapperName, const int id) const; ///< m-file
const std::string& className, const std::string& matlabClassName, std::string wrapper_fragment(FileWriter& file,
const std::string& matlabClassName,
const std::string& cppClassName, const std::string& cppClassName,
const std::vector<std::string>& using_namespaces, int id,
const std::vector<std::string>& includes) const; ///< cpp wrapper const std::vector<std::string>& using_namespaces) const; ///< cpp wrapper
}; };
} // \namespace wrap } // \namespace wrap

View File

@ -38,6 +38,7 @@ extern "C" {
#include <sstream> #include <sstream>
#include <typeinfo> #include <typeinfo>
#include <set> #include <set>
#include <streambuf>
using namespace std; using namespace std;
using namespace boost; // not usual, but for conciseness of generated code using namespace boost; // not usual, but for conciseness of generated code
@ -54,6 +55,18 @@ using namespace boost; // not usual, but for conciseness of generated code
#define mxUINT32OR64_CLASS mxUINT32_CLASS #define mxUINT32OR64_CLASS mxUINT32_CLASS
#endif #endif
// "Unique" key to signal calling the matlab object constructor with a raw pointer
// Also present in Class.cpp
static const uint64_t ptr_constructor_key =
(uint64_t('G') << 56) |
(uint64_t('T') << 48) |
(uint64_t('S') << 40) |
(uint64_t('A') << 32) |
(uint64_t('M') << 24) |
(uint64_t('p') << 16) |
(uint64_t('t') << 8) |
(uint64_t('r'));
//***************************************************************************** //*****************************************************************************
// Utilities // Utilities
//***************************************************************************** //*****************************************************************************
@ -73,6 +86,22 @@ void checkScalar(const mxArray* array, const char* str) {
mexErrMsgIdAndTxt("wrap: not a scalar in ", str); mexErrMsgIdAndTxt("wrap: not a scalar in ", str);
} }
// Replacement streambuf for cout that writes to the MATLAB console
// Thanks to http://stackoverflow.com/a/249008
class mstream : public std::streambuf {
protected:
virtual std::streamsize xsputn(const char *s, std::streamsize n) {
mexPrintf("%.*s",n,s);
return n;
}
virtual int overflow(int c = EOF) {
if (c != EOF) {
mexPrintf("%.1s",&c);
}
return 1;
}
};
//***************************************************************************** //*****************************************************************************
// Check arguments // Check arguments
//***************************************************************************** //*****************************************************************************
@ -316,25 +345,20 @@ gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) {
dummy arguments to let the constructor know we want an object without dummy arguments to let the constructor know we want an object without
the self property initialized. We then assign the mexhandle to self. the self property initialized. We then assign the mexhandle to self.
*/ */
mxArray* create_object(const char *classname, mxArray* h) { mxArray* create_object(const char *classname, void *pointer) {
mxArray *result; mxArray *result;
mxArray* dummy[13] = {h,h,h,h,h, h,h,h,h,h, h,h,h}; mxArray *input[2];
mexCallMATLAB(1,&result,13,dummy,classname); // First input argument is pointer constructor key
mxSetProperty(result, 0, "self", h); input[0] = mxCreateNumericMatrix(1, 1, mxUINT64_CLASS, mxREAL);
return result; *reinterpret_cast<uint64_t*>(mxGetData(input[0])) = ptr_constructor_key;
} // Second input argument is the pointer
input[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
/* *reinterpret_cast<void**>(mxGetData(input[1])) = pointer;
* Similar to create object, this also collects the shared_ptr in addition // Call special pointer constructor, which sets 'self'
* to creating the dummy object. Mainly used for static constructor methods mexCallMATLAB(1,&result,2,input,classname);
* which don't have direct access to the function. // Deallocate our memory
*/ mxDestroyArray(input[0]);
mxArray* create_collect_object(const char *classname, mxArray* h){ mxDestroyArray(input[1]);
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; return result;
} }
@ -345,18 +369,9 @@ mxArray* create_collect_object(const char *classname, mxArray* h){
*/ */
template <typename Class> template <typename Class>
mxArray* wrap_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) { mxArray* wrap_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) {
mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); // Create actual class object from out pointer
*reinterpret_cast<boost::shared_ptr<Class>**> (mxGetData(mxh)) = shared_ptr; mxArray* result = create_object(classname, shared_ptr);
//return mxh; return result;
return create_object(classname, mxh);
}
template <typename Class>
mxArray* wrap_collect_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *classname) {
mxArray* mxh = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<boost::shared_ptr<Class>**> (mxGetData(mxh)) = shared_ptr;
//return mxh;
return create_collect_object(classname, mxh);
} }
template <typename Class> template <typename Class>

View File

@ -123,7 +123,6 @@ void generateUsingNamespace(FileWriter& file, const vector<string>& using_namesp
/* ************************************************************************* */ /* ************************************************************************* */
void generateIncludes(FileWriter& file, const string& class_name, void generateIncludes(FileWriter& file, const string& class_name,
const vector<string>& includes) { const vector<string>& includes) {
file.oss << "#include <wrap/matlab.h>" << endl;
bool added_include = false; bool added_include = false;
BOOST_FOREACH(const string& s, includes) { BOOST_FOREACH(const string& s, includes) {
if (!s.empty()) { if (!s.empty()) {