Removing empty in favor of boost::optional

release/4.3a0
dellaert 2014-11-30 10:38:24 +01:00
parent 74361ce64a
commit 14ef786dfe
19 changed files with 105 additions and 93 deletions

View File

@ -29,11 +29,9 @@
#include <iostream>
#include <fstream>
#include <iterator> // std::ostream_iterator
//#include <cstdint> // on Linux GCC: fails with error regarding needing C++0x std flags
//#include <cinttypes> // same failure as above
#include <stdint.h> // works on Linux GCC
using namespace std;
using namespace wrap;
@ -67,12 +65,11 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
const string matlabQualName = qualifiedName(".");
const string matlabUniqueName = qualifiedName();
const string cppName = qualifiedName("::");
const string matlabBaseName = qualifiedParent.qualifiedName(".");
const string cppBaseName = qualifiedParent.qualifiedName("::");
// emit class proxy code
// we want our class to inherit the handle class for memory purposes
const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName;
const string parent =
parentClass ? "handle" : parentClass->qualifiedName(".");
comment_fragment(proxyFile);
proxyFile.oss << "classdef " << name << " < " << parent << endl;
proxyFile.oss << " properties\n";
@ -94,11 +91,14 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
wrapperFile.oss << "\n";
// Regular constructors
boost::optional<string> cppBaseName;
if (parentClass)
cppBaseName = parentClass->qualifiedName("::");
for (size_t i = 0; i < constructor.nrOverloads(); i++) {
ArgumentList args = constructor.argumentList(i);
const int id = (int) functionNames.size();
constructor.proxy_fragment(proxyFile, wrapperName, !qualifiedParent.empty(),
id, args);
constructor.proxy_fragment(proxyFile, wrapperName, (bool) parentClass, id,
args);
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
cppName, matlabUniqueName, cppBaseName, id, args);
wrapperFile.oss << "\n";
@ -108,9 +108,9 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
proxyFile.oss << " error('Arguments do not match any overload of "
<< matlabQualName << " constructor');\n";
proxyFile.oss << " end\n";
if (!qualifiedParent.empty())
proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64("
<< ptr_constructor_key << "), base_ptr);\n";
if (parentClass)
proxyFile.oss << " obj = obj@" << parentClass->qualifiedName(".")
<< "(uint64(" << ptr_constructor_key << "), base_ptr);\n";
proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n";
proxyFile.oss << " end\n\n";
@ -170,7 +170,6 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile,
const string matlabUniqueName = qualifiedName();
const string cppName = qualifiedName("::");
const string baseCppName = qualifiedParent.qualifiedName("::");
const int collectorInsertId = (int) functionNames.size();
const string collectorInsertFunctionName = matlabUniqueName
@ -207,7 +206,7 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile,
} else {
proxyFile.oss << " my_ptr = varargin{2};\n";
}
if (qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back
if (!parentClass) // If this class has a base class, we'll get a base class pointer back
proxyFile.oss << " ";
else
proxyFile.oss << " base_ptr = ";
@ -230,7 +229,8 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile,
// Add to collector
wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n";
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
if (!qualifiedParent.empty()) {
if (parentClass) {
const string baseCppName = parentClass->qualifiedName("::");
wrapperFile.oss << "\n";
wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName
<< "> SharedBase;\n";
@ -297,7 +297,7 @@ 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, *this);
// substitute template in arguments
ArgumentList expandedArgs = argumentList.expandTemplate(ts);
// do the same for return type
@ -353,10 +353,10 @@ void Class::verifyAll(vector<string>& validTypes, bool& hasSerialiable) const {
verifyReturnTypes<Method>(validTypes, methods_);
// verify parents
if (!qualifiedParent.empty()
if (parentClass
&& find(validTypes.begin(), validTypes.end(),
qualifiedParent.qualifiedName("::")) == validTypes.end())
throw DependencyMissing(qualifiedParent.qualifiedName("::"),
parentClass->qualifiedName("::")) == validTypes.end())
throw DependencyMissing(parentClass->qualifiedName("::"),
qualifiedName("::"));
}
@ -364,12 +364,12 @@ void Class::verifyAll(vector<string>& validTypes, bool& hasSerialiable) const {
void Class::appendInheritedMethods(const Class& cls,
const vector<Class>& classes) {
if (!cls.qualifiedParent.empty()) {
if (cls.parentClass) {
// 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.parentClass->name) {
methods_.insert(parent.methods_.begin(), parent.methods_.end());
appendInheritedMethods(parent, classes);
}

View File

@ -27,6 +27,7 @@
#include <boost/foreach.hpp>
#include <boost/range/adaptor/map.hpp>
#include <boost/optional.hpp>
#include <string>
#include <map>
@ -53,7 +54,7 @@ public:
bool isVirtual; ///< Whether the class is part of a virtual inheritance chain
bool isSerializable; ///< Whether we can use boost.serialization to serialize the class - creates exports
bool hasSerialization; ///< Whether we should create the serialization functions
Qualified qualifiedParent; ///< The *single* parent
boost::optional<Qualified> parentClass; ///< The *single* parent
Constructor constructor; ///< Class constructors
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
bool verbose_; ///< verbose flag

View File

@ -69,7 +69,7 @@ void Constructor::proxy_fragment(FileWriter& file,
/* ************************************************************************* */
string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName,
Str matlabUniqueName, Str cppBaseClassName, int id,
Str matlabUniqueName, boost::optional<string> cppBaseClassName, int id,
const ArgumentList& al) const {
const string wrapFunctionName = matlabUniqueName + "_constructor_"
@ -100,9 +100,9 @@ string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName,
<< endl;
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
if (!cppBaseClassName.empty()) {
if (cppBaseClassName) {
file.oss << "\n";
file.oss << " typedef boost::shared_ptr<" << cppBaseClassName
file.oss << " typedef boost::shared_ptr<" << *cppBaseClassName
<< "> SharedBase;\n";
file.oss
<< " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";

View File

@ -19,7 +19,7 @@
#pragma once
#include "OverloadedFunction.h"
#include <boost/optional.hpp>
#include <string>
#include <vector>
@ -68,7 +68,7 @@ struct Constructor: public OverloadedFunction {
/// cpp wrapper
std::string wrapper_fragment(FileWriter& file, Str cppClassName,
Str matlabUniqueName, Str cppBaseClassName, int id,
Str matlabUniqueName, boost::optional<std::string> cppBaseClassName, int id,
const ArgumentList& al) const;
/// constructor function

View File

@ -29,8 +29,8 @@ using namespace std;
using namespace wrap;
/* ************************************************************************* */
bool Function::initializeOrCheck(const string& name, const Qualified& instName,
bool verbose) {
bool Function::initializeOrCheck(const string& name,
boost::optional<const Qualified> instName, bool verbose) {
if (name.empty())
throw runtime_error("Function::initializeOrCheck called with empty name");
@ -44,10 +44,7 @@ bool Function::initializeOrCheck(const string& name, const Qualified& instName,
} else {
if (name_ != name || templateArgValue_ != instName || verbose_ != verbose)
throw runtime_error(
"Function::initializeOrCheck called with different arguments: with name "
+ name + " instead of expected " + name_
+ ", or with template argument " + instName.qualifiedName(":")
+ " instead of expected " + templateArgValue_.qualifiedName(":"));
"Function::initializeOrCheck called with different arguments");
return false;
}

View File

@ -19,6 +19,7 @@
#pragma once
#include "Argument.h"
#include <boost/optional.hpp>
namespace wrap {
@ -28,7 +29,7 @@ class Function {
protected:
std::string name_; ///< name of method
Qualified templateArgValue_; ///< value of template argument if applicable
boost::optional<Qualified> templateArgValue_; ///< value of template argument if applicable
bool verbose_;
public:
@ -37,8 +38,8 @@ public:
* @brief first time, fill in instance variables, otherwise check if same
* @return true if first time, false thereafter
*/
bool initializeOrCheck(const std::string& name, const Qualified& instName =
Qualified(), bool verbose = false);
bool initializeOrCheck(const std::string& name, boost::optional<const Qualified> instName =
boost::none, bool verbose = false);
std::string name() const {
return name_;
@ -50,10 +51,10 @@ public:
}
std::string matlabName() const {
if (templateArgValue_.empty())
if (templateArgValue_)
return name_;
else
return name_ + templateArgValue_.name;
return name_ + templateArgValue_->name;
}
/// Emit function call to MATLAB (no argument checking)

View File

@ -52,8 +52,7 @@ void Method::proxy_header(FileWriter& proxyFile) const {
/* ************************************************************************* */
string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, const ArgumentList& args,
const Qualified& instName) const {
Str matlabUniqueName, const ArgumentList& args) const {
// check arguments
// extra argument obj -> nargin-1 is passed !
// example: checkArguments("equals",nargout,nargin-1,2);
@ -71,8 +70,8 @@ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
// call method and wrap result
// example: out[0]=wrap<bool>(obj->return_field(t));
string expanded = "obj->" + name_;
if (!instName.empty())
expanded += ("<" + instName.qualifiedName("::") + ">");
if (templateArgValue_)
expanded += ("<" + templateArgValue_->qualifiedName("::") + ">");
return expanded;
}

View File

@ -55,8 +55,7 @@ private:
void proxy_header(FileWriter& proxyFile) const;
virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, const ArgumentList& args,
const Qualified& instName) const;
Str matlabUniqueName, const ArgumentList& args) const;
};
} // \namespace wrap

View File

@ -59,7 +59,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile,
// Output C++ wrapper code
const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName,
matlabUniqueName, 0, id, typeAttributes, templateArgValue_);
matlabUniqueName, 0, id, typeAttributes);
// Add to function list
functionNames.push_back(wrapFunctionName);
@ -75,8 +75,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile,
// Output C++ wrapper code
const string wrapFunctionName = wrapper_fragment(wrapperFile,
cppClassName, matlabUniqueName, i, id, typeAttributes,
templateArgValue_);
cppClassName, matlabUniqueName, i, id, typeAttributes);
// Add to function list
functionNames.push_back(wrapFunctionName);
@ -94,8 +93,7 @@ void MethodBase::proxy_wrapper_fragments(FileWriter& proxyFile,
/* ************************************************************************* */
string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, int overload, int id,
const TypeAttributesTable& typeAttributes,
const Qualified& instName) const {
const TypeAttributesTable& typeAttributes) const {
// generate code
@ -120,7 +118,7 @@ string MethodBase::wrapper_fragment(FileWriter& wrapperFile, Str cppClassName,
// for static methods: cppClassName::staticMethod<TemplateVal>
// for instance methods: obj->instanceMethod<TemplateVal>
string expanded = wrapper_call(wrapperFile, cppClassName, matlabUniqueName,
args, instName);
args);
expanded += ("(" + args.names() + ")");
if (returnVal.type1.name != "void")

View File

@ -57,12 +57,10 @@ protected:
std::string wrapper_fragment(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, int overload, int id,
const TypeAttributesTable& typeAttributes, const Qualified& instName =
Qualified()) const; ///< cpp wrapper
const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper
virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, const ArgumentList& args,
const Qualified& instName) const = 0;
Str matlabUniqueName, const ArgumentList& args) const = 0;
};
} // \namespace wrap

View File

@ -26,26 +26,53 @@ namespace wrap {
/**
* Class to encapuslate a qualified name, i.e., with (nested) namespaces
*/
struct Qualified {
class Qualified {
public:
std::vector<std::string> namespaces; ///< Stack of namespaces
std::string name; ///< type name
Qualified(const std::string& name_ = "") :
name(name_) {
/// the different supported return value categories
typedef enum {
CLASS = 1, EIGEN = 2, BASIS = 3, VOID = 4
} Category;
Category category_;
Qualified() :
category_(CLASS) {
}
bool empty() const {
return namespaces.empty() && name.empty();
Qualified(std::vector<std::string> ns, const std::string& name) :
namespaces(ns), name(name), category_(CLASS) {
}
void clear() {
namespaces.clear();
name.clear();
Qualified(const std::string& n, Category category) :
name(n), category_(category) {
}
public:
static Qualified MakeClass(std::vector<std::string> namespaces,
const std::string& name) {
return Qualified(namespaces, name);
}
static Qualified MakeEigen(const std::string& name) {
return Qualified(name, EIGEN);
}
static Qualified MakeBasis(const std::string& name) {
return Qualified(name, BASIS);
}
static Qualified MakeVoid() {
return Qualified("void", VOID);
}
bool operator!=(const Qualified& other) const {
return other.name != name || other.namespaces != namespaces;
return other.name != name || other.namespaces != namespaces
|| other.category_ != category_;
}
/// Return a qualified string using given delimiter

View File

@ -23,7 +23,7 @@ void ReturnType::wrap_result(const string& out, const string& result,
string cppType = qualifiedName("::"), matlabType = qualifiedName(".");
if (category == CLASS) {
if (category_ == CLASS) {
string objCopy, ptrType;
ptrType = "Shared" + name;
const bool isVirtual = typeAttributes.attributes(cppType).isVirtual;
@ -52,7 +52,7 @@ void ReturnType::wrap_result(const string& out, const string& result,
/* ************************************************************************* */
void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const {
if (category == CLASS)
if (category_ == CLASS)
wrapperFile.oss << " typedef boost::shared_ptr<" << qualifiedName("::")
<< "> Shared" << name << ";" << endl;
}

View File

@ -17,22 +17,16 @@ 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;
struct ReturnType: public Qualified {
bool isPtr;
return_category category;
ReturnType() :
isPtr(false), category(CLASS) {
isPtr(false) {
}
ReturnType(const std::string& name) :
isPtr(false), category(CLASS) {
isPtr(false) {
Qualified::name = name;
}

View File

@ -64,7 +64,7 @@ void ReturnValue::emit_matlab(FileWriter& proxyFile) const {
string output;
if (isPair)
proxyFile.oss << "[ varargout{1} varargout{2} ] = ";
else if (type1.category != ReturnType::VOID)
else if (type1.category_ != ReturnType::VOID)
proxyFile.oss << "varargout{1} = ";
}

View File

@ -50,7 +50,7 @@ struct ReturnValue {
void emit_matlab(FileWriter& proxyFile) const;
friend std::ostream& operator<<(std::ostream& os, const ReturnValue& r) {
if (!r.isPair && r.type1.category == ReturnType::VOID)
if (!r.isPair && r.type1.category_ == ReturnType::VOID)
os << "void";
else
os << r.return_type(true);

View File

@ -38,8 +38,7 @@ void StaticMethod::proxy_header(FileWriter& proxyFile) const {
/* ************************************************************************* */
string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, const ArgumentList& args,
const Qualified& instName) const {
Str matlabUniqueName, const ArgumentList& args) const {
// check arguments
// NOTE: for static functions, there is no object passed
wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << "." << name_
@ -51,8 +50,8 @@ string StaticMethod::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
// call method and wrap result
// example: out[0]=wrap<bool>(staticMethod(t));
string expanded = cppClassName + "::" + name_;
if (!instName.empty())
expanded += ("<" + instName.qualifiedName("::") + ">");
if (templateArgValue_)
expanded += ("<" + templateArgValue_->qualifiedName("::") + ">");
return expanded;
}

View File

@ -39,8 +39,7 @@ protected:
virtual void proxy_header(FileWriter& proxyFile) const;
virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, const ArgumentList& args,
const Qualified& instName) const;
Str matlabUniqueName, const ArgumentList& args) const;
};
} // \namespace wrap

View File

@ -65,14 +65,14 @@ void TypeAttributesTable::addForwardDeclarations(
void TypeAttributesTable::checkValidity(const vector<Class>& classes) const {
BOOST_FOREACH(const Class& cls, classes) {
// Check that class is virtual if it has a parent
if (!cls.qualifiedParent.empty() && !cls.isVirtual)
if (cls.parentClass && !cls.isVirtual)
throw AttributeError(cls.qualifiedName("::"),
"Has a base class so needs to be declared virtual, change to 'virtual class "
+ cls.name + " ...'");
// Check that parent is virtual as well
Qualified parent = cls.qualifiedParent;
if (!parent.empty() && !table_.at(parent.qualifiedName("::")).isVirtual)
throw AttributeError(parent.qualifiedName("::"),
if (cls.parentClass
&& !table_.at(cls.parentClass->qualifiedName("::")).isVirtual)
throw AttributeError(cls.parentClass->qualifiedName("::"),
"Is the base class of " + cls.qualifiedName("::")
+ ", so needs to be declared virtual");
}

View File

@ -104,7 +104,7 @@ TEST( wrap, Small ) {
EXPECT(!rv1.isPair);
EXPECT(!rv1.type1.isPtr);
EXPECT(assert_equal("double", rv1.type1.name));
EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category);
EXPECT_LONGS_EQUAL(ReturnType::BASIS, rv1.type1.category_);
// Method 2
Method m2 = cls.method("returnMatrix");
@ -116,7 +116,7 @@ TEST( wrap, Small ) {
EXPECT(!rv2.isPair);
EXPECT(!rv2.type1.isPtr);
EXPECT(assert_equal("Matrix", rv2.type1.name));
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category);
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv2.type1.category_);
// Method 3
Method m3 = cls.method("returnPoint2");
@ -128,7 +128,7 @@ TEST( wrap, Small ) {
EXPECT(!rv3.isPair);
EXPECT(!rv3.type1.isPtr);
EXPECT(assert_equal("Point2", rv3.type1.name));
EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category);
EXPECT_LONGS_EQUAL(ReturnType::CLASS, rv3.type1.category_);
// Static Method 1
// static Vector returnVector();
@ -140,7 +140,7 @@ TEST( wrap, Small ) {
EXPECT(!rv4.isPair);
EXPECT(!rv4.type1.isPtr);
EXPECT(assert_equal("Vector", rv4.type1.name));
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category);
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, rv4.type1.category_);
}
@ -192,7 +192,7 @@ TEST( wrap, Geometry ) {
Method m1 = cls.method("returnChar");
LONGS_EQUAL(1, m1.nrOverloads());
EXPECT(assert_equal("char", m1.returnValue(0).type1.name));
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category);
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category_);
EXPECT(!m1.returnValue(0).isPair);
EXPECT(assert_equal("returnChar", m1.name()));
LONGS_EQUAL(1, m1.nrOverloads());
@ -206,7 +206,7 @@ TEST( wrap, Geometry ) {
Method m1 = cls.method("vectorConfusion");
LONGS_EQUAL(1, m1.nrOverloads());
EXPECT(assert_equal("VectorNotEigen", m1.returnValue(0).type1.name));
EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category);
EXPECT_LONGS_EQUAL(ReturnType::CLASS, m1.returnValue(0).type1.category_);
EXPECT(!m1.returnValue(0).isPair);
EXPECT(assert_equal("vectorConfusion", m1.name()));
LONGS_EQUAL(1, m1.nrOverloads());
@ -249,7 +249,7 @@ TEST( wrap, Geometry ) {
Method m1 = cls.method("norm");
LONGS_EQUAL(1, m1.nrOverloads());
EXPECT(assert_equal("double", m1.returnValue(0).type1.name));
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category);
EXPECT_LONGS_EQUAL(ReturnType::BASIS, m1.returnValue(0).type1.category_);
EXPECT(assert_equal("norm", m1.name()));
LONGS_EQUAL(1, m1.nrOverloads());
EXPECT_LONGS_EQUAL(0, m1.argumentList(0).size());
@ -275,9 +275,9 @@ TEST( wrap, Geometry ) {
Method m2 = testCls.method("return_pair");
LONGS_EQUAL(1, m2.nrOverloads());
EXPECT(m2.returnValue(0).isPair);
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category);
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type1.category_);
EXPECT(assert_equal("Vector", m2.returnValue(0).type1.name));
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category);
EXPECT_LONGS_EQUAL(ReturnType::EIGEN, m2.returnValue(0).type2.category_);
EXPECT(assert_equal("Matrix", m2.returnValue(0).type2.name));
// checking pointer args and return values