Added overload constructor comments to matlab files
parent
f9c3af7e3d
commit
ea70673b36
669
wrap/Class.cpp
669
wrap/Class.cpp
|
@ -1,325 +1,346 @@
|
||||||
/* ----------------------------------------------------------------------------
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||||
* Atlanta, Georgia 30332-0415
|
* Atlanta, Georgia 30332-0415
|
||||||
* All Rights Reserved
|
* All Rights Reserved
|
||||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||||
|
|
||||||
* See LICENSE for the license information
|
* See LICENSE for the license information
|
||||||
|
|
||||||
* -------------------------------------------------------------------------- */
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @file Class.cpp
|
* @file Class.cpp
|
||||||
* @author Frank Dellaert
|
* @author Frank Dellaert
|
||||||
* @author Andrew Melim
|
* @author Andrew Melim
|
||||||
* @author Richard Roberts
|
* @author Richard Roberts
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
//#include <cstdint> // on Linux GCC: fails with error regarding needing C++0x std flags
|
//#include <cstdint> // on Linux GCC: fails with error regarding needing C++0x std flags
|
||||||
//#include <cinttypes> // same failure as above
|
//#include <cinttypes> // same failure as above
|
||||||
#include <stdint.h> // works on Linux GCC
|
#include <stdint.h> // works on Linux GCC
|
||||||
|
|
||||||
#include <boost/foreach.hpp>
|
#include <boost/foreach.hpp>
|
||||||
#include <boost/lexical_cast.hpp>
|
#include <boost/lexical_cast.hpp>
|
||||||
|
|
||||||
#include "Class.h"
|
#include "Class.h"
|
||||||
#include "utilities.h"
|
#include "utilities.h"
|
||||||
#include "Argument.h"
|
#include "Argument.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace wrap;
|
using namespace wrap;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
const TypeAttributesTable& typeAttributes,
|
const TypeAttributesTable& typeAttributes,
|
||||||
FileWriter& wrapperFile, vector<string>& functionNames) const {
|
FileWriter& wrapperFile, vector<string>& functionNames) const {
|
||||||
|
|
||||||
// Create namespace folders
|
// Create namespace folders
|
||||||
createNamespaceStructure(namespaces, toolboxPath);
|
createNamespaceStructure(namespaces, toolboxPath);
|
||||||
|
|
||||||
// open destination classFile
|
// open destination classFile
|
||||||
string classFile = toolboxPath;
|
string classFile = toolboxPath;
|
||||||
if(!namespaces.empty())
|
if(!namespaces.empty())
|
||||||
classFile += "/+" + wrap::qualifiedName("/+", namespaces);
|
classFile += "/+" + wrap::qualifiedName("/+", namespaces);
|
||||||
classFile += "/" + name + ".m";
|
classFile += "/" + name + ".m";
|
||||||
FileWriter proxyFile(classFile, verbose_, "%");
|
FileWriter proxyFile(classFile, verbose_, "%");
|
||||||
|
|
||||||
// get the name of actual matlab object
|
// get the name of actual matlab object
|
||||||
const string matlabQualName = qualifiedName("."), matlabUniqueName = qualifiedName(), cppName = qualifiedName("::");
|
const string matlabQualName = qualifiedName("."), matlabUniqueName = qualifiedName(), cppName = qualifiedName("::");
|
||||||
const string matlabBaseName = wrap::qualifiedName(".", qualifiedParent);
|
const string matlabBaseName = wrap::qualifiedName(".", qualifiedParent);
|
||||||
const string cppBaseName = wrap::qualifiedName("::", qualifiedParent);
|
const string cppBaseName = wrap::qualifiedName("::", qualifiedParent);
|
||||||
|
|
||||||
// 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
|
||||||
const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName;
|
const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName;
|
||||||
proxyFile.oss << "classdef " << name << " < " << parent << endl;
|
comment_fragment(proxyFile);
|
||||||
proxyFile.oss << " properties" << endl;
|
proxyFile.oss << "classdef " << name << " < " << parent << endl;
|
||||||
proxyFile.oss << " ptr_" << matlabUniqueName << " = 0" << endl;
|
proxyFile.oss << " properties" << endl;
|
||||||
proxyFile.oss << " end" << endl;
|
proxyFile.oss << " ptr_" << matlabUniqueName << " = 0" << endl;
|
||||||
proxyFile.oss << " methods" << endl;
|
proxyFile.oss << " end" << endl;
|
||||||
|
proxyFile.oss << " methods" << endl;
|
||||||
// Constructor
|
|
||||||
proxyFile.oss << " function obj = " << name << "(varargin)" << endl;
|
// Constructor
|
||||||
// Special pointer constructors - one in MATLAB to create an object and
|
proxyFile.oss << " function obj = " << name << "(varargin)" << endl;
|
||||||
// assign a pointer returned from a C++ function. In turn this MATLAB
|
// Special pointer constructors - one in MATLAB to create an object and
|
||||||
// constructor calls a special C++ function that just adds the object to
|
// assign a pointer returned from a C++ function. In turn this MATLAB
|
||||||
// its collector. This allows wrapped functions to return objects in
|
// constructor calls a special C++ function that just adds the object to
|
||||||
// other wrap modules - to add these to their collectors the pointer is
|
// its collector. This allows wrapped functions to return objects in
|
||||||
// passed from one C++ module into matlab then back into the other C++
|
// other wrap modules - to add these to their collectors the pointer is
|
||||||
// module.
|
// passed from one C++ module into matlab then back into the other C++
|
||||||
pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName, functionNames);
|
// module.
|
||||||
wrapperFile.oss << "\n";
|
pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName, functionNames);
|
||||||
// Regular constructors
|
wrapperFile.oss << "\n";
|
||||||
BOOST_FOREACH(ArgumentList a, constructor.args_list)
|
// Regular constructors
|
||||||
{
|
BOOST_FOREACH(ArgumentList a, constructor.args_list)
|
||||||
const int id = (int)functionNames.size();
|
{
|
||||||
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), id, a);
|
const int id = (int)functionNames.size();
|
||||||
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(), id, a);
|
||||||
cppName, matlabUniqueName, cppBaseName, id, a);
|
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
||||||
wrapperFile.oss << "\n";
|
cppName, matlabUniqueName, cppBaseName, id, a);
|
||||||
functionNames.push_back(wrapFunctionName);
|
wrapperFile.oss << "\n";
|
||||||
}
|
functionNames.push_back(wrapFunctionName);
|
||||||
proxyFile.oss << " else\n";
|
}
|
||||||
proxyFile.oss << " error('Arguments do not match any overload of " << matlabQualName << " constructor');" << endl;
|
proxyFile.oss << " else\n";
|
||||||
proxyFile.oss << " end\n";
|
proxyFile.oss << " error('Arguments do not match any overload of " << matlabQualName << " constructor');" << endl;
|
||||||
if(!qualifiedParent.empty())
|
proxyFile.oss << " end\n";
|
||||||
proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n";
|
if(!qualifiedParent.empty())
|
||||||
proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n";
|
proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n";
|
||||||
proxyFile.oss << " end\n\n";
|
proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n";
|
||||||
|
proxyFile.oss << " end\n\n";
|
||||||
// Deconstructor
|
|
||||||
{
|
// Deconstructor
|
||||||
const int id = (int)functionNames.size();
|
{
|
||||||
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabUniqueName, id);
|
const int id = (int)functionNames.size();
|
||||||
proxyFile.oss << "\n";
|
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabUniqueName, id);
|
||||||
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, id);
|
proxyFile.oss << "\n";
|
||||||
wrapperFile.oss << "\n";
|
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabUniqueName, id);
|
||||||
functionNames.push_back(functionName);
|
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";
|
proxyFile.oss << " function display(obj), obj.print(''); end\n\n";
|
||||||
|
proxyFile.oss << " function disp(obj), obj.display; end\n\n";
|
||||||
// Methods
|
|
||||||
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
|
// Methods
|
||||||
const Method& m = name_m.second;
|
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
|
||||||
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
const Method& m = name_m.second;
|
||||||
proxyFile.oss << "\n";
|
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
||||||
wrapperFile.oss << "\n";
|
proxyFile.oss << "\n";
|
||||||
}
|
wrapperFile.oss << "\n";
|
||||||
|
}
|
||||||
proxyFile.oss << " end\n";
|
|
||||||
proxyFile.oss << "\n";
|
proxyFile.oss << " end\n";
|
||||||
proxyFile.oss << " methods(Static = true)\n";
|
proxyFile.oss << "\n";
|
||||||
|
proxyFile.oss << " methods(Static = true)\n";
|
||||||
// Static methods
|
|
||||||
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) {
|
// Static methods
|
||||||
const StaticMethod& m = name_m.second;
|
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) {
|
||||||
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
const StaticMethod& m = name_m.second;
|
||||||
proxyFile.oss << "\n";
|
m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames);
|
||||||
wrapperFile.oss << "\n";
|
proxyFile.oss << "\n";
|
||||||
}
|
wrapperFile.oss << "\n";
|
||||||
|
}
|
||||||
proxyFile.oss << " end" << endl;
|
|
||||||
proxyFile.oss << "end" << endl;
|
proxyFile.oss << " end" << endl;
|
||||||
|
proxyFile.oss << "end" << endl;
|
||||||
// Close file
|
|
||||||
proxyFile.emit(true);
|
// Close file
|
||||||
}
|
proxyFile.emit(true);
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
string Class::qualifiedName(const string& delim) const {
|
/* ************************************************************************* */
|
||||||
return ::wrap::qualifiedName(delim, namespaces, name);
|
string Class::qualifiedName(const string& delim) const {
|
||||||
}
|
return ::wrap::qualifiedName(delim, namespaces, name);
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
void Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, vector<string>& functionNames) const {
|
/* ************************************************************************* */
|
||||||
|
void Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, vector<string>& functionNames) const {
|
||||||
const string matlabUniqueName = qualifiedName(), cppName = qualifiedName("::");
|
|
||||||
const string baseCppName = wrap::qualifiedName("::", qualifiedParent);
|
const string matlabUniqueName = qualifiedName(), cppName = qualifiedName("::");
|
||||||
|
const string baseCppName = wrap::qualifiedName("::", qualifiedParent);
|
||||||
const int collectorInsertId = (int)functionNames.size();
|
|
||||||
const string collectorInsertFunctionName = matlabUniqueName + "_collectorInsertAndMakeBase_" + boost::lexical_cast<string>(collectorInsertId);
|
const int collectorInsertId = (int)functionNames.size();
|
||||||
functionNames.push_back(collectorInsertFunctionName);
|
const string collectorInsertFunctionName = matlabUniqueName + "_collectorInsertAndMakeBase_" + boost::lexical_cast<string>(collectorInsertId);
|
||||||
|
functionNames.push_back(collectorInsertFunctionName);
|
||||||
int upcastFromVoidId;
|
|
||||||
string upcastFromVoidFunctionName;
|
int upcastFromVoidId;
|
||||||
if(isVirtual) {
|
string upcastFromVoidFunctionName;
|
||||||
upcastFromVoidId = (int)functionNames.size();
|
if(isVirtual) {
|
||||||
upcastFromVoidFunctionName = matlabUniqueName + "_upcastFromVoid_" + boost::lexical_cast<string>(upcastFromVoidId);
|
upcastFromVoidId = (int)functionNames.size();
|
||||||
functionNames.push_back(upcastFromVoidFunctionName);
|
upcastFromVoidFunctionName = matlabUniqueName + "_upcastFromVoid_" + boost::lexical_cast<string>(upcastFromVoidId);
|
||||||
}
|
functionNames.push_back(upcastFromVoidFunctionName);
|
||||||
|
}
|
||||||
// MATLAB constructor that assigns pointer to matlab object then calls c++
|
|
||||||
// function to add the object to the collector.
|
// MATLAB constructor that assigns pointer to matlab object then calls c++
|
||||||
if(isVirtual) {
|
// function to add the object to the collector.
|
||||||
proxyFile.oss << " if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void')))";
|
if(isVirtual) {
|
||||||
} else {
|
proxyFile.oss << " if (nargin == 2 || (nargin == 3 && strcmp(varargin{3}, 'void')))";
|
||||||
proxyFile.oss << " if nargin == 2";
|
} else {
|
||||||
}
|
proxyFile.oss << " if nargin == 2";
|
||||||
proxyFile.oss << " && isa(varargin{1}, 'uint64') && varargin{1} == uint64(" << ptr_constructor_key << ")\n";
|
}
|
||||||
if(isVirtual) {
|
proxyFile.oss << " && isa(varargin{1}, 'uint64') && varargin{1} == uint64(" << ptr_constructor_key << ")\n";
|
||||||
proxyFile.oss << " if nargin == 2\n";
|
if(isVirtual) {
|
||||||
proxyFile.oss << " my_ptr = varargin{2};\n";
|
proxyFile.oss << " if nargin == 2\n";
|
||||||
proxyFile.oss << " else\n";
|
proxyFile.oss << " my_ptr = varargin{2};\n";
|
||||||
proxyFile.oss << " my_ptr = " << wrapperName << "(" << upcastFromVoidId << ", varargin{2});\n";
|
proxyFile.oss << " else\n";
|
||||||
proxyFile.oss << " end\n";
|
proxyFile.oss << " my_ptr = " << wrapperName << "(" << upcastFromVoidId << ", varargin{2});\n";
|
||||||
} else {
|
proxyFile.oss << " end\n";
|
||||||
proxyFile.oss << " my_ptr = varargin{2};\n";
|
} else {
|
||||||
}
|
proxyFile.oss << " my_ptr = varargin{2};\n";
|
||||||
if(qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back
|
}
|
||||||
proxyFile.oss << " ";
|
if(qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back
|
||||||
else
|
proxyFile.oss << " ";
|
||||||
proxyFile.oss << " base_ptr = ";
|
else
|
||||||
proxyFile.oss << wrapperName << "(" << collectorInsertId << ", my_ptr);\n"; // Call collector insert and get base class ptr
|
proxyFile.oss << " base_ptr = ";
|
||||||
|
proxyFile.oss << wrapperName << "(" << collectorInsertId << ", my_ptr);\n"; // Call collector insert and get base class ptr
|
||||||
// C++ function to add pointer from MATLAB to collector. The pointer always
|
|
||||||
// comes from a C++ return value; this mechanism allows the object to be added
|
// C++ function to add pointer from MATLAB to collector. The pointer always
|
||||||
// to a collector in a different wrap module. If this class has a base class,
|
// comes from a C++ return value; this mechanism allows the object to be added
|
||||||
// a new pointer to the base class is allocated and returned.
|
// to a collector in a different wrap module. If this class has a base class,
|
||||||
wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
// a new pointer to the base class is allocated and returned.
|
||||||
wrapperFile.oss << "{\n";
|
wrapperFile.oss << "void " << collectorInsertFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
||||||
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
|
wrapperFile.oss << "{\n";
|
||||||
// Typedef boost::shared_ptr
|
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
|
||||||
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
|
// Typedef boost::shared_ptr
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
|
||||||
// Get self pointer passed in
|
wrapperFile.oss << "\n";
|
||||||
wrapperFile.oss << " Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));\n";
|
// Get self pointer passed in
|
||||||
// Add to collector
|
wrapperFile.oss << " Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));\n";
|
||||||
wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n";
|
// Add to collector
|
||||||
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
|
wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n";
|
||||||
if(!qualifiedParent.empty()) {
|
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
|
||||||
wrapperFile.oss << "\n";
|
if(!qualifiedParent.empty()) {
|
||||||
wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n";
|
wrapperFile.oss << "\n";
|
||||||
wrapperFile.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
|
wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n";
|
||||||
wrapperFile.oss << " *reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);\n";
|
wrapperFile.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
|
||||||
}
|
wrapperFile.oss << " *reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);\n";
|
||||||
wrapperFile.oss << "}\n";
|
}
|
||||||
|
wrapperFile.oss << "}\n";
|
||||||
// If this is a virtual function, C++ function to dynamic upcast it from a
|
|
||||||
// shared_ptr<void>. This mechanism allows automatic dynamic creation of the
|
// If this is a virtual function, C++ function to dynamic upcast it from a
|
||||||
// real underlying derived-most class when a C++ method returns a virtual
|
// shared_ptr<void>. This mechanism allows automatic dynamic creation of the
|
||||||
// base class.
|
// real underlying derived-most class when a C++ method returns a virtual
|
||||||
if(isVirtual)
|
// base class.
|
||||||
wrapperFile.oss <<
|
if(isVirtual)
|
||||||
"\n"
|
wrapperFile.oss <<
|
||||||
"void " << upcastFromVoidFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {\n"
|
"\n"
|
||||||
" mexAtExit(&_deleteAllObjects);\n"
|
"void " << upcastFromVoidFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {\n"
|
||||||
" typedef boost::shared_ptr<" << cppName << "> Shared;\n"
|
" mexAtExit(&_deleteAllObjects);\n"
|
||||||
" boost::shared_ptr<void> *asVoid = *reinterpret_cast<boost::shared_ptr<void>**> (mxGetData(in[0]));\n"
|
" typedef boost::shared_ptr<" << cppName << "> Shared;\n"
|
||||||
" out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"
|
" boost::shared_ptr<void> *asVoid = *reinterpret_cast<boost::shared_ptr<void>**> (mxGetData(in[0]));\n"
|
||||||
" Shared *self = new Shared(boost::static_pointer_cast<" << cppName << ">(*asVoid));\n"
|
" out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"
|
||||||
" *reinterpret_cast<Shared**>(mxGetData(out[0])) = self;\n"
|
" Shared *self = new Shared(boost::static_pointer_cast<" << cppName << ">(*asVoid));\n"
|
||||||
"}\n";
|
" *reinterpret_cast<Shared**>(mxGetData(out[0])) = self;\n"
|
||||||
}
|
"}\n";
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
vector<ArgumentList> expandArgumentListsTemplate(const vector<ArgumentList>& argLists, const string& templateArg, const vector<string>& instName, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) {
|
/* ************************************************************************* */
|
||||||
vector<ArgumentList> result;
|
vector<ArgumentList> expandArgumentListsTemplate(const vector<ArgumentList>& argLists, const string& templateArg, const vector<string>& instName, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) {
|
||||||
BOOST_FOREACH(const ArgumentList& argList, argLists) {
|
vector<ArgumentList> result;
|
||||||
ArgumentList instArgList;
|
BOOST_FOREACH(const ArgumentList& argList, argLists) {
|
||||||
BOOST_FOREACH(const Argument& arg, argList) {
|
ArgumentList instArgList;
|
||||||
Argument instArg = arg;
|
BOOST_FOREACH(const Argument& arg, argList) {
|
||||||
if(arg.type == templateArg) {
|
Argument instArg = arg;
|
||||||
instArg.namespaces.assign(instName.begin(), instName.end()-1);
|
if(arg.type == templateArg) {
|
||||||
instArg.type = instName.back();
|
instArg.namespaces.assign(instName.begin(), instName.end()-1);
|
||||||
} else if(arg.type == "This") {
|
instArg.type = instName.back();
|
||||||
instArg.namespaces.assign(expandedClassNamespace.begin(), expandedClassNamespace.end());
|
} else if(arg.type == "This") {
|
||||||
instArg.type = expandedClassName;
|
instArg.namespaces.assign(expandedClassNamespace.begin(), expandedClassNamespace.end());
|
||||||
}
|
instArg.type = expandedClassName;
|
||||||
instArgList.push_back(instArg);
|
}
|
||||||
}
|
instArgList.push_back(instArg);
|
||||||
result.push_back(instArgList);
|
}
|
||||||
}
|
result.push_back(instArgList);
|
||||||
return result;
|
}
|
||||||
}
|
return result;
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
template<class METHOD>
|
/* ************************************************************************* */
|
||||||
map<string, METHOD> expandMethodTemplate(const map<string, METHOD>& methods, const string& templateArg, const vector<string>& instName, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) {
|
template<class METHOD>
|
||||||
map<string, METHOD> result;
|
map<string, METHOD> expandMethodTemplate(const map<string, METHOD>& methods, const string& templateArg, const vector<string>& instName, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) {
|
||||||
typedef pair<const string, METHOD> Name_Method;
|
map<string, METHOD> result;
|
||||||
BOOST_FOREACH(const Name_Method& name_method, methods) {
|
typedef pair<const string, METHOD> Name_Method;
|
||||||
const METHOD& method = name_method.second;
|
BOOST_FOREACH(const Name_Method& name_method, methods) {
|
||||||
METHOD instMethod = method;
|
const METHOD& method = name_method.second;
|
||||||
instMethod.argLists = expandArgumentListsTemplate(method.argLists, templateArg, instName, expandedClassNamespace, expandedClassName);
|
METHOD instMethod = method;
|
||||||
instMethod.returnVals.clear();
|
instMethod.argLists = expandArgumentListsTemplate(method.argLists, templateArg, instName, expandedClassNamespace, expandedClassName);
|
||||||
BOOST_FOREACH(const ReturnValue& retVal, method.returnVals) {
|
instMethod.returnVals.clear();
|
||||||
ReturnValue instRetVal = retVal;
|
BOOST_FOREACH(const ReturnValue& retVal, method.returnVals) {
|
||||||
if(retVal.type1 == templateArg) {
|
ReturnValue instRetVal = retVal;
|
||||||
instRetVal.namespaces1.assign(instName.begin(), instName.end()-1);
|
if(retVal.type1 == templateArg) {
|
||||||
instRetVal.type1 = instName.back();
|
instRetVal.namespaces1.assign(instName.begin(), instName.end()-1);
|
||||||
} else if(retVal.type1 == "This") {
|
instRetVal.type1 = instName.back();
|
||||||
instRetVal.namespaces1.assign(expandedClassNamespace.begin(), expandedClassNamespace.end());
|
} else if(retVal.type1 == "This") {
|
||||||
instRetVal.type1 = expandedClassName;
|
instRetVal.namespaces1.assign(expandedClassNamespace.begin(), expandedClassNamespace.end());
|
||||||
}
|
instRetVal.type1 = expandedClassName;
|
||||||
if(retVal.type2 == templateArg) {
|
}
|
||||||
instRetVal.namespaces2.assign(instName.begin(), instName.end()-1);
|
if(retVal.type2 == templateArg) {
|
||||||
instRetVal.type2 = instName.back();
|
instRetVal.namespaces2.assign(instName.begin(), instName.end()-1);
|
||||||
} else if(retVal.type1 == "This") {
|
instRetVal.type2 = instName.back();
|
||||||
instRetVal.namespaces2.assign(expandedClassNamespace.begin(), expandedClassNamespace.end());
|
} else if(retVal.type1 == "This") {
|
||||||
instRetVal.type2 = expandedClassName;
|
instRetVal.namespaces2.assign(expandedClassNamespace.begin(), expandedClassNamespace.end());
|
||||||
}
|
instRetVal.type2 = expandedClassName;
|
||||||
instMethod.returnVals.push_back(instRetVal);
|
}
|
||||||
}
|
instMethod.returnVals.push_back(instRetVal);
|
||||||
result.insert(make_pair(name_method.first, instMethod));
|
}
|
||||||
}
|
result.insert(make_pair(name_method.first, instMethod));
|
||||||
return result;
|
}
|
||||||
}
|
return result;
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
Class expandClassTemplate(const Class& cls, const string& templateArg, const vector<string>& instName, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) {
|
/* ************************************************************************* */
|
||||||
Class inst;
|
Class expandClassTemplate(const Class& cls, const string& templateArg, const vector<string>& instName, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) {
|
||||||
inst.name = cls.name;
|
Class inst;
|
||||||
inst.templateArgs = cls.templateArgs;
|
inst.name = cls.name;
|
||||||
inst.typedefName = cls.typedefName;
|
inst.templateArgs = cls.templateArgs;
|
||||||
inst.isVirtual = cls.isVirtual;
|
inst.typedefName = cls.typedefName;
|
||||||
inst.qualifiedParent = cls.qualifiedParent;
|
inst.isVirtual = cls.isVirtual;
|
||||||
inst.methods = expandMethodTemplate(cls.methods, templateArg, instName, expandedClassNamespace, expandedClassName);
|
inst.qualifiedParent = cls.qualifiedParent;
|
||||||
inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName, expandedClassNamespace, expandedClassName);
|
inst.methods = expandMethodTemplate(cls.methods, templateArg, instName, expandedClassNamespace, expandedClassName);
|
||||||
inst.namespaces = cls.namespaces;
|
inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName, expandedClassNamespace, expandedClassName);
|
||||||
inst.constructor = cls.constructor;
|
inst.namespaces = cls.namespaces;
|
||||||
inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName, expandedClassNamespace, expandedClassName);
|
inst.constructor = cls.constructor;
|
||||||
inst.constructor.name = inst.name;
|
inst.constructor.args_list = expandArgumentListsTemplate(cls.constructor.args_list, templateArg, instName, expandedClassNamespace, expandedClassName);
|
||||||
inst.deconstructor = cls.deconstructor;
|
inst.constructor.name = inst.name;
|
||||||
inst.deconstructor.name = inst.name;
|
inst.deconstructor = cls.deconstructor;
|
||||||
inst.verbose_ = cls.verbose_;
|
inst.deconstructor.name = inst.name;
|
||||||
return inst;
|
inst.verbose_ = cls.verbose_;
|
||||||
}
|
return inst;
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
vector<Class> Class::expandTemplate(const string& templateArg, const vector<vector<string> >& instantiations) const {
|
/* ************************************************************************* */
|
||||||
vector<Class> result;
|
vector<Class> Class::expandTemplate(const string& templateArg, const vector<vector<string> >& instantiations) const {
|
||||||
BOOST_FOREACH(const vector<string>& instName, instantiations) {
|
vector<Class> result;
|
||||||
const string expandedName = name + instName.back();
|
BOOST_FOREACH(const vector<string>& instName, instantiations) {
|
||||||
Class inst = expandClassTemplate(*this, templateArg, instName, this->namespaces, expandedName);
|
const string expandedName = name + instName.back();
|
||||||
inst.name = expandedName;
|
Class inst = expandClassTemplate(*this, templateArg, instName, this->namespaces, expandedName);
|
||||||
inst.templateArgs.clear();
|
inst.name = expandedName;
|
||||||
inst.typedefName = qualifiedName("::") + "<" + wrap::qualifiedName("::", instName) + ">";
|
inst.templateArgs.clear();
|
||||||
result.push_back(inst);
|
inst.typedefName = qualifiedName("::") + "<" + wrap::qualifiedName("::", instName) + ">";
|
||||||
}
|
result.push_back(inst);
|
||||||
return result;
|
}
|
||||||
}
|
return result;
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
Class Class::expandTemplate(const string& templateArg, const vector<string>& instantiation, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) const {
|
/* ************************************************************************* */
|
||||||
return expandClassTemplate(*this, templateArg, instantiation, expandedClassNamespace, expandedClassName);
|
Class Class::expandTemplate(const string& templateArg, const vector<string>& instantiation, const std::vector<string>& expandedClassNamespace, const string& expandedClassName) const {
|
||||||
}
|
return expandClassTemplate(*this, templateArg, instantiation, expandedClassNamespace, expandedClassName);
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
std::string Class::getTypedef() const {
|
/* ************************************************************************* */
|
||||||
string result;
|
std::string Class::getTypedef() const {
|
||||||
BOOST_FOREACH(const string& namesp, namespaces) {
|
string result;
|
||||||
result += ("namespace " + namesp + " { ");
|
BOOST_FOREACH(const string& namesp, namespaces) {
|
||||||
}
|
result += ("namespace " + namesp + " { ");
|
||||||
result += ("typedef " + typedefName + " " + name + ";");
|
}
|
||||||
for (size_t i = 0; i<namespaces.size(); ++i) {
|
result += ("typedef " + typedefName + " " + name + ";");
|
||||||
result += " }";
|
for (size_t i = 0; i<namespaces.size(); ++i) {
|
||||||
}
|
result += " }";
|
||||||
return result;
|
}
|
||||||
}
|
return result;
|
||||||
|
}
|
||||||
/* ************************************************************************* */
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
||||||
|
void Class::comment_fragment(FileWriter& proxyFile) const
|
||||||
|
{
|
||||||
|
proxyFile.oss << "%%" << " --Overloads--" << endl;
|
||||||
|
BOOST_FOREACH(ArgumentList argList, constructor.args_list)
|
||||||
|
{
|
||||||
|
proxyFile.oss << "%" << name << "(";
|
||||||
|
int i = 0;
|
||||||
|
BOOST_FOREACH(const Argument& arg, argList)
|
||||||
|
{
|
||||||
|
if(i != argList.size()-1)
|
||||||
|
proxyFile.oss << arg.type << " " << arg.name << ", ";
|
||||||
|
else
|
||||||
|
proxyFile.oss << arg.type << " " << arg.name;
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
proxyFile.oss << ")" << endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -62,8 +62,10 @@ struct Class {
|
||||||
// The typedef line for this class, if this class is a typedef, otherwise returns an empty string.
|
// The typedef line for this class, if this class is a typedef, otherwise returns an empty string.
|
||||||
std::string getTypedef() const;
|
std::string getTypedef() const;
|
||||||
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector<std::string>& functionNames) const;
|
void pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector<std::string>& functionNames) const;
|
||||||
|
void comment_fragment(FileWriter& proxyFile) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
@ -38,10 +38,6 @@ void FileWriter::emit(bool add_header, bool force_overwrite) const {
|
||||||
ofstream ofs(filename_.c_str(), ios::binary); // Binary to use LF line endings instead of CRLF
|
ofstream ofs(filename_.c_str(), ios::binary); // Binary to use LF line endings instead of CRLF
|
||||||
if (!ofs) throw CantOpenFile(filename_);
|
if (!ofs) throw CantOpenFile(filename_);
|
||||||
|
|
||||||
// header
|
|
||||||
if (add_header)
|
|
||||||
ofs << comment_str_ << " automatically generated by wrap" << endl;
|
|
||||||
|
|
||||||
// dump in stringstream
|
// dump in stringstream
|
||||||
ofs << new_contents;
|
ofs << new_contents;
|
||||||
ofs.close();
|
ofs.close();
|
||||||
|
|
Loading…
Reference in New Issue