Major re-factor, but I think this will fix everything
commit
d9e8ec400b
|
@ -28,12 +28,30 @@
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace wrap;
|
using namespace wrap;
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
Argument Argument::expandTemplate(const TemplateSubstitution& ts) const {
|
||||||
|
Argument instArg = *this;
|
||||||
|
instArg.type = ts(type);
|
||||||
|
return instArg;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
ArgumentList ArgumentList::expandTemplate(const TemplateSubstitution& ts) const {
|
||||||
|
ArgumentList instArgList;
|
||||||
|
BOOST_FOREACH(const Argument& arg, *this) {
|
||||||
|
Argument instArg = arg.expandTemplate(ts);
|
||||||
|
instArgList.push_back(instArg);
|
||||||
|
}
|
||||||
|
return instArgList;
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string Argument::matlabClass(const string& delim) const {
|
string Argument::matlabClass(const string& delim) const {
|
||||||
string result;
|
string result;
|
||||||
BOOST_FOREACH(const string& ns, type.namespaces)
|
BOOST_FOREACH(const string& ns, type.namespaces)
|
||||||
result += ns + delim;
|
result += ns + delim;
|
||||||
if (type.name == "string" || type.name == "unsigned char" || type.name == "char")
|
if (type.name == "string" || type.name == "unsigned char"
|
||||||
|
|| type.name == "char")
|
||||||
return result + "char";
|
return result + "char";
|
||||||
if (type.name == "Vector" || type.name == "Matrix")
|
if (type.name == "Vector" || type.name == "Matrix")
|
||||||
return result + "double";
|
return result + "double";
|
||||||
|
@ -46,8 +64,9 @@ string Argument::matlabClass(const string& delim) const {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
bool Argument::isScalar() const {
|
bool Argument::isScalar() const {
|
||||||
return (type.name == "bool" || type.name == "char" || type.name == "unsigned char"
|
return (type.name == "bool" || type.name == "char"
|
||||||
|| type.name == "int" || type.name == "size_t" || type.name == "double");
|
|| type.name == "unsigned char" || type.name == "int"
|
||||||
|
|| type.name == "size_t" || type.name == "double");
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -128,7 +147,8 @@ string ArgumentList::names() const {
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
bool ArgumentList::allScalar() const {
|
bool ArgumentList::allScalar() const {
|
||||||
BOOST_FOREACH(Argument arg, *this)
|
BOOST_FOREACH(Argument arg, *this)
|
||||||
if (!arg.isScalar()) return false;
|
if (!arg.isScalar())
|
||||||
|
return false;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Qualified.h"
|
#include "TemplateSubstitution.h"
|
||||||
#include "FileWriter.h"
|
#include "FileWriter.h"
|
||||||
#include "ReturnValue.h"
|
#include "ReturnValue.h"
|
||||||
|
|
||||||
|
@ -35,6 +35,8 @@ struct Argument {
|
||||||
is_const(false), is_ref(false), is_ptr(false) {
|
is_const(false), is_ref(false), is_ptr(false) {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Argument expandTemplate(const TemplateSubstitution& ts) const;
|
||||||
|
|
||||||
/// return MATLAB class for use in isa(x,class)
|
/// return MATLAB class for use in isa(x,class)
|
||||||
std::string matlabClass(const std::string& delim = "") const;
|
std::string matlabClass(const std::string& delim = "") const;
|
||||||
|
|
||||||
|
@ -43,6 +45,13 @@ struct Argument {
|
||||||
|
|
||||||
/// MATLAB code generation, MATLAB to C++
|
/// MATLAB code generation, MATLAB to C++
|
||||||
void matlab_unwrap(FileWriter& file, const std::string& matlabName) const;
|
void matlab_unwrap(FileWriter& file, const std::string& matlabName) const;
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os, const Argument& arg) {
|
||||||
|
os << (arg.is_const ? "const " : "") << arg.type << (arg.is_ptr ? "*" : "")
|
||||||
|
<< (arg.is_ref ? "&" : "");
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Argument list is just a container with Arguments
|
/// Argument list is just a container with Arguments
|
||||||
|
@ -60,6 +69,8 @@ struct ArgumentList: public std::vector<Argument> {
|
||||||
/// Check if all arguments scalar
|
/// Check if all arguments scalar
|
||||||
bool allScalar() const;
|
bool allScalar() const;
|
||||||
|
|
||||||
|
ArgumentList expandTemplate(const TemplateSubstitution& ts) const;
|
||||||
|
|
||||||
// MATLAB code generation:
|
// MATLAB code generation:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -93,25 +104,30 @@ struct ArgumentList: public std::vector<Argument> {
|
||||||
* @param wrapperName of method or function
|
* @param wrapperName of method or function
|
||||||
* @param staticMethod flag to emit "this" in call
|
* @param staticMethod flag to emit "this" in call
|
||||||
*/
|
*/
|
||||||
void emit_conditional_call(FileWriter& proxyFile, const ReturnValue& returnVal,
|
void emit_conditional_call(FileWriter& proxyFile,
|
||||||
const std::string& wrapperName, int id, bool staticMethod = false) const;
|
const ReturnValue& returnVal, const std::string& wrapperName, int id,
|
||||||
|
bool staticMethod = false) const;
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os,
|
||||||
|
const ArgumentList& argList) {
|
||||||
|
os << "(";
|
||||||
|
if (argList.size() > 0)
|
||||||
|
os << argList.front();
|
||||||
|
if (argList.size() > 1)
|
||||||
|
for (size_t i = 1; i < argList.size(); i++)
|
||||||
|
os << ", " << argList[i];
|
||||||
|
os << ")";
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
template<class T>
|
template<class T>
|
||||||
inline void verifyArguments(const std::vector<std::string>& validArgs,
|
inline void verifyArguments(const std::vector<std::string>& validArgs,
|
||||||
const std::map<std::string, T>& vt) {
|
const std::map<std::string, T>& vt) {
|
||||||
typedef typename std::map<std::string, T>::value_type NamedMethod;
|
typedef typename std::map<std::string, T>::value_type NamedMethod;
|
||||||
BOOST_FOREACH(const NamedMethod& namedMethod, vt) {
|
BOOST_FOREACH(const NamedMethod& namedMethod, vt)
|
||||||
const T& t = namedMethod.second;
|
namedMethod.second.verifyArguments(validArgs);
|
||||||
BOOST_FOREACH(const ArgumentList& argList, t.argLists) {
|
|
||||||
BOOST_FOREACH(Argument arg, argList) {
|
|
||||||
std::string fullType = arg.type.qualifiedName("::");
|
|
||||||
if (find(validArgs.begin(), validArgs.end(), fullType)
|
|
||||||
== validArgs.end())
|
|
||||||
throw DependencyMissing(fullType, t.name);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
149
wrap/Class.cpp
149
wrap/Class.cpp
|
@ -33,7 +33,7 @@ using namespace std;
|
||||||
using namespace wrap;
|
using namespace wrap;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
|
||||||
const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile,
|
const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile,
|
||||||
vector<string>& functionNames) const {
|
vector<string>& functionNames) const {
|
||||||
|
|
||||||
|
@ -73,13 +73,15 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName,
|
pointer_constructor_fragments(proxyFile, wrapperFile, wrapperName,
|
||||||
functionNames);
|
functionNames);
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
|
|
||||||
// Regular constructors
|
// Regular constructors
|
||||||
BOOST_FOREACH(ArgumentList a, constructor.args_list) {
|
for (size_t i = 0; i < constructor.nrOverloads(); i++) {
|
||||||
|
ArgumentList args = constructor.argumentList(i);
|
||||||
const int id = (int) functionNames.size();
|
const int id = (int) functionNames.size();
|
||||||
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(),
|
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(),
|
||||||
id, a);
|
id, args);
|
||||||
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
||||||
cppName, matlabUniqueName, cppBaseName, id, a);
|
cppName, matlabUniqueName, cppBaseName, id, args);
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
functionNames.push_back(wrapFunctionName);
|
functionNames.push_back(wrapFunctionName);
|
||||||
}
|
}
|
||||||
|
@ -144,7 +146,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName,
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Class::pointer_constructor_fragments(FileWriter& proxyFile,
|
void Class::pointer_constructor_fragments(FileWriter& proxyFile,
|
||||||
FileWriter& wrapperFile, const string& wrapperName,
|
FileWriter& wrapperFile, Str wrapperName,
|
||||||
vector<string>& functionNames) const {
|
vector<string>& functionNames) const {
|
||||||
|
|
||||||
const string matlabUniqueName = qualifiedName();
|
const string matlabUniqueName = qualifiedName();
|
||||||
|
@ -240,85 +242,24 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
static vector<ArgumentList> expandArgumentListsTemplate(
|
Class Class::expandTemplate(const TemplateSubstitution& ts) const {
|
||||||
const vector<ArgumentList>& argLists, const string& templateArg,
|
|
||||||
const Qualified& qualifiedType, const Qualified& expandedClass) {
|
|
||||||
vector<ArgumentList> result;
|
|
||||||
BOOST_FOREACH(const ArgumentList& argList, argLists) {
|
|
||||||
ArgumentList instArgList;
|
|
||||||
BOOST_FOREACH(const Argument& arg, argList) {
|
|
||||||
Argument instArg = arg;
|
|
||||||
if (arg.type.name == templateArg) {
|
|
||||||
instArg.type = qualifiedType;
|
|
||||||
} else if (arg.type.name == "This") {
|
|
||||||
instArg.type = expandedClass;
|
|
||||||
}
|
|
||||||
instArgList.push_back(instArg);
|
|
||||||
}
|
|
||||||
result.push_back(instArgList);
|
|
||||||
}
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
// TODO, Method, StaticMethod, and GlobalFunction should have common base ?
|
|
||||||
template<class METHOD>
|
|
||||||
METHOD expandMethodTemplate(const METHOD& method, const string& templateArg,
|
|
||||||
const Qualified& qualifiedType, const Qualified& expandedClass) {
|
|
||||||
// Create new instance
|
|
||||||
METHOD instMethod = method;
|
|
||||||
// substitute template in arguments
|
|
||||||
instMethod.argLists = expandArgumentListsTemplate(method.argLists,
|
|
||||||
templateArg, qualifiedType, expandedClass);
|
|
||||||
// do the same for return types
|
|
||||||
instMethod.returnVals.clear();
|
|
||||||
BOOST_FOREACH(const ReturnValue& retVal, method.returnVals) {
|
|
||||||
ReturnValue instRetVal = retVal.substituteTemplate(templateArg,
|
|
||||||
qualifiedType, expandedClass);
|
|
||||||
instMethod.returnVals.push_back(instRetVal);
|
|
||||||
}
|
|
||||||
// return new method
|
|
||||||
return instMethod;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
template<class METHOD>
|
|
||||||
static map<string, METHOD> expandMethodTemplate(
|
|
||||||
const map<string, METHOD>& methods, const string& templateArg,
|
|
||||||
const Qualified& qualifiedType, const Qualified& expandedClass) {
|
|
||||||
map<string, METHOD> result;
|
|
||||||
typedef pair<const string, METHOD> NamedMethod;
|
|
||||||
BOOST_FOREACH(NamedMethod namedMethod, methods) {
|
|
||||||
namedMethod.second = expandMethodTemplate(namedMethod.second, templateArg,
|
|
||||||
qualifiedType, expandedClass);
|
|
||||||
result.insert(namedMethod);
|
|
||||||
}
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
Class Class::expandTemplate(const string& templateArg,
|
|
||||||
const Qualified& instName, const Qualified& expandedClass) const {
|
|
||||||
Class inst = *this;
|
Class inst = *this;
|
||||||
inst.methods = expandMethodTemplate(methods, templateArg, instName,
|
inst.methods = expandMethodTemplate(methods, ts);
|
||||||
expandedClass);
|
inst.static_methods = expandMethodTemplate(static_methods, ts);
|
||||||
inst.static_methods = expandMethodTemplate(static_methods, templateArg,
|
inst.constructor = constructor.expandTemplate(ts);
|
||||||
instName, expandedClass);
|
|
||||||
inst.constructor.args_list = expandArgumentListsTemplate(
|
|
||||||
constructor.args_list, templateArg, instName, expandedClass);
|
|
||||||
inst.constructor.name = inst.name;
|
|
||||||
inst.deconstructor.name = inst.name;
|
inst.deconstructor.name = inst.name;
|
||||||
return inst;
|
return inst;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
vector<Class> Class::expandTemplate(const string& templateArg,
|
vector<Class> Class::expandTemplate(Str templateArg,
|
||||||
const vector<Qualified>& instantiations) const {
|
const vector<Qualified>& instantiations) const {
|
||||||
vector<Class> result;
|
vector<Class> result;
|
||||||
BOOST_FOREACH(const Qualified& instName, instantiations) {
|
BOOST_FOREACH(const Qualified& instName, instantiations) {
|
||||||
Qualified expandedClass = (Qualified) (*this);
|
Qualified expandedClass = (Qualified) (*this);
|
||||||
expandedClass.name += instName.name;
|
expandedClass.name += instName.name;
|
||||||
Class inst = expandTemplate(templateArg, instName, expandedClass);
|
const TemplateSubstitution ts(templateArg, instName, expandedClass);
|
||||||
|
Class inst = expandTemplate(ts);
|
||||||
inst.name = expandedClass.name;
|
inst.name = expandedClass.name;
|
||||||
inst.templateArgs.clear();
|
inst.templateArgs.clear();
|
||||||
inst.typedefName = qualifiedName("::") + "<" + instName.qualifiedName("::")
|
inst.typedefName = qualifiedName("::") + "<" + instName.qualifiedName("::")
|
||||||
|
@ -329,24 +270,29 @@ vector<Class> Class::expandTemplate(const string& templateArg,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Class::addMethod(bool verbose, bool is_const, const string& name,
|
void Class::addMethod(bool verbose, bool is_const, Str methodName,
|
||||||
const ArgumentList& args, const ReturnValue& retVal,
|
const ArgumentList& argumentList, const ReturnValue& returnValue,
|
||||||
const string& templateArgName, const vector<Qualified>& templateArgValues) {
|
Str templateArgName, const vector<Qualified>& templateArgValues) {
|
||||||
// Check if templated
|
// Check if templated
|
||||||
if (!templateArgName.empty() && templateArgValues.size() > 0) {
|
if (!templateArgName.empty() && templateArgValues.size() > 0) {
|
||||||
// Create method to expand
|
// Create method to expand
|
||||||
Method method;
|
|
||||||
method.addOverload(verbose, is_const, name, args, retVal);
|
|
||||||
// For all values of the template argument, create a new method
|
// For all values of the template argument, create a new method
|
||||||
BOOST_FOREACH(const Qualified& instName, templateArgValues) {
|
BOOST_FOREACH(const Qualified& instName, templateArgValues) {
|
||||||
Method expanded = //
|
const TemplateSubstitution ts(templateArgName, instName, this->name);
|
||||||
expandMethodTemplate(method, templateArgName, instName, *this);
|
// substitute template in arguments
|
||||||
methods[name].addOverload(verbose, is_const, name, expanded.argLists[0],
|
ArgumentList expandedArgs = argumentList.expandTemplate(ts);
|
||||||
expanded.returnVals[0], instName);
|
// do the same for return type
|
||||||
|
ReturnValue expandedRetVal = returnValue.expandTemplate(ts);
|
||||||
|
// Now stick in new overload stack with expandedMethodName key
|
||||||
|
// but note we use the same, unexpanded methodName in overload
|
||||||
|
string expandedMethodName = methodName + instName.name;
|
||||||
|
methods[expandedMethodName].addOverload(verbose, is_const, methodName,
|
||||||
|
expandedArgs, expandedRetVal, instName);
|
||||||
}
|
}
|
||||||
} else
|
} else
|
||||||
// just add overload
|
// just add overload
|
||||||
methods[name].addOverload(verbose, is_const, name, args, retVal);
|
methods[methodName].addOverload(verbose, is_const, methodName, argumentList,
|
||||||
|
returnValue);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -415,7 +361,7 @@ void Class::appendInheritedMethods(const Class& cls,
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string Class::getTypedef() const {
|
string Class::getTypedef() const {
|
||||||
string result;
|
string result;
|
||||||
BOOST_FOREACH(const string& namesp, namespaces) {
|
BOOST_FOREACH(Str namesp, namespaces) {
|
||||||
result += ("namespace " + namesp + " { ");
|
result += ("namespace " + namesp + " { ");
|
||||||
}
|
}
|
||||||
result += ("typedef " + typedefName + " " + name + ";");
|
result += ("typedef " + typedefName + " " + name + ";");
|
||||||
|
@ -426,43 +372,22 @@ string Class::getTypedef() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
||||||
void Class::comment_fragment(FileWriter& proxyFile) const {
|
void Class::comment_fragment(FileWriter& proxyFile) const {
|
||||||
proxyFile.oss << "%class " << name << ", see Doxygen page for details\n";
|
proxyFile.oss << "%class " << name << ", see Doxygen page for details\n";
|
||||||
proxyFile.oss
|
proxyFile.oss
|
||||||
<< "%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n";
|
<< "%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n";
|
||||||
|
|
||||||
if (!constructor.args_list.empty())
|
constructor.comment_fragment(proxyFile);
|
||||||
proxyFile.oss << "%\n%-------Constructors-------\n";
|
|
||||||
BOOST_FOREACH(ArgumentList argList, constructor.args_list) {
|
|
||||||
proxyFile.oss << "%";
|
|
||||||
argList.emit_prototype(proxyFile, name);
|
|
||||||
proxyFile.oss << "\n";
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!methods.empty())
|
if (!methods.empty())
|
||||||
proxyFile.oss << "%\n%-------Methods-------\n";
|
proxyFile.oss << "%\n%-------Methods-------\n";
|
||||||
BOOST_FOREACH(const Methods::value_type& name_m, methods) {
|
BOOST_FOREACH(const Methods::value_type& name_m, methods)
|
||||||
const Method& m = name_m.second;
|
name_m.second.comment_fragment(proxyFile);
|
||||||
BOOST_FOREACH(ArgumentList argList, m.argLists) {
|
|
||||||
proxyFile.oss << "%";
|
|
||||||
argList.emit_prototype(proxyFile, m.name);
|
|
||||||
proxyFile.oss << " : returns " << m.returnVals[0].return_type(false)
|
|
||||||
<< endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!static_methods.empty())
|
if (!static_methods.empty())
|
||||||
proxyFile.oss << "%\n%-------Static Methods-------\n";
|
proxyFile.oss << "%\n%-------Static Methods-------\n";
|
||||||
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods) {
|
BOOST_FOREACH(const StaticMethods::value_type& name_m, static_methods)
|
||||||
const StaticMethod& m = name_m.second;
|
name_m.second.comment_fragment(proxyFile);
|
||||||
BOOST_FOREACH(ArgumentList argList, m.argLists) {
|
|
||||||
proxyFile.oss << "%";
|
|
||||||
argList.emit_prototype(proxyFile, m.name);
|
|
||||||
proxyFile.oss << " : returns " << m.returnVals[0].return_type(false)
|
|
||||||
<< endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (hasSerialization) {
|
if (hasSerialization) {
|
||||||
proxyFile.oss << "%\n%-------Serialization Interface-------\n";
|
proxyFile.oss << "%\n%-------Serialization Interface-------\n";
|
||||||
|
@ -476,7 +401,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Class::serialization_fragments(FileWriter& proxyFile,
|
void Class::serialization_fragments(FileWriter& proxyFile,
|
||||||
FileWriter& wrapperFile, const string& wrapperName,
|
FileWriter& wrapperFile, Str wrapperName,
|
||||||
vector<string>& functionNames) const {
|
vector<string>& functionNames) const {
|
||||||
|
|
||||||
//void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
//void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
@ -568,7 +493,7 @@ void Class::serialization_fragments(FileWriter& proxyFile,
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Class::deserialization_fragments(FileWriter& proxyFile,
|
void Class::deserialization_fragments(FileWriter& proxyFile,
|
||||||
FileWriter& wrapperFile, const string& wrapperName,
|
FileWriter& wrapperFile, Str wrapperName,
|
||||||
vector<string>& functionNames) const {
|
vector<string>& functionNames) const {
|
||||||
//void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
//void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
//{
|
//{
|
||||||
|
|
59
wrap/Class.h
59
wrap/Class.h
|
@ -19,15 +19,18 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <map>
|
|
||||||
|
|
||||||
#include "Constructor.h"
|
#include "Constructor.h"
|
||||||
#include "Deconstructor.h"
|
#include "Deconstructor.h"
|
||||||
#include "Method.h"
|
#include "Method.h"
|
||||||
#include "StaticMethod.h"
|
#include "StaticMethod.h"
|
||||||
#include "TypeAttributesTable.h"
|
#include "TypeAttributesTable.h"
|
||||||
|
|
||||||
|
#include <boost/foreach.hpp>
|
||||||
|
#include <boost/range/adaptor/map.hpp>
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <map>
|
||||||
|
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
/// Class has name, constructors, methods
|
/// Class has name, constructors, methods
|
||||||
|
@ -38,6 +41,7 @@ class Class: public Qualified {
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
typedef const std::string& Str;
|
||||||
typedef std::map<std::string, StaticMethod> StaticMethods;
|
typedef std::map<std::string, StaticMethod> StaticMethods;
|
||||||
|
|
||||||
// Then the instance variables are set directly by the Module constructor
|
// Then the instance variables are set directly by the Module constructor
|
||||||
|
@ -58,26 +62,30 @@ public:
|
||||||
verbose), verbose_(verbose) {
|
verbose), verbose_(verbose) {
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t nrMethods() const { return methods.size(); }
|
size_t nrMethods() const {
|
||||||
Method& method(const std::string& name) { return methods.at(name); }
|
return methods.size();
|
||||||
bool exists(const std::string& name) const { return methods.find(name) != methods.end(); }
|
}
|
||||||
|
Method& method(Str name) {
|
||||||
|
return methods.at(name);
|
||||||
|
}
|
||||||
|
bool exists(Str name) const {
|
||||||
|
return methods.find(name) != methods.end();
|
||||||
|
}
|
||||||
|
|
||||||
// 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& toolboxPath,
|
void matlab_proxy(Str toolboxPath, Str wrapperName,
|
||||||
const std::string& wrapperName, const TypeAttributesTable& typeAttributes,
|
const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile,
|
||||||
FileWriter& wrapperFile, std::vector<std::string>& functionNames) const; ///< emit proxy class
|
std::vector<std::string>& functionNames) const; ///< emit proxy class
|
||||||
|
|
||||||
Class expandTemplate(const std::string& templateArg,
|
Class expandTemplate(const TemplateSubstitution& ts) const;
|
||||||
const Qualified& instantiation, const Qualified& expandedClass) const;
|
|
||||||
|
|
||||||
std::vector<Class> expandTemplate(const std::string& templateArg,
|
std::vector<Class> expandTemplate(Str templateArg,
|
||||||
const std::vector<Qualified>& instantiations) const;
|
const std::vector<Qualified>& instantiations) const;
|
||||||
|
|
||||||
/// Add potentially overloaded, potentially templated method
|
/// Add potentially overloaded, potentially templated method
|
||||||
void addMethod(bool verbose, bool is_const, const std::string& name,
|
void addMethod(bool verbose, bool is_const, Str methodName,
|
||||||
const ArgumentList& args, const ReturnValue& retVal,
|
const ArgumentList& argumentList, const ReturnValue& returnValue,
|
||||||
const std::string& templateArgName,
|
Str templateArgName, const std::vector<Qualified>& templateArgValues);
|
||||||
const std::vector<Qualified>& templateArgValues);
|
|
||||||
|
|
||||||
/// Post-process classes for serialization markers
|
/// Post-process classes for serialization markers
|
||||||
void erase_serialization(); // non-const !
|
void erase_serialization(); // non-const !
|
||||||
|
@ -97,18 +105,27 @@ public:
|
||||||
|
|
||||||
/// Creates a member function that performs serialization
|
/// Creates a member function that performs serialization
|
||||||
void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||||
const std::string& wrapperName,
|
Str wrapperName, std::vector<std::string>& functionNames) const;
|
||||||
std::vector<std::string>& functionNames) const;
|
|
||||||
|
|
||||||
/// Creates a static member function that performs deserialization
|
/// Creates a static member function that performs deserialization
|
||||||
void deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
void deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||||
const std::string& wrapperName,
|
Str wrapperName, std::vector<std::string>& functionNames) const;
|
||||||
std::vector<std::string>& functionNames) const;
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os, const Class& cls) {
|
||||||
|
os << "class " << cls.name << "{\n";
|
||||||
|
os << cls.constructor << ";\n";
|
||||||
|
BOOST_FOREACH(const StaticMethod& m, cls.static_methods | boost::adaptors::map_values)
|
||||||
|
os << m << ";\n";
|
||||||
|
BOOST_FOREACH(const Method& m, cls.methods | boost::adaptors::map_values)
|
||||||
|
os << m << ";\n";
|
||||||
|
os << "};" << std::endl;
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void pointer_constructor_fragments(FileWriter& proxyFile,
|
void pointer_constructor_fragments(FileWriter& proxyFile,
|
||||||
FileWriter& wrapperFile, const std::string& wrapperName,
|
FileWriter& wrapperFile, Str wrapperName,
|
||||||
std::vector<std::string>& functionNames) const;
|
std::vector<std::string>& functionNames) const;
|
||||||
|
|
||||||
void comment_fragment(FileWriter& proxyFile) const;
|
void comment_fragment(FileWriter& proxyFile) const;
|
||||||
|
|
|
@ -18,7 +18,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Argument.h"
|
#include "Function.h"
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
@ -26,7 +26,7 @@
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
// Constructor class
|
// Constructor class
|
||||||
struct Constructor {
|
struct Constructor: public ArgumentOverloads {
|
||||||
|
|
||||||
/// Constructor creates an empty class
|
/// Constructor creates an empty class
|
||||||
Constructor(bool verbose = false) :
|
Constructor(bool verbose = false) :
|
||||||
|
@ -34,10 +34,16 @@ struct Constructor {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Then the instance variables are set directly by the Module constructor
|
// Then the instance variables are set directly by the Module constructor
|
||||||
std::vector<ArgumentList> args_list;
|
|
||||||
std::string name;
|
std::string name;
|
||||||
bool verbose_;
|
bool verbose_;
|
||||||
|
|
||||||
|
Constructor expandTemplate(const TemplateSubstitution& ts) const {
|
||||||
|
Constructor inst = *this;
|
||||||
|
inst.argLists_ = expandArgumentListsTemplate(ts);
|
||||||
|
inst.name = ts.expandedClassName();
|
||||||
|
return inst;
|
||||||
|
}
|
||||||
|
|
||||||
// MATLAB code generation
|
// MATLAB code generation
|
||||||
// toolboxPath is main toolbox directory, e.g., ../matlab
|
// toolboxPath is main toolbox directory, e.g., ../matlab
|
||||||
// classFile is class proxy file, e.g., ../matlab/@Point2/Point2.m
|
// classFile is class proxy file, e.g., ../matlab/@Point2/Point2.m
|
||||||
|
@ -45,6 +51,16 @@ struct Constructor {
|
||||||
/// wrapper name
|
/// wrapper name
|
||||||
std::string matlab_wrapper_name(const std::string& className) const;
|
std::string matlab_wrapper_name(const std::string& className) const;
|
||||||
|
|
||||||
|
void comment_fragment(FileWriter& proxyFile) const {
|
||||||
|
if (nrOverloads() > 0)
|
||||||
|
proxyFile.oss << "%\n%-------Constructors-------\n";
|
||||||
|
for (size_t i = 0; i < nrOverloads(); i++) {
|
||||||
|
proxyFile.oss << "%";
|
||||||
|
argumentList(i).emit_prototype(proxyFile, name);
|
||||||
|
proxyFile.oss << "\n";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* 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
|
||||||
|
@ -62,6 +78,12 @@ struct Constructor {
|
||||||
void generate_construct(FileWriter& file, const std::string& cppClassName,
|
void generate_construct(FileWriter& file, const std::string& cppClassName,
|
||||||
std::vector<ArgumentList>& args_list) const;
|
std::vector<ArgumentList>& args_list) const;
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os, const Constructor& m) {
|
||||||
|
for (size_t i = 0; i < m.nrOverloads(); i++)
|
||||||
|
os << m.name << m.argLists_[i];
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
@ -0,0 +1,66 @@
|
||||||
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||||
|
* Atlanta, Georgia 30332-0415
|
||||||
|
* All Rights Reserved
|
||||||
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||||
|
|
||||||
|
* See LICENSE for the license information
|
||||||
|
|
||||||
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file Function.ccp
|
||||||
|
* @author Frank Dellaert
|
||||||
|
* @date Nov 13, 2014
|
||||||
|
**/
|
||||||
|
|
||||||
|
#include "Function.h"
|
||||||
|
#include "utilities.h"
|
||||||
|
|
||||||
|
#include <boost/foreach.hpp>
|
||||||
|
#include <boost/lexical_cast.hpp>
|
||||||
|
#include <boost/algorithm/string.hpp>
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
#include <fstream>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace wrap;
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void Function::addOverload(bool verbose, const std::string& name,
|
||||||
|
const Qualified& instName) {
|
||||||
|
|
||||||
|
// Check if this overload is give to the correct method
|
||||||
|
if (name_.empty())
|
||||||
|
name_ = name;
|
||||||
|
else if (name_ != name)
|
||||||
|
throw std::runtime_error(
|
||||||
|
"Function::addOverload: tried to add overload with name " + name
|
||||||
|
+ " instead of expected " + name_);
|
||||||
|
|
||||||
|
// Check if this overload is give to the correct method
|
||||||
|
if (templateArgValue_.empty())
|
||||||
|
templateArgValue_ = instName;
|
||||||
|
else if (templateArgValue_ != instName)
|
||||||
|
throw std::runtime_error(
|
||||||
|
"Function::addOverload: tried to add overload with template argument "
|
||||||
|
+ instName.qualifiedName(":") + " instead of expected "
|
||||||
|
+ templateArgValue_.qualifiedName(":"));
|
||||||
|
|
||||||
|
verbose_ = verbose;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
vector<ArgumentList> ArgumentOverloads::expandArgumentListsTemplate(
|
||||||
|
const TemplateSubstitution& ts) const {
|
||||||
|
vector<ArgumentList> result;
|
||||||
|
BOOST_FOREACH(const ArgumentList& argList, argLists_) {
|
||||||
|
ArgumentList instArgList = argList.expandTemplate(ts);
|
||||||
|
result.push_back(instArgList);
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
|
@ -0,0 +1,228 @@
|
||||||
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||||
|
* Atlanta, Georgia 30332-0415
|
||||||
|
* All Rights Reserved
|
||||||
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||||
|
|
||||||
|
* See LICENSE for the license information
|
||||||
|
|
||||||
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file Function.h
|
||||||
|
* @brief Base class for global functions and methods
|
||||||
|
* @author Frank Dellaert
|
||||||
|
* @date Nov 13, 2014
|
||||||
|
**/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "Argument.h"
|
||||||
|
#include "ReturnValue.h"
|
||||||
|
#include "TypeAttributesTable.h"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <list>
|
||||||
|
|
||||||
|
namespace wrap {
|
||||||
|
|
||||||
|
/// Function class
|
||||||
|
class Function {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
bool verbose_;
|
||||||
|
std::string name_; ///< name of method
|
||||||
|
Qualified templateArgValue_; ///< value of template argument if applicable
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
/// Constructor creates empty object
|
||||||
|
Function(bool verbose = true) :
|
||||||
|
verbose_(verbose) {
|
||||||
|
}
|
||||||
|
|
||||||
|
Function(const std::string& name, bool verbose = true) :
|
||||||
|
verbose_(verbose), name_(name) {
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string name() const {
|
||||||
|
return name_;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string matlabName() const {
|
||||||
|
if (templateArgValue_.empty())
|
||||||
|
return name_;
|
||||||
|
else
|
||||||
|
return name_ + templateArgValue_.name;
|
||||||
|
}
|
||||||
|
|
||||||
|
// The first time this function is called, it initializes the class members
|
||||||
|
// with those in rhs, but in subsequent calls it adds additional argument
|
||||||
|
// lists as function overloads.
|
||||||
|
void addOverload(bool verbose, const std::string& name,
|
||||||
|
const Qualified& instName = Qualified());
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* ArgumentList Overloads
|
||||||
|
*/
|
||||||
|
class ArgumentOverloads {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
std::vector<ArgumentList> argLists_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
size_t nrOverloads() const {
|
||||||
|
return argLists_.size();
|
||||||
|
}
|
||||||
|
|
||||||
|
const ArgumentList& argumentList(size_t i) const {
|
||||||
|
return argLists_.at(i);
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOverload(const ArgumentList& args) {
|
||||||
|
argLists_.push_back(args);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<ArgumentList> expandArgumentListsTemplate(
|
||||||
|
const TemplateSubstitution& ts) const;
|
||||||
|
|
||||||
|
/// Expand templates, imperative !
|
||||||
|
virtual void ExpandTemplate(const TemplateSubstitution& ts) {
|
||||||
|
argLists_ = expandArgumentListsTemplate(ts);
|
||||||
|
}
|
||||||
|
|
||||||
|
void verifyArguments(const std::vector<std::string>& validArgs,
|
||||||
|
const std::string s) const {
|
||||||
|
BOOST_FOREACH(const ArgumentList& argList, argLists_) {
|
||||||
|
BOOST_FOREACH(Argument arg, argList) {
|
||||||
|
std::string fullType = arg.type.qualifiedName("::");
|
||||||
|
if (find(validArgs.begin(), validArgs.end(), fullType)
|
||||||
|
== validArgs.end())
|
||||||
|
throw DependencyMissing(fullType, "checking argument of " + s);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os,
|
||||||
|
const ArgumentOverloads& overloads) {
|
||||||
|
BOOST_FOREACH(const ArgumentList& argList, overloads.argLists_)
|
||||||
|
os << argList << std::endl;
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Signature Overload (including return value)
|
||||||
|
*/
|
||||||
|
class SignatureOverloads: public ArgumentOverloads {
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
std::vector<ReturnValue> returnVals_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
const ReturnValue& returnValue(size_t i) const {
|
||||||
|
return returnVals_.at(i);
|
||||||
|
}
|
||||||
|
|
||||||
|
void addOverload(const ArgumentList& args, const ReturnValue& retVal) {
|
||||||
|
argLists_.push_back(args);
|
||||||
|
returnVals_.push_back(retVal);
|
||||||
|
}
|
||||||
|
|
||||||
|
void verifyReturnTypes(const std::vector<std::string>& validtypes,
|
||||||
|
const std::string& s) const {
|
||||||
|
BOOST_FOREACH(const ReturnValue& retval, returnVals_) {
|
||||||
|
retval.type1.verify(validtypes, s);
|
||||||
|
if (retval.isPair)
|
||||||
|
retval.type2.verify(validtypes, s);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO use transform ?
|
||||||
|
std::vector<ReturnValue> expandReturnValuesTemplate(
|
||||||
|
const TemplateSubstitution& ts) const {
|
||||||
|
std::vector<ReturnValue> result;
|
||||||
|
BOOST_FOREACH(const ReturnValue& retVal, returnVals_) {
|
||||||
|
ReturnValue instRetVal = retVal.expandTemplate(ts);
|
||||||
|
result.push_back(instRetVal);
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Expand templates, imperative !
|
||||||
|
void expandTemplate(const TemplateSubstitution& ts) {
|
||||||
|
// substitute template in arguments
|
||||||
|
argLists_ = expandArgumentListsTemplate(ts);
|
||||||
|
// do the same for return types
|
||||||
|
returnVals_ = expandReturnValuesTemplate(ts);
|
||||||
|
}
|
||||||
|
|
||||||
|
// emit a list of comments, one for each overload
|
||||||
|
void usage_fragment(FileWriter& proxyFile, const std::string& name) const {
|
||||||
|
unsigned int argLCount = 0;
|
||||||
|
BOOST_FOREACH(ArgumentList argList, argLists_) {
|
||||||
|
argList.emit_prototype(proxyFile, name);
|
||||||
|
if (argLCount != nrOverloads() - 1)
|
||||||
|
proxyFile.oss << ", ";
|
||||||
|
else
|
||||||
|
proxyFile.oss << " : returns " << returnValue(0).return_type(false)
|
||||||
|
<< std::endl;
|
||||||
|
argLCount++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// emit a list of comments, one for each overload
|
||||||
|
void comment_fragment(FileWriter& proxyFile, const std::string& name) const {
|
||||||
|
size_t i = 0;
|
||||||
|
BOOST_FOREACH(ArgumentList argList, argLists_) {
|
||||||
|
proxyFile.oss << "%";
|
||||||
|
argList.emit_prototype(proxyFile, name);
|
||||||
|
proxyFile.oss << " : returns " << returnVals_[i++].return_type(false)
|
||||||
|
<< std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os,
|
||||||
|
const SignatureOverloads& overloads) {
|
||||||
|
for (size_t i = 0; i < overloads.nrOverloads(); i++)
|
||||||
|
os << overloads.returnVals_[i] << overloads.argLists_[i] << std::endl;
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
// Templated checking functions
|
||||||
|
// TODO: do this via polymorphism ?
|
||||||
|
|
||||||
|
// TODO use transform
|
||||||
|
template<class F>
|
||||||
|
static std::map<std::string, F> expandMethodTemplate(
|
||||||
|
const std::map<std::string, F>& methods, const TemplateSubstitution& ts) {
|
||||||
|
std::map<std::string, F> result;
|
||||||
|
typedef std::pair<const std::string, F> NamedMethod;
|
||||||
|
BOOST_FOREACH(NamedMethod namedMethod, methods) {
|
||||||
|
F instMethod = namedMethod.second;
|
||||||
|
instMethod.expandTemplate(ts);
|
||||||
|
namedMethod.second = instMethod;
|
||||||
|
result.insert(namedMethod);
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
template<class F>
|
||||||
|
inline void verifyReturnTypes(const std::vector<std::string>& validTypes,
|
||||||
|
const std::map<std::string, F>& vt) {
|
||||||
|
typedef typename std::map<std::string, F>::value_type NamedMethod;
|
||||||
|
BOOST_FOREACH(const NamedMethod& namedMethod, vt)
|
||||||
|
namedMethod.second.verifyReturnTypes(validTypes);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // \namespace wrap
|
||||||
|
|
|
@ -17,16 +17,10 @@ using namespace std;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void GlobalFunction::addOverload(bool verbose, const Qualified& overload,
|
void GlobalFunction::addOverload(bool verbose, const Qualified& overload,
|
||||||
const ArgumentList& args, const ReturnValue& retVal) {
|
const ArgumentList& args, const ReturnValue& retVal,
|
||||||
if (name.empty())
|
const Qualified& instName) {
|
||||||
name = overload.name;
|
Function::addOverload(verbose, overload.name, instName);
|
||||||
else if (overload.name != name)
|
SignatureOverloads::addOverload(args, retVal);
|
||||||
throw std::runtime_error(
|
|
||||||
"GlobalFunction::addOverload: tried to add overload with name "
|
|
||||||
+ overload.name + " instead of expected " + name);
|
|
||||||
verbose_ = verbose;
|
|
||||||
argLists.push_back(args);
|
|
||||||
returnVals.push_back(retVal);
|
|
||||||
overloads.push_back(overload);
|
overloads.push_back(overload);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -44,15 +38,10 @@ void GlobalFunction::matlab_proxy(const std::string& toolboxPath,
|
||||||
Qualified overload = overloads.at(i);
|
Qualified overload = overloads.at(i);
|
||||||
// use concatenated namespaces as key
|
// use concatenated namespaces as key
|
||||||
string str_ns = qualifiedName("", overload.namespaces);
|
string str_ns = qualifiedName("", overload.namespaces);
|
||||||
ReturnValue ret = returnVals.at(i);
|
const ReturnValue& ret = returnValue(i);
|
||||||
ArgumentList args = argLists.at(i);
|
const ArgumentList& args = argumentList(i);
|
||||||
|
grouped_functions[str_ns].addOverload(verbose_, overload, args, ret,
|
||||||
if (!grouped_functions.count(str_ns))
|
templateArgValue_);
|
||||||
grouped_functions[str_ns] = GlobalFunction(name, verbose_);
|
|
||||||
|
|
||||||
grouped_functions[str_ns].argLists.push_back(args);
|
|
||||||
grouped_functions[str_ns].returnVals.push_back(ret);
|
|
||||||
grouped_functions[str_ns].overloads.push_back(overload);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t lastcheck = grouped_functions.size();
|
size_t lastcheck = grouped_functions.size();
|
||||||
|
@ -82,18 +71,17 @@ void GlobalFunction::generateSingleFunction(const std::string& toolboxPath,
|
||||||
const string matlabUniqueName = overload1.qualifiedName("");
|
const string matlabUniqueName = overload1.qualifiedName("");
|
||||||
const string cppName = overload1.qualifiedName("::");
|
const string cppName = overload1.qualifiedName("::");
|
||||||
|
|
||||||
mfunctionFile.oss << "function varargout = " << name << "(varargin)\n";
|
mfunctionFile.oss << "function varargout = " << name_ << "(varargin)\n";
|
||||||
|
|
||||||
for (size_t overload = 0; overload < argLists.size(); ++overload) {
|
for (size_t i = 0; i < nrOverloads(); ++i) {
|
||||||
const ArgumentList& args = argLists[overload];
|
const ArgumentList& args = argumentList(i);
|
||||||
const ReturnValue& returnVal = returnVals[overload];
|
const ReturnValue& returnVal = returnValue(i);
|
||||||
|
|
||||||
const int id = functionNames.size();
|
const int id = functionNames.size();
|
||||||
|
|
||||||
// Output proxy matlab code
|
// Output proxy matlab code
|
||||||
mfunctionFile.oss << " " << (overload == 0 ? "" : "else");
|
mfunctionFile.oss << " " << (i == 0 ? "" : "else");
|
||||||
argLists[overload].emit_conditional_call(mfunctionFile,
|
args.emit_conditional_call(mfunctionFile, returnVal, wrapperName, id, true); // true omits "this"
|
||||||
returnVals[overload], wrapperName, id, true); // true omits "this"
|
|
||||||
|
|
||||||
// Output C++ wrapper code
|
// Output C++ wrapper code
|
||||||
|
|
||||||
|
|
|
@ -9,34 +9,36 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Argument.h"
|
#include "Function.h"
|
||||||
#include "ReturnValue.h"
|
|
||||||
|
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
struct GlobalFunction {
|
struct GlobalFunction: public Function, public SignatureOverloads {
|
||||||
|
|
||||||
bool verbose_;
|
|
||||||
std::string name;
|
|
||||||
|
|
||||||
// each overload, regardless of namespace
|
|
||||||
std::vector<ArgumentList> argLists; ///< arugments for each overload
|
|
||||||
std::vector<ReturnValue> returnVals; ///< returnVals for each overload
|
|
||||||
std::vector<Qualified> overloads; ///< Stack of qualified names
|
std::vector<Qualified> overloads; ///< Stack of qualified names
|
||||||
|
|
||||||
// Constructor only used in Module
|
// Constructor only used in Module
|
||||||
GlobalFunction(bool verbose = true) :
|
GlobalFunction(bool verbose = true) :
|
||||||
verbose_(verbose) {
|
Function(verbose) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Used to reconstruct
|
// Used to reconstruct
|
||||||
GlobalFunction(const std::string& name_, bool verbose = true) :
|
GlobalFunction(const std::string& name, bool verbose = true) :
|
||||||
verbose_(verbose), name(name_) {
|
Function(name,verbose) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// adds an overloaded version of this function
|
void verifyArguments(const std::vector<std::string>& validArgs) const {
|
||||||
|
SignatureOverloads::verifyArguments(validArgs, name_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void verifyReturnTypes(const std::vector<std::string>& validtypes) const {
|
||||||
|
SignatureOverloads::verifyReturnTypes(validtypes, name_);
|
||||||
|
}
|
||||||
|
|
||||||
|
// adds an overloaded version of this function,
|
||||||
void addOverload(bool verbose, const Qualified& overload,
|
void addOverload(bool verbose, const Qualified& overload,
|
||||||
const ArgumentList& args, const ReturnValue& retVal);
|
const ArgumentList& args, const ReturnValue& retVal,
|
||||||
|
const Qualified& instName = Qualified());
|
||||||
|
|
||||||
// codegen function called from Module to build the cpp and matlab versions of the function
|
// codegen function called from Module to build the cpp and matlab versions of the function
|
||||||
void matlab_proxy(const std::string& toolboxPath,
|
void matlab_proxy(const std::string& toolboxPath,
|
||||||
|
|
139
wrap/Method.cpp
139
wrap/Method.cpp
|
@ -29,156 +29,45 @@ using namespace std;
|
||||||
using namespace wrap;
|
using namespace wrap;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Method::addOverload(bool verbose, bool is_const, const std::string& name,
|
void Method::addOverload(bool verbose, bool is_const, Str name,
|
||||||
const ArgumentList& args, const ReturnValue& retVal,
|
const ArgumentList& args, const ReturnValue& retVal,
|
||||||
const Qualified& instName) {
|
const Qualified& instName) {
|
||||||
if (!this->name.empty() && this->name != name)
|
|
||||||
throw std::runtime_error(
|
StaticMethod::addOverload(verbose, name, args, retVal, instName);
|
||||||
"Method::addOverload: tried to add overload with name " + name
|
|
||||||
+ " instead of expected " + this->name);
|
|
||||||
else
|
|
||||||
this->name = name;
|
|
||||||
verbose_ = verbose;
|
|
||||||
is_const_ = is_const;
|
is_const_ = is_const;
|
||||||
argLists.push_back(args);
|
|
||||||
returnVals.push_back(retVal);
|
|
||||||
templateArgValues.push_back(instName);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Method::proxy_wrapper_fragments(FileWriter& proxyFile,
|
void Method::proxy_header(FileWriter& proxyFile) const {
|
||||||
FileWriter& wrapperFile, const string& cppClassName,
|
proxyFile.oss << " function varargout = " << matlabName() << "(this, varargin)\n";
|
||||||
const std::string& matlabQualName, const std::string& matlabUniqueName,
|
|
||||||
const string& wrapperName, const TypeAttributesTable& typeAttributes,
|
|
||||||
vector<string>& functionNames) const {
|
|
||||||
|
|
||||||
// Create function header
|
|
||||||
proxyFile.oss << " function varargout = " << name << "(this, varargin)\n";
|
|
||||||
|
|
||||||
// Emit comments for documentation
|
|
||||||
string up_name = boost::to_upper_copy(name);
|
|
||||||
proxyFile.oss << " % " << up_name << " usage: ";
|
|
||||||
unsigned int argLCount = 0;
|
|
||||||
BOOST_FOREACH(ArgumentList argList, argLists) {
|
|
||||||
argList.emit_prototype(proxyFile, name);
|
|
||||||
if (argLCount != argLists.size() - 1)
|
|
||||||
proxyFile.oss << ", ";
|
|
||||||
else
|
|
||||||
proxyFile.oss << " : returns " << returnVals[0].return_type(false)
|
|
||||||
<< endl;
|
|
||||||
argLCount++;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Emit URL to Doxygen page
|
|
||||||
proxyFile.oss << " % "
|
|
||||||
<< "Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html"
|
|
||||||
<< endl;
|
|
||||||
|
|
||||||
// Document all overloads, if any
|
|
||||||
if (argLists.size() > 1) {
|
|
||||||
proxyFile.oss << " % " << "" << endl;
|
|
||||||
proxyFile.oss << " % " << "Method Overloads" << endl;
|
|
||||||
BOOST_FOREACH(ArgumentList argList, argLists) {
|
|
||||||
proxyFile.oss << " % ";
|
|
||||||
argList.emit_prototype(proxyFile, name);
|
|
||||||
proxyFile.oss << endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Handle special case of single overload with all numeric arguments
|
|
||||||
if (argLists.size() == 1 && argLists[0].allScalar()) {
|
|
||||||
// Output proxy matlab code
|
|
||||||
proxyFile.oss << " ";
|
|
||||||
const int id = (int) functionNames.size();
|
|
||||||
argLists[0].emit_call(proxyFile, returnVals[0], wrapperName, id);
|
|
||||||
|
|
||||||
// Output C++ wrapper code
|
|
||||||
const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName,
|
|
||||||
matlabUniqueName, 0, id, typeAttributes, templateArgValues[0]);
|
|
||||||
|
|
||||||
// Add to function list
|
|
||||||
functionNames.push_back(wrapFunctionName);
|
|
||||||
} else {
|
|
||||||
// Check arguments for all overloads
|
|
||||||
for (size_t overload = 0; overload < argLists.size(); ++overload) {
|
|
||||||
|
|
||||||
// Output proxy matlab code
|
|
||||||
proxyFile.oss << " " << (overload == 0 ? "" : "else");
|
|
||||||
const int id = (int) functionNames.size();
|
|
||||||
argLists[overload].emit_conditional_call(proxyFile, returnVals[overload],
|
|
||||||
wrapperName, id);
|
|
||||||
|
|
||||||
// Output C++ wrapper code
|
|
||||||
const string wrapFunctionName = wrapper_fragment(wrapperFile,
|
|
||||||
cppClassName, matlabUniqueName, overload, id, typeAttributes,
|
|
||||||
templateArgValues[overload]);
|
|
||||||
|
|
||||||
// Add to function list
|
|
||||||
functionNames.push_back(wrapFunctionName);
|
|
||||||
}
|
|
||||||
proxyFile.oss << " else\n";
|
|
||||||
proxyFile.oss
|
|
||||||
<< " error('Arguments do not match any overload of function "
|
|
||||||
<< matlabQualName << "." << name << "');" << endl;
|
|
||||||
proxyFile.oss << " end\n";
|
|
||||||
}
|
|
||||||
|
|
||||||
proxyFile.oss << " end\n";
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string Method::wrapper_fragment(FileWriter& wrapperFile,
|
string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
|
||||||
const string& cppClassName, const string& matlabUniqueName, int overload,
|
Str matlabUniqueName, const ArgumentList& args,
|
||||||
int id, const TypeAttributesTable& typeAttributes,
|
const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes,
|
||||||
const Qualified& instName) const {
|
const Qualified& instName) const {
|
||||||
|
|
||||||
// generate code
|
|
||||||
|
|
||||||
const string wrapFunctionName = matlabUniqueName + "_" + name + "_"
|
|
||||||
+ boost::lexical_cast<string>(id);
|
|
||||||
|
|
||||||
const ArgumentList& args = argLists[overload];
|
|
||||||
const ReturnValue& returnVal = returnVals[overload];
|
|
||||||
|
|
||||||
// call
|
|
||||||
wrapperFile.oss << "void " << wrapFunctionName
|
|
||||||
<< "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
|
||||||
// start
|
|
||||||
wrapperFile.oss << "{\n";
|
|
||||||
|
|
||||||
returnVal.wrapTypeUnwrap(wrapperFile);
|
|
||||||
|
|
||||||
wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName
|
|
||||||
<< "> Shared;" << endl;
|
|
||||||
|
|
||||||
// check arguments
|
// check arguments
|
||||||
// extra argument obj -> nargin-1 is passed !
|
// extra argument obj -> nargin-1 is passed !
|
||||||
// example: checkArguments("equals",nargout,nargin-1,2);
|
// example: checkArguments("equals",nargout,nargin-1,2);
|
||||||
wrapperFile.oss << " checkArguments(\"" << name << "\",nargout,nargin-1,"
|
wrapperFile.oss << " checkArguments(\"" << name_ << "\",nargout,nargin-1,"
|
||||||
<< args.size() << ");\n";
|
<< args.size() << ");\n";
|
||||||
|
|
||||||
// get class pointer
|
// get class pointer
|
||||||
// example: shared_ptr<Test> = unwrap_shared_ptr< Test >(in[0], "Test");
|
// example: shared_ptr<Test> = unwrap_shared_ptr< Test >(in[0], "Test");
|
||||||
wrapperFile.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName
|
wrapperFile.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName
|
||||||
<< ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl;
|
<< ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl;
|
||||||
// unwrap arguments, see Argument.cpp
|
|
||||||
|
// unwrap arguments, see Argument.cpp, we start at 1 as first is obj
|
||||||
args.matlab_unwrap(wrapperFile, 1);
|
args.matlab_unwrap(wrapperFile, 1);
|
||||||
|
|
||||||
// call method and wrap result
|
// call method and wrap result
|
||||||
// example: out[0]=wrap<bool>(self->return_field(t));
|
// example: out[0]=wrap<bool>(obj->return_field(t));
|
||||||
string expanded = "obj->" + name;
|
string expanded = "obj->" + name_;
|
||||||
if (!instName.empty())
|
if (!instName.empty())
|
||||||
expanded += ("<" + instName.qualifiedName("::") + ">");
|
expanded += ("<" + instName.qualifiedName("::") + ">");
|
||||||
expanded += ("(" + args.names() + ")");
|
|
||||||
if (returnVal.type1.name != "void")
|
|
||||||
returnVal.wrap_result(expanded, wrapperFile, typeAttributes);
|
|
||||||
else
|
|
||||||
wrapperFile.oss << " " + expanded + ";\n";
|
|
||||||
|
|
||||||
// finish
|
return expanded;
|
||||||
wrapperFile.oss << "}\n";
|
|
||||||
|
|
||||||
return wrapFunctionName;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -18,53 +18,54 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Argument.h"
|
#include "StaticMethod.h"
|
||||||
#include "ReturnValue.h"
|
|
||||||
#include "TypeAttributesTable.h"
|
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <list>
|
|
||||||
|
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
/// Method class
|
/// Method class
|
||||||
struct Method {
|
class Method: public StaticMethod {
|
||||||
|
|
||||||
|
bool is_const_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
typedef const std::string& Str;
|
||||||
|
|
||||||
/// Constructor creates empty object
|
/// Constructor creates empty object
|
||||||
Method(bool verbose = true) :
|
Method(bool verbose = true) :
|
||||||
verbose_(verbose), is_const_(false) {
|
StaticMethod(verbose), is_const_(false) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Then the instance variables are set directly by the Module constructor
|
virtual bool isStatic() const {
|
||||||
bool verbose_;
|
return false;
|
||||||
bool is_const_;
|
}
|
||||||
std::string name;
|
|
||||||
std::vector<ArgumentList> argLists;
|
virtual bool isConst() const {
|
||||||
std::vector<ReturnValue> returnVals;
|
return is_const_;
|
||||||
std::vector<Qualified> templateArgValues; ///< value of template argument if applicable
|
}
|
||||||
|
|
||||||
// The first time this function is called, it initializes the class members
|
// The first time this function is called, it initializes the class members
|
||||||
// with those in rhs, but in subsequent calls it adds additional argument
|
// with those in rhs, but in subsequent calls it adds additional argument
|
||||||
// lists as function overloads.
|
// lists as function overloads.
|
||||||
void addOverload(bool verbose, bool is_const, const std::string& name,
|
void addOverload(bool verbose, bool is_const, Str name,
|
||||||
const ArgumentList& args, const ReturnValue& retVal,
|
const ArgumentList& args, const ReturnValue& retVal,
|
||||||
const Qualified& instName = Qualified());
|
const Qualified& instName = Qualified());
|
||||||
|
|
||||||
// MATLAB code generation
|
friend std::ostream& operator<<(std::ostream& os, const Method& m) {
|
||||||
// classPath is class directory, e.g., ../matlab/@Point2
|
for (size_t i = 0; i < m.nrOverloads(); i++)
|
||||||
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
os << m.returnVals_[i] << " " << m.name_ << m.argLists_[i];
|
||||||
const std::string& cppClassName, const std::string& matlabQualName,
|
return os;
|
||||||
const std::string& matlabUniqueName, const std::string& wrapperName,
|
}
|
||||||
const TypeAttributesTable& typeAttributes,
|
|
||||||
std::vector<std::string>& functionNames) const;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
/// Emit C++ code
|
// Emit method header
|
||||||
std::string wrapper_fragment(FileWriter& wrapperFile,
|
void proxy_header(FileWriter& proxyFile) const;
|
||||||
const std::string& cppClassName, const std::string& matlabUniqueName,
|
|
||||||
int overload, int id, const TypeAttributesTable& typeAttributes,
|
virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName,
|
||||||
const Qualified& instName) const; ///< cpp wrapper
|
Str matlabUniqueName, const ArgumentList& args,
|
||||||
|
const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes,
|
||||||
|
const Qualified& instName) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
@ -217,7 +217,7 @@ void Module::parseMarkup(const std::string& data) {
|
||||||
Constructor constructor0(verbose), constructor(verbose);
|
Constructor constructor0(verbose), constructor(verbose);
|
||||||
Rule constructor_p =
|
Rule constructor_p =
|
||||||
(className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p)
|
(className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p)
|
||||||
[push_back_a(constructor.args_list, args)]
|
[bl::bind(&Constructor::addOverload, bl::var(constructor), bl::var(args))]
|
||||||
[clear_a(args)];
|
[clear_a(args)];
|
||||||
|
|
||||||
vector<string> namespaces_return; /// namespace for current return type
|
vector<string> namespaces_return; /// namespace for current return type
|
||||||
|
@ -274,7 +274,7 @@ void Module::parseMarkup(const std::string& data) {
|
||||||
'(' >> argumentList_p >> ')' >> ';' >> *comments_p)
|
'(' >> argumentList_p >> ')' >> ';' >> *comments_p)
|
||||||
[bl::bind(&StaticMethod::addOverload,
|
[bl::bind(&StaticMethod::addOverload,
|
||||||
bl::var(cls.static_methods)[bl::var(methodName)],
|
bl::var(cls.static_methods)[bl::var(methodName)],
|
||||||
verbose, bl::var(methodName), bl::var(args), bl::var(retVal))]
|
verbose, bl::var(methodName), bl::var(args), bl::var(retVal), Qualified())]
|
||||||
[assign_a(retVal,retVal0)]
|
[assign_a(retVal,retVal0)]
|
||||||
[clear_a(args)];
|
[clear_a(args)];
|
||||||
|
|
||||||
|
@ -313,7 +313,7 @@ void Module::parseMarkup(const std::string& data) {
|
||||||
[assign_a(globalFunction.namespaces,namespaces)]
|
[assign_a(globalFunction.namespaces,namespaces)]
|
||||||
[bl::bind(&GlobalFunction::addOverload,
|
[bl::bind(&GlobalFunction::addOverload,
|
||||||
bl::var(global_functions)[bl::var(globalFunction.name)],
|
bl::var(global_functions)[bl::var(globalFunction.name)],
|
||||||
verbose, bl::var(globalFunction), bl::var(args), bl::var(retVal))]
|
verbose, bl::var(globalFunction), bl::var(args), bl::var(retVal), Qualified())]
|
||||||
[assign_a(retVal,retVal0)]
|
[assign_a(retVal,retVal0)]
|
||||||
[clear_a(globalFunction)]
|
[clear_a(globalFunction)]
|
||||||
[clear_a(args)];
|
[clear_a(args)];
|
||||||
|
|
|
@ -44,6 +44,10 @@ struct Qualified {
|
||||||
name.clear();
|
name.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool operator!=(const Qualified& other) const {
|
||||||
|
return other.name != name || other.namespaces != namespaces;
|
||||||
|
}
|
||||||
|
|
||||||
/// Return a qualified string using given delimiter
|
/// Return a qualified string using given delimiter
|
||||||
std::string qualifiedName(const std::string& delimiter = "") const {
|
std::string qualifiedName(const std::string& delimiter = "") const {
|
||||||
std::string result;
|
std::string result;
|
||||||
|
@ -62,6 +66,11 @@ struct Qualified {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os, const Qualified& q) {
|
||||||
|
os << q.qualifiedName("::");
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
@ -0,0 +1,61 @@
|
||||||
|
/**
|
||||||
|
* @file ReturnType.cpp
|
||||||
|
* @date Nov 13, 2014
|
||||||
|
* @author Frank Dellaert
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "ReturnType.h"
|
||||||
|
#include "utilities.h"
|
||||||
|
#include <boost/foreach.hpp>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace wrap;
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
string ReturnType::str(bool add_ptr) const {
|
||||||
|
return maybe_shared_ptr(add_ptr && isPtr, qualifiedName("::"), name);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void ReturnType::wrap_result(const string& out, const string& result,
|
||||||
|
FileWriter& wrapperFile, const TypeAttributesTable& typeAttributes) const {
|
||||||
|
|
||||||
|
string cppType = qualifiedName("::"), matlabType = qualifiedName(".");
|
||||||
|
|
||||||
|
if (category == CLASS) {
|
||||||
|
string objCopy, ptrType;
|
||||||
|
ptrType = "Shared" + name;
|
||||||
|
const bool isVirtual = typeAttributes.at(cppType).isVirtual;
|
||||||
|
if (isVirtual) {
|
||||||
|
if (isPtr)
|
||||||
|
objCopy = result;
|
||||||
|
else
|
||||||
|
objCopy = result + ".clone()";
|
||||||
|
} else {
|
||||||
|
if (isPtr)
|
||||||
|
objCopy = result;
|
||||||
|
else
|
||||||
|
objCopy = ptrType + "(new " + cppType + "(" + result + "))";
|
||||||
|
}
|
||||||
|
wrapperFile.oss << out << " = wrap_shared_ptr(" << objCopy << ",\""
|
||||||
|
<< matlabType << "\", " << (isVirtual ? "true" : "false") << ");\n";
|
||||||
|
} else if (isPtr) {
|
||||||
|
wrapperFile.oss << " Shared" << name << "* ret = new Shared" << name << "("
|
||||||
|
<< result << ");" << endl;
|
||||||
|
wrapperFile.oss << out << " = wrap_shared_ptr(ret,\"" << matlabType
|
||||||
|
<< "\");\n";
|
||||||
|
} else if (matlabType != "void")
|
||||||
|
wrapperFile.oss << out << " = wrap< " << str(false) << " >(" << result
|
||||||
|
<< ");\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const {
|
||||||
|
if (category == CLASS)
|
||||||
|
wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedName("::")
|
||||||
|
<< "> Shared" << name << ";" << endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -0,0 +1,67 @@
|
||||||
|
/**
|
||||||
|
* @file ReturnValue.h
|
||||||
|
* @brief Encapsulates a return type of a method
|
||||||
|
* @date Nov 13, 2014
|
||||||
|
* @author Frank Dellaert
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "Qualified.h"
|
||||||
|
#include "FileWriter.h"
|
||||||
|
#include "TypeAttributesTable.h"
|
||||||
|
#include "utilities.h"
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
namespace wrap {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Encapsulates return value of a method or function
|
||||||
|
*/
|
||||||
|
struct ReturnType: Qualified {
|
||||||
|
|
||||||
|
/// the different supported return value categories
|
||||||
|
typedef enum {
|
||||||
|
CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4
|
||||||
|
} return_category;
|
||||||
|
|
||||||
|
bool isPtr;
|
||||||
|
return_category category;
|
||||||
|
|
||||||
|
ReturnType() :
|
||||||
|
isPtr(false), category(CLASS) {
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnType(const std::string& name) :
|
||||||
|
isPtr(false), category(CLASS) {
|
||||||
|
Qualified::name = name;
|
||||||
|
}
|
||||||
|
|
||||||
|
void rename(const Qualified& q) {
|
||||||
|
name = q.name;
|
||||||
|
namespaces = q.namespaces;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Check if this type is in a set of valid types
|
||||||
|
template<class TYPES>
|
||||||
|
void verify(TYPES validtypes, const std::string& s) const {
|
||||||
|
std::string key = qualifiedName("::");
|
||||||
|
if (find(validtypes.begin(), validtypes.end(), key) == validtypes.end())
|
||||||
|
throw DependencyMissing(key, "checking return type of " + s);
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
friend struct ReturnValue;
|
||||||
|
|
||||||
|
std::string str(bool add_ptr) const;
|
||||||
|
|
||||||
|
/// Example: out[1] = wrap_shared_ptr(pairResult.second,"Test", false);
|
||||||
|
void wrap_result(const std::string& out, const std::string& result,
|
||||||
|
FileWriter& wrapperFile, const TypeAttributesTable& typeAttributes) const;
|
||||||
|
|
||||||
|
/// Creates typedef
|
||||||
|
void wrapTypeUnwrap(FileWriter& wrapperFile) const;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
} // \namespace wrap
|
|
@ -1,6 +1,5 @@
|
||||||
/**
|
/**
|
||||||
* @file ReturnValue.cpp
|
* @file ReturnValue.cpp
|
||||||
*
|
|
||||||
* @date Dec 1, 2011
|
* @date Dec 1, 2011
|
||||||
* @author Alex Cunningham
|
* @author Alex Cunningham
|
||||||
* @author Andrew Melim
|
* @author Andrew Melim
|
||||||
|
@ -16,62 +15,11 @@ using namespace std;
|
||||||
using namespace wrap;
|
using namespace wrap;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string ReturnType::str(bool add_ptr) const {
|
ReturnValue ReturnValue::expandTemplate(const TemplateSubstitution& ts) const {
|
||||||
return maybe_shared_ptr(add_ptr && isPtr, qualifiedName("::"), name);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void ReturnType::wrap_result(const string& out, const string& result,
|
|
||||||
FileWriter& file, const TypeAttributesTable& typeAttributes) const {
|
|
||||||
|
|
||||||
string cppType = qualifiedName("::"), matlabType = qualifiedName(".");
|
|
||||||
|
|
||||||
if (category == CLASS) {
|
|
||||||
string objCopy, ptrType;
|
|
||||||
ptrType = "Shared" + name;
|
|
||||||
const bool isVirtual = typeAttributes.at(cppType).isVirtual;
|
|
||||||
if (isVirtual) {
|
|
||||||
if (isPtr)
|
|
||||||
objCopy = result;
|
|
||||||
else
|
|
||||||
objCopy = result + ".clone()";
|
|
||||||
} else {
|
|
||||||
if (isPtr)
|
|
||||||
objCopy = result;
|
|
||||||
else
|
|
||||||
objCopy = ptrType + "(new " + cppType + "(" + result + "))";
|
|
||||||
}
|
|
||||||
file.oss << out << " = wrap_shared_ptr(" << objCopy << ",\"" << matlabType
|
|
||||||
<< "\", " << (isVirtual ? "true" : "false") << ");\n";
|
|
||||||
} else if (isPtr) {
|
|
||||||
file.oss << " Shared" << name << "* ret = new Shared" << name << "("
|
|
||||||
<< result << ");" << endl;
|
|
||||||
file.oss << out << " = wrap_shared_ptr(ret,\"" << matlabType << "\");\n";
|
|
||||||
} else if (matlabType != "void")
|
|
||||||
file.oss << out << " = wrap< " << str(false) << " >(" << result << ");\n";
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const {
|
|
||||||
if (category == CLASS)
|
|
||||||
wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedName("::")
|
|
||||||
<< "> Shared" << name << ";" << endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
ReturnValue ReturnValue::substituteTemplate(const string& templateArg,
|
|
||||||
const Qualified& qualifiedType, const Qualified& expandedClass) const {
|
|
||||||
ReturnValue instRetVal = *this;
|
ReturnValue instRetVal = *this;
|
||||||
if (type1.name == templateArg) {
|
instRetVal.type1 = ts(type1);
|
||||||
instRetVal.type1.rename(qualifiedType);
|
if (isPair)
|
||||||
} else if (type1.name == "This") {
|
instRetVal.type2 = ts(type2);
|
||||||
instRetVal.type1.rename(expandedClass);
|
|
||||||
}
|
|
||||||
if (type2.name == templateArg) {
|
|
||||||
instRetVal.type2.rename(qualifiedType);
|
|
||||||
} else if (type2.name == "This") {
|
|
||||||
instRetVal.type2.rename(expandedClass);
|
|
||||||
}
|
|
||||||
return instRetVal;
|
return instRetVal;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -2,13 +2,13 @@
|
||||||
* @file ReturnValue.h
|
* @file ReturnValue.h
|
||||||
*
|
*
|
||||||
* @brief Encapsulates a return value from a method
|
* @brief Encapsulates a return value from a method
|
||||||
*
|
|
||||||
* @date Dec 1, 2011
|
* @date Dec 1, 2011
|
||||||
* @author Alex Cunningham
|
* @author Alex Cunningham
|
||||||
* @author Richard Roberts
|
* @author Richard Roberts
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "Qualified.h"
|
#include "ReturnType.h"
|
||||||
|
#include "TemplateSubstitution.h"
|
||||||
#include "FileWriter.h"
|
#include "FileWriter.h"
|
||||||
#include "TypeAttributesTable.h"
|
#include "TypeAttributesTable.h"
|
||||||
#include "utilities.h"
|
#include "utilities.h"
|
||||||
|
@ -18,57 +18,7 @@
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Encapsulates return value of a method or function
|
* Encapsulates return type of a method or function, possibly a pair
|
||||||
*/
|
|
||||||
struct ReturnType: Qualified {
|
|
||||||
|
|
||||||
/// the different supported return value categories
|
|
||||||
typedef enum {
|
|
||||||
CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4
|
|
||||||
} return_category;
|
|
||||||
|
|
||||||
bool isPtr;
|
|
||||||
return_category category;
|
|
||||||
|
|
||||||
ReturnType() :
|
|
||||||
isPtr(false), category(CLASS) {
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnType(const std::string& name) :
|
|
||||||
isPtr(false), category(CLASS) {
|
|
||||||
Qualified::name = name;
|
|
||||||
}
|
|
||||||
|
|
||||||
void rename(const Qualified& q) {
|
|
||||||
name = q.name;
|
|
||||||
namespaces = q.namespaces;
|
|
||||||
}
|
|
||||||
|
|
||||||
/// Check if this type is in a set of valid types
|
|
||||||
template<class TYPES>
|
|
||||||
void verify(TYPES validtypes, const std::string& s) const {
|
|
||||||
std::string key = qualifiedName("::");
|
|
||||||
if (find(validtypes.begin(), validtypes.end(), key) == validtypes.end())
|
|
||||||
throw DependencyMissing(key, s);
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
|
||||||
|
|
||||||
friend struct ReturnValue;
|
|
||||||
|
|
||||||
std::string str(bool add_ptr) const;
|
|
||||||
|
|
||||||
/// Example: out[1] = wrap_shared_ptr(pairResult.second,"Test", false);
|
|
||||||
void wrap_result(const std::string& out, const std::string& result,
|
|
||||||
FileWriter& file, const TypeAttributesTable& typeAttributes) const;
|
|
||||||
|
|
||||||
/// Creates typedef
|
|
||||||
void wrapTypeUnwrap(FileWriter& wrapperFile) const;
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Encapsulates return value of a method or function, possibly a pair
|
|
||||||
*/
|
*/
|
||||||
struct ReturnValue {
|
struct ReturnValue {
|
||||||
|
|
||||||
|
@ -86,8 +36,7 @@ struct ReturnValue {
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Substitute template argument
|
/// Substitute template argument
|
||||||
ReturnValue substituteTemplate(const std::string& templateArg,
|
ReturnValue expandTemplate(const TemplateSubstitution& ts) const;
|
||||||
const Qualified& qualifiedType, const Qualified& expandedClass) const;
|
|
||||||
|
|
||||||
std::string return_type(bool add_ptr) const;
|
std::string return_type(bool add_ptr) const;
|
||||||
|
|
||||||
|
@ -100,20 +49,14 @@ struct ReturnValue {
|
||||||
|
|
||||||
void emit_matlab(FileWriter& proxyFile) const;
|
void emit_matlab(FileWriter& proxyFile) const;
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os, const ReturnValue& r) {
|
||||||
|
if (!r.isPair && r.type1.category == ReturnType::VOID)
|
||||||
|
os << "void";
|
||||||
|
else
|
||||||
|
os << r.return_type(true);
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
template<class T>
|
|
||||||
inline void verifyReturnTypes(const std::vector<std::string>& validtypes,
|
|
||||||
const std::map<std::string, T>& vt) {
|
|
||||||
typedef typename std::map<std::string, T>::value_type NamedMethod;
|
|
||||||
BOOST_FOREACH(const NamedMethod& namedMethod, vt) {
|
|
||||||
const T& t = namedMethod.second;
|
|
||||||
BOOST_FOREACH(const ReturnValue& retval, t.returnVals) {
|
|
||||||
retval.type1.verify(validtypes, t.name);
|
|
||||||
if (retval.isPair)
|
|
||||||
retval.type2.verify(validtypes, t.name);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
* @author Richard Roberts
|
* @author Richard Roberts
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include "StaticMethod.h"
|
#include "Method.h"
|
||||||
#include "utilities.h"
|
#include "utilities.h"
|
||||||
|
|
||||||
#include <boost/foreach.hpp>
|
#include <boost/foreach.hpp>
|
||||||
|
@ -30,117 +30,146 @@ using namespace std;
|
||||||
using namespace wrap;
|
using namespace wrap;
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void StaticMethod::addOverload(bool verbose, const std::string& name,
|
void StaticMethod::addOverload(bool verbose, Str name, const ArgumentList& args,
|
||||||
const ArgumentList& args, const ReturnValue& retVal) {
|
const ReturnValue& retVal, const Qualified& instName) {
|
||||||
this->verbose = verbose;
|
|
||||||
this->name = name;
|
Function::addOverload(verbose, name, instName);
|
||||||
this->argLists.push_back(args);
|
SignatureOverloads::addOverload(args, retVal);
|
||||||
this->returnVals.push_back(retVal);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void StaticMethod::proxy_wrapper_fragments(FileWriter& file,
|
void StaticMethod::proxy_header(FileWriter& proxyFile) const {
|
||||||
FileWriter& wrapperFile, const string& cppClassName,
|
string upperName = matlabName();
|
||||||
const std::string& matlabQualName, const std::string& matlabUniqueName,
|
upperName[0] = toupper(upperName[0], locale());
|
||||||
const string& wrapperName, const TypeAttributesTable& typeAttributes,
|
proxyFile.oss << " function varargout = " << upperName << "(varargin)\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
void StaticMethod::proxy_wrapper_fragments(FileWriter& proxyFile,
|
||||||
|
FileWriter& wrapperFile, Str cppClassName, Str matlabQualName,
|
||||||
|
Str matlabUniqueName, Str wrapperName,
|
||||||
|
const TypeAttributesTable& typeAttributes,
|
||||||
vector<string>& functionNames) const {
|
vector<string>& functionNames) const {
|
||||||
|
|
||||||
string upperName = name;
|
// emit header, e.g., function varargout = templatedMethod(this, varargin)
|
||||||
upperName[0] = std::toupper(upperName[0], std::locale());
|
proxy_header(proxyFile);
|
||||||
|
|
||||||
file.oss << " function varargout = " << upperName << "(varargin)\n";
|
// Emit comments for documentation
|
||||||
//Comments for documentation
|
string up_name = boost::to_upper_copy(matlabName());
|
||||||
string up_name = boost::to_upper_copy(name);
|
proxyFile.oss << " % " << up_name << " usage: ";
|
||||||
file.oss << " % " << up_name << " usage: ";
|
usage_fragment(proxyFile, matlabName());
|
||||||
unsigned int argLCount = 0;
|
|
||||||
BOOST_FOREACH(ArgumentList argList, argLists) {
|
|
||||||
argList.emit_prototype(file, name);
|
|
||||||
if (argLCount != argLists.size() - 1)
|
|
||||||
file.oss << ", ";
|
|
||||||
else
|
|
||||||
file.oss << " : returns "
|
|
||||||
<< returnVals[0].return_type(false) << endl;
|
|
||||||
argLCount++;
|
|
||||||
}
|
|
||||||
|
|
||||||
file.oss << " % "
|
// Emit URL to Doxygen page
|
||||||
|
proxyFile.oss << " % "
|
||||||
<< "Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html"
|
<< "Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html"
|
||||||
<< endl;
|
<< endl;
|
||||||
file.oss << " % " << "" << endl;
|
|
||||||
file.oss << " % " << "Usage" << endl;
|
|
||||||
BOOST_FOREACH(ArgumentList argList, argLists) {
|
|
||||||
file.oss << " % ";
|
|
||||||
argList.emit_prototype(file, up_name);
|
|
||||||
file.oss << endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Check arguments for all overloads
|
|
||||||
for (size_t overload = 0; overload < argLists.size(); ++overload) {
|
|
||||||
|
|
||||||
|
// Handle special case of single overload with all numeric arguments
|
||||||
|
if (nrOverloads() == 1 && argumentList(0).allScalar()) {
|
||||||
// Output proxy matlab code
|
// Output proxy matlab code
|
||||||
file.oss << " " << (overload == 0 ? "" : "else");
|
// TODO: document why is it OK to not check arguments in this case
|
||||||
|
proxyFile.oss << " ";
|
||||||
const int id = (int) functionNames.size();
|
const int id = (int) functionNames.size();
|
||||||
argLists[overload].emit_conditional_call(file, returnVals[overload],
|
argumentList(0).emit_call(proxyFile, returnValue(0), wrapperName, id,
|
||||||
wrapperName, id, true); // last bool is to indicate static !
|
isStatic());
|
||||||
|
|
||||||
// Output C++ wrapper code
|
// Output C++ wrapper code
|
||||||
const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName,
|
const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName,
|
||||||
matlabUniqueName, (int) overload, id, typeAttributes);
|
matlabUniqueName, 0, id, typeAttributes, templateArgValue_);
|
||||||
|
|
||||||
|
// Add to function list
|
||||||
|
functionNames.push_back(wrapFunctionName);
|
||||||
|
} else {
|
||||||
|
// Check arguments for all overloads
|
||||||
|
for (size_t i = 0; i < nrOverloads(); ++i) {
|
||||||
|
|
||||||
|
// Output proxy matlab code
|
||||||
|
proxyFile.oss << " " << (i == 0 ? "" : "else");
|
||||||
|
const int id = (int) functionNames.size();
|
||||||
|
argumentList(i).emit_conditional_call(proxyFile, returnValue(i),
|
||||||
|
wrapperName, id, isStatic());
|
||||||
|
|
||||||
|
// Output C++ wrapper code
|
||||||
|
const string wrapFunctionName = wrapper_fragment(wrapperFile,
|
||||||
|
cppClassName, matlabUniqueName, i, id, typeAttributes,
|
||||||
|
templateArgValue_);
|
||||||
|
|
||||||
// Add to function list
|
// Add to function list
|
||||||
functionNames.push_back(wrapFunctionName);
|
functionNames.push_back(wrapFunctionName);
|
||||||
}
|
}
|
||||||
file.oss << " else\n";
|
proxyFile.oss << " else\n";
|
||||||
file.oss << " error('Arguments do not match any overload of function "
|
proxyFile.oss
|
||||||
<< matlabQualName << "." << upperName << "');" << endl;
|
<< " error('Arguments do not match any overload of function "
|
||||||
file.oss << " end\n";
|
<< matlabQualName << "." << name_ << "');" << endl;
|
||||||
|
proxyFile.oss << " end\n";
|
||||||
|
}
|
||||||
|
|
||||||
file.oss << " end\n";
|
proxyFile.oss << " end\n";
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string StaticMethod::wrapper_fragment(FileWriter& file,
|
string StaticMethod::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName,
|
||||||
const string& cppClassName, const string& matlabUniqueName, int overload,
|
Str matlabUniqueName, int overload, int id,
|
||||||
int id, const TypeAttributesTable& typeAttributes) const {
|
const TypeAttributesTable& typeAttributes,
|
||||||
|
const Qualified& instName) const {
|
||||||
|
|
||||||
// generate code
|
// generate code
|
||||||
|
|
||||||
const string wrapFunctionName = matlabUniqueName + "_" + name + "_"
|
const string wrapFunctionName = matlabUniqueName + "_" + name_ + "_"
|
||||||
+ boost::lexical_cast<string>(id);
|
+ boost::lexical_cast<string>(id);
|
||||||
|
|
||||||
const ArgumentList& args = argLists[overload];
|
const ArgumentList& args = argumentList(overload);
|
||||||
const ReturnValue& returnVal = returnVals[overload];
|
const ReturnValue& returnVal = returnValue(overload);
|
||||||
|
|
||||||
// call
|
// call
|
||||||
file.oss << "void " << wrapFunctionName
|
wrapperFile.oss << "void " << wrapFunctionName
|
||||||
<< "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
<< "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
|
||||||
// start
|
// start
|
||||||
file.oss << "{\n";
|
wrapperFile.oss << "{\n";
|
||||||
|
|
||||||
returnVal.wrapTypeUnwrap(file);
|
returnVal.wrapTypeUnwrap(wrapperFile);
|
||||||
|
|
||||||
file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;"
|
wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName
|
||||||
<< endl;
|
<< "> Shared;" << endl;
|
||||||
|
|
||||||
// check arguments
|
// get call
|
||||||
// NOTE: for static functions, there is no object passed
|
// for static methods: cppClassName::staticMethod<TemplateVal>
|
||||||
file.oss << " checkArguments(\"" << matlabUniqueName << "." << name
|
// for instance methods: obj->instanceMethod<TemplateVal>
|
||||||
<< "\",nargout,nargin," << args.size() << ");\n";
|
string expanded = wrapper_call(wrapperFile, cppClassName, matlabUniqueName,
|
||||||
|
args, returnVal, typeAttributes, instName);
|
||||||
|
|
||||||
// unwrap arguments, see Argument.cpp
|
expanded += ("(" + args.names() + ")");
|
||||||
args.matlab_unwrap(file, 0); // We start at 0 because there is no self object
|
|
||||||
|
|
||||||
// call method with default type and wrap result
|
|
||||||
if (returnVal.type1.name != "void")
|
if (returnVal.type1.name != "void")
|
||||||
returnVal.wrap_result(cppClassName + "::" + name + "(" + args.names() + ")",
|
returnVal.wrap_result(expanded, wrapperFile, typeAttributes);
|
||||||
file, typeAttributes);
|
|
||||||
else
|
else
|
||||||
file.oss << cppClassName + "::" + name + "(" + args.names() + ");\n";
|
wrapperFile.oss << " " + expanded + ";\n";
|
||||||
|
|
||||||
// finish
|
// finish
|
||||||
file.oss << "}\n";
|
wrapperFile.oss << "}\n";
|
||||||
|
|
||||||
return wrapFunctionName;
|
return wrapFunctionName;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
|
||||||
|
Str matlabUniqueName, const ArgumentList& args,
|
||||||
|
const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes,
|
||||||
|
const Qualified& instName) const {
|
||||||
|
// check arguments
|
||||||
|
// NOTE: for static functions, there is no object passed
|
||||||
|
wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << "." << name_
|
||||||
|
<< "\",nargout,nargin," << args.size() << ");\n";
|
||||||
|
|
||||||
|
// unwrap arguments, see Argument.cpp
|
||||||
|
args.matlab_unwrap(wrapperFile, 0); // We start at 0 because there is no self object
|
||||||
|
|
||||||
|
// call method and wrap result
|
||||||
|
// example: out[0]=wrap<bool>(staticMethod(t));
|
||||||
|
string expanded = cppClassName + "::" + name_;
|
||||||
|
if (!instName.empty())
|
||||||
|
expanded += ("<" + instName.qualifiedName("::") + ">");
|
||||||
|
|
||||||
|
return expanded;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -19,44 +19,66 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Argument.h"
|
#include "Function.h"
|
||||||
#include "ReturnValue.h"
|
|
||||||
#include "TypeAttributesTable.h"
|
|
||||||
|
|
||||||
namespace wrap {
|
namespace wrap {
|
||||||
|
|
||||||
/// StaticMethod class
|
/// StaticMethod class
|
||||||
struct StaticMethod {
|
struct StaticMethod: public Function, public SignatureOverloads {
|
||||||
|
|
||||||
|
typedef const std::string& Str;
|
||||||
|
|
||||||
/// Constructor creates empty object
|
/// Constructor creates empty object
|
||||||
StaticMethod(bool verbosity = true) :
|
StaticMethod(bool verbosity = true) :
|
||||||
verbose(verbosity) {
|
Function(verbosity) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Then the instance variables are set directly by the Module constructor
|
virtual bool isStatic() const {
|
||||||
bool verbose;
|
return true;
|
||||||
std::string name;
|
}
|
||||||
std::vector<ArgumentList> argLists;
|
|
||||||
std::vector<ReturnValue> returnVals;
|
|
||||||
|
|
||||||
// The first time this function is called, it initializes the class members
|
void addOverload(bool verbose, Str name, const ArgumentList& args,
|
||||||
// with those in rhs, but in subsequent calls it adds additional argument
|
const ReturnValue& retVal, const Qualified& instName);
|
||||||
// lists as function overloads.
|
|
||||||
void addOverload(bool verbose, const std::string& name,
|
// emit a list of comments, one for each overload
|
||||||
const ArgumentList& args, const ReturnValue& retVal);
|
void comment_fragment(FileWriter& proxyFile) const {
|
||||||
|
SignatureOverloads::comment_fragment(proxyFile, name_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void verifyArguments(const std::vector<std::string>& validArgs) const {
|
||||||
|
SignatureOverloads::verifyArguments(validArgs, name_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void verifyReturnTypes(const std::vector<std::string>& validtypes) const {
|
||||||
|
SignatureOverloads::verifyReturnTypes(validtypes, name_);
|
||||||
|
}
|
||||||
|
|
||||||
// MATLAB code generation
|
// MATLAB code generation
|
||||||
// classPath is class directory, e.g., ../matlab/@Point2
|
// classPath is class directory, e.g., ../matlab/@Point2
|
||||||
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
void proxy_wrapper_fragments(FileWriter& proxyFile, FileWriter& wrapperFile,
|
||||||
const std::string& cppClassName, const std::string& matlabQualName,
|
Str cppClassName, Str matlabQualName, Str matlabUniqueName,
|
||||||
const std::string& matlabUniqueName, const std::string& wrapperName,
|
Str wrapperName, const TypeAttributesTable& typeAttributes,
|
||||||
const TypeAttributesTable& typeAttributes,
|
|
||||||
std::vector<std::string>& functionNames) const;
|
std::vector<std::string>& functionNames) const;
|
||||||
|
|
||||||
private:
|
friend std::ostream& operator<<(std::ostream& os, const StaticMethod& m) {
|
||||||
std::string wrapper_fragment(FileWriter& file,
|
for (size_t i = 0; i < m.nrOverloads(); i++)
|
||||||
const std::string& cppClassName, const std::string& matlabUniqueName,
|
os << "static " << m.returnVals_[i] << " " << m.name_ << m.argLists_[i];
|
||||||
int overload, int id, const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
virtual void proxy_header(FileWriter& proxyFile) const;
|
||||||
|
|
||||||
|
std::string wrapper_fragment(FileWriter& wrapperFile, Str cppClassName,
|
||||||
|
Str matlabUniqueName, int overload, int id,
|
||||||
|
const TypeAttributesTable& typeAttributes, const Qualified& instName =
|
||||||
|
Qualified()) const; ///< cpp wrapper
|
||||||
|
|
||||||
|
virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName,
|
||||||
|
Str matlabUniqueName, const ArgumentList& args,
|
||||||
|
const ReturnValue& returnVal, const TypeAttributesTable& typeAttributes,
|
||||||
|
const Qualified& instName) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
@ -46,8 +46,10 @@ Class TemplateInstantiationTypedef::findAndExpand(
|
||||||
|
|
||||||
// Instantiate it
|
// Instantiate it
|
||||||
Class classInst = *matchedClass;
|
Class classInst = *matchedClass;
|
||||||
for (size_t i = 0; i < typeList.size(); ++i)
|
for (size_t i = 0; i < typeList.size(); ++i) {
|
||||||
classInst = classInst.expandTemplate(classInst.templateArgs[i], typeList[i], *this);
|
TemplateSubstitution ts(classInst.templateArgs[i], typeList[i], *this);
|
||||||
|
classInst = classInst.expandTemplate(ts);
|
||||||
|
}
|
||||||
|
|
||||||
// Fix class properties
|
// Fix class properties
|
||||||
classInst.name = name;
|
classInst.name = name;
|
||||||
|
|
|
@ -0,0 +1,76 @@
|
||||||
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||||
|
* Atlanta, Georgia 30332-0415
|
||||||
|
* All Rights Reserved
|
||||||
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||||
|
|
||||||
|
* See LICENSE for the license information
|
||||||
|
|
||||||
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file TemplateSubstitution.h
|
||||||
|
* @brief Auxiliary class for template substitutions
|
||||||
|
* @author Frank Dellaert
|
||||||
|
* @date Nov 13, 2014
|
||||||
|
**/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "ReturnType.h"
|
||||||
|
#include <string>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
namespace wrap {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* e.g. TemplateSubstitution("T", gtsam::Point2, gtsam::PriorFactorPoint2)
|
||||||
|
*/
|
||||||
|
class TemplateSubstitution {
|
||||||
|
|
||||||
|
std::string templateArg_;
|
||||||
|
Qualified qualifiedType_, expandedClass_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
TemplateSubstitution(const std::string& a, const Qualified& t,
|
||||||
|
const Qualified& e) :
|
||||||
|
templateArg_(a), qualifiedType_(t), expandedClass_(e) {
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string expandedClassName() const {
|
||||||
|
return expandedClass_.name;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Substitute if needed
|
||||||
|
Qualified operator()(const Qualified& type) const {
|
||||||
|
if (type.name == templateArg_ && type.namespaces.empty())
|
||||||
|
return qualifiedType_;
|
||||||
|
else if (type.name == "This")
|
||||||
|
return expandedClass_;
|
||||||
|
else
|
||||||
|
return type;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Substitute if needed
|
||||||
|
ReturnType operator()(const ReturnType& type) const {
|
||||||
|
ReturnType instType = type;
|
||||||
|
if (type.name == templateArg_ && type.namespaces.empty())
|
||||||
|
instType.rename(qualifiedType_);
|
||||||
|
else if (type.name == "This")
|
||||||
|
instType.rename(expandedClass_);
|
||||||
|
return instType;
|
||||||
|
}
|
||||||
|
|
||||||
|
friend std::ostream& operator<<(std::ostream& os,
|
||||||
|
const TemplateSubstitution& ts) {
|
||||||
|
os << ts.templateArg_ << '/' << ts.qualifiedType_.qualifiedName("::")
|
||||||
|
<< " (" << ts.expandedClass_.qualifiedName("::") << ")";
|
||||||
|
return os;
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
} // \namespace wrap
|
||||||
|
|
|
@ -0,0 +1,90 @@
|
||||||
|
%class Point2, see Doxygen page for details
|
||||||
|
%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
%
|
||||||
|
%-------Constructors-------
|
||||||
|
%Point2()
|
||||||
|
%Point2(double x, double y)
|
||||||
|
%
|
||||||
|
%-------Methods-------
|
||||||
|
%argChar(char a) : returns void
|
||||||
|
%argUChar(unsigned char a) : returns void
|
||||||
|
%dim() : returns int
|
||||||
|
%returnChar() : returns char
|
||||||
|
%vectorConfusion() : returns VectorNotEigen
|
||||||
|
%x() : returns double
|
||||||
|
%y() : returns double
|
||||||
|
%
|
||||||
|
classdef Point2 < handle
|
||||||
|
properties
|
||||||
|
ptr_gtsamPoint2 = 0
|
||||||
|
end
|
||||||
|
methods
|
||||||
|
function obj = Point2(varargin)
|
||||||
|
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
||||||
|
my_ptr = varargin{2};
|
||||||
|
geometry_wrapper(0, my_ptr);
|
||||||
|
elseif nargin == 0
|
||||||
|
my_ptr = geometry_wrapper(1);
|
||||||
|
elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')
|
||||||
|
my_ptr = geometry_wrapper(2, varargin{1}, varargin{2});
|
||||||
|
else
|
||||||
|
error('Arguments do not match any overload of gtsam.Point2 constructor');
|
||||||
|
end
|
||||||
|
obj.ptr_gtsamPoint2 = my_ptr;
|
||||||
|
end
|
||||||
|
|
||||||
|
function delete(obj)
|
||||||
|
geometry_wrapper(3, obj.ptr_gtsamPoint2);
|
||||||
|
end
|
||||||
|
|
||||||
|
function display(obj), obj.print(''); end
|
||||||
|
%DISPLAY Calls print on the object
|
||||||
|
function disp(obj), obj.display; end
|
||||||
|
%DISP Calls print on the object
|
||||||
|
function varargout = argChar(this, varargin)
|
||||||
|
% ARGCHAR usage: argChar(char a) : returns void
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
geometry_wrapper(4, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = argUChar(this, varargin)
|
||||||
|
% ARGUCHAR usage: argUChar(unsigned char a) : returns void
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
geometry_wrapper(5, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = dim(this, varargin)
|
||||||
|
% DIM usage: dim() : returns int
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(6, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = returnChar(this, varargin)
|
||||||
|
% RETURNCHAR usage: returnChar() : returns char
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(7, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = vectorConfusion(this, varargin)
|
||||||
|
% VECTORCONFUSION usage: vectorConfusion() : returns VectorNotEigen
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(8, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = x(this, varargin)
|
||||||
|
% X usage: x() : returns double
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(9, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = y(this, varargin)
|
||||||
|
% Y usage: y() : returns double
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(10, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
end
|
||||||
|
|
||||||
|
methods(Static = true)
|
||||||
|
end
|
||||||
|
end
|
|
@ -0,0 +1,61 @@
|
||||||
|
%class Point3, see Doxygen page for details
|
||||||
|
%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
%
|
||||||
|
%-------Constructors-------
|
||||||
|
%Point3(double x, double y, double z)
|
||||||
|
%
|
||||||
|
%-------Methods-------
|
||||||
|
%norm() : returns double
|
||||||
|
%
|
||||||
|
%-------Static Methods-------
|
||||||
|
%StaticFunctionRet(double z) : returns gtsam::Point3
|
||||||
|
%staticFunction() : returns double
|
||||||
|
%
|
||||||
|
classdef Point3 < handle
|
||||||
|
properties
|
||||||
|
ptr_gtsamPoint3 = 0
|
||||||
|
end
|
||||||
|
methods
|
||||||
|
function obj = Point3(varargin)
|
||||||
|
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
||||||
|
my_ptr = varargin{2};
|
||||||
|
geometry_wrapper(11, my_ptr);
|
||||||
|
elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')
|
||||||
|
my_ptr = geometry_wrapper(12, varargin{1}, varargin{2}, varargin{3});
|
||||||
|
else
|
||||||
|
error('Arguments do not match any overload of gtsam.Point3 constructor');
|
||||||
|
end
|
||||||
|
obj.ptr_gtsamPoint3 = my_ptr;
|
||||||
|
end
|
||||||
|
|
||||||
|
function delete(obj)
|
||||||
|
geometry_wrapper(13, obj.ptr_gtsamPoint3);
|
||||||
|
end
|
||||||
|
|
||||||
|
function display(obj), obj.print(''); end
|
||||||
|
%DISPLAY Calls print on the object
|
||||||
|
function disp(obj), obj.display; end
|
||||||
|
%DISP Calls print on the object
|
||||||
|
function varargout = norm(this, varargin)
|
||||||
|
% NORM usage: norm() : returns double
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(14, this, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
end
|
||||||
|
|
||||||
|
methods(Static = true)
|
||||||
|
function varargout = StaticFunctionRet(varargin)
|
||||||
|
% STATICFUNCTIONRET usage: StaticFunctionRet(double z) : returns gtsam::Point3
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(15, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = StaticFunction(varargin)
|
||||||
|
% STATICFUNCTION usage: staticFunction() : returns double
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
varargout{1} = geometry_wrapper(16, varargin{:});
|
||||||
|
end
|
||||||
|
|
||||||
|
end
|
||||||
|
end
|
|
@ -107,16 +107,20 @@ classdef MyTemplatePoint2 < MyBase
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
function varargout = templatedMethod(this, varargin)
|
function varargout = templatedMethodPoint2(this, varargin)
|
||||||
% TEMPLATEDMETHOD usage: templatedMethod(Point2 t), templatedMethod(Point3 t) : returns void
|
% TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void
|
||||||
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
%
|
|
||||||
% Method Overloads
|
|
||||||
% templatedMethod(Point2 t)
|
|
||||||
% templatedMethod(Point3 t)
|
|
||||||
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
|
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
|
||||||
geometry_wrapper(54, this, varargin{:});
|
geometry_wrapper(54, this, varargin{:});
|
||||||
elseif length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
|
else
|
||||||
|
error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod');
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = templatedMethodPoint3(this, varargin)
|
||||||
|
% TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
|
||||||
geometry_wrapper(55, this, varargin{:});
|
geometry_wrapper(55, this, varargin{:});
|
||||||
else
|
else
|
||||||
error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod');
|
error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod');
|
||||||
|
|
|
@ -107,16 +107,20 @@ classdef MyTemplatePoint3 < MyBase
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
function varargout = templatedMethod(this, varargin)
|
function varargout = templatedMethodPoint2(this, varargin)
|
||||||
% TEMPLATEDMETHOD usage: templatedMethod(Point2 t), templatedMethod(Point3 t) : returns void
|
% TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void
|
||||||
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
%
|
|
||||||
% Method Overloads
|
|
||||||
% templatedMethod(Point2 t)
|
|
||||||
% templatedMethod(Point3 t)
|
|
||||||
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
|
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
|
||||||
geometry_wrapper(67, this, varargin{:});
|
geometry_wrapper(67, this, varargin{:});
|
||||||
elseif length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
|
else
|
||||||
|
error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod');
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
function varargout = templatedMethodPoint3(this, varargin)
|
||||||
|
% TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void
|
||||||
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
|
||||||
geometry_wrapper(68, this, varargin{:});
|
geometry_wrapper(68, this, varargin{:});
|
||||||
else
|
else
|
||||||
error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod');
|
error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod');
|
||||||
|
|
|
@ -672,6 +672,7 @@ void MyTemplatePoint2_templatedMethod_54(int nargout, mxArray *out[], int nargin
|
||||||
gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
|
gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
|
||||||
obj->templatedMethod<gtsam::Point2>(t);
|
obj->templatedMethod<gtsam::Point2>(t);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
|
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
|
||||||
|
@ -815,6 +816,7 @@ void MyTemplatePoint3_templatedMethod_67(int nargout, mxArray *out[], int nargin
|
||||||
gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
|
gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
|
||||||
obj->templatedMethod<gtsam::Point2>(t);
|
obj->templatedMethod<gtsam::Point2>(t);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyTemplatePoint3_templatedMethod_68(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyTemplatePoint3_templatedMethod_68(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
|
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
|
||||||
|
|
|
@ -65,14 +65,7 @@ classdef ClassA < handle
|
||||||
function varargout = Afunction(varargin)
|
function varargout = Afunction(varargin)
|
||||||
% AFUNCTION usage: afunction() : returns double
|
% AFUNCTION usage: afunction() : returns double
|
||||||
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
%
|
|
||||||
% Usage
|
|
||||||
% AFUNCTION()
|
|
||||||
if length(varargin) == 0
|
|
||||||
varargout{1} = testNamespaces_wrapper(12, varargin{:});
|
varargout{1} = testNamespaces_wrapper(12, varargin{:});
|
||||||
else
|
|
||||||
error('Arguments do not match any overload of function ns2.ClassA.Afunction');
|
|
||||||
end
|
|
||||||
end
|
end
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|
|
@ -97,12 +97,11 @@ TEST( wrap, Small ) {
|
||||||
|
|
||||||
// Method 1
|
// Method 1
|
||||||
Method m1 = cls.method("x");
|
Method m1 = cls.method("x");
|
||||||
EXPECT(assert_equal("x", m1.name));
|
EXPECT(assert_equal("x", m1.name()));
|
||||||
EXPECT(m1.is_const_);
|
EXPECT(m1.isConst());
|
||||||
LONGS_EQUAL(1, m1.argLists.size());
|
LONGS_EQUAL(1, m1.nrOverloads());
|
||||||
LONGS_EQUAL(1, m1.returnVals.size());
|
|
||||||
|
|
||||||
ReturnValue rv1 = m1.returnVals.front();
|
ReturnValue rv1 = m1.returnValue(0);
|
||||||
EXPECT(!rv1.isPair);
|
EXPECT(!rv1.isPair);
|
||||||
EXPECT(!rv1.type1.isPtr);
|
EXPECT(!rv1.type1.isPtr);
|
||||||
EXPECT(assert_equal("double", rv1.type1.name));
|
EXPECT(assert_equal("double", rv1.type1.name));
|
||||||
|
@ -110,12 +109,11 @@ TEST( wrap, Small ) {
|
||||||
|
|
||||||
// Method 2
|
// Method 2
|
||||||
Method m2 = cls.method("returnMatrix");
|
Method m2 = cls.method("returnMatrix");
|
||||||
EXPECT(assert_equal("returnMatrix", m2.name));
|
EXPECT(assert_equal("returnMatrix", m2.name()));
|
||||||
EXPECT(m2.is_const_);
|
EXPECT(m2.isConst());
|
||||||
LONGS_EQUAL(1, m2.argLists.size());
|
LONGS_EQUAL(1, m2.nrOverloads());
|
||||||
LONGS_EQUAL(1, m2.returnVals.size());
|
|
||||||
|
|
||||||
ReturnValue rv2 = m2.returnVals.front();
|
ReturnValue rv2 = m2.returnValue(0);
|
||||||
EXPECT(!rv2.isPair);
|
EXPECT(!rv2.isPair);
|
||||||
EXPECT(!rv2.type1.isPtr);
|
EXPECT(!rv2.type1.isPtr);
|
||||||
EXPECT(assert_equal("Matrix", rv2.type1.name));
|
EXPECT(assert_equal("Matrix", rv2.type1.name));
|
||||||
|
@ -123,12 +121,11 @@ TEST( wrap, Small ) {
|
||||||
|
|
||||||
// Method 3
|
// Method 3
|
||||||
Method m3 = cls.method("returnPoint2");
|
Method m3 = cls.method("returnPoint2");
|
||||||
EXPECT(assert_equal("returnPoint2", m3.name));
|
EXPECT(assert_equal("returnPoint2", m3.name()));
|
||||||
EXPECT(m3.is_const_);
|
EXPECT(m3.isConst());
|
||||||
LONGS_EQUAL(1, m3.argLists.size());
|
LONGS_EQUAL(1, m3.nrOverloads());
|
||||||
LONGS_EQUAL(1, m3.returnVals.size());
|
|
||||||
|
|
||||||
ReturnValue rv3 = m3.returnVals.front();
|
ReturnValue rv3 = m3.returnValue(0);
|
||||||
EXPECT(!rv3.isPair);
|
EXPECT(!rv3.isPair);
|
||||||
EXPECT(!rv3.type1.isPtr);
|
EXPECT(!rv3.type1.isPtr);
|
||||||
EXPECT(assert_equal("Point2", rv3.type1.name));
|
EXPECT(assert_equal("Point2", rv3.type1.name));
|
||||||
|
@ -137,11 +134,10 @@ TEST( wrap, Small ) {
|
||||||
// Static Method 1
|
// Static Method 1
|
||||||
// static Vector returnVector();
|
// static Vector returnVector();
|
||||||
StaticMethod sm1 = cls.static_methods.at("returnVector");
|
StaticMethod sm1 = cls.static_methods.at("returnVector");
|
||||||
EXPECT(assert_equal("returnVector", sm1.name));
|
EXPECT(assert_equal("returnVector", sm1.name()));
|
||||||
LONGS_EQUAL(1, sm1.argLists.size());
|
LONGS_EQUAL(1, sm1.nrOverloads());
|
||||||
LONGS_EQUAL(1, sm1.returnVals.size());
|
|
||||||
|
|
||||||
ReturnValue rv4 = sm1.returnVals.front();
|
ReturnValue rv4 = sm1.returnValue(0);
|
||||||
EXPECT(!rv4.isPair);
|
EXPECT(!rv4.isPair);
|
||||||
EXPECT(!rv4.type1.isPtr);
|
EXPECT(!rv4.type1.isPtr);
|
||||||
EXPECT(assert_equal("Vector", rv4.type1.name));
|
EXPECT(assert_equal("Vector", rv4.type1.name));
|
||||||
|
@ -188,35 +184,35 @@ TEST( wrap, Geometry ) {
|
||||||
|
|
||||||
Class cls = module.classes.at(0);
|
Class cls = module.classes.at(0);
|
||||||
EXPECT(assert_equal("Point2", cls.name));
|
EXPECT(assert_equal("Point2", cls.name));
|
||||||
EXPECT_LONGS_EQUAL(2, cls.constructor.args_list.size());
|
EXPECT_LONGS_EQUAL(2, cls.constructor.nrOverloads());
|
||||||
EXPECT_LONGS_EQUAL(7, cls.nrMethods());
|
EXPECT_LONGS_EQUAL(7, cls.nrMethods());
|
||||||
|
|
||||||
{
|
{
|
||||||
// char returnChar() const;
|
// char returnChar() const;
|
||||||
CHECK(cls.exists("returnChar"));
|
CHECK(cls.exists("returnChar"));
|
||||||
Method m1 = cls.method("returnChar");
|
Method m1 = cls.method("returnChar");
|
||||||
LONGS_EQUAL(1, m1.returnVals.size());
|
LONGS_EQUAL(1, m1.nrOverloads());
|
||||||
EXPECT(assert_equal("char", m1.returnVals.front().type1.name));
|
EXPECT(assert_equal("char", m1.returnValue(0).type1.name));
|
||||||
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnVals.front().type1.category);
|
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category);
|
||||||
EXPECT(!m1.returnVals.front().isPair);
|
EXPECT(!m1.returnValue(0).isPair);
|
||||||
EXPECT(assert_equal("returnChar", m1.name));
|
EXPECT(assert_equal("returnChar", m1.name()));
|
||||||
LONGS_EQUAL(1, m1.argLists.size());
|
LONGS_EQUAL(1, m1.nrOverloads());
|
||||||
EXPECT_LONGS_EQUAL(0, m1.argLists.front().size());
|
EXPECT_LONGS_EQUAL(0, m1.argumentList(0).size());
|
||||||
EXPECT(m1.is_const_);
|
EXPECT(m1.isConst());
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
{
|
||||||
// VectorNotEigen vectorConfusion();
|
// VectorNotEigen vectorConfusion();
|
||||||
CHECK(cls.exists("vectorConfusion"));
|
CHECK(cls.exists("vectorConfusion"));
|
||||||
Method m1 = cls.method("vectorConfusion");
|
Method m1 = cls.method("vectorConfusion");
|
||||||
LONGS_EQUAL(1, m1.returnVals.size());
|
LONGS_EQUAL(1, m1.nrOverloads());
|
||||||
EXPECT(assert_equal("VectorNotEigen", m1.returnVals.front().type1.name));
|
EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name));
|
||||||
EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnVals.front().type1.category);
|
EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category);
|
||||||
EXPECT(!m1.returnVals.front().isPair);
|
EXPECT(!m1.returnValue(0).isPair);
|
||||||
EXPECT(assert_equal("vectorConfusion", m1.name));
|
EXPECT(assert_equal("vectorConfusion", m1.name()));
|
||||||
LONGS_EQUAL(1, m1.argLists.size());
|
LONGS_EQUAL(1, m1.nrOverloads());
|
||||||
EXPECT_LONGS_EQUAL(0, m1.argLists.front().size());
|
EXPECT_LONGS_EQUAL(0, m1.argumentList(0).size());
|
||||||
EXPECT(!m1.is_const_);
|
EXPECT(!m1.isConst());
|
||||||
}
|
}
|
||||||
|
|
||||||
EXPECT_LONGS_EQUAL(0, cls.static_methods.size());
|
EXPECT_LONGS_EQUAL(0, cls.static_methods.size());
|
||||||
|
@ -233,13 +229,13 @@ TEST( wrap, Geometry ) {
|
||||||
{
|
{
|
||||||
Class cls = module.classes.at(1);
|
Class cls = module.classes.at(1);
|
||||||
EXPECT(assert_equal("Point3", cls.name));
|
EXPECT(assert_equal("Point3", cls.name));
|
||||||
EXPECT_LONGS_EQUAL(1, cls.constructor.args_list.size());
|
EXPECT_LONGS_EQUAL(1, cls.constructor.nrOverloads());
|
||||||
EXPECT_LONGS_EQUAL(1, cls.nrMethods());
|
EXPECT_LONGS_EQUAL(1, cls.nrMethods());
|
||||||
EXPECT_LONGS_EQUAL(2, cls.static_methods.size());
|
EXPECT_LONGS_EQUAL(2, cls.static_methods.size());
|
||||||
EXPECT_LONGS_EQUAL(1, cls.namespaces.size());
|
EXPECT_LONGS_EQUAL(1, cls.namespaces.size());
|
||||||
|
|
||||||
// first constructor takes 3 doubles
|
// first constructor takes 3 doubles
|
||||||
ArgumentList c1 = cls.constructor.args_list.front();
|
ArgumentList c1 = cls.constructor.argumentList(0);
|
||||||
EXPECT_LONGS_EQUAL(3, c1.size());
|
EXPECT_LONGS_EQUAL(3, c1.size());
|
||||||
|
|
||||||
// check first double argument
|
// check first double argument
|
||||||
|
@ -252,13 +248,13 @@ TEST( wrap, Geometry ) {
|
||||||
// check method
|
// check method
|
||||||
CHECK(cls.exists("norm"));
|
CHECK(cls.exists("norm"));
|
||||||
Method m1 = cls.method("norm");
|
Method m1 = cls.method("norm");
|
||||||
LONGS_EQUAL(1, m1.returnVals.size());
|
LONGS_EQUAL(1, m1.nrOverloads());
|
||||||
EXPECT(assert_equal("double", m1.returnVals.front().type1.name));
|
EXPECT(assert_equal("double", m1.returnValue(0).type1.name));
|
||||||
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnVals.front().type1.category);
|
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category);
|
||||||
EXPECT(assert_equal("norm", m1.name));
|
EXPECT(assert_equal("norm", m1.name()));
|
||||||
LONGS_EQUAL(1, m1.argLists.size());
|
LONGS_EQUAL(1, m1.nrOverloads());
|
||||||
EXPECT_LONGS_EQUAL(0, m1.argLists.front().size());
|
EXPECT_LONGS_EQUAL(0, m1.argumentList(0).size());
|
||||||
EXPECT(m1.is_const_);
|
EXPECT(m1.isConst());
|
||||||
|
|
||||||
#ifndef WRAP_DISABLE_SERIALIZE
|
#ifndef WRAP_DISABLE_SERIALIZE
|
||||||
// check serialization flag
|
// check serialization flag
|
||||||
|
@ -270,7 +266,7 @@ TEST( wrap, Geometry ) {
|
||||||
// Test class is the third one
|
// Test class is the third one
|
||||||
{
|
{
|
||||||
Class testCls = module.classes.at(2);
|
Class testCls = module.classes.at(2);
|
||||||
EXPECT_LONGS_EQUAL( 2, testCls.constructor.args_list.size());
|
EXPECT_LONGS_EQUAL( 2, testCls.constructor.nrOverloads());
|
||||||
EXPECT_LONGS_EQUAL(19, testCls.nrMethods());
|
EXPECT_LONGS_EQUAL(19, testCls.nrMethods());
|
||||||
EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size());
|
EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size());
|
||||||
EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size());
|
EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size());
|
||||||
|
@ -278,19 +274,19 @@ TEST( wrap, Geometry ) {
|
||||||
// function to parse: pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
|
// function to parse: pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
|
||||||
CHECK(testCls.exists("return_pair"));
|
CHECK(testCls.exists("return_pair"));
|
||||||
Method m2 = testCls.method("return_pair");
|
Method m2 = testCls.method("return_pair");
|
||||||
LONGS_EQUAL(1, m2.returnVals.size());
|
LONGS_EQUAL(1, m2.nrOverloads());
|
||||||
EXPECT(m2.returnVals.front().isPair);
|
EXPECT(m2.returnValue(0).isPair);
|
||||||
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnVals.front().type1.category);
|
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category);
|
||||||
EXPECT(assert_equal("Vector", m2.returnVals.front().type1.name));
|
EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name));
|
||||||
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnVals.front().type2.category);
|
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category);
|
||||||
EXPECT(assert_equal("Matrix", m2.returnVals.front().type2.name));
|
EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name));
|
||||||
|
|
||||||
// checking pointer args and return values
|
// checking pointer args and return values
|
||||||
// pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
|
// pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
|
||||||
CHECK(testCls.exists("return_ptrs"));
|
CHECK(testCls.exists("return_ptrs"));
|
||||||
Method m3 = testCls.method("return_ptrs");
|
Method m3 = testCls.method("return_ptrs");
|
||||||
LONGS_EQUAL(1, m3.argLists.size());
|
LONGS_EQUAL(1, m3.nrOverloads());
|
||||||
ArgumentList args = m3.argLists.front();
|
ArgumentList args = m3.argumentList(0);
|
||||||
LONGS_EQUAL(2, args.size());
|
LONGS_EQUAL(2, args.size());
|
||||||
|
|
||||||
Argument arg1 = args.at(0);
|
Argument arg1 = args.at(0);
|
||||||
|
@ -316,10 +312,10 @@ TEST( wrap, Geometry ) {
|
||||||
CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end());
|
CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end());
|
||||||
{
|
{
|
||||||
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
||||||
EXPECT(assert_equal("aGlobalFunction", gfunc.name));
|
EXPECT(assert_equal("aGlobalFunction", gfunc.name()));
|
||||||
LONGS_EQUAL(1, gfunc.returnVals.size());
|
LONGS_EQUAL(1, gfunc.nrOverloads());
|
||||||
EXPECT(assert_equal("Vector", gfunc.returnVals.front().type1.name));
|
EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name));
|
||||||
EXPECT_LONGS_EQUAL(1, gfunc.argLists.size());
|
EXPECT_LONGS_EQUAL(1, gfunc.nrOverloads());
|
||||||
LONGS_EQUAL(1, gfunc.overloads.size());
|
LONGS_EQUAL(1, gfunc.overloads.size());
|
||||||
EXPECT(gfunc.overloads.front().namespaces.empty());
|
EXPECT(gfunc.overloads.front().namespaces.empty());
|
||||||
}
|
}
|
||||||
|
@ -390,10 +386,9 @@ TEST( wrap, parse_namespaces ) {
|
||||||
CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end());
|
CHECK(module.global_functions.find("aGlobalFunction") != module.global_functions.end());
|
||||||
{
|
{
|
||||||
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
||||||
EXPECT(assert_equal("aGlobalFunction", gfunc.name));
|
EXPECT(assert_equal("aGlobalFunction", gfunc.name()));
|
||||||
LONGS_EQUAL(2, gfunc.returnVals.size());
|
LONGS_EQUAL(2, gfunc.nrOverloads());
|
||||||
EXPECT(assert_equal("Vector", gfunc.returnVals.front().type1.name));
|
EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name));
|
||||||
EXPECT_LONGS_EQUAL(2, gfunc.argLists.size());
|
|
||||||
|
|
||||||
// check namespaces
|
// check namespaces
|
||||||
LONGS_EQUAL(2, gfunc.overloads.size());
|
LONGS_EQUAL(2, gfunc.overloads.size());
|
||||||
|
|
Loading…
Reference in New Issue