Semi-private name/namespaces
parent
f1c91d5d4b
commit
6d916c6b75
|
@ -50,25 +50,25 @@ ArgumentList ArgumentList::expandTemplate(
|
|||
/* ************************************************************************* */
|
||||
string Argument::matlabClass(const string& delim) const {
|
||||
string result;
|
||||
BOOST_FOREACH(const string& ns, type.namespaces)
|
||||
BOOST_FOREACH(const string& ns, type.namespaces())
|
||||
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";
|
||||
if (type.name == "Vector" || type.name == "Matrix")
|
||||
if (type.name() == "Vector" || type.name() == "Matrix")
|
||||
return result + "double";
|
||||
if (type.name == "int" || type.name == "size_t")
|
||||
if (type.name() == "int" || type.name() == "size_t")
|
||||
return result + "numeric";
|
||||
if (type.name == "bool")
|
||||
if (type.name() == "bool")
|
||||
return result + "logical";
|
||||
return result + type.name;
|
||||
return result + type.name();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool Argument::isScalar() const {
|
||||
return (type.name == "bool" || type.name == "char"
|
||||
|| type.name == "unsigned char" || type.name == "int"
|
||||
|| type.name == "size_t" || type.name == "double");
|
||||
return (type.name() == "bool" || type.name() == "char"
|
||||
|| type.name() == "unsigned char" || type.name() == "int"
|
||||
|| type.name() == "size_t" || type.name() == "double");
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -102,7 +102,7 @@ void Argument::matlab_unwrap(FileWriter& file, const string& matlabName) const {
|
|||
/* ************************************************************************* */
|
||||
void Argument::proxy_check(FileWriter& proxyFile, const string& s) const {
|
||||
proxyFile.oss << "isa(" << s << ",'" << matlabClass(".") << "')";
|
||||
if (type.name == "Vector")
|
||||
if (type.name() == "Vector")
|
||||
proxyFile.oss << " && size(" << s << ",2)==1";
|
||||
}
|
||||
|
||||
|
@ -113,7 +113,7 @@ string ArgumentList::types() const {
|
|||
BOOST_FOREACH(Argument arg, *this) {
|
||||
if (!first)
|
||||
str += ",";
|
||||
str += arg.type.name;
|
||||
str += arg.type.name();
|
||||
first = false;
|
||||
}
|
||||
return str;
|
||||
|
@ -125,14 +125,14 @@ string ArgumentList::signature() const {
|
|||
bool cap = false;
|
||||
|
||||
BOOST_FOREACH(Argument arg, *this) {
|
||||
BOOST_FOREACH(char ch, arg.type.name)
|
||||
BOOST_FOREACH(char ch, arg.type.name())
|
||||
if (isupper(ch)) {
|
||||
sig += ch;
|
||||
//If there is a capital letter, we don't want to read it below
|
||||
cap = true;
|
||||
}
|
||||
if (!cap)
|
||||
sig += arg.type.name[0];
|
||||
sig += arg.type.name()[0];
|
||||
//Reset to default
|
||||
cap = false;
|
||||
}
|
||||
|
@ -179,7 +179,7 @@ void ArgumentList::emit_prototype(FileWriter& file, const string& name) const {
|
|||
BOOST_FOREACH(Argument arg, *this) {
|
||||
if (!first)
|
||||
file.oss << ", ";
|
||||
file.oss << arg.type.name << " " << arg.name;
|
||||
file.oss << arg.type.name() << " " << arg.name;
|
||||
first = false;
|
||||
}
|
||||
file.oss << ")";
|
||||
|
|
|
@ -57,7 +57,7 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
|
|||
vector<string>& functionNames) const {
|
||||
|
||||
// Create namespace folders
|
||||
createNamespaceStructure(namespaces, toolboxPath);
|
||||
createNamespaceStructure(namespaces(), toolboxPath);
|
||||
|
||||
// open destination classFile
|
||||
string classFile = matlabName(toolboxPath);
|
||||
|
@ -74,14 +74,14 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
|
|||
// we want our class to inherit the handle class for memory purposes
|
||||
const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName;
|
||||
comment_fragment(proxyFile);
|
||||
proxyFile.oss << "classdef " << name << " < " << parent << endl;
|
||||
proxyFile.oss << "classdef " << name() << " < " << parent << endl;
|
||||
proxyFile.oss << " properties\n";
|
||||
proxyFile.oss << " ptr_" << matlabUniqueName << " = 0\n";
|
||||
proxyFile.oss << " end\n";
|
||||
proxyFile.oss << " methods\n";
|
||||
|
||||
// Constructor
|
||||
proxyFile.oss << " function obj = " << name << "(varargin)\n";
|
||||
proxyFile.oss << " function obj = " << name() << "(varargin)\n";
|
||||
// Special pointer constructors - one in MATLAB to create an object and
|
||||
// assign a pointer returned from a C++ function. In turn this MATLAB
|
||||
// constructor calls a special C++ function that just adds the object to
|
||||
|
@ -266,7 +266,7 @@ Class Class::expandTemplate(const TemplateSubstitution& ts) const {
|
|||
inst.methods_ = expandMethodTemplate(methods_, ts);
|
||||
inst.static_methods = expandMethodTemplate(static_methods, ts);
|
||||
inst.constructor = constructor.expandTemplate(ts);
|
||||
inst.deconstructor.name = inst.name;
|
||||
inst.deconstructor.name = inst.name();
|
||||
return inst;
|
||||
}
|
||||
|
||||
|
@ -276,10 +276,10 @@ vector<Class> Class::expandTemplate(Str templateArg,
|
|||
vector<Class> result;
|
||||
BOOST_FOREACH(const Qualified& instName, instantiations) {
|
||||
Qualified expandedClass = (Qualified) (*this);
|
||||
expandedClass.name += instName.name;
|
||||
expandedClass.expand(instName.name());
|
||||
const TemplateSubstitution ts(templateArg, instName, expandedClass);
|
||||
Class inst = expandTemplate(ts);
|
||||
inst.name = expandedClass.name;
|
||||
inst.name_ = expandedClass.name();
|
||||
inst.templateArgs.clear();
|
||||
inst.typedefName = qualifiedName("::") + "<" + instName.qualifiedName("::")
|
||||
+ ">";
|
||||
|
@ -297,14 +297,14 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName,
|
|||
// Create method to expand
|
||||
// For all values of the template argument, create a new method
|
||||
BOOST_FOREACH(const Qualified& instName, templateArgValues) {
|
||||
const TemplateSubstitution ts(templateArgName, instName, this->name);
|
||||
const TemplateSubstitution ts(templateArgName, instName, name());
|
||||
// substitute template in arguments
|
||||
ArgumentList expandedArgs = argumentList.expandTemplate(ts);
|
||||
// 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;
|
||||
string expandedMethodName = methodName + instName.name();
|
||||
methods_[expandedMethodName].addOverload(methodName, expandedArgs,
|
||||
expandedRetVal, is_const, instName, verbose);
|
||||
}
|
||||
|
@ -369,7 +369,7 @@ void Class::appendInheritedMethods(const Class& cls,
|
|||
// Find parent
|
||||
BOOST_FOREACH(const Class& parent, classes) {
|
||||
// We found a parent class for our parent, TODO improve !
|
||||
if (parent.name == cls.qualifiedParent.name) {
|
||||
if (parent.name() == cls.qualifiedParent.name()) {
|
||||
methods_.insert(parent.methods_.begin(), parent.methods_.end());
|
||||
appendInheritedMethods(parent, classes);
|
||||
}
|
||||
|
@ -380,11 +380,11 @@ void Class::appendInheritedMethods(const Class& cls,
|
|||
/* ************************************************************************* */
|
||||
string Class::getTypedef() const {
|
||||
string result;
|
||||
BOOST_FOREACH(Str namesp, namespaces) {
|
||||
BOOST_FOREACH(Str namesp, namespaces()) {
|
||||
result += ("namespace " + namesp + " { ");
|
||||
}
|
||||
result += ("typedef " + typedefName + " " + name + ";");
|
||||
for (size_t i = 0; i < namespaces.size(); ++i) {
|
||||
result += ("typedef " + typedefName + " " + name() + ";");
|
||||
for (size_t i = 0; i < namespaces().size(); ++i) {
|
||||
result += " }";
|
||||
}
|
||||
return result;
|
||||
|
@ -392,7 +392,7 @@ string Class::getTypedef() 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
|
||||
<< "%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n";
|
||||
|
||||
|
@ -412,7 +412,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const {
|
|||
proxyFile.oss << "%\n%-------Serialization Interface-------\n";
|
||||
proxyFile.oss << "%string_serialize() : returns string\n";
|
||||
proxyFile.oss << "%string_deserialize(string serialized) : returns "
|
||||
<< this->name << "\n";
|
||||
<< name() << "\n";
|
||||
}
|
||||
|
||||
proxyFile.oss << "%\n";
|
||||
|
@ -605,12 +605,12 @@ string Class::getSerializationExport() const {
|
|||
|
||||
/* ************************************************************************* */
|
||||
void Class::python_wrapper(FileWriter& wrapperFile) const {
|
||||
wrapperFile.oss << "class_<" << name << ">(\"" << name << "\")\n";
|
||||
constructor.python_wrapper(wrapperFile, name);
|
||||
wrapperFile.oss << "class_<" << name() << ">(\"" << name() << "\")\n";
|
||||
constructor.python_wrapper(wrapperFile, name());
|
||||
BOOST_FOREACH(const StaticMethod& m, static_methods | boost::adaptors::map_values)
|
||||
m.python_wrapper(wrapperFile, name);
|
||||
m.python_wrapper(wrapperFile, name());
|
||||
BOOST_FOREACH(const Method& m, methods_ | boost::adaptors::map_values)
|
||||
m.python_wrapper(wrapperFile, name);
|
||||
m.python_wrapper(wrapperFile, name());
|
||||
wrapperFile.oss << ";\n\n";
|
||||
}
|
||||
|
||||
|
|
|
@ -117,7 +117,7 @@ public:
|
|||
void python_wrapper(FileWriter& wrapperFile) const;
|
||||
|
||||
friend std::ostream& operator<<(std::ostream& os, const Class& cls) {
|
||||
os << "class " << cls.name << "{\n";
|
||||
os << "class " << cls.name() << "{\n";
|
||||
os << cls.constructor << ";\n";
|
||||
BOOST_FOREACH(const StaticMethod& m, cls.static_methods | boost::adaptors::map_values)
|
||||
os << m << ";\n";
|
||||
|
|
|
@ -42,7 +42,7 @@ bool Function::initializeOrCheck(const string& name, const Qualified& instName,
|
|||
verbose_ = verbose;
|
||||
return true;
|
||||
} else {
|
||||
if (name_ != name || templateArgValue_ != instName || verbose_ != verbose)
|
||||
if (name_ != name || !(templateArgValue_ == instName) || verbose_ != verbose)
|
||||
throw runtime_error(
|
||||
"Function::initializeOrCheck called with different arguments: with name "
|
||||
+ name + " instead of expected " + name_
|
||||
|
|
|
@ -53,7 +53,7 @@ public:
|
|||
if (templateArgValue_.empty())
|
||||
return name_;
|
||||
else
|
||||
return name_ + templateArgValue_.name;
|
||||
return name_ + templateArgValue_.name();
|
||||
}
|
||||
|
||||
/// Emit function call to MATLAB (no argument checking)
|
||||
|
|
|
@ -19,8 +19,8 @@ using namespace std;
|
|||
void GlobalFunction::addOverload(const Qualified& overload,
|
||||
const ArgumentList& args, const ReturnValue& retVal,
|
||||
const Qualified& instName, bool verbose) {
|
||||
string name(overload.name);
|
||||
FullyOverloadedFunction::addOverload(name, args, retVal, instName, verbose);
|
||||
FullyOverloadedFunction::addOverload(overload.name(), args, retVal, instName,
|
||||
verbose);
|
||||
overloads.push_back(overload);
|
||||
}
|
||||
|
||||
|
@ -37,7 +37,7 @@ void GlobalFunction::matlab_proxy(const string& toolboxPath,
|
|||
for (size_t i = 0; i < overloads.size(); ++i) {
|
||||
Qualified overload = overloads.at(i);
|
||||
// use concatenated namespaces as key
|
||||
string str_ns = qualifiedName("", overload.namespaces);
|
||||
string str_ns = qualifiedName("", overload.namespaces());
|
||||
const ReturnValue& ret = returnValue(i);
|
||||
const ArgumentList& args = argumentList(i);
|
||||
grouped_functions[str_ns].addOverload(overload, args, ret);
|
||||
|
@ -59,7 +59,7 @@ void GlobalFunction::generateSingleFunction(const string& toolboxPath,
|
|||
|
||||
// create the folder for the namespace
|
||||
const Qualified& overload1 = overloads.front();
|
||||
createNamespaceStructure(overload1.namespaces, toolboxPath);
|
||||
createNamespaceStructure(overload1.namespaces(), toolboxPath);
|
||||
|
||||
// open destination mfunctionFileName
|
||||
string mfunctionFileName = overload1.matlabName(toolboxPath);
|
||||
|
@ -104,7 +104,7 @@ void GlobalFunction::generateSingleFunction(const string& toolboxPath,
|
|||
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(cppName + "(" + args.names() + ")", file,
|
||||
typeAttributes);
|
||||
else
|
||||
|
|
|
@ -123,7 +123,7 @@ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName,
|
|||
args, instName);
|
||||
|
||||
expanded += ("(" + args.names() + ")");
|
||||
if (returnVal.type1.name != "void")
|
||||
if (returnVal.type1.name() != "void")
|
||||
returnVal.wrap_result(expanded, wrapperFile, typeAttributes);
|
||||
else
|
||||
wrapperFile.oss << " " + expanded + ";\n";
|
||||
|
|
151
wrap/Module.cpp
151
wrap/Module.cpp
|
@ -25,9 +25,6 @@
|
|||
//#define BOOST_SPIRIT_DEBUG
|
||||
#include "spirit_actors.h"
|
||||
|
||||
#include <boost/spirit/include/classic_confix.hpp>
|
||||
#include <boost/spirit/include/classic_clear_actor.hpp>
|
||||
#include <boost/spirit/include/classic_insert_at_actor.hpp>
|
||||
#ifdef __GNUC__
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
|
@ -51,8 +48,6 @@ using namespace BOOST_SPIRIT_CLASSIC_NS;
|
|||
namespace bl = boost::lambda;
|
||||
namespace fs = boost::filesystem;
|
||||
|
||||
typedef rule<BOOST_SPIRIT_CLASSIC_NS::phrase_scanner_t> Rule;
|
||||
|
||||
/* ************************************************************************* */
|
||||
// We parse an interface file into a Module object.
|
||||
// The grammar is defined using the boost/spirit combinatorial parser.
|
||||
|
@ -102,7 +97,6 @@ Module::Module(const string& interfacePath,
|
|||
void Module::parseMarkup(const std::string& data) {
|
||||
// The parse imperatively :-( updates variables gradually during parse
|
||||
// The one with postfix 0 are used to reset the variables after parse.
|
||||
vector<string> namespaces; // current namespace tag
|
||||
|
||||
//----------------------------------------------------------------------------
|
||||
// Grammar with actions that build the Class object. Actions are
|
||||
|
@ -113,129 +107,74 @@ void Module::parseMarkup(const std::string& data) {
|
|||
// http://www.boost.org/doc/libs/1_37_0/libs/spirit/classic/doc/directives.html
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
Rule comments_p = comment_p("/*", "*/") | comment_p("//", eol_p);
|
||||
|
||||
Rule basisType_p =
|
||||
(str_p("string") | "bool" | "size_t" | "int" | "double" | "char" | "unsigned char");
|
||||
|
||||
Rule keywords_p =
|
||||
(str_p("const") | "static" | "namespace" | "void" | basisType_p);
|
||||
|
||||
Rule eigenType_p =
|
||||
(str_p("Vector") | "Matrix");
|
||||
|
||||
//Rule for STL Containers (class names are lowercase)
|
||||
Rule stlType_p = (str_p("vector") | "list");
|
||||
|
||||
Rule className_p = (lexeme_d[upper_p >> *(alnum_p | '_')] - eigenType_p - keywords_p) | stlType_p;
|
||||
|
||||
Rule namespace_name_p = lexeme_d[lower_p >> *(alnum_p | '_')] - keywords_p;
|
||||
|
||||
Argument arg0, arg;
|
||||
Rule namespace_arg_p = namespace_name_p
|
||||
[push_back_a(arg.type.namespaces)] >> str_p("::");
|
||||
|
||||
Rule argEigenType_p =
|
||||
eigenType_p[assign_a(arg.type.name)];
|
||||
|
||||
Rule eigenRef_p =
|
||||
!str_p("const") [assign_a(arg.is_const,true)] >>
|
||||
eigenType_p [assign_a(arg.type.name)] >>
|
||||
ch_p('&') [assign_a(arg.is_ref,true)];
|
||||
|
||||
Rule classArg_p =
|
||||
!str_p("const") [assign_a(arg.is_const,true)] >>
|
||||
*namespace_arg_p >>
|
||||
className_p[assign_a(arg.type.name)] >>
|
||||
!ch_p('&')[assign_a(arg.is_ref,true)];
|
||||
|
||||
Rule name_p = lexeme_d[alpha_p >> *(alnum_p | '_')];
|
||||
// Define Rule and instantiate basic rules
|
||||
typedef rule<phrase_scanner_t> Rule;
|
||||
basic_rules<phrase_scanner_t> basic;
|
||||
|
||||
// TODO, do we really need cls here? Non-local
|
||||
Class cls0(verbose),cls(verbose);
|
||||
Rule classParent_p =
|
||||
*(namespace_name_p[push_back_a(cls.qualifiedParent.namespaces)] >> str_p("::")) >>
|
||||
className_p[assign_a(cls.qualifiedParent.name)];
|
||||
TypeGrammar classParent_p(cls.qualifiedParent);
|
||||
|
||||
// parse "gtsam::Pose2" and add to templateArgValues
|
||||
Qualified templateArgValue;
|
||||
vector<Qualified> templateArgValues;
|
||||
Rule templateArgValue_p =
|
||||
(*(namespace_name_p[push_back_a(templateArgValue.namespaces)] >> str_p("::")) >>
|
||||
(className_p | eigenType_p)[assign_a(templateArgValue.name)])
|
||||
[push_back_a(templateArgValues, templateArgValue)]
|
||||
[clear_a(templateArgValue)];
|
||||
TypeGrammar(templateArgValue)
|
||||
[push_back_a( templateArgValues, templateArgValue)];
|
||||
|
||||
// template<CALIBRATION = {gtsam::Cal3DS2}>
|
||||
string templateArgName;
|
||||
Rule templateArgValues_p =
|
||||
(str_p("template") >>
|
||||
'<' >> name_p[assign_a(templateArgName)] >> '=' >>
|
||||
'<' >> basic.name_p[assign_a(templateArgName)] >> '=' >>
|
||||
'{' >> !(templateArgValue_p >> *(',' >> templateArgValue_p)) >> '}' >>
|
||||
'>');
|
||||
|
||||
// parse "gtsam::Pose2" and add to singleInstantiation.typeList
|
||||
TemplateInstantiationTypedef singleInstantiation;
|
||||
TemplateInstantiationTypedef singleInstantiation, singleInstantiation0;
|
||||
Rule templateSingleInstantiationArg_p =
|
||||
(*(namespace_name_p[push_back_a(templateArgValue.namespaces)] >> str_p("::")) >>
|
||||
(className_p | eigenType_p)[assign_a(templateArgValue.name)])
|
||||
[push_back_a(singleInstantiation.typeList, templateArgValue)]
|
||||
[clear_a(templateArgValue)];
|
||||
TypeGrammar(templateArgValue)
|
||||
[push_back_a(singleInstantiation.typeList, templateArgValue)];
|
||||
|
||||
// typedef gtsam::RangeFactor<gtsam::Pose2, gtsam::Point2> RangeFactorPosePoint2;
|
||||
TemplateInstantiationTypedef singleInstantiation0;
|
||||
Rule templateSingleInstantiation_p =
|
||||
(str_p("typedef") >>
|
||||
*(namespace_name_p[push_back_a(singleInstantiation.class_.namespaces)] >> str_p("::")) >>
|
||||
className_p[assign_a(singleInstantiation.class_.name)] >>
|
||||
'<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >>
|
||||
'>' >>
|
||||
className_p[assign_a(singleInstantiation.name)] >>
|
||||
TypeGrammar(singleInstantiation.class_) >>
|
||||
'<' >> templateSingleInstantiationArg_p >> *(',' >> templateSingleInstantiationArg_p) >> '>' >>
|
||||
TypeGrammar(singleInstantiation) >>
|
||||
';')
|
||||
[assign_a(singleInstantiation.namespaces, namespaces)]
|
||||
[push_back_a(templateInstantiationTypedefs, singleInstantiation)]
|
||||
[assign_a(singleInstantiation, singleInstantiation0)];
|
||||
|
||||
// template<POSE, POINT>
|
||||
Rule templateList_p =
|
||||
(str_p("template") >>
|
||||
'<' >> name_p[push_back_a(cls.templateArgs)] >> *(',' >> name_p[push_back_a(cls.templateArgs)]) >>
|
||||
'<' >> basic.name_p[push_back_a(cls.templateArgs)] >> *(',' >> basic.name_p[push_back_a(cls.templateArgs)]) >>
|
||||
'>');
|
||||
|
||||
// NOTE: allows for pointers to all types
|
||||
// Slightly more permissive than before on basis/eigen type qualification
|
||||
ArgumentList args;
|
||||
Rule argument_p =
|
||||
((basisType_p[assign_a(arg.type.name)] | argEigenType_p | eigenRef_p | classArg_p)
|
||||
>> !ch_p('*')[assign_a(arg.is_ptr,true)]
|
||||
>> name_p[assign_a(arg.name)])
|
||||
[push_back_a(args, arg)]
|
||||
[assign_a(arg,arg0)];
|
||||
Argument arg0, arg;
|
||||
TypeGrammar argument_type_g(arg.type);
|
||||
Rule argument_p =
|
||||
!str_p("const")[assign_a(arg.is_const, true)]
|
||||
>> argument_type_g
|
||||
>> (!ch_p('&')[assign_a(arg.is_ref, true)] | !ch_p('*')[assign_a(arg.is_ptr, true)])
|
||||
[push_back_a(args, arg)]
|
||||
[assign_a(arg,arg0)];
|
||||
|
||||
Rule argumentList_p = !argument_p >> * (',' >> argument_p);
|
||||
|
||||
// parse class constructor
|
||||
Constructor constructor0(verbose), constructor(verbose);
|
||||
Rule constructor_p =
|
||||
(className_p >> '(' >> argumentList_p >> ')' >> ';' >> !comments_p)
|
||||
(basic.className_p >> '(' >> argumentList_p >> ')' >> ';' >> !basic.comments_p)
|
||||
[bl::bind(&Constructor::push_back, bl::var(constructor), bl::var(args))]
|
||||
[clear_a(args)];
|
||||
|
||||
vector<string> namespaces_return; /// namespace for current return type
|
||||
Rule namespace_ret_p = namespace_name_p[push_back_a(namespaces_return)] >> str_p("::");
|
||||
|
||||
// HACK: use const values instead of using enums themselves - somehow this doesn't result in values getting assigned to gibberish
|
||||
static const ReturnType::return_category RETURN_EIGEN = ReturnType::EIGEN;
|
||||
static const ReturnType::return_category RETURN_BASIS = ReturnType::BASIS;
|
||||
static const ReturnType::return_category RETURN_CLASS = ReturnType::CLASS;
|
||||
static const ReturnType::return_category RETURN_VOID = ReturnType::VOID;
|
||||
|
||||
ReturnType retType0, retType;
|
||||
Rule returnType_p =
|
||||
(basisType_p[assign_a(retType.name)][assign_a(retType.category, RETURN_BASIS)]) |
|
||||
((*namespace_ret_p)[assign_a(retType.namespaces, namespaces_return)][clear_a(namespaces_return)]
|
||||
>> (className_p[assign_a(retType.name)][assign_a(retType.category, RETURN_CLASS)]) >>
|
||||
!ch_p('*')[assign_a(retType.isPtr,true)]) |
|
||||
(eigenType_p[assign_a(retType.name)][assign_a(retType.category, RETURN_EIGEN)]);
|
||||
Rule returnType_p = TypeGrammar(retType);
|
||||
|
||||
ReturnValue retVal0, retVal;
|
||||
Rule returnType1_p = returnType_p[assign_a(retVal.type1,retType)][assign_a(retType,retType0)];
|
||||
|
@ -245,9 +184,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
(str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p >> '>')
|
||||
[assign_a(retVal.isPair,true)];
|
||||
|
||||
Rule void_p = str_p("void")[assign_a(retVal.type1.name)][assign_a(retVal.type1.category, RETURN_VOID)];
|
||||
|
||||
Rule returnValue_p = void_p | pair_p | returnType1_p;
|
||||
Rule returnValue_p = pair_p | returnType1_p;
|
||||
|
||||
Rule methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')];
|
||||
|
||||
|
@ -258,7 +195,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
!templateArgValues_p >>
|
||||
(returnValue_p >> methodName_p[assign_a(methodName)] >>
|
||||
'(' >> argumentList_p >> ')' >>
|
||||
!str_p("const")[assign_a(isConst,true)] >> ';' >> *comments_p)
|
||||
!str_p("const")[assign_a(isConst,true)] >> ';' >> *basic.comments_p)
|
||||
[bl::bind(&Class::addMethod, bl::var(cls), verbose, bl::var(isConst),
|
||||
bl::var(methodName), bl::var(args), bl::var(retVal),
|
||||
bl::var(templateArgName), bl::var(templateArgValues))]
|
||||
|
@ -271,7 +208,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
|
||||
Rule static_method_p =
|
||||
(str_p("static") >> returnValue_p >> staticMethodName_p[assign_a(methodName)] >>
|
||||
'(' >> argumentList_p >> ')' >> ';' >> *comments_p)
|
||||
'(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p)
|
||||
[bl::bind(&StaticMethod::addOverload,
|
||||
bl::var(cls.static_methods)[bl::var(methodName)],
|
||||
bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)]
|
||||
|
@ -281,6 +218,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
Rule functions_p = constructor_p | method_p | static_method_p;
|
||||
|
||||
// parse a full class
|
||||
vector<string> namespaces; // current namespace tag
|
||||
vector<Qualified> templateInstantiations;
|
||||
Rule class_p =
|
||||
eps_p[assign_a(cls,cls0)]
|
||||
|
@ -291,15 +229,15 @@ void Module::parseMarkup(const std::string& data) {
|
|||
| templateList_p)
|
||||
>> !(str_p("virtual")[assign_a(cls.isVirtual, true)])
|
||||
>> str_p("class")
|
||||
>> className_p[assign_a(cls.name)]
|
||||
>> basic.className_p[assign_a(cls.name_)]
|
||||
>> ((':' >> classParent_p >> '{') | '{')
|
||||
>> *(functions_p | comments_p)
|
||||
>> *(functions_p | basic.comments_p)
|
||||
>> str_p("};"))
|
||||
[bl::bind(&Constructor::initializeOrCheck, bl::var(constructor),
|
||||
bl::var(cls.name), Qualified(), verbose)]
|
||||
bl::var(cls.name_), Qualified(), verbose)]
|
||||
[assign_a(cls.constructor, constructor)]
|
||||
[assign_a(cls.namespaces, namespaces)]
|
||||
[assign_a(cls.deconstructor.name,cls.name)]
|
||||
[assign_a(cls.namespaces_, namespaces)]
|
||||
[assign_a(cls.deconstructor.name,cls.name_)]
|
||||
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls),
|
||||
bl::var(templateInstantiations))]
|
||||
[clear_a(templateInstantiations)]
|
||||
|
@ -309,11 +247,11 @@ void Module::parseMarkup(const std::string& data) {
|
|||
// parse a global function
|
||||
Qualified globalFunction;
|
||||
Rule global_function_p =
|
||||
(returnValue_p >> staticMethodName_p[assign_a(globalFunction.name)] >>
|
||||
'(' >> argumentList_p >> ')' >> ';' >> *comments_p)
|
||||
[assign_a(globalFunction.namespaces,namespaces)]
|
||||
(returnValue_p >> staticMethodName_p[assign_a(globalFunction.name_)] >>
|
||||
'(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p)
|
||||
[assign_a(globalFunction.namespaces_,namespaces)]
|
||||
[bl::bind(&GlobalFunction::addOverload,
|
||||
bl::var(global_functions)[bl::var(globalFunction.name)],
|
||||
bl::var(global_functions)[bl::var(globalFunction.name_)],
|
||||
bl::var(globalFunction), bl::var(args), bl::var(retVal), Qualified(),verbose)]
|
||||
[assign_a(retVal,retVal0)]
|
||||
[clear_a(globalFunction)]
|
||||
|
@ -328,9 +266,9 @@ void Module::parseMarkup(const std::string& data) {
|
|||
|
||||
Rule namespace_def_p =
|
||||
(str_p("namespace")
|
||||
>> namespace_name_p[push_back_a(namespaces)]
|
||||
>> basic.namepsace_p[push_back_a(namespaces)]
|
||||
>> ch_p('{')
|
||||
>> *(include_p | class_p | templateSingleInstantiation_p | global_function_p | namespace_def_p | comments_p)
|
||||
>> *(include_p | class_p | templateSingleInstantiation_p | global_function_p | namespace_def_p | basic.comments_p)
|
||||
>> ch_p('}'))
|
||||
[pop_a(namespaces)];
|
||||
|
||||
|
@ -343,17 +281,20 @@ void Module::parseMarkup(const std::string& data) {
|
|||
Rule forward_declaration_p =
|
||||
!(str_p("virtual")[assign_a(fwDec.isVirtual, true)])
|
||||
>> str_p("class")
|
||||
>> (*(namespace_name_p >> str_p("::")) >> className_p)[assign_a(fwDec.name)]
|
||||
>> (*(basic.namepsace_p >> str_p("::")) >> basic.className_p)[assign_a(fwDec.name)]
|
||||
>> ch_p(';')
|
||||
[push_back_a(forward_declarations, fwDec)]
|
||||
[assign_a(fwDec, fwDec0)];
|
||||
|
||||
Rule module_content_p = comments_p | include_p | class_p | templateSingleInstantiation_p | forward_declaration_p | global_function_p | namespace_def_p;
|
||||
Rule module_content_p = basic.comments_p | include_p | class_p
|
||||
| templateSingleInstantiation_p | forward_declaration_p
|
||||
| global_function_p | namespace_def_p;
|
||||
|
||||
Rule module_p = *module_content_p >> !end_p;
|
||||
|
||||
//----------------------------------------------------------------------------
|
||||
// for debugging, define BOOST_SPIRIT_DEBUG
|
||||
#define BOOST_SPIRIT_DEBUG
|
||||
# ifdef BOOST_SPIRIT_DEBUG
|
||||
BOOST_SPIRIT_DEBUG_NODE(className_p);
|
||||
BOOST_SPIRIT_DEBUG_NODE(classPtr_p);
|
||||
|
@ -381,7 +322,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
if(!info.full) {
|
||||
printf("parsing stopped at \n%.20s\n",info.stop);
|
||||
cout << "Stopped near:\n"
|
||||
"class '" << cls.name << "'\n"
|
||||
"class '" << cls.name() << "'\n"
|
||||
"method '" << methodName << "'\n"
|
||||
"argument '" << arg.name << "'" << endl;
|
||||
throw ParseFailed((int)info.length);
|
||||
|
|
|
@ -34,10 +34,18 @@ namespace wrap {
|
|||
/**
|
||||
* Class to encapuslate a qualified name, i.e., with (nested) namespaces
|
||||
*/
|
||||
struct Qualified {
|
||||
class Qualified {
|
||||
|
||||
std::vector<std::string> namespaces; ///< Stack of namespaces
|
||||
std::string name; ///< type name
|
||||
//protected:
|
||||
public:
|
||||
|
||||
std::vector<std::string> namespaces_; ///< Stack of namespaces
|
||||
std::string name_; ///< type name
|
||||
|
||||
friend class TypeGrammar;
|
||||
friend class TemplateSubstitution;
|
||||
|
||||
public:
|
||||
|
||||
/// the different categories
|
||||
typedef enum {
|
||||
|
@ -49,43 +57,76 @@ struct Qualified {
|
|||
category(VOID) {
|
||||
}
|
||||
|
||||
Qualified(const std::string& name_, Category c = CLASS) :
|
||||
name(name_), category(c) {
|
||||
Qualified(const std::string& n, Category c = CLASS) :
|
||||
name_(n), category(c) {
|
||||
}
|
||||
|
||||
Qualified(const std::string& ns1, const std::string& ns2,
|
||||
const std::string& n, Category c = CLASS) :
|
||||
name_(n), category(c) {
|
||||
namespaces_.push_back(ns1);
|
||||
namespaces_.push_back(ns2);
|
||||
}
|
||||
|
||||
Qualified(const std::string& ns1, const std::string& n, Category c = CLASS) :
|
||||
name_(n), category(c) {
|
||||
namespaces_.push_back(ns1);
|
||||
}
|
||||
|
||||
std::string name() const {
|
||||
return name_;
|
||||
}
|
||||
|
||||
std::vector<std::string> namespaces() const {
|
||||
return namespaces_;
|
||||
}
|
||||
|
||||
// Qualified is 'abused' as template argument name as well
|
||||
// this function checks whether *this matches with templateArg
|
||||
bool match(const std::string& templateArg) const {
|
||||
return (name_ == templateArg && namespaces_.empty() && category == CLASS);
|
||||
}
|
||||
|
||||
void rename(const Qualified& q) {
|
||||
namespaces_ = q.namespaces_;
|
||||
name_ = q.name_;
|
||||
category = q.category;
|
||||
}
|
||||
|
||||
void expand(const std::string& expansion) {
|
||||
name_ += expansion;
|
||||
}
|
||||
|
||||
bool operator==(const Qualified& other) const {
|
||||
return namespaces == other.namespaces && name == other.name
|
||||
return namespaces_ == other.namespaces_ && name_ == other.name_
|
||||
&& category == other.category;
|
||||
}
|
||||
|
||||
bool empty() const {
|
||||
return namespaces.empty() && name.empty();
|
||||
return namespaces_.empty() && name_.empty();
|
||||
}
|
||||
|
||||
void clear() {
|
||||
namespaces.clear();
|
||||
name.clear();
|
||||
}
|
||||
|
||||
bool operator!=(const Qualified& other) const {
|
||||
return other.name != name || other.namespaces != namespaces;
|
||||
namespaces_.clear();
|
||||
name_.clear();
|
||||
category = VOID;
|
||||
}
|
||||
|
||||
/// Return a qualified string using given delimiter
|
||||
std::string qualifiedName(const std::string& delimiter = "") const {
|
||||
std::string result;
|
||||
for (std::size_t i = 0; i < namespaces.size(); ++i)
|
||||
result += (namespaces[i] + delimiter);
|
||||
result += name;
|
||||
for (std::size_t i = 0; i < namespaces_.size(); ++i)
|
||||
result += (namespaces_[i] + delimiter);
|
||||
result += name_;
|
||||
return result;
|
||||
}
|
||||
|
||||
/// Return a matlab file name, i.e. "toolboxPath/+ns1/+ns2/name.m"
|
||||
std::string matlabName(const std::string& toolboxPath) const {
|
||||
std::string result = toolboxPath;
|
||||
for (std::size_t i = 0; i < namespaces.size(); ++i)
|
||||
result += ("/+" + namespaces[i]);
|
||||
result += "/" + name + ".m";
|
||||
for (std::size_t i = 0; i < namespaces_.size(); ++i)
|
||||
result += ("/+" + namespaces_[i]);
|
||||
result += "/" + name_ + ".m";
|
||||
return result;
|
||||
}
|
||||
|
||||
|
@ -130,12 +171,14 @@ struct basic_rules {
|
|||
};
|
||||
|
||||
// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html
|
||||
struct type_grammar: public classic::grammar<type_grammar> {
|
||||
class TypeGrammar: public classic::grammar<TypeGrammar> {
|
||||
|
||||
wrap::Qualified& result_; ///< successful parse will be placed in here
|
||||
|
||||
public:
|
||||
|
||||
/// Construct type grammar and specify where result is placed
|
||||
type_grammar(wrap::Qualified& result) :
|
||||
TypeGrammar(wrap::Qualified& result) :
|
||||
result_(result) {
|
||||
}
|
||||
|
||||
|
@ -148,7 +191,7 @@ struct type_grammar: public classic::grammar<type_grammar> {
|
|||
Rule void_p, my_basisType_p, my_eigenType_p, namespace_del_p, class_p,
|
||||
type_p;
|
||||
|
||||
definition(type_grammar const& self) {
|
||||
definition(TypeGrammar const& self) {
|
||||
|
||||
using namespace wrap;
|
||||
using namespace classic;
|
||||
|
@ -159,22 +202,22 @@ struct type_grammar: public classic::grammar<type_grammar> {
|
|||
static const Qualified::Category CLASS = Qualified::CLASS;
|
||||
static const Qualified::Category VOID = Qualified::VOID;
|
||||
|
||||
void_p = str_p("void")[assign_a(self.result_.name)] //
|
||||
void_p = str_p("void")[assign_a(self.result_.name_)] //
|
||||
[assign_a(self.result_.category, VOID)];
|
||||
|
||||
my_basisType_p = basic_rules<ScannerT>::basisType_p //
|
||||
[assign_a(self.result_.name)] //
|
||||
[assign_a(self.result_.name_)] //
|
||||
[assign_a(self.result_.category, BASIS)];
|
||||
|
||||
my_eigenType_p = basic_rules<ScannerT>::eigenType_p //
|
||||
[assign_a(self.result_.name)] //
|
||||
[assign_a(self.result_.name_)] //
|
||||
[assign_a(self.result_.category, EIGEN)];
|
||||
|
||||
namespace_del_p = basic_rules<ScannerT>::namepsace_p //
|
||||
[push_back_a(self.result_.namespaces)] >> str_p("::");
|
||||
[push_back_a(self.result_.namespaces_)] >> str_p("::");
|
||||
|
||||
class_p = *namespace_del_p >> basic_rules<ScannerT>::className_p //
|
||||
[assign_a(self.result_.name)] //
|
||||
[assign_a(self.result_.name_)] //
|
||||
[assign_a(self.result_.category, CLASS)];
|
||||
|
||||
type_p = void_p | my_basisType_p | my_eigenType_p | class_p;
|
||||
|
|
|
@ -14,7 +14,7 @@ using namespace wrap;
|
|||
|
||||
/* ************************************************************************* */
|
||||
string ReturnType::str(bool add_ptr) const {
|
||||
return maybe_shared_ptr(add_ptr && isPtr, qualifiedName("::"), name);
|
||||
return maybe_shared_ptr(add_ptr && isPtr, qualifiedName("::"), name());
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -25,7 +25,7 @@ void ReturnType::wrap_result(const string& out, const string& result,
|
|||
|
||||
if (category == CLASS) {
|
||||
string objCopy, ptrType;
|
||||
ptrType = "Shared" + name;
|
||||
ptrType = "Shared" + name();
|
||||
const bool isVirtual = typeAttributes.attributes(cppType).isVirtual;
|
||||
if (isVirtual) {
|
||||
if (isPtr)
|
||||
|
@ -41,7 +41,7 @@ void ReturnType::wrap_result(const string& out, const string& result,
|
|||
wrapperFile.oss << out << " = wrap_shared_ptr(" << objCopy << ",\""
|
||||
<< matlabType << "\", " << (isVirtual ? "true" : "false") << ");\n";
|
||||
} else if (isPtr) {
|
||||
wrapperFile.oss << " Shared" << name << "* ret = new Shared" << name << "("
|
||||
wrapperFile.oss << " Shared" << name() << "* ret = new Shared" << name() << "("
|
||||
<< result << ");" << endl;
|
||||
wrapperFile.oss << out << " = wrap_shared_ptr(ret,\"" << matlabType
|
||||
<< "\");\n";
|
||||
|
@ -54,7 +54,7 @@ void ReturnType::wrap_result(const string& out, const string& result,
|
|||
void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const {
|
||||
if (category == CLASS)
|
||||
wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedName("::")
|
||||
<< "> Shared" << name << ";" << endl;
|
||||
<< "> Shared" << name() << ";" << endl;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -21,18 +21,14 @@ struct ReturnType: Qualified {
|
|||
|
||||
bool isPtr;
|
||||
|
||||
/// Makes a void type
|
||||
ReturnType() :
|
||||
isPtr(false) {
|
||||
}
|
||||
|
||||
/// Make a Class type, no namespaces
|
||||
ReturnType(const std::string& name) :
|
||||
isPtr(false) {
|
||||
Qualified::name = name;
|
||||
}
|
||||
|
||||
void rename(const Qualified& q) {
|
||||
name = q.name;
|
||||
namespaces = q.namespaces;
|
||||
Qualified(name,Qualified::CLASS), isPtr(false) {
|
||||
}
|
||||
|
||||
/// Check if this type is in a set of valid types
|
||||
|
|
|
@ -32,7 +32,7 @@ Class TemplateInstantiationTypedef::findAndExpand(
|
|||
// Find matching class
|
||||
boost::optional<Class const &> matchedClass;
|
||||
BOOST_FOREACH(const Class& cls, classes) {
|
||||
if (cls.name == class_.name && cls.namespaces == class_.namespaces
|
||||
if (cls.name() == class_.name() && cls.namespaces() == class_.namespaces()
|
||||
&& cls.templateArgs.size() == typeList.size()) {
|
||||
matchedClass.reset(cls);
|
||||
break;
|
||||
|
@ -52,7 +52,8 @@ Class TemplateInstantiationTypedef::findAndExpand(
|
|||
}
|
||||
|
||||
// Fix class properties
|
||||
classInst.name = name;
|
||||
classInst.name_ = name();
|
||||
classInst.namespaces_ = namespaces();
|
||||
classInst.templateArgs.clear();
|
||||
classInst.typedefName = matchedClass->qualifiedName("::") + "<";
|
||||
if (typeList.size() > 0)
|
||||
|
@ -60,7 +61,6 @@ Class TemplateInstantiationTypedef::findAndExpand(
|
|||
for (size_t i = 1; i < typeList.size(); ++i)
|
||||
classInst.typedefName += (", " + typeList[i].qualifiedName("::"));
|
||||
classInst.typedefName += ">";
|
||||
classInst.namespaces = namespaces;
|
||||
|
||||
return classInst;
|
||||
}
|
||||
|
|
|
@ -40,14 +40,14 @@ public:
|
|||
}
|
||||
|
||||
std::string expandedClassName() const {
|
||||
return expandedClass_.name;
|
||||
return expandedClass_.name();
|
||||
}
|
||||
|
||||
// Substitute if needed
|
||||
Qualified tryToSubstitite(const Qualified& type) const {
|
||||
if (type.name == templateArg_ && type.namespaces.empty())
|
||||
if (type.match(templateArg_))
|
||||
return qualifiedType_;
|
||||
else if (type.name == "This")
|
||||
else if (type.match("This"))
|
||||
return expandedClass_;
|
||||
else
|
||||
return type;
|
||||
|
@ -56,9 +56,9 @@ public:
|
|||
// Substitute if needed
|
||||
ReturnType tryToSubstitite(const ReturnType& type) const {
|
||||
ReturnType instType = type;
|
||||
if (type.name == templateArg_ && type.namespaces.empty())
|
||||
if (type.match(templateArg_))
|
||||
instType.rename(qualifiedType_);
|
||||
else if (type.name == "This")
|
||||
else if (type.match("This"))
|
||||
instType.rename(expandedClass_);
|
||||
return instType;
|
||||
}
|
||||
|
|
|
@ -68,7 +68,7 @@ void TypeAttributesTable::checkValidity(const vector<Class>& classes) const {
|
|||
if (!cls.qualifiedParent.empty() && !cls.isVirtual)
|
||||
throw AttributeError(cls.qualifiedName("::"),
|
||||
"Has a base class so needs to be declared virtual, change to 'virtual class "
|
||||
+ cls.name + " ...'");
|
||||
+ cls.name() + " ...'");
|
||||
// Check that parent is virtual as well
|
||||
Qualified parent = cls.qualifiedParent;
|
||||
if (!parent.empty() && !table_.at(parent.qualifiedName("::")).isVirtual)
|
||||
|
|
|
@ -7,126 +7,128 @@ namespace gtsam {
|
|||
|
||||
class Point2 {
|
||||
Point2();
|
||||
Point2(double x, double y);
|
||||
// Point2(double x, double y);
|
||||
double x() const;
|
||||
double y() const;
|
||||
int dim() const;
|
||||
char returnChar() const;
|
||||
void argChar(char a) const;
|
||||
void argUChar(unsigned char a) const;
|
||||
void eigenArguments(Vector v, Matrix m) const;
|
||||
VectorNotEigen vectorConfusion();
|
||||
|
||||
void serializable() const; // Sets flag and creates export, but does not make serialization functions
|
||||
// double y() const;
|
||||
// int dim() const;
|
||||
// char returnChar() const;
|
||||
// void argChar(char a) const;
|
||||
// void argUChar(unsigned char a) const;
|
||||
// void eigenArguments(Vector v, Matrix m) const;
|
||||
// VectorNotEigen vectorConfusion();
|
||||
//
|
||||
// void serializable() const; // Sets flag and creates export, but does not make serialization functions
|
||||
};
|
||||
|
||||
class Point3 {
|
||||
Point3(double x, double y, double z);
|
||||
double norm() const;
|
||||
} // end namespace should be removed
|
||||
|
||||
// static functions - use static keyword and uppercase
|
||||
static double staticFunction();
|
||||
static gtsam::Point3 StaticFunctionRet(double z);
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const; // Just triggers a flag internally and removes actual function
|
||||
};
|
||||
|
||||
}
|
||||
// another comment
|
||||
|
||||
// another comment
|
||||
|
||||
/**
|
||||
* A multi-line comment!
|
||||
*/
|
||||
|
||||
// An include! Can go anywhere outside of a class, in any order
|
||||
#include <folder/path/to/Test.h>
|
||||
|
||||
class Test {
|
||||
|
||||
/* a comment! */
|
||||
// another comment
|
||||
Test();
|
||||
|
||||
pair<Vector,Matrix> return_pair (Vector v, Matrix A) const; // intentionally the first method
|
||||
|
||||
bool return_bool (bool value) const; // comment after a line!
|
||||
size_t return_size_t (size_t value) const;
|
||||
int return_int (int value) const;
|
||||
double return_double (double value) const;
|
||||
|
||||
Test(double a, Matrix b); // a constructor in the middle of a class
|
||||
|
||||
// comments in the middle!
|
||||
|
||||
// (more) comments in the middle!
|
||||
|
||||
string return_string (string value) const;
|
||||
Vector return_vector1(Vector value) const;
|
||||
Matrix return_matrix1(Matrix value) const;
|
||||
Vector return_vector2(Vector value) const;
|
||||
Matrix return_matrix2(Matrix value) const;
|
||||
void arg_EigenConstRef(const Matrix& value) const;
|
||||
|
||||
bool return_field(const Test& t) const;
|
||||
|
||||
Test* return_TestPtr(Test* value) const;
|
||||
Test return_Test(Test* value) const;
|
||||
|
||||
gtsam::Point2* return_Point2Ptr(bool value) const;
|
||||
|
||||
pair<Test*,Test*> create_ptrs () const;
|
||||
pair<Test ,Test*> create_MixedPtrs () const;
|
||||
pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
|
||||
|
||||
void print() const;
|
||||
|
||||
// comments at the end!
|
||||
|
||||
// even more comments at the end!
|
||||
};
|
||||
|
||||
|
||||
Vector aGlobalFunction();
|
||||
|
||||
// An overloaded global function
|
||||
Vector overloadedGlobalFunction(int a);
|
||||
Vector overloadedGlobalFunction(int a, double b);
|
||||
|
||||
// A base class
|
||||
virtual class MyBase {
|
||||
|
||||
};
|
||||
|
||||
// A templated class
|
||||
template<T = {gtsam::Point2, gtsam::Point3}>
|
||||
virtual class MyTemplate : MyBase {
|
||||
MyTemplate();
|
||||
|
||||
template<ARG = {gtsam::Point2, gtsam::Point3, Vector, Matrix}>
|
||||
void templatedMethod(const ARG& t);
|
||||
|
||||
// Stress test templates and pointer combinations
|
||||
void accept_T(const T& value) const;
|
||||
void accept_Tptr(T* value) const;
|
||||
T* return_Tptr(T* value) const;
|
||||
T return_T(T* value) const;
|
||||
pair<T*,T*> create_ptrs () const;
|
||||
pair<T ,T*> create_MixedPtrs () const;
|
||||
pair<T*,T*> return_ptrs (T* p1, T* p2) const;
|
||||
};
|
||||
|
||||
// A doubly templated class
|
||||
template<POSE, POINT>
|
||||
class MyFactor {
|
||||
MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
|
||||
};
|
||||
|
||||
// and a typedef specializing it
|
||||
typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
||||
|
||||
// comments at the end!
|
||||
|
||||
// even more comments at the end!
|
||||
//class Point3 {
|
||||
// Point3(double x, double y, double z);
|
||||
// double norm() const;
|
||||
//
|
||||
// // static functions - use static keyword and uppercase
|
||||
// static double staticFunction();
|
||||
// static gtsam::Point3 StaticFunctionRet(double z);
|
||||
//
|
||||
// // enabling serialization functionality
|
||||
// void serialize() const; // Just triggers a flag internally and removes actual function
|
||||
//};
|
||||
//
|
||||
//}
|
||||
//// another comment
|
||||
//
|
||||
//// another comment
|
||||
//
|
||||
///**
|
||||
// * A multi-line comment!
|
||||
// */
|
||||
//
|
||||
//// An include! Can go anywhere outside of a class, in any order
|
||||
//#include <folder/path/to/Test.h>
|
||||
//
|
||||
//class Test {
|
||||
//
|
||||
// /* a comment! */
|
||||
// // another comment
|
||||
// Test();
|
||||
//
|
||||
// pair<Vector,Matrix> return_pair (Vector v, Matrix A) const; // intentionally the first method
|
||||
//
|
||||
// bool return_bool (bool value) const; // comment after a line!
|
||||
// size_t return_size_t (size_t value) const;
|
||||
// int return_int (int value) const;
|
||||
// double return_double (double value) const;
|
||||
//
|
||||
// Test(double a, Matrix b); // a constructor in the middle of a class
|
||||
//
|
||||
// // comments in the middle!
|
||||
//
|
||||
// // (more) comments in the middle!
|
||||
//
|
||||
// string return_string (string value) const;
|
||||
// Vector return_vector1(Vector value) const;
|
||||
// Matrix return_matrix1(Matrix value) const;
|
||||
// Vector return_vector2(Vector value) const;
|
||||
// Matrix return_matrix2(Matrix value) const;
|
||||
// void arg_EigenConstRef(const Matrix& value) const;
|
||||
//
|
||||
// bool return_field(const Test& t) const;
|
||||
//
|
||||
// Test* return_TestPtr(Test* value) const;
|
||||
// Test return_Test(Test* value) const;
|
||||
//
|
||||
// gtsam::Point2* return_Point2Ptr(bool value) const;
|
||||
//
|
||||
// pair<Test*,Test*> create_ptrs () const;
|
||||
// pair<Test ,Test*> create_MixedPtrs () const;
|
||||
// pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
|
||||
//
|
||||
// void print() const;
|
||||
//
|
||||
// // comments at the end!
|
||||
//
|
||||
// // even more comments at the end!
|
||||
//};
|
||||
//
|
||||
//
|
||||
//Vector aGlobalFunction();
|
||||
//
|
||||
//// An overloaded global function
|
||||
//Vector overloadedGlobalFunction(int a);
|
||||
//Vector overloadedGlobalFunction(int a, double b);
|
||||
//
|
||||
//// A base class
|
||||
//virtual class MyBase {
|
||||
//
|
||||
//};
|
||||
//
|
||||
//// A templated class
|
||||
//template<T = {gtsam::Point2, gtsam::Point3}>
|
||||
//virtual class MyTemplate : MyBase {
|
||||
// MyTemplate();
|
||||
//
|
||||
// template<ARG = {gtsam::Point2, gtsam::Point3, Vector, Matrix}>
|
||||
// void templatedMethod(const ARG& t);
|
||||
//
|
||||
// // Stress test templates and pointer combinations
|
||||
// void accept_T(const T& value) const;
|
||||
// void accept_Tptr(T* value) const;
|
||||
// T* return_Tptr(T* value) const;
|
||||
// T return_T(T* value) const;
|
||||
// pair<T*,T*> create_ptrs () const;
|
||||
// pair<T ,T*> create_MixedPtrs () const;
|
||||
// pair<T*,T*> return_ptrs (T* p1, T* p2) const;
|
||||
//};
|
||||
//
|
||||
//// A doubly templated class
|
||||
//template<POSE, POINT>
|
||||
//class MyFactor {
|
||||
// MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
|
||||
//};
|
||||
//
|
||||
//// and a typedef specializing it
|
||||
//typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
||||
//
|
||||
//// comments at the end!
|
||||
//
|
||||
//// even more comments at the end!
|
||||
|
|
|
@ -30,7 +30,7 @@ static const bool T = true;
|
|||
struct ArgumentGrammar: public classic::grammar<ArgumentGrammar> {
|
||||
|
||||
wrap::Argument& result_; ///< successful parse will be placed in here
|
||||
type_grammar argument_type_g;
|
||||
TypeGrammar argument_type_g;
|
||||
|
||||
/// Construct type grammar and specify where result is placed
|
||||
ArgumentGrammar(wrap::Argument& result) :
|
||||
|
@ -78,9 +78,7 @@ TEST( Argument, grammar ) {
|
|||
ArgumentGrammar g(actual);
|
||||
|
||||
EXPECT(parse("const gtsam::Point2& p4", g, space_p).full);
|
||||
EXPECT_LONGS_EQUAL(1, actual.type.namespaces.size());
|
||||
EXPECT(actual.type.namespaces[0]=="gtsam");
|
||||
EXPECT(actual.type.name=="Point2");
|
||||
EXPECT(actual.type==Qualified("gtsam","Point2",Qualified::CLASS));
|
||||
EXPECT(actual.name=="p4");
|
||||
EXPECT(actual.is_const);
|
||||
EXPECT(actual.is_ref);
|
||||
|
@ -88,8 +86,7 @@ TEST( Argument, grammar ) {
|
|||
actual = arg0;
|
||||
|
||||
EXPECT(parse("Point2& p", g, space_p).full);
|
||||
EXPECT(actual.type.namespaces.empty());
|
||||
EXPECT(actual.type.name=="Point2");
|
||||
EXPECT(actual.type==Qualified("Point2",Qualified::CLASS));
|
||||
EXPECT(actual.name=="p");
|
||||
EXPECT(!actual.is_const);
|
||||
EXPECT(actual.is_ref);
|
||||
|
@ -97,9 +94,7 @@ TEST( Argument, grammar ) {
|
|||
actual = arg0;
|
||||
|
||||
EXPECT(parse("gtsam::Point2* p3", g, space_p).full);
|
||||
EXPECT_LONGS_EQUAL(1, actual.type.namespaces.size());
|
||||
EXPECT(actual.type.namespaces[0]=="gtsam");
|
||||
EXPECT(actual.type.name=="Point2");
|
||||
EXPECT(actual.type==Qualified("gtsam","Point2",Qualified::CLASS));
|
||||
EXPECT(actual.name=="p3");
|
||||
EXPECT(!actual.is_const);
|
||||
EXPECT(!actual.is_ref);
|
||||
|
@ -119,8 +114,7 @@ TEST( Argument, grammar ) {
|
|||
actual = arg0;
|
||||
|
||||
EXPECT(parse("const Matrix& m", g, space_p).full);
|
||||
EXPECT(actual.type.namespaces.empty());
|
||||
EXPECT(actual.type.name=="Matrix");
|
||||
EXPECT(actual.type==Qualified("Matrix",Qualified::EIGEN));
|
||||
EXPECT(actual.name=="m");
|
||||
EXPECT(actual.is_const);
|
||||
EXPECT(actual.is_ref);
|
||||
|
|
|
@ -64,7 +64,7 @@ TEST( Class, TemplatedMethods ) {
|
|||
bool verbose = true, is_const = true;
|
||||
ArgumentList args;
|
||||
Argument arg;
|
||||
arg.type.name = "T";
|
||||
arg.type.name_ = "T";
|
||||
args.push_back(arg);
|
||||
const ReturnValue retVal(ReturnType("T"));
|
||||
const string templateArgName("T");
|
||||
|
|
|
@ -42,6 +42,102 @@ TEST( Method, addOverload ) {
|
|||
EXPECT_LONGS_EQUAL(2, method.nrOverloads());
|
||||
}
|
||||
|
||||
// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html
|
||||
struct method_grammar: public classic::grammar<method_grammar> {
|
||||
|
||||
wrap::Method& result_; ///< successful parse will be placed in here
|
||||
|
||||
ArgumentList args;
|
||||
Argument arg0, arg;
|
||||
TypeGrammar argument_type_g;
|
||||
|
||||
ReturnType retType0, retType;
|
||||
TypeGrammar returntype_g;
|
||||
|
||||
ReturnValue retVal0, retVal;
|
||||
|
||||
/// Construct type grammar and specify where result is placed
|
||||
method_grammar(wrap::Method& result) :
|
||||
result_(result), argument_type_g(arg.type), returntype_g(retType) {
|
||||
}
|
||||
|
||||
/// Definition of type grammar
|
||||
template<typename ScannerT>
|
||||
struct definition: basic_rules<ScannerT> {
|
||||
|
||||
typedef classic::rule<ScannerT> Rule;
|
||||
|
||||
Rule templateArgValue_p, templateArgValues_p, argument_p, argumentList_p,
|
||||
returnType1_p, returnType2_p, pair_p, returnValue_p, methodName_p,
|
||||
method_p;
|
||||
|
||||
definition(method_grammar const& self) {
|
||||
|
||||
using namespace wrap;
|
||||
using namespace classic;
|
||||
|
||||
// Rule templateArgValue_p = type_grammar(self.templateArgValue);
|
||||
//
|
||||
// // template<CALIBRATION = {gtsam::Cal3DS2}>
|
||||
// Rule templateArgValues_p = (str_p("template") >> '<' >> name_p >> '='
|
||||
// >> '{' >> !(templateArgValue_p >> *(',' >> templateArgValue_p)) >> '}'
|
||||
// >> '>');
|
||||
//
|
||||
// NOTE: allows for pointers to all types
|
||||
// Slightly more permissive than before on basis/eigen type qualification
|
||||
argument_p = //
|
||||
!str_p("const")[assign_a(self.arg.is_const, true)] //
|
||||
>> self.argument_type_g //
|
||||
>> (!ch_p('&')[assign_a(self.arg.is_ref, true)]
|
||||
| !ch_p('*')[assign_a(self.arg.is_ptr, true)]) //
|
||||
[push_back_a(self.args, self.arg)] //
|
||||
[assign_a(self.arg, self.arg0)];
|
||||
|
||||
argumentList_p = !argument_p >> *(',' >> argument_p);
|
||||
//
|
||||
returnType1_p = self.returntype_g //
|
||||
[assign_a(self.retVal.type1, retType)] //
|
||||
[assign_a(self.retType, self.retType0)];
|
||||
|
||||
returnType2_p = self.returntype_g //
|
||||
[assign_a(self.retVal.type2, retType)] //
|
||||
[assign_a(self.retType, self.retType0)];
|
||||
|
||||
pair_p = (str_p("pair") >> '<' >> returnType1_p >> ',' >> returnType2_p
|
||||
>> '>')[assign_a(self.retVal.isPair, true)];
|
||||
|
||||
returnValue_p = pair_p | returnType1_p;
|
||||
|
||||
methodName_p = lexeme_d[(upper_p | lower_p) >> *(alnum_p | '_')];
|
||||
|
||||
// gtsam::Values retract(const gtsam::VectorValues& delta) const;
|
||||
method_p =
|
||||
// !templateArgValues_p >>
|
||||
(returnValue_p >> methodName_p >> '(' >> argumentList_p >> ')'
|
||||
>> !str_p("const") >> ';' >> *basic_rules<ScannerT>::comments_p);
|
||||
}
|
||||
|
||||
Rule const& start() const {
|
||||
return method_p;
|
||||
}
|
||||
|
||||
};
|
||||
};
|
||||
// method_grammar
|
||||
|
||||
//******************************************************************************
|
||||
TEST( Method, grammar ) {
|
||||
|
||||
using classic::space_p;
|
||||
|
||||
// Create type grammar that will place result in actual
|
||||
Method actual;
|
||||
method_grammar method_g(actual);
|
||||
|
||||
// a class type with namespaces
|
||||
EXPECT(parse("double x() const;", method_g, space_p).full);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() {
|
||||
TestResult tr;
|
||||
|
|
|
@ -29,51 +29,36 @@ TEST( Type, grammar ) {
|
|||
|
||||
// Create type grammar that will place result in actual
|
||||
Qualified actual;
|
||||
type_grammar type_g(actual);
|
||||
TypeGrammar type_g(actual);
|
||||
|
||||
// a class type with 2 namespaces
|
||||
EXPECT(parse("gtsam::internal::Point2", type_g, space_p).full);
|
||||
EXPECT(actual.name=="Point2");
|
||||
EXPECT_LONGS_EQUAL(2, actual.namespaces.size());
|
||||
EXPECT(actual.namespaces[0]=="gtsam");
|
||||
EXPECT(actual.namespaces[1]=="internal");
|
||||
EXPECT(actual.category==Qualified::CLASS);
|
||||
EXPECT(actual==Qualified("gtsam","internal","Point2",Qualified::CLASS));
|
||||
actual.clear();
|
||||
|
||||
// a class type with 1 namespace
|
||||
EXPECT(parse("gtsam::Point2", type_g, space_p).full);
|
||||
EXPECT(actual.name=="Point2");
|
||||
EXPECT_LONGS_EQUAL(1, actual.namespaces.size());
|
||||
EXPECT(actual.namespaces[0]=="gtsam");
|
||||
EXPECT(actual.category==Qualified::CLASS);
|
||||
EXPECT(actual==Qualified("gtsam","Point2",Qualified::CLASS));
|
||||
actual.clear();
|
||||
|
||||
// a class type with no namespaces
|
||||
EXPECT(parse("Point2", type_g, space_p).full);
|
||||
EXPECT(actual.name=="Point2");
|
||||
EXPECT(actual.namespaces.empty());
|
||||
EXPECT(actual.category==Qualified::CLASS);
|
||||
EXPECT(actual==Qualified("Point2",Qualified::CLASS));
|
||||
actual.clear();
|
||||
|
||||
// an Eigen type
|
||||
EXPECT(parse("Vector", type_g, space_p).full);
|
||||
EXPECT(actual.name=="Vector");
|
||||
EXPECT(actual.namespaces.empty());
|
||||
EXPECT(actual.category==Qualified::EIGEN);
|
||||
EXPECT(actual==Qualified("Vector",Qualified::EIGEN));
|
||||
actual.clear();
|
||||
|
||||
// a basic type
|
||||
EXPECT(parse("double", type_g, space_p).full);
|
||||
EXPECT(actual.name=="double");
|
||||
EXPECT(actual.namespaces.empty());
|
||||
EXPECT(actual.category==Qualified::BASIS);
|
||||
EXPECT(actual==Qualified("double",Qualified::BASIS));
|
||||
actual.clear();
|
||||
|
||||
// void
|
||||
EXPECT(parse("void", type_g, space_p).full);
|
||||
EXPECT(actual.name=="void");
|
||||
EXPECT(actual.namespaces.empty());
|
||||
EXPECT(actual.category==Qualified::VOID);
|
||||
EXPECT(actual==Qualified("void",Qualified::VOID));
|
||||
actual.clear();
|
||||
}
|
||||
|
||||
|
|
|
@ -48,9 +48,9 @@ static const std::string headerPath = "/not_really_a_real_path/borg/gtsam/wrap";
|
|||
/* ************************************************************************* */
|
||||
TEST( wrap, ArgumentList ) {
|
||||
ArgumentList args;
|
||||
Argument arg1; arg1.type.name = "double"; arg1.name = "x";
|
||||
Argument arg2; arg2.type.name = "double"; arg2.name = "y";
|
||||
Argument arg3; arg3.type.name = "double"; arg3.name = "z";
|
||||
Argument arg1; arg1.type.name_ = "double"; arg1.name = "x";
|
||||
Argument arg2; arg2.type.name_ = "double"; arg2.name = "y";
|
||||
Argument arg3; arg3.type.name_ = "double"; arg3.name = "z";
|
||||
args.push_back(arg1);
|
||||
args.push_back(arg2);
|
||||
args.push_back(arg3);
|
||||
|
@ -88,9 +88,9 @@ TEST( wrap, Small ) {
|
|||
// check return types
|
||||
LONGS_EQUAL(1, module.classes.size());
|
||||
Class cls = module.classes.front();
|
||||
EXPECT(assert_equal("Point2", cls.name));
|
||||
EXPECT(assert_equal("Point2", cls.name()));
|
||||
EXPECT(!cls.isVirtual);
|
||||
EXPECT(cls.namespaces.empty());
|
||||
EXPECT(cls.namespaces().empty());
|
||||
LONGS_EQUAL(3, cls.nrMethods());
|
||||
LONGS_EQUAL(1, cls.static_methods.size());
|
||||
|
||||
|
@ -103,7 +103,7 @@ TEST( wrap, Small ) {
|
|||
ReturnValue rv1 = m1.returnValue(0);
|
||||
EXPECT(!rv1.isPair);
|
||||
EXPECT(!rv1.type1.isPtr);
|
||||
EXPECT(assert_equal("double", rv1.type1.name));
|
||||
EXPECT(assert_equal("double", rv1.type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category);
|
||||
|
||||
// Method 2
|
||||
|
@ -115,7 +115,7 @@ TEST( wrap, Small ) {
|
|||
ReturnValue rv2 = m2.returnValue(0);
|
||||
EXPECT(!rv2.isPair);
|
||||
EXPECT(!rv2.type1.isPtr);
|
||||
EXPECT(assert_equal("Matrix", rv2.type1.name));
|
||||
EXPECT(assert_equal("Matrix", rv2.type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category);
|
||||
|
||||
// Method 3
|
||||
|
@ -127,7 +127,7 @@ TEST( wrap, Small ) {
|
|||
ReturnValue rv3 = m3.returnValue(0);
|
||||
EXPECT(!rv3.isPair);
|
||||
EXPECT(!rv3.type1.isPtr);
|
||||
EXPECT(assert_equal("Point2", rv3.type1.name));
|
||||
EXPECT(assert_equal("Point2", rv3.type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category);
|
||||
|
||||
// Static Method 1
|
||||
|
@ -139,7 +139,7 @@ TEST( wrap, Small ) {
|
|||
ReturnValue rv4 = sm1.returnValue(0);
|
||||
EXPECT(!rv4.isPair);
|
||||
EXPECT(!rv4.type1.isPtr);
|
||||
EXPECT(assert_equal("Vector", rv4.type1.name));
|
||||
EXPECT(assert_equal("Vector", rv4.type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category);
|
||||
|
||||
}
|
||||
|
@ -182,7 +182,7 @@ TEST( wrap, Geometry ) {
|
|||
// };
|
||||
|
||||
Class cls = module.classes.at(0);
|
||||
EXPECT(assert_equal("Point2", cls.name));
|
||||
EXPECT(assert_equal("Point2", cls.name()));
|
||||
EXPECT_LONGS_EQUAL(2, cls.constructor.nrOverloads());
|
||||
EXPECT_LONGS_EQUAL(8, cls.nrMethods());
|
||||
|
||||
|
@ -191,7 +191,7 @@ TEST( wrap, Geometry ) {
|
|||
CHECK(cls.exists("returnChar"));
|
||||
Method m1 = cls.method("returnChar");
|
||||
LONGS_EQUAL(1, m1.nrOverloads());
|
||||
EXPECT(assert_equal("char", m1.returnValue(0).type1.name));
|
||||
EXPECT(assert_equal("char", m1.returnValue(0).type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category);
|
||||
EXPECT(!m1.returnValue(0).isPair);
|
||||
EXPECT(assert_equal("returnChar", m1.name()));
|
||||
|
@ -205,7 +205,7 @@ TEST( wrap, Geometry ) {
|
|||
CHECK(cls.exists("vectorConfusion"));
|
||||
Method m1 = cls.method("vectorConfusion");
|
||||
LONGS_EQUAL(1, m1.nrOverloads());
|
||||
EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name));
|
||||
EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category);
|
||||
EXPECT(!m1.returnValue(0).isPair);
|
||||
EXPECT(assert_equal("vectorConfusion", m1.name()));
|
||||
|
@ -215,7 +215,7 @@ TEST( wrap, Geometry ) {
|
|||
}
|
||||
|
||||
EXPECT_LONGS_EQUAL(0, cls.static_methods.size());
|
||||
EXPECT_LONGS_EQUAL(1, cls.namespaces.size());
|
||||
EXPECT_LONGS_EQUAL(1, cls.namespaces().size());
|
||||
|
||||
#ifndef WRAP_DISABLE_SERIALIZE
|
||||
// check serialization flag
|
||||
|
@ -227,11 +227,11 @@ TEST( wrap, Geometry ) {
|
|||
// check second class, Point3
|
||||
{
|
||||
Class cls = module.classes.at(1);
|
||||
EXPECT(assert_equal("Point3", cls.name));
|
||||
EXPECT(assert_equal("Point3", cls.name()));
|
||||
EXPECT_LONGS_EQUAL(1, cls.constructor.nrOverloads());
|
||||
EXPECT_LONGS_EQUAL(1, cls.nrMethods());
|
||||
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
|
||||
ArgumentList c1 = cls.constructor.argumentList(0);
|
||||
|
@ -240,7 +240,7 @@ TEST( wrap, Geometry ) {
|
|||
// check first double argument
|
||||
Argument a1 = c1.front();
|
||||
EXPECT(!a1.is_const);
|
||||
EXPECT(assert_equal("double", a1.type.name));
|
||||
EXPECT(assert_equal("double", a1.type.name_));
|
||||
EXPECT(!a1.is_ref);
|
||||
EXPECT(assert_equal("x", a1.name));
|
||||
|
||||
|
@ -248,7 +248,7 @@ TEST( wrap, Geometry ) {
|
|||
CHECK(cls.exists("norm"));
|
||||
Method m1 = cls.method("norm");
|
||||
LONGS_EQUAL(1, m1.nrOverloads());
|
||||
EXPECT(assert_equal("double", m1.returnValue(0).type1.name));
|
||||
EXPECT(assert_equal("double", m1.returnValue(0).type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category);
|
||||
EXPECT(assert_equal("norm", m1.name()));
|
||||
LONGS_EQUAL(1, m1.nrOverloads());
|
||||
|
@ -268,7 +268,7 @@ TEST( wrap, Geometry ) {
|
|||
EXPECT_LONGS_EQUAL( 2, testCls.constructor.nrOverloads());
|
||||
EXPECT_LONGS_EQUAL(19, testCls.nrMethods());
|
||||
EXPECT_LONGS_EQUAL( 0, testCls.static_methods.size());
|
||||
EXPECT_LONGS_EQUAL( 0, testCls.namespaces.size());
|
||||
EXPECT_LONGS_EQUAL( 0, testCls.namespaces().size());
|
||||
|
||||
// function to parse: pair<Vector,Matrix> return_pair (Vector v, Matrix A) const;
|
||||
CHECK(testCls.exists("return_pair"));
|
||||
|
@ -276,9 +276,9 @@ TEST( wrap, Geometry ) {
|
|||
LONGS_EQUAL(1, m2.nrOverloads());
|
||||
EXPECT(m2.returnValue(0).isPair);
|
||||
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category);
|
||||
EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name));
|
||||
EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name()));
|
||||
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category);
|
||||
EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name));
|
||||
EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name()));
|
||||
|
||||
// checking pointer args and return values
|
||||
// pair<Test*,Test*> return_ptrs (Test* p1, Test* p2) const;
|
||||
|
@ -292,17 +292,17 @@ TEST( wrap, Geometry ) {
|
|||
EXPECT(arg1.is_ptr);
|
||||
EXPECT(!arg1.is_const);
|
||||
EXPECT(!arg1.is_ref);
|
||||
EXPECT(assert_equal("Test", arg1.type.name));
|
||||
EXPECT(assert_equal("Test", arg1.type.name_));
|
||||
EXPECT(assert_equal("p1", arg1.name));
|
||||
EXPECT(arg1.type.namespaces.empty());
|
||||
EXPECT(arg1.type.namespaces_.empty());
|
||||
|
||||
Argument arg2 = args.at(1);
|
||||
EXPECT(arg2.is_ptr);
|
||||
EXPECT(!arg2.is_const);
|
||||
EXPECT(!arg2.is_ref);
|
||||
EXPECT(assert_equal("Test", arg2.type.name));
|
||||
EXPECT(assert_equal("Test", arg2.type.name_));
|
||||
EXPECT(assert_equal("p2", arg2.name));
|
||||
EXPECT(arg2.type.namespaces.empty());
|
||||
EXPECT(arg2.type.namespaces_.empty());
|
||||
}
|
||||
|
||||
// evaluate global functions
|
||||
|
@ -313,10 +313,10 @@ TEST( wrap, Geometry ) {
|
|||
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
||||
EXPECT(assert_equal("aGlobalFunction", gfunc.name()));
|
||||
LONGS_EQUAL(1, gfunc.nrOverloads());
|
||||
EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name));
|
||||
EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name()));
|
||||
EXPECT_LONGS_EQUAL(1, gfunc.nrOverloads());
|
||||
LONGS_EQUAL(1, gfunc.overloads.size());
|
||||
EXPECT(gfunc.overloads.front().namespaces.empty());
|
||||
EXPECT(gfunc.overloads.front().namespaces().empty());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -338,44 +338,44 @@ TEST( wrap, parse_namespaces ) {
|
|||
|
||||
{
|
||||
Class cls = module.classes.at(0);
|
||||
EXPECT(assert_equal("ClassA", cls.name));
|
||||
EXPECT(assert_equal("ClassA", cls.name()));
|
||||
strvec exp_namespaces; exp_namespaces += "ns1";
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces()));
|
||||
}
|
||||
|
||||
{
|
||||
Class cls = module.classes.at(1);
|
||||
EXPECT(assert_equal("ClassB", cls.name));
|
||||
EXPECT(assert_equal("ClassB", cls.name()));
|
||||
strvec exp_namespaces; exp_namespaces += "ns1";
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces()));
|
||||
}
|
||||
|
||||
{
|
||||
Class cls = module.classes.at(2);
|
||||
EXPECT(assert_equal("ClassA", cls.name));
|
||||
EXPECT(assert_equal("ClassA", cls.name()));
|
||||
strvec exp_namespaces; exp_namespaces += "ns2";
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces()));
|
||||
}
|
||||
|
||||
{
|
||||
Class cls = module.classes.at(3);
|
||||
EXPECT(assert_equal("ClassB", cls.name));
|
||||
EXPECT(assert_equal("ClassB", cls.name()));
|
||||
strvec exp_namespaces; exp_namespaces += "ns2", "ns3";
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces()));
|
||||
}
|
||||
|
||||
{
|
||||
Class cls = module.classes.at(4);
|
||||
EXPECT(assert_equal("ClassC", cls.name));
|
||||
EXPECT(assert_equal("ClassC", cls.name()));
|
||||
strvec exp_namespaces; exp_namespaces += "ns2";
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces()));
|
||||
}
|
||||
|
||||
{
|
||||
Class cls = module.classes.at(5);
|
||||
EXPECT(assert_equal("ClassD", cls.name));
|
||||
EXPECT(assert_equal("ClassD", cls.name()));
|
||||
strvec exp_namespaces;
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces, cls.namespaces()));
|
||||
}
|
||||
|
||||
// evaluate global functions
|
||||
|
@ -387,15 +387,15 @@ TEST( wrap, parse_namespaces ) {
|
|||
GlobalFunction gfunc = module.global_functions.at("aGlobalFunction");
|
||||
EXPECT(assert_equal("aGlobalFunction", gfunc.name()));
|
||||
LONGS_EQUAL(2, gfunc.nrOverloads());
|
||||
EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name));
|
||||
EXPECT(assert_equal("Vector", gfunc.returnValue(0).type1.name()));
|
||||
|
||||
// check namespaces
|
||||
LONGS_EQUAL(2, gfunc.overloads.size());
|
||||
strvec exp_namespaces1; exp_namespaces1 += "ns1";
|
||||
EXPECT(assert_equal(exp_namespaces1, gfunc.overloads.at(0).namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces1, gfunc.overloads.at(0).namespaces()));
|
||||
|
||||
strvec exp_namespaces2; exp_namespaces2 += "ns2";
|
||||
EXPECT(assert_equal(exp_namespaces2, gfunc.overloads.at(1).namespaces));
|
||||
EXPECT(assert_equal(exp_namespaces2, gfunc.overloads.at(1).namespaces()));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue