Moving to optionals fixed template dreturn argument!

Merge branch 'qualified' into grammar_wrongtest

Conflicts:
	wrap/Class.cpp
	wrap/Function.h
	wrap/Qualified.h
	wrap/ReturnType.h
	wrap/tests/testWrap.cpp
release/4.3a0
dellaert 2014-12-01 09:48:56 +01:00
commit ba51b02cf0
27 changed files with 230 additions and 127 deletions

1
matlab/gtsam_tests/.gitignore vendored Normal file
View File

@ -0,0 +1 @@
*.m~

View File

@ -0,0 +1,40 @@
% test wrapping of Values
import gtsam.*;
values = Values;
E = EssentialMatrix(Rot3,Unit3);
tol = 1e-9;
values.insert(0, Point2);
values.insert(1, Point3);
values.insert(2, Rot2);
values.insert(3, Pose2);
values.insert(4, Rot3);
values.insert(5, Pose3);
values.insert(6, Cal3_S2);
values.insert(7, Cal3DS2);
values.insert(8, Cal3Bundler);
values.insert(9, E);
values.insert(10, imuBias.ConstantBias);
% special cases for Vector and Matrix:
values.insert(11, [1;2;3]);
values.insert(12, [1 2;3 4]);
EXPECT('at',values.atPoint2(0).equals(Point2,tol));
EXPECT('at',values.atPoint3(1).equals(Point3,tol));
EXPECT('at',values.atRot2(2).equals(Rot2,tol));
EXPECT('at',values.atPose2(3).equals(Pose2,tol));
EXPECT('at',values.atRot3(4).equals(Rot3,tol));
EXPECT('at',values.atPose3(5).equals(Pose3,tol));
EXPECT('at',values.atCal3_S2(6).equals(Cal3_S2,tol));
EXPECT('at',values.atCal3DS2(7).equals(Cal3DS2,tol));
EXPECT('at',values.atCal3Bundler(8).equals(Cal3Bundler,tol));
EXPECT('at',values.atEssentialMatrix(9).equals(E,tol));
EXPECT('at',values.atConstantBias(10).equals(imuBias.ConstantBias,tol));
% special cases for Vector and Matrix:
actualVector = values.atVector(11);
EQUALITY('at',[1 2;3 4],actualVector,tol);
actualMatrix = values.atMatrix(12);
EQUALITY('at',[1 2;3 4],actualMatrix,tol);

View File

@ -1,5 +1,8 @@
% Test runner script - runs each test % Test runner script - runs each test
display 'Starting: testValues'
testValues
display 'Starting: testJacobianFactor' display 'Starting: testJacobianFactor'
testJacobianFactor testJacobianFactor

View File

@ -29,24 +29,49 @@
#include <iostream> #include <iostream>
#include <fstream> #include <fstream>
#include <iterator> // std::ostream_iterator #include <iterator> // std::ostream_iterator
//#include <cstdint> // on Linux GCC: fails with error regarding needing C++0x std flags //#include <cstdint> // on Linux GCC: fails with error regarding needing C++0x std flags
//#include <cinttypes> // same failure as above //#include <cinttypes> // same failure as above
#include <stdint.h> // works on Linux GCC #include <stdint.h> // works on Linux GCC
using namespace std; using namespace std;
using namespace wrap; using namespace wrap;
/* ************************************************************************* */ /* ************************************************************************* */
Method& Class::method(Str key) { void Class::assignParent(const Qualified& parent) {
parentClass.reset(parent);
}
/* ************************************************************************* */
boost::optional<string> Class::qualifiedParent() const {
boost::optional<string> result = boost::none;
if (parentClass) result = parentClass->qualifiedName("::");
return result;
}
/* ************************************************************************* */
static void handleException(const out_of_range& oor,
const Class::Methods& methods) {
cerr << "Class::method: key not found: " << oor.what() << ", methods are:\n";
using boost::adaptors::map_keys;
ostream_iterator<string> out_it(cerr, "\n");
boost::copy(methods | map_keys, out_it);
}
/* ************************************************************************* */
Method& Class::mutableMethod(Str key) {
try { try {
return methods_.at(key); return methods_.at(key);
} catch (const out_of_range& oor) { } catch (const out_of_range& oor) {
cerr << "Class::method: key not found: " << oor.what() handleException(oor,methods_);
<< ", methods are:\n"; throw runtime_error("Internal error in wrap");
using boost::adaptors::map_keys; }
ostream_iterator<string> out_it(cerr, "\n"); }
boost::copy(methods_ | map_keys, out_it);
/* ************************************************************************* */
const Method& Class::method(Str key) const {
try {
return methods_.at(key);
} catch (const out_of_range& oor) {
handleException(oor,methods_);
throw runtime_error("Internal error in wrap"); throw runtime_error("Internal error in wrap");
} }
} }
@ -67,12 +92,11 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
const string matlabQualName = qualifiedName("."); const string matlabQualName = qualifiedName(".");
const string matlabUniqueName = qualifiedName(); const string matlabUniqueName = qualifiedName();
const string cppName = qualifiedName("::"); const string cppName = qualifiedName("::");
const string matlabBaseName = qualifiedParent.qualifiedName(".");
const string cppBaseName = qualifiedParent.qualifiedName("::");
// emit class proxy code // emit class proxy code
// we want our class to inherit the handle class for memory purposes // we want our class to inherit the handle class for memory purposes
const string parent = qualifiedParent.empty() ? "handle" : matlabBaseName; const string parent =
parentClass ? parentClass->qualifiedName(".") : "handle";
comment_fragment(proxyFile); comment_fragment(proxyFile);
proxyFile.oss << "classdef " << name() << " < " << parent << endl; proxyFile.oss << "classdef " << name() << " < " << parent << endl;
proxyFile.oss << " properties\n"; proxyFile.oss << " properties\n";
@ -94,11 +118,12 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
wrapperFile.oss << "\n"; wrapperFile.oss << "\n";
// Regular constructors // Regular constructors
boost::optional<string> cppBaseName = qualifiedParent();
for (size_t i = 0; i < constructor.nrOverloads(); i++) { for (size_t i = 0; i < constructor.nrOverloads(); i++) {
ArgumentList args = constructor.argumentList(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, (bool) parentClass, id,
id, args); args);
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile, const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
cppName, matlabUniqueName, cppBaseName, id, args); cppName, matlabUniqueName, cppBaseName, id, args);
wrapperFile.oss << "\n"; wrapperFile.oss << "\n";
@ -108,9 +133,9 @@ void Class::matlab_proxy(Str toolboxPath, Str wrapperName,
proxyFile.oss << " error('Arguments do not match any overload of " proxyFile.oss << " error('Arguments do not match any overload of "
<< matlabQualName << " constructor');\n"; << matlabQualName << " constructor');\n";
proxyFile.oss << " end\n"; proxyFile.oss << " end\n";
if (!qualifiedParent.empty()) if (parentClass)
proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" proxyFile.oss << " obj = obj@" << parentClass->qualifiedName(".")
<< ptr_constructor_key << "), base_ptr);\n"; << "(uint64(" << ptr_constructor_key << "), base_ptr);\n";
proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n"; proxyFile.oss << " obj.ptr_" << matlabUniqueName << " = my_ptr;\n";
proxyFile.oss << " end\n\n"; proxyFile.oss << " end\n\n";
@ -170,7 +195,6 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile,
const string matlabUniqueName = qualifiedName(); const string matlabUniqueName = qualifiedName();
const string cppName = qualifiedName("::"); const string cppName = qualifiedName("::");
const string baseCppName = qualifiedParent.qualifiedName("::");
const int collectorInsertId = (int) functionNames.size(); const int collectorInsertId = (int) functionNames.size();
const string collectorInsertFunctionName = matlabUniqueName const string collectorInsertFunctionName = matlabUniqueName
@ -207,7 +231,7 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile,
} else { } else {
proxyFile.oss << " my_ptr = varargin{2};\n"; 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 << " "; proxyFile.oss << " ";
else else
proxyFile.oss << " base_ptr = "; proxyFile.oss << " base_ptr = ";
@ -230,9 +254,10 @@ void Class::pointer_constructor_fragments(FileWriter& proxyFile,
// Add to collector // Add to collector
wrapperFile.oss << " collector_" << matlabUniqueName << ".insert(self);\n"; 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 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()) { boost::optional<string> cppBaseName = qualifiedParent();
if (cppBaseName) {
wrapperFile.oss << "\n"; wrapperFile.oss << "\n";
wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName wrapperFile.oss << " typedef boost::shared_ptr<" << *cppBaseName
<< "> SharedBase;\n"; << "> SharedBase;\n";
wrapperFile.oss wrapperFile.oss
<< " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
@ -297,7 +322,7 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName,
// Create method to expand // Create method to expand
// 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) {
const TemplateSubstitution ts(templateArgName, instName, name()); const TemplateSubstitution ts(templateArgName, instName, *this);
// substitute template in arguments // substitute template in arguments
ArgumentList expandedArgs = argumentList.expandTemplate(ts); ArgumentList expandedArgs = argumentList.expandTemplate(ts);
// do the same for return type // do the same for return type
@ -311,7 +336,7 @@ void Class::addMethod(bool verbose, bool is_const, Str methodName,
} else } else
// just add overload // just add overload
methods_[methodName].addOverload(methodName, argumentList, returnValue, methods_[methodName].addOverload(methodName, argumentList, returnValue,
is_const, Qualified(), verbose); is_const, boost::none, verbose);
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -353,23 +378,23 @@ void Class::verifyAll(vector<string>& validTypes, bool& hasSerialiable) const {
verifyReturnTypes<Method>(validTypes, methods_); verifyReturnTypes<Method>(validTypes, methods_);
// verify parents // verify parents
if (!qualifiedParent.empty() boost::optional<string> parent = qualifiedParent();
&& find(validTypes.begin(), validTypes.end(), if (parent
qualifiedParent.qualifiedName("::")) == validTypes.end()) && find(validTypes.begin(), validTypes.end(), *parent)
throw DependencyMissing(qualifiedParent.qualifiedName("::"), == validTypes.end())
qualifiedName("::")); throw DependencyMissing(*parent, qualifiedName("::"));
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Class::appendInheritedMethods(const Class& cls, void Class::appendInheritedMethods(const Class& cls,
const vector<Class>& classes) { const vector<Class>& classes) {
if (!cls.qualifiedParent.empty()) { if (cls.parentClass) {
// Find parent // Find parent
BOOST_FOREACH(const Class& parent, classes) { BOOST_FOREACH(const Class& parent, classes) {
// We found a parent class for our parent, TODO improve ! // 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()); methods_.insert(parent.methods_.begin(), parent.methods_.end());
appendInheritedMethods(parent, classes); appendInheritedMethods(parent, classes);
} }

View File

@ -27,6 +27,7 @@
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <boost/range/adaptor/map.hpp> #include <boost/range/adaptor/map.hpp>
#include <boost/optional.hpp>
#include <string> #include <string>
#include <map> #include <map>
@ -36,15 +37,19 @@ namespace wrap {
/// Class has name, constructors, methods /// Class has name, constructors, methods
class Class: public Qualified { class Class: public Qualified {
public:
typedef const std::string& Str; typedef const std::string& Str;
typedef std::map<std::string, Method> Methods; typedef std::map<std::string, Method> Methods;
typedef std::map<std::string, StaticMethod> StaticMethods;
private:
boost::optional<Qualified> parentClass; ///< The *single* parent
Methods methods_; ///< Class methods Methods methods_; ///< Class methods
Method& mutableMethod(Str key);
public: public:
typedef std::map<std::string, StaticMethod> StaticMethods;
StaticMethods static_methods; ///< Static methods StaticMethods static_methods; ///< Static methods
// Then the instance variables are set directly by the Module constructor // Then the instance variables are set directly by the Module constructor
@ -53,22 +58,25 @@ public:
bool isVirtual; ///< Whether the class is part of a virtual inheritance chain 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 isSerializable; ///< Whether we can use boost.serialization to serialize the class - creates exports
bool hasSerialization; ///< Whether we should create the serialization functions bool hasSerialization; ///< Whether we should create the serialization functions
Qualified qualifiedParent; ///< The *single* parent
Constructor constructor; ///< Class constructors Constructor constructor; ///< Class constructors
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
bool verbose_; ///< verbose flag bool verbose_; ///< verbose flag
/// Constructor creates an empty class /// Constructor creates an empty class
Class(bool verbose = true) : Class(bool verbose = true) :
isVirtual(false), isSerializable(false), hasSerialization(false), deconstructor( parentClass(boost::none), isVirtual(false), isSerializable(false), hasSerialization(
verbose), verbose_(verbose) { false), deconstructor(verbose), verbose_(verbose) {
} }
void assignParent(const Qualified& parent);
boost::optional<std::string> qualifiedParent() const;
size_t nrMethods() const { size_t nrMethods() const {
return methods_.size(); return methods_.size();
} }
Method& method(Str key); const Method& method(Str key) const;
bool exists(Str name) const { bool exists(Str name) const {
return methods_.find(name) != methods_.end(); return methods_.find(name) != methods_.end();

View File

@ -69,7 +69,7 @@ void Constructor::proxy_fragment(FileWriter& file,
/* ************************************************************************* */ /* ************************************************************************* */
string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName, 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 ArgumentList& al) const {
const string wrapFunctionName = matlabUniqueName + "_constructor_" const string wrapFunctionName = matlabUniqueName + "_constructor_"
@ -100,9 +100,9 @@ string Constructor::wrapper_fragment(FileWriter& file, Str cppClassName,
<< endl; << 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 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 << "\n";
file.oss << " typedef boost::shared_ptr<" << cppBaseClassName file.oss << " typedef boost::shared_ptr<" << *cppBaseClassName
<< "> SharedBase;\n"; << "> SharedBase;\n";
file.oss file.oss
<< " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n"; << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";

View File

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

View File

@ -109,8 +109,8 @@ class FullyOverloadedFunction: public Function, public SignatureOverloads {
public: public:
bool addOverload(const std::string& name, const ArgumentList& args, bool addOverload(const std::string& name, const ArgumentList& args,
const ReturnValue& retVal, const Qualified& instName = Qualified(), const ReturnValue& retVal, boost::optional<const Qualified> instName =
bool verbose = false) { boost::none, bool verbose = false) {
bool first = initializeOrCheck(name, instName, verbose); bool first = initializeOrCheck(name, instName, verbose);
SignatureOverloads::push_back(args, retVal); SignatureOverloads::push_back(args, retVal);
return first; return first;

View File

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

View File

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

View File

@ -18,7 +18,7 @@ using namespace std;
/* ************************************************************************* */ /* ************************************************************************* */
void GlobalFunction::addOverload(const Qualified& overload, void GlobalFunction::addOverload(const Qualified& overload,
const ArgumentList& args, const ReturnValue& retVal, const ArgumentList& args, const ReturnValue& retVal,
const Qualified& instName, bool verbose) { boost::optional<const Qualified> instName, bool verbose) {
FullyOverloadedFunction::addOverload(overload.name(), args, retVal, instName, FullyOverloadedFunction::addOverload(overload.name(), args, retVal, instName,
verbose); verbose);
overloads.push_back(overload); overloads.push_back(overload);

View File

@ -19,8 +19,8 @@ struct GlobalFunction: public FullyOverloadedFunction {
// adds an overloaded version of this function, // adds an overloaded version of this function,
void addOverload(const Qualified& overload, const ArgumentList& args, void addOverload(const Qualified& overload, const ArgumentList& args,
const ReturnValue& retVal, const Qualified& instName = Qualified(), const ReturnValue& retVal, boost::optional<const Qualified> instName =
bool verbose = false); boost::none, bool verbose = false);
void verifyArguments(const std::vector<std::string>& validArgs) const { void verifyArguments(const std::vector<std::string>& validArgs) const {
SignatureOverloads::verifyArguments(validArgs, name_); SignatureOverloads::verifyArguments(validArgs, name_);

View File

@ -30,8 +30,8 @@ using namespace wrap;
/* ************************************************************************* */ /* ************************************************************************* */
bool Method::addOverload(Str name, const ArgumentList& args, bool Method::addOverload(Str name, const ArgumentList& args,
const ReturnValue& retVal, bool is_const, const Qualified& instName, const ReturnValue& retVal, bool is_const,
bool verbose) { boost::optional<const Qualified> instName, bool verbose) {
bool first = MethodBase::addOverload(name, args, retVal, instName, verbose); bool first = MethodBase::addOverload(name, args, retVal, instName, verbose);
if (first) if (first)
is_const_ = is_const; is_const_ = is_const;
@ -52,8 +52,7 @@ void Method::proxy_header(FileWriter& proxyFile) const {
/* ************************************************************************* */ /* ************************************************************************* */
string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName, string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, const ArgumentList& args, Str matlabUniqueName, const ArgumentList& args) const {
const Qualified& instName) const {
// 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);
@ -71,8 +70,8 @@ string Method::wrapper_call(FileWriter& wrapperFile, Str cppClassName,
// call method and wrap result // call method and wrap result
// example: out[0]=wrap<bool>(obj->return_field(t)); // example: out[0]=wrap<bool>(obj->return_field(t));
string expanded = "obj->" + name_; string expanded = "obj->" + name_;
if (!instName.empty()) if (templateArgValue_)
expanded += ("<" + instName.qualifiedName("::") + ">"); expanded += ("<" + templateArgValue_->qualifiedName("::") + ">");
return expanded; return expanded;
} }

View File

@ -32,8 +32,9 @@ public:
typedef const std::string& Str; typedef const std::string& Str;
bool addOverload(Str name, const ArgumentList& args, bool addOverload(Str name, const ArgumentList& args,
const ReturnValue& retVal, bool is_const, const Qualified& instName = const ReturnValue& retVal, bool is_const,
Qualified(), bool verbose = false); boost::optional<const Qualified> instName = boost::none, bool verbose =
false);
virtual bool isStatic() const { virtual bool isStatic() const {
return false; return false;
@ -55,8 +56,7 @@ private:
void proxy_header(FileWriter& proxyFile) const; void proxy_header(FileWriter& proxyFile) const;
virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName, virtual std::string wrapper_call(FileWriter& wrapperFile, Str cppClassName,
Str matlabUniqueName, const ArgumentList& args, Str matlabUniqueName, const ArgumentList& args) const;
const Qualified& instName) const;
}; };
} // \namespace wrap } // \namespace wrap

View File

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

View File

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

View File

@ -113,7 +113,6 @@ void Module::parseMarkup(const std::string& data) {
// TODO, do we really need cls here? Non-local // TODO, do we really need cls here? Non-local
Class cls0(verbose),cls(verbose); Class cls0(verbose),cls(verbose);
TypeGrammar classParent_p(cls.qualifiedParent);
// parse "gtsam::Pose2" and add to templateArgValues // parse "gtsam::Pose2" and add to templateArgValues
Qualified templateArgValue; Qualified templateArgValue;
@ -203,12 +202,15 @@ void Module::parseMarkup(const std::string& data) {
'(' >> argumentList_p >> ')' >> ';' >> *basic.comments_p) '(' >> argumentList_p >> ')' >> ';' >> *basic.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)],
bl::var(methodName), bl::var(args), bl::var(retVal), Qualified(),verbose)] bl::var(methodName), bl::var(args), bl::var(retVal), boost::none,verbose)]
[assign_a(retVal,retVal0)] [assign_a(retVal,retVal0)]
[clear_a(args)]; [clear_a(args)];
Rule functions_p = constructor_p | method_p | static_method_p; Rule functions_p = constructor_p | method_p | static_method_p;
Qualified possibleParent;
TypeGrammar classParent_p(possibleParent);
// parse a full class // parse a full class
vector<Qualified> templateInstantiations; vector<Qualified> templateInstantiations;
Rule class_p = Rule class_p =
@ -221,11 +223,13 @@ void Module::parseMarkup(const std::string& data) {
>> !(str_p("virtual")[assign_a(cls.isVirtual, true)]) >> !(str_p("virtual")[assign_a(cls.isVirtual, true)])
>> str_p("class") >> str_p("class")
>> basic.className_p[assign_a(cls.name_)] >> basic.className_p[assign_a(cls.name_)]
>> ((':' >> classParent_p >> '{') | '{') >> ((':' >> classParent_p >> '{')
[bl::bind(&Class::assignParent, bl::var(cls), bl::var(possibleParent))]
[clear_a(possibleParent)] | '{')
>> *(functions_p | basic.comments_p) >> *(functions_p | basic.comments_p)
>> str_p("};")) >> str_p("};"))
[bl::bind(&Constructor::initializeOrCheck, bl::var(constructor), [bl::bind(&Constructor::initializeOrCheck, bl::var(constructor),
bl::var(cls.name_), Qualified(), verbose)] bl::var(cls.name_), boost::none, verbose)]
[assign_a(cls.constructor, constructor)] [assign_a(cls.constructor, constructor)]
[assign_a(cls.namespaces_, namespaces)] [assign_a(cls.namespaces_, namespaces)]
[assign_a(cls.deconstructor.name,cls.name_)] [assign_a(cls.deconstructor.name,cls.name_)]
@ -243,7 +247,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_)],
bl::var(globalFunction), bl::var(args), bl::var(retVal), Qualified(),verbose)] bl::var(globalFunction), bl::var(args), bl::var(retVal), boost::none,verbose)]
[assign_a(retVal,retVal0)] [assign_a(retVal,retVal0)]
[clear_a(globalFunction)] [clear_a(globalFunction)]
[clear_a(args)]; [clear_a(args)];

View File

@ -87,7 +87,8 @@ class OverloadedFunction: public Function, public ArgumentOverloads {
public: public:
bool addOverload(const std::string& name, const ArgumentList& args, bool addOverload(const std::string& name, const ArgumentList& args,
const Qualified& instName = Qualified(), bool verbose = false) { boost::optional<const Qualified> instName = boost::none, bool verbose =
false) {
bool first = initializeOrCheck(name, instName, verbose); bool first = initializeOrCheck(name, instName, verbose);
ArgumentOverloads::push_back(args); ArgumentOverloads::push_back(args);
return first; return first;

View File

@ -73,6 +73,10 @@ public:
namespaces_.push_back(ns1); namespaces_.push_back(ns1);
} }
Qualified(std::vector<std::string> ns, const std::string& name) :
namespaces_(ns), name_(name), category(CLASS) {
}
std::string name() const { std::string name() const {
return name_; return name_;
} }
@ -112,6 +116,26 @@ public:
category = VOID; category = VOID;
} }
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);
}
/// 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;

View File

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

View File

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

View File

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

View File

@ -12,10 +12,10 @@
%return_T(Point2 value) : returns gtsam::Point2 %return_T(Point2 value) : returns gtsam::Point2
%return_Tptr(Point2 value) : returns gtsam::Point2 %return_Tptr(Point2 value) : returns gtsam::Point2
%return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 > %return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 >
%templatedMethodMatrix(Matrix t) : returns void %templatedMethodMatrix(Matrix t) : returns Matrix
%templatedMethodPoint2(Point2 t) : returns void %templatedMethodPoint2(Point2 t) : returns gtsam::Point2
%templatedMethodPoint3(Point3 t) : returns void %templatedMethodPoint3(Point3 t) : returns gtsam::Point3
%templatedMethodVector(Vector t) : returns void %templatedMethodVector(Vector t) : returns Vector
% %
classdef MyTemplatePoint2 < MyBase classdef MyTemplatePoint2 < MyBase
properties properties
@ -110,7 +110,7 @@ classdef MyTemplatePoint2 < MyBase
end end
function varargout = templatedMethodMatrix(this, varargin) function varargout = templatedMethodMatrix(this, varargin)
% TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix
% 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
if length(varargin) == 1 && isa(varargin{1},'double') if length(varargin) == 1 && isa(varargin{1},'double')
geometry_wrapper(55, this, varargin{:}); geometry_wrapper(55, this, varargin{:});
@ -120,7 +120,7 @@ classdef MyTemplatePoint2 < MyBase
end end
function varargout = templatedMethodPoint2(this, varargin) function varargout = templatedMethodPoint2(this, varargin)
% TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2
% 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
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
geometry_wrapper(56, this, varargin{:}); geometry_wrapper(56, this, varargin{:});
@ -130,7 +130,7 @@ classdef MyTemplatePoint2 < MyBase
end end
function varargout = templatedMethodPoint3(this, varargin) function varargout = templatedMethodPoint3(this, varargin)
% TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3
% 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
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
geometry_wrapper(57, this, varargin{:}); geometry_wrapper(57, this, varargin{:});
@ -140,7 +140,7 @@ classdef MyTemplatePoint2 < MyBase
end end
function varargout = templatedMethodVector(this, varargin) function varargout = templatedMethodVector(this, varargin)
% TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector
% 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
if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1
geometry_wrapper(58, this, varargin{:}); geometry_wrapper(58, this, varargin{:});

View File

@ -12,10 +12,10 @@
%return_T(Point3 value) : returns gtsam::Point3 %return_T(Point3 value) : returns gtsam::Point3
%return_Tptr(Point3 value) : returns gtsam::Point3 %return_Tptr(Point3 value) : returns gtsam::Point3
%return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 > %return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 >
%templatedMethodMatrix(Matrix t) : returns void %templatedMethodMatrix(Matrix t) : returns Matrix
%templatedMethodPoint2(Point2 t) : returns void %templatedMethodPoint2(Point2 t) : returns gtsam::Point2
%templatedMethodPoint3(Point3 t) : returns void %templatedMethodPoint3(Point3 t) : returns gtsam::Point3
%templatedMethodVector(Vector t) : returns void %templatedMethodVector(Vector t) : returns Vector
% %
classdef MyTemplatePoint3 < MyBase classdef MyTemplatePoint3 < MyBase
properties properties
@ -110,7 +110,7 @@ classdef MyTemplatePoint3 < MyBase
end end
function varargout = templatedMethodMatrix(this, varargin) function varargout = templatedMethodMatrix(this, varargin)
% TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns void % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix
% 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
if length(varargin) == 1 && isa(varargin{1},'double') if length(varargin) == 1 && isa(varargin{1},'double')
geometry_wrapper(70, this, varargin{:}); geometry_wrapper(70, this, varargin{:});
@ -120,7 +120,7 @@ classdef MyTemplatePoint3 < MyBase
end end
function varargout = templatedMethodPoint2(this, varargin) function varargout = templatedMethodPoint2(this, varargin)
% TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns gtsam::Point2
% 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
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
geometry_wrapper(71, this, varargin{:}); geometry_wrapper(71, this, varargin{:});
@ -130,7 +130,7 @@ classdef MyTemplatePoint3 < MyBase
end end
function varargout = templatedMethodPoint3(this, varargin) function varargout = templatedMethodPoint3(this, varargin)
% TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns gtsam::Point3
% 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
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
geometry_wrapper(72, this, varargin{:}); geometry_wrapper(72, this, varargin{:});
@ -140,7 +140,7 @@ classdef MyTemplatePoint3 < MyBase
end end
function varargout = templatedMethodVector(this, varargin) function varargout = templatedMethodVector(this, varargin)
% TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns void % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector
% 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
if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1
geometry_wrapper(73, this, varargin{:}); geometry_wrapper(73, this, varargin{:});

View File

@ -678,7 +678,7 @@ void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodMatrix",nargout,nargin-1,1); checkArguments("templatedMethodMatrix",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
obj->templatedMethod<Matrix>(t); out[0] = wrap< Matrix >(obj->templatedMethod<Matrix>(t));
} }
void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -687,7 +687,7 @@ void MyTemplatePoint2_templatedMethod_56(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodPoint2",nargout,nargin-1,1); checkArguments("templatedMethodPoint2",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
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); out[0] = wrap< gtsam::Point2 >(obj->templatedMethod<gtsam::Point2>(t));
} }
void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -696,7 +696,7 @@ void MyTemplatePoint2_templatedMethod_57(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodPoint3",nargout,nargin-1,1); checkArguments("templatedMethodPoint3",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
obj->templatedMethod<gtsam::Point3>(t); out[0] = wrap< gtsam::Point3 >(obj->templatedMethod<gtsam::Point3>(t));
} }
void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -705,7 +705,7 @@ void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodVector",nargout,nargin-1,1); checkArguments("templatedMethodVector",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector");
obj->templatedMethod<Vector>(t); out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
} }
void MyTemplatePoint3_collectorInsertAndMakeBase_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_collectorInsertAndMakeBase_59(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -838,7 +838,7 @@ void MyTemplatePoint3_templatedMethod_70(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodMatrix",nargout,nargin-1,1); checkArguments("templatedMethodMatrix",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix"); Matrix& t = *unwrap_shared_ptr< Matrix >(in[1], "ptr_Matrix");
obj->templatedMethod<Matrix>(t); out[0] = wrap< Matrix >(obj->templatedMethod<Matrix>(t));
} }
void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -847,7 +847,7 @@ void MyTemplatePoint3_templatedMethod_71(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodPoint2",nargout,nargin-1,1); checkArguments("templatedMethodPoint2",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
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); out[0] = wrap< gtsam::Point2 >(obj->templatedMethod<gtsam::Point2>(t));
} }
void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -856,7 +856,7 @@ void MyTemplatePoint3_templatedMethod_72(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodPoint3",nargout,nargin-1,1); checkArguments("templatedMethodPoint3",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
obj->templatedMethod<gtsam::Point3>(t); out[0] = wrap< gtsam::Point3 >(obj->templatedMethod<gtsam::Point3>(t));
} }
void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -865,7 +865,7 @@ void MyTemplatePoint3_templatedMethod_73(int nargout, mxArray *out[], int nargin
checkArguments("templatedMethodVector",nargout,nargin-1,1); checkArguments("templatedMethodVector",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector"); Vector& t = *unwrap_shared_ptr< Vector >(in[1], "ptr_Vector");
obj->templatedMethod<Vector>(t); out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
} }
void MyFactorPosePoint2_collectorInsertAndMakeBase_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyFactorPosePoint2_collectorInsertAndMakeBase_74(int nargout, mxArray *out[], int nargin, const mxArray *in[])

View File

@ -106,7 +106,7 @@ virtual class MyTemplate : MyBase {
MyTemplate(); MyTemplate();
template<ARG = {gtsam::Point2, gtsam::Point3, Vector, Matrix}> template<ARG = {gtsam::Point2, gtsam::Point3, Vector, Matrix}>
void templatedMethod(const ARG& t); ARG templatedMethod(const ARG& t);
// Stress test templates and pointer combinations // Stress test templates and pointer combinations
void accept_T(const T& value) const; void accept_T(const T& value) const;

View File

@ -45,7 +45,7 @@ TEST( Class, OverloadingMethod ) {
templateArgValues); templateArgValues);
EXPECT_LONGS_EQUAL(1, cls.nrMethods()); EXPECT_LONGS_EQUAL(1, cls.nrMethods());
EXPECT(cls.exists(name)); EXPECT(cls.exists(name));
Method& method = cls.method(name); Method method = cls.method(name);
EXPECT_LONGS_EQUAL(1, method.nrOverloads()); EXPECT_LONGS_EQUAL(1, method.nrOverloads());
cls.addMethod(verbose, is_const, name, args, retVal, templateArgName, cls.addMethod(verbose, is_const, name, args, retVal, templateArgName,