gtsam.h with templated Values::at now compiles !

release/4.3a0
dellaert 2014-11-13 01:26:06 +01:00
parent 3c1daa5d6f
commit 341ad9f288
12 changed files with 257 additions and 428 deletions

14
gtsam.h
View File

@ -1749,17 +1749,9 @@ class Values {
void update(size_t j, const gtsam::Cal3Bundler& t); void update(size_t j, const gtsam::Cal3Bundler& t);
void update(size_t j, const gtsam::EssentialMatrix& t); void update(size_t j, const gtsam::EssentialMatrix& t);
// But it would be nice if this worked: template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2,
// template<class T = { gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2}>
// gtsam::Point2, T at(size_t j);
// gtsam::Point3,
// gtsam::Rot2,
// gtsam::Pose2,
// gtsam::Rot3,
// gtsam::Pose3,
// gtsam::Cal3_S2,
// gtsam::Cal3DS2}>
// void insert(size_t j, const T& value);
}; };
// Actually a FastList<Key> // Actually a FastList<Key>

View File

@ -341,11 +341,8 @@ void Class::addMethod(bool verbose, bool is_const, const string& name,
BOOST_FOREACH(const Qualified& instName, templateArgValues) { BOOST_FOREACH(const Qualified& instName, templateArgValues) {
Method expanded = // Method expanded = //
expandMethodTemplate(method, templateArgName, instName, *this); expandMethodTemplate(method, templateArgName, instName, *this);
expanded.name += instName.name; methods[name].addOverload(verbose, is_const, name, expanded.argLists[0],
if (exists(expanded.name)) expanded.returnVals[0], instName);
throw runtime_error(
"Class::addMethod: Overloading and templates are mutex, for now");
methods[expanded.name] = expanded;
} }
} else } else
// just add overload // just add overload

View File

@ -30,17 +30,19 @@ using namespace wrap;
/* ************************************************************************* */ /* ************************************************************************* */
void Method::addOverload(bool verbose, bool is_const, const std::string& name, void Method::addOverload(bool verbose, bool is_const, const std::string& name,
const ArgumentList& args, const ReturnValue& retVal) { const ArgumentList& args, const ReturnValue& retVal,
const Qualified& instName) {
if (!this->name.empty() && this->name != name) if (!this->name.empty() && this->name != name)
throw std::runtime_error( throw std::runtime_error(
"Method::addOverload: tried to add overload with name " + name "Method::addOverload: tried to add overload with name " + name
+ " instead of expected " + this->name); + " instead of expected " + this->name);
else else
this->name = name; this->name = name;
this->verbose_ = verbose; verbose_ = verbose;
this->is_const_ = is_const; is_const_ = is_const;
this->argLists.push_back(args); argLists.push_back(args);
this->returnVals.push_back(retVal); returnVals.push_back(retVal);
templateArgValues.push_back(instName);
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -92,7 +94,7 @@ void Method::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); matlabUniqueName, 0, id, typeAttributes, templateArgValues[0]);
// Add to function list // Add to function list
functionNames.push_back(wrapFunctionName); functionNames.push_back(wrapFunctionName);
@ -108,7 +110,8 @@ void Method::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, overload, id, typeAttributes); cppClassName, matlabUniqueName, overload, id, typeAttributes,
templateArgValues[overload]);
// Add to function list // Add to function list
functionNames.push_back(wrapFunctionName); functionNames.push_back(wrapFunctionName);
@ -126,7 +129,8 @@ void Method::proxy_wrapper_fragments(FileWriter& proxyFile,
/* ************************************************************************* */ /* ************************************************************************* */
string Method::wrapper_fragment(FileWriter& wrapperFile, string Method::wrapper_fragment(FileWriter& wrapperFile,
const string& cppClassName, const string& matlabUniqueName, int overload, const string& cppClassName, const string& matlabUniqueName, int overload,
int id, const TypeAttributesTable& typeAttributes) const { int id, const TypeAttributesTable& typeAttributes,
const Qualified& instName) const {
// generate code // generate code
@ -162,11 +166,14 @@ string Method::wrapper_fragment(FileWriter& wrapperFile,
// call method and wrap result // call method and wrap result
// example: out[0]=wrap<bool>(self->return_field(t)); // example: out[0]=wrap<bool>(self->return_field(t));
string expanded = "obj->" + name;
if (!instName.empty())
expanded += ("<" + instName.qualifiedName("::") + ">");
expanded += ("(" + args.names() + ")");
if (returnVal.type1.name != "void") if (returnVal.type1.name != "void")
returnVal.wrap_result("obj->" + name + "(" + args.names() + ")", returnVal.wrap_result(expanded, wrapperFile, typeAttributes);
wrapperFile, typeAttributes);
else else
wrapperFile.oss << " obj->" + name + "(" + args.names() + ");\n"; wrapperFile.oss << " " + expanded + ";\n";
// finish // finish
wrapperFile.oss << "}\n"; wrapperFile.oss << "}\n";

View File

@ -41,12 +41,14 @@ struct Method {
std::string name; std::string name;
std::vector<ArgumentList> argLists; std::vector<ArgumentList> argLists;
std::vector<ReturnValue> returnVals; std::vector<ReturnValue> returnVals;
std::vector<Qualified> templateArgValues; ///< value of template argument if applicable
// The first time this function is called, it initializes the class members // The first time this function is called, it initializes the class members
// with those in rhs, but in subsequent calls it adds additional argument // with those in rhs, but in subsequent calls it adds additional argument
// lists as function overloads. // lists as function overloads.
void addOverload(bool verbose, bool is_const, const std::string& name, void addOverload(bool verbose, bool is_const, const std::string& name,
const ArgumentList& args, const ReturnValue& retVal); const ArgumentList& args, const ReturnValue& retVal,
const Qualified& instName = Qualified());
// MATLAB code generation // MATLAB code generation
// classPath is class directory, e.g., ../matlab/@Point2 // classPath is class directory, e.g., ../matlab/@Point2
@ -57,9 +59,12 @@ struct Method {
std::vector<std::string>& functionNames) const; std::vector<std::string>& functionNames) const;
private: private:
/// Emit C++ code
std::string wrapper_fragment(FileWriter& wrapperFile, std::string wrapper_fragment(FileWriter& wrapperFile,
const std::string& cppClassName, const std::string& matlabUniqueName, const std::string& cppClassName, const std::string& matlabUniqueName,
int overload, int id, const TypeAttributesTable& typeAttributes) const; ///< cpp wrapper int overload, int id, const TypeAttributesTable& typeAttributes,
const Qualified& instName) const; ///< cpp wrapper
}; };
} // \namespace wrap } // \namespace wrap

View File

@ -7,13 +7,13 @@
%-------Methods------- %-------Methods-------
%accept_T(Point2 value) : returns void %accept_T(Point2 value) : returns void
%accept_Tptr(Point2 value) : returns void %accept_Tptr(Point2 value) : returns void
%create_MixedPtrs() : returns pair< Point2, Point2 > %create_MixedPtrs() : returns pair< gtsam::Point2, gtsam::Point2 >
%create_ptrs() : returns pair< Point2, Point2 > %create_ptrs() : returns pair< gtsam::Point2, gtsam::Point2 >
%return_T(Point2 value) : returns Point2 %return_T(Point2 value) : returns gtsam::Point2
%return_Tptr(Point2 value) : returns Point2 %return_Tptr(Point2 value) : returns gtsam::Point2
%return_ptrs(Point2 p1, Point2 p2) : returns pair< Point2, Point2 > %return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, gtsam::Point2 >
%templatedMethodPoint2(Point2 t) : returns void %templatedMethod(Point2 t) : returns void
%templatedMethodPoint3(Point3 t) : returns void %templatedMethod(Point3 t) : returns void
% %
classdef MyTemplatePoint2 < MyBase classdef MyTemplatePoint2 < MyBase
properties properties
@ -48,7 +48,7 @@ classdef MyTemplatePoint2 < MyBase
function varargout = accept_T(this, varargin) function varargout = accept_T(this, varargin)
% ACCEPT_T usage: accept_T(Point2 value) : returns void % ACCEPT_T usage: accept_T(Point2 value) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point2') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
geometry_wrapper(47, this, varargin{:}); geometry_wrapper(47, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint2.accept_T'); error('Arguments do not match any overload of function MyTemplatePoint2.accept_T');
@ -58,7 +58,7 @@ classdef MyTemplatePoint2 < MyBase
function varargout = accept_Tptr(this, varargin) function varargout = accept_Tptr(this, varargin)
% ACCEPT_TPTR usage: accept_Tptr(Point2 value) : returns void % ACCEPT_TPTR usage: accept_Tptr(Point2 value) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point2') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
geometry_wrapper(48, this, varargin{:}); geometry_wrapper(48, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr'); error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr');
@ -66,21 +66,21 @@ classdef MyTemplatePoint2 < MyBase
end end
function varargout = create_MixedPtrs(this, varargin) function varargout = create_MixedPtrs(this, varargin)
% CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Point2, Point2 > % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point2, 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
[ varargout{1} varargout{2} ] = geometry_wrapper(49, this, varargin{:}); [ varargout{1} varargout{2} ] = geometry_wrapper(49, this, varargin{:});
end end
function varargout = create_ptrs(this, varargin) function varargout = create_ptrs(this, varargin)
% CREATE_PTRS usage: create_ptrs() : returns pair< Point2, Point2 > % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point2, 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
[ varargout{1} varargout{2} ] = geometry_wrapper(50, this, varargin{:}); [ varargout{1} varargout{2} ] = geometry_wrapper(50, this, varargin{:});
end end
function varargout = return_T(this, varargin) function varargout = return_T(this, varargin)
% RETURN_T usage: return_T(Point2 value) : returns Point2 % RETURN_T usage: return_T(Point2 value) : 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},'Point2') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
varargout{1} = geometry_wrapper(51, this, varargin{:}); varargout{1} = geometry_wrapper(51, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); error('Arguments do not match any overload of function MyTemplatePoint2.return_T');
@ -88,9 +88,9 @@ classdef MyTemplatePoint2 < MyBase
end end
function varargout = return_Tptr(this, varargin) function varargout = return_Tptr(this, varargin)
% RETURN_TPTR usage: return_Tptr(Point2 value) : returns Point2 % RETURN_TPTR usage: return_Tptr(Point2 value) : 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},'Point2') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
varargout{1} = geometry_wrapper(52, this, varargin{:}); varargout{1} = geometry_wrapper(52, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr');
@ -98,32 +98,28 @@ classdef MyTemplatePoint2 < MyBase
end end
function varargout = return_ptrs(this, varargin) function varargout = return_ptrs(this, varargin)
% RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< Point2, Point2 > % RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< gtsam::Point2, 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) == 2 && isa(varargin{1},'Point2') && isa(varargin{2},'Point2') if length(varargin) == 2 && isa(varargin{1},'gtsam.Point2') && isa(varargin{2},'gtsam.Point2')
[ varargout{1} varargout{2} ] = geometry_wrapper(53, this, varargin{:}); [ varargout{1} varargout{2} ] = geometry_wrapper(53, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs'); error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs');
end end
end end
function varargout = templatedMethodPoint2(this, varargin) function varargout = templatedMethod(this, varargin)
% TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % TEMPLATEDMETHOD usage: templatedMethod(Point2 t), templatedMethod(Point3 t) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point2') %
% Method Overloads
% templatedMethod(Point2 t)
% templatedMethod(Point3 t)
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
geometry_wrapper(54, this, varargin{:}); geometry_wrapper(54, this, varargin{:});
else elseif length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodPoint2');
end
end
function varargout = templatedMethodPoint3(this, varargin)
% TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point3')
geometry_wrapper(55, this, varargin{:}); geometry_wrapper(55, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodPoint3'); error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod');
end end
end end

View File

@ -7,13 +7,13 @@
%-------Methods------- %-------Methods-------
%accept_T(Point3 value) : returns void %accept_T(Point3 value) : returns void
%accept_Tptr(Point3 value) : returns void %accept_Tptr(Point3 value) : returns void
%create_MixedPtrs() : returns pair< Point3, Point3 > %create_MixedPtrs() : returns pair< gtsam::Point3, gtsam::Point3 >
%create_ptrs() : returns pair< Point3, Point3 > %create_ptrs() : returns pair< gtsam::Point3, gtsam::Point3 >
%return_T(Point3 value) : returns Point3 %return_T(Point3 value) : returns gtsam::Point3
%return_Tptr(Point3 value) : returns Point3 %return_Tptr(Point3 value) : returns gtsam::Point3
%return_ptrs(Point3 p1, Point3 p2) : returns pair< Point3, Point3 > %return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, gtsam::Point3 >
%templatedMethodPoint2(Point2 t) : returns void %templatedMethod(Point2 t) : returns void
%templatedMethodPoint3(Point3 t) : returns void %templatedMethod(Point3 t) : returns void
% %
classdef MyTemplatePoint3 < MyBase classdef MyTemplatePoint3 < MyBase
properties properties
@ -48,7 +48,7 @@ classdef MyTemplatePoint3 < MyBase
function varargout = accept_T(this, varargin) function varargout = accept_T(this, varargin)
% ACCEPT_T usage: accept_T(Point3 value) : returns void % ACCEPT_T usage: accept_T(Point3 value) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point3') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
geometry_wrapper(60, this, varargin{:}); geometry_wrapper(60, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint3.accept_T'); error('Arguments do not match any overload of function MyTemplatePoint3.accept_T');
@ -58,7 +58,7 @@ classdef MyTemplatePoint3 < MyBase
function varargout = accept_Tptr(this, varargin) function varargout = accept_Tptr(this, varargin)
% ACCEPT_TPTR usage: accept_Tptr(Point3 value) : returns void % ACCEPT_TPTR usage: accept_Tptr(Point3 value) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point3') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
geometry_wrapper(61, this, varargin{:}); geometry_wrapper(61, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr'); error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr');
@ -66,21 +66,21 @@ classdef MyTemplatePoint3 < MyBase
end end
function varargout = create_MixedPtrs(this, varargin) function varargout = create_MixedPtrs(this, varargin)
% CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Point3, Point3 > % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< gtsam::Point3, 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
[ varargout{1} varargout{2} ] = geometry_wrapper(62, this, varargin{:}); [ varargout{1} varargout{2} ] = geometry_wrapper(62, this, varargin{:});
end end
function varargout = create_ptrs(this, varargin) function varargout = create_ptrs(this, varargin)
% CREATE_PTRS usage: create_ptrs() : returns pair< Point3, Point3 > % CREATE_PTRS usage: create_ptrs() : returns pair< gtsam::Point3, 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
[ varargout{1} varargout{2} ] = geometry_wrapper(63, this, varargin{:}); [ varargout{1} varargout{2} ] = geometry_wrapper(63, this, varargin{:});
end end
function varargout = return_T(this, varargin) function varargout = return_T(this, varargin)
% RETURN_T usage: return_T(Point3 value) : returns Point3 % RETURN_T usage: return_T(Point3 value) : 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},'Point3') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
varargout{1} = geometry_wrapper(64, this, varargin{:}); varargout{1} = geometry_wrapper(64, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint3.return_T'); error('Arguments do not match any overload of function MyTemplatePoint3.return_T');
@ -88,9 +88,9 @@ classdef MyTemplatePoint3 < MyBase
end end
function varargout = return_Tptr(this, varargin) function varargout = return_Tptr(this, varargin)
% RETURN_TPTR usage: return_Tptr(Point3 value) : returns Point3 % RETURN_TPTR usage: return_Tptr(Point3 value) : 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},'Point3') if length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
varargout{1} = geometry_wrapper(65, this, varargin{:}); varargout{1} = geometry_wrapper(65, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr'); error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr');
@ -98,32 +98,28 @@ classdef MyTemplatePoint3 < MyBase
end end
function varargout = return_ptrs(this, varargin) function varargout = return_ptrs(this, varargin)
% RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< Point3, Point3 > % RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< gtsam::Point3, 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) == 2 && isa(varargin{1},'Point3') && isa(varargin{2},'Point3') if length(varargin) == 2 && isa(varargin{1},'gtsam.Point3') && isa(varargin{2},'gtsam.Point3')
[ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:}); [ varargout{1} varargout{2} ] = geometry_wrapper(66, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs'); error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs');
end end
end end
function varargout = templatedMethodPoint2(this, varargin) function varargout = templatedMethod(this, varargin)
% TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns void % TEMPLATEDMETHOD usage: templatedMethod(Point2 t), templatedMethod(Point3 t) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point2') %
% Method Overloads
% templatedMethod(Point2 t)
% templatedMethod(Point3 t)
if length(varargin) == 1 && isa(varargin{1},'gtsam.Point2')
geometry_wrapper(67, this, varargin{:}); geometry_wrapper(67, this, varargin{:});
else elseif length(varargin) == 1 && isa(varargin{1},'gtsam.Point3')
error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethodPoint2');
end
end
function varargout = templatedMethodPoint3(this, varargin)
% TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'Point3')
geometry_wrapper(68, this, varargin{:}); geometry_wrapper(68, this, varargin{:});
else else
error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethodPoint3'); error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod');
end end
end end

View File

@ -1,90 +0,0 @@
%class Point2, see Doxygen page for details
%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
%
%-------Constructors-------
%Point2()
%Point2(double x, double y)
%
%-------Methods-------
%argChar(char a) : returns void
%argUChar(unsigned char a) : returns void
%dim() : returns int
%returnChar() : returns char
%vectorConfusion() : returns VectorNotEigen
%x() : returns double
%y() : returns double
%
classdef Point2 < handle
properties
ptr_Point2 = 0
end
methods
function obj = Point2(varargin)
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
my_ptr = varargin{2};
geometry_wrapper(0, my_ptr);
elseif nargin == 0
my_ptr = geometry_wrapper(1);
elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double')
my_ptr = geometry_wrapper(2, varargin{1}, varargin{2});
else
error('Arguments do not match any overload of Point2 constructor');
end
obj.ptr_Point2 = my_ptr;
end
function delete(obj)
geometry_wrapper(3, obj.ptr_Point2);
end
function display(obj), obj.print(''); end
%DISPLAY Calls print on the object
function disp(obj), obj.display; end
%DISP Calls print on the object
function varargout = argChar(this, varargin)
% ARGCHAR usage: argChar(char a) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
geometry_wrapper(4, this, varargin{:});
end
function varargout = argUChar(this, varargin)
% ARGUCHAR usage: argUChar(unsigned char a) : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
geometry_wrapper(5, this, varargin{:});
end
function varargout = dim(this, varargin)
% DIM usage: dim() : returns int
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
varargout{1} = geometry_wrapper(6, this, varargin{:});
end
function varargout = returnChar(this, varargin)
% RETURNCHAR usage: returnChar() : returns char
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
varargout{1} = geometry_wrapper(7, this, varargin{:});
end
function varargout = vectorConfusion(this, varargin)
% VECTORCONFUSION usage: vectorConfusion() : returns VectorNotEigen
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
varargout{1} = geometry_wrapper(8, this, varargin{:});
end
function varargout = x(this, varargin)
% X usage: x() : returns double
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
varargout{1} = geometry_wrapper(9, this, varargin{:});
end
function varargout = y(this, varargin)
% Y usage: y() : returns double
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
varargout{1} = geometry_wrapper(10, this, varargin{:});
end
end
methods(Static = true)
end
end

View File

@ -1,75 +0,0 @@
%class Point3, see Doxygen page for details
%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
%
%-------Constructors-------
%Point3(double x, double y, double z)
%
%-------Methods-------
%norm() : returns double
%
%-------Static Methods-------
%StaticFunctionRet(double z) : returns Point3
%staticFunction() : returns double
%
classdef Point3 < handle
properties
ptr_Point3 = 0
end
methods
function obj = Point3(varargin)
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
my_ptr = varargin{2};
geometry_wrapper(11, my_ptr);
elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double')
my_ptr = geometry_wrapper(12, varargin{1}, varargin{2}, varargin{3});
else
error('Arguments do not match any overload of Point3 constructor');
end
obj.ptr_Point3 = my_ptr;
end
function delete(obj)
geometry_wrapper(13, obj.ptr_Point3);
end
function display(obj), obj.print(''); end
%DISPLAY Calls print on the object
function disp(obj), obj.display; end
%DISP Calls print on the object
function varargout = norm(this, varargin)
% NORM usage: norm() : returns double
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
varargout{1} = geometry_wrapper(14, this, varargin{:});
end
end
methods(Static = true)
function varargout = StaticFunctionRet(varargin)
% STATICFUNCTIONRET usage: StaticFunctionRet(double z) : returns Point3
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
%
% Usage
% STATICFUNCTIONRET(double z)
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(15, varargin{:});
else
error('Arguments do not match any overload of function Point3.StaticFunctionRet');
end
end
function varargout = StaticFunction(varargin)
% STATICFUNCTION usage: staticFunction() : returns double
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
%
% Usage
% STATICFUNCTION()
if length(varargin) == 0
varargout{1} = geometry_wrapper(16, varargin{:});
else
error('Arguments do not match any overload of function Point3.StaticFunction');
end
end
end
end

View File

@ -10,7 +10,7 @@
%create_MixedPtrs() : returns pair< Test, Test > %create_MixedPtrs() : returns pair< Test, Test >
%create_ptrs() : returns pair< Test, Test > %create_ptrs() : returns pair< Test, Test >
%print() : returns void %print() : returns void
%return_Point2Ptr(bool value) : returns Point2 %return_Point2Ptr(bool value) : returns gtsam::Point2
%return_Test(Test value) : returns Test %return_Test(Test value) : returns Test
%return_TestPtr(Test value) : returns Test %return_TestPtr(Test value) : returns Test
%return_bool(bool value) : returns bool %return_bool(bool value) : returns bool
@ -82,7 +82,7 @@ classdef Test < handle
end end
function varargout = return_Point2Ptr(this, varargin) function varargout = return_Point2Ptr(this, varargin)
% RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns Point2 % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : 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
varargout{1} = geometry_wrapper(25, this, varargin{:}); varargout{1} = geometry_wrapper(25, this, varargin{:});
end end

View File

@ -4,14 +4,14 @@
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
typedef MyTemplate<Point2> MyTemplatePoint2; typedef MyTemplate<gtsam::Point2> MyTemplatePoint2;
typedef MyTemplate<Point3> MyTemplatePoint3; typedef MyTemplate<gtsam::Point3> MyTemplatePoint3;
typedef MyFactor<gtsam::Pose2, gtsam::Point2> MyFactorPosePoint2; typedef MyFactor<gtsam::Pose2, gtsam::Point2> MyFactorPosePoint2;
typedef std::set<boost::shared_ptr<Point2>*> Collector_Point2; typedef std::set<boost::shared_ptr<gtsam::Point2>*> Collector_gtsamPoint2;
static Collector_Point2 collector_Point2; static Collector_gtsamPoint2 collector_gtsamPoint2;
typedef std::set<boost::shared_ptr<Point3>*> Collector_Point3; typedef std::set<boost::shared_ptr<gtsam::Point3>*> Collector_gtsamPoint3;
static Collector_Point3 collector_Point3; static Collector_gtsamPoint3 collector_gtsamPoint3;
typedef std::set<boost::shared_ptr<Test>*> Collector_Test; typedef std::set<boost::shared_ptr<Test>*> Collector_Test;
static Collector_Test collector_Test; static Collector_Test collector_Test;
typedef std::set<boost::shared_ptr<MyBase>*> Collector_MyBase; typedef std::set<boost::shared_ptr<MyBase>*> Collector_MyBase;
@ -29,16 +29,16 @@ void _deleteAllObjects()
std::streambuf *outbuf = std::cout.rdbuf(&mout); std::streambuf *outbuf = std::cout.rdbuf(&mout);
bool anyDeleted = false; bool anyDeleted = false;
{ for(Collector_Point2::iterator iter = collector_Point2.begin(); { for(Collector_gtsamPoint2::iterator iter = collector_gtsamPoint2.begin();
iter != collector_Point2.end(); ) { iter != collector_gtsamPoint2.end(); ) {
delete *iter; delete *iter;
collector_Point2.erase(iter++); collector_gtsamPoint2.erase(iter++);
anyDeleted = true; anyDeleted = true;
} } } }
{ for(Collector_Point3::iterator iter = collector_Point3.begin(); { for(Collector_gtsamPoint3::iterator iter = collector_gtsamPoint3.begin();
iter != collector_Point3.end(); ) { iter != collector_gtsamPoint3.end(); ) {
delete *iter; delete *iter;
collector_Point3.erase(iter++); collector_gtsamPoint3.erase(iter++);
anyDeleted = true; anyDeleted = true;
} } } }
{ for(Collector_Test::iterator iter = collector_Test.begin(); { for(Collector_Test::iterator iter = collector_Test.begin();
@ -109,169 +109,169 @@ void _geometry_RTTIRegister() {
} }
} }
void Point2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
mexAtExit(&_deleteAllObjects); mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0])); Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
collector_Point2.insert(self); collector_gtsamPoint2.insert(self);
} }
void Point2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
mexAtExit(&_deleteAllObjects); mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
Shared *self = new Shared(new Point2()); Shared *self = new Shared(new gtsam::Point2());
collector_Point2.insert(self); collector_gtsamPoint2.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self; *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
} }
void Point2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
mexAtExit(&_deleteAllObjects); mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
double x = unwrap< double >(in[0]); double x = unwrap< double >(in[0]);
double y = unwrap< double >(in[1]); double y = unwrap< double >(in[1]);
Shared *self = new Shared(new Point2(x,y)); Shared *self = new Shared(new gtsam::Point2(x,y));
collector_Point2.insert(self); collector_gtsamPoint2.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self; *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
} }
void Point2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("delete_Point2",nargout,nargin,1); checkArguments("delete_gtsamPoint2",nargout,nargin,1);
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0])); Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
Collector_Point2::iterator item; Collector_gtsamPoint2::iterator item;
item = collector_Point2.find(self); item = collector_gtsamPoint2.find(self);
if(item != collector_Point2.end()) { if(item != collector_gtsamPoint2.end()) {
delete self; delete self;
collector_Point2.erase(item); collector_gtsamPoint2.erase(item);
} }
} }
void Point2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("argChar",nargout,nargin-1,1); checkArguments("argChar",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "ptr_Point2"); Shared obj = unwrap_shared_ptr<gtsam::Point2>(in[0], "ptr_gtsamPoint2");
char a = unwrap< char >(in[1]); char a = unwrap< char >(in[1]);
obj->argChar(a); obj->argChar(a);
} }
void Point2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("argUChar",nargout,nargin-1,1); checkArguments("argUChar",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "ptr_Point2"); Shared obj = unwrap_shared_ptr<gtsam::Point2>(in[0], "ptr_gtsamPoint2");
unsigned char a = unwrap< unsigned char >(in[1]); unsigned char a = unwrap< unsigned char >(in[1]);
obj->argUChar(a); obj->argUChar(a);
} }
void Point2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("dim",nargout,nargin-1,0); checkArguments("dim",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "ptr_Point2"); Shared obj = unwrap_shared_ptr<gtsam::Point2>(in[0], "ptr_gtsamPoint2");
out[0] = wrap< int >(obj->dim()); out[0] = wrap< int >(obj->dim());
} }
void Point2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_returnChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("returnChar",nargout,nargin-1,0); checkArguments("returnChar",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "ptr_Point2"); Shared obj = unwrap_shared_ptr<gtsam::Point2>(in[0], "ptr_gtsamPoint2");
out[0] = wrap< char >(obj->returnChar()); out[0] = wrap< char >(obj->returnChar());
} }
void Point2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_vectorConfusion_8(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<VectorNotEigen> SharedVectorNotEigen; typedef boost::shared_ptr<VectorNotEigen> SharedVectorNotEigen;
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("vectorConfusion",nargout,nargin-1,0); checkArguments("vectorConfusion",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "ptr_Point2"); Shared obj = unwrap_shared_ptr<gtsam::Point2>(in[0], "ptr_gtsamPoint2");
out[0] = wrap_shared_ptr(SharedVectorNotEigen(new VectorNotEigen(obj->vectorConfusion())),"VectorNotEigen", false); out[0] = wrap_shared_ptr(SharedVectorNotEigen(new VectorNotEigen(obj->vectorConfusion())),"VectorNotEigen", false);
} }
void Point2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_x_9(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("x",nargout,nargin-1,0); checkArguments("x",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "ptr_Point2"); Shared obj = unwrap_shared_ptr<gtsam::Point2>(in[0], "ptr_gtsamPoint2");
out[0] = wrap< double >(obj->x()); out[0] = wrap< double >(obj->x());
} }
void Point2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint2_y_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> Shared; typedef boost::shared_ptr<gtsam::Point2> Shared;
checkArguments("y",nargout,nargin-1,0); checkArguments("y",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point2>(in[0], "ptr_Point2"); Shared obj = unwrap_shared_ptr<gtsam::Point2>(in[0], "ptr_gtsamPoint2");
out[0] = wrap< double >(obj->y()); out[0] = wrap< double >(obj->y());
} }
void Point3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint3_collectorInsertAndMakeBase_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
mexAtExit(&_deleteAllObjects); mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point3> Shared; typedef boost::shared_ptr<gtsam::Point3> Shared;
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0])); Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
collector_Point3.insert(self); collector_gtsamPoint3.insert(self);
} }
void Point3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint3_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
mexAtExit(&_deleteAllObjects); mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<Point3> Shared; typedef boost::shared_ptr<gtsam::Point3> Shared;
double x = unwrap< double >(in[0]); double x = unwrap< double >(in[0]);
double y = unwrap< double >(in[1]); double y = unwrap< double >(in[1]);
double z = unwrap< double >(in[2]); double z = unwrap< double >(in[2]);
Shared *self = new Shared(new Point3(x,y,z)); Shared *self = new Shared(new gtsam::Point3(x,y,z));
collector_Point3.insert(self); collector_gtsamPoint3.insert(self);
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self; *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
} }
void Point3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint3_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> Shared; typedef boost::shared_ptr<gtsam::Point3> Shared;
checkArguments("delete_Point3",nargout,nargin,1); checkArguments("delete_gtsamPoint3",nargout,nargin,1);
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0])); Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
Collector_Point3::iterator item; Collector_gtsamPoint3::iterator item;
item = collector_Point3.find(self); item = collector_gtsamPoint3.find(self);
if(item != collector_Point3.end()) { if(item != collector_gtsamPoint3.end()) {
delete self; delete self;
collector_Point3.erase(item); collector_gtsamPoint3.erase(item);
} }
} }
void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> Shared; typedef boost::shared_ptr<gtsam::Point3> Shared;
checkArguments("norm",nargout,nargin-1,0); checkArguments("norm",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<Point3>(in[0], "ptr_Point3"); Shared obj = unwrap_shared_ptr<gtsam::Point3>(in[0], "ptr_gtsamPoint3");
out[0] = wrap< double >(obj->norm()); out[0] = wrap< double >(obj->norm());
} }
void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> Shared; typedef boost::shared_ptr<gtsam::Point3> Shared;
checkArguments("Point3.StaticFunctionRet",nargout,nargin,1); checkArguments("gtsamPoint3.StaticFunctionRet",nargout,nargin,1);
double z = unwrap< double >(in[0]); double z = unwrap< double >(in[0]);
out[0] = wrap_shared_ptr(SharedPoint3(new Point3(Point3::StaticFunctionRet(z))),"Point3", false); out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(gtsam::Point3::StaticFunctionRet(z))),"gtsam.Point3", false);
} }
void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void gtsamPoint3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> Shared; typedef boost::shared_ptr<gtsam::Point3> Shared;
checkArguments("Point3.staticFunction",nargout,nargin,0); checkArguments("gtsamPoint3.staticFunction",nargout,nargin,0);
out[0] = wrap< double >(Point3::staticFunction()); out[0] = wrap< double >(gtsam::Point3::staticFunction());
} }
void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -363,12 +363,12 @@ void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<Test> Shared; typedef boost::shared_ptr<Test> Shared;
checkArguments("return_Point2Ptr",nargout,nargin-1,1); checkArguments("return_Point2Ptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test"); Shared obj = unwrap_shared_ptr<Test>(in[0], "ptr_Test");
bool value = unwrap< bool >(in[1]); bool value = unwrap< bool >(in[1]);
out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"Point2", false); out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"gtsam.Point2", false);
} }
void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -593,7 +593,7 @@ void MyTemplatePoint2_accept_T_47(int nargout, mxArray *out[], int nargin, const
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("accept_T",nargout,nargin-1,1); checkArguments("accept_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Point2& value = *unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2"); gtsam::Point2& value = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
obj->accept_T(value); obj->accept_T(value);
} }
@ -602,84 +602,83 @@ void MyTemplatePoint2_accept_Tptr_48(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("accept_Tptr",nargout,nargin-1,1); checkArguments("accept_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
boost::shared_ptr<Point2> value = unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2"); boost::shared_ptr<gtsam::Point2> value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
obj->accept_Tptr(value); obj->accept_Tptr(value);
} }
void MyTemplatePoint2_create_MixedPtrs_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_create_MixedPtrs_49(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("create_MixedPtrs",nargout,nargin-1,0); checkArguments("create_MixedPtrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
pair< Point2, SharedPoint2 > pairResult = obj->create_MixedPtrs(); pair< gtsam::Point2, SharedPoint2 > pairResult = obj->create_MixedPtrs();
out[0] = wrap_shared_ptr(SharedPoint2(new Point2(pairResult.first)),"Point2", false); out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(pairResult.first)),"gtsam.Point2", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point2", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false);
} }
void MyTemplatePoint2_create_ptrs_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_create_ptrs_50(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("create_ptrs",nargout,nargin-1,0); checkArguments("create_ptrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
pair< SharedPoint2, SharedPoint2 > pairResult = obj->create_ptrs(); pair< SharedPoint2, SharedPoint2 > pairResult = obj->create_ptrs();
out[0] = wrap_shared_ptr(pairResult.first,"Point2", false); out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point2", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false);
} }
void MyTemplatePoint2_return_T_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_return_T_51(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("return_T",nargout,nargin-1,1); checkArguments("return_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
boost::shared_ptr<Point2> value = unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2"); boost::shared_ptr<gtsam::Point2> value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
out[0] = wrap_shared_ptr(SharedPoint2(new Point2(obj->return_T(value))),"Point2", false); out[0] = wrap_shared_ptr(SharedPoint2(new gtsam::Point2(obj->return_T(value))),"gtsam.Point2", false);
} }
void MyTemplatePoint2_return_Tptr_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_return_Tptr_52(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("return_Tptr",nargout,nargin-1,1); checkArguments("return_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
boost::shared_ptr<Point2> value = unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2"); boost::shared_ptr<gtsam::Point2> value = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
out[0] = wrap_shared_ptr(obj->return_Tptr(value),"Point2", false); out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point2", false);
} }
void MyTemplatePoint2_return_ptrs_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_return_ptrs_53(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<Point2> SharedPoint2; typedef boost::shared_ptr<gtsam::Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("return_ptrs",nargout,nargin-1,2); checkArguments("return_ptrs",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
boost::shared_ptr<Point2> p1 = unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2"); boost::shared_ptr<gtsam::Point2> p1 = unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
boost::shared_ptr<Point2> p2 = unwrap_shared_ptr< Point2 >(in[2], "ptr_Point2"); boost::shared_ptr<gtsam::Point2> p2 = unwrap_shared_ptr< gtsam::Point2 >(in[2], "ptr_gtsamPoint2");
pair< SharedPoint2, SharedPoint2 > pairResult = obj->return_ptrs(p1,p2); pair< SharedPoint2, SharedPoint2 > pairResult = obj->return_ptrs(p1,p2);
out[0] = wrap_shared_ptr(pairResult.first,"Point2", false); out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point2", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point2", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point2", false);
} }
void MyTemplatePoint2_templatedMethodPoint2_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint2_templatedMethod_54(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("templatedMethodPoint2",nargout,nargin-1,1); checkArguments("templatedMethod",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Point2& t = *unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
obj->templatedMethodPoint2(t); obj->templatedMethod<gtsam::Point2>(t);
} }
void MyTemplatePoint2_templatedMethod_55(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint2_templatedMethodPoint3_55(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<MyTemplatePoint2> Shared; typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("templatedMethodPoint3",nargout,nargin-1,1); checkArguments("templatedMethod",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2"); Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Point3& t = *unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
obj->templatedMethodPoint3(t); obj->templatedMethod<gtsam::Point3>(t);
} }
void MyTemplatePoint3_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -737,7 +736,7 @@ void MyTemplatePoint3_accept_T_60(int nargout, mxArray *out[], int nargin, const
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("accept_T",nargout,nargin-1,1); checkArguments("accept_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
Point3& value = *unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3"); gtsam::Point3& value = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
obj->accept_T(value); obj->accept_T(value);
} }
@ -746,84 +745,83 @@ void MyTemplatePoint3_accept_Tptr_61(int nargout, mxArray *out[], int nargin, co
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("accept_Tptr",nargout,nargin-1,1); checkArguments("accept_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
boost::shared_ptr<Point3> value = unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3"); boost::shared_ptr<gtsam::Point3> value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
obj->accept_Tptr(value); obj->accept_Tptr(value);
} }
void MyTemplatePoint3_create_MixedPtrs_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_create_MixedPtrs_62(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("create_MixedPtrs",nargout,nargin-1,0); checkArguments("create_MixedPtrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
pair< Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs(); pair< gtsam::Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs();
out[0] = wrap_shared_ptr(SharedPoint3(new Point3(pairResult.first)),"Point3", false); out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(pairResult.first)),"gtsam.Point3", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point3", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false);
} }
void MyTemplatePoint3_create_ptrs_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_create_ptrs_63(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("create_ptrs",nargout,nargin-1,0); checkArguments("create_ptrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs(); pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs();
out[0] = wrap_shared_ptr(pairResult.first,"Point3", false); out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point3", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false);
} }
void MyTemplatePoint3_return_T_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_return_T_64(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("return_T",nargout,nargin-1,1); checkArguments("return_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
boost::shared_ptr<Point3> value = unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3"); boost::shared_ptr<gtsam::Point3> value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
out[0] = wrap_shared_ptr(SharedPoint3(new Point3(obj->return_T(value))),"Point3", false); out[0] = wrap_shared_ptr(SharedPoint3(new gtsam::Point3(obj->return_T(value))),"gtsam.Point3", false);
} }
void MyTemplatePoint3_return_Tptr_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_return_Tptr_65(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("return_Tptr",nargout,nargin-1,1); checkArguments("return_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
boost::shared_ptr<Point3> value = unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3"); boost::shared_ptr<gtsam::Point3> value = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
out[0] = wrap_shared_ptr(obj->return_Tptr(value),"Point3", false); out[0] = wrap_shared_ptr(obj->return_Tptr(value),"gtsam.Point3", false);
} }
void MyTemplatePoint3_return_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_return_ptrs_66(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> SharedPoint3; typedef boost::shared_ptr<gtsam::Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("return_ptrs",nargout,nargin-1,2); checkArguments("return_ptrs",nargout,nargin-1,2);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
boost::shared_ptr<Point3> p1 = unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3"); boost::shared_ptr<gtsam::Point3> p1 = unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
boost::shared_ptr<Point3> p2 = unwrap_shared_ptr< Point3 >(in[2], "ptr_Point3"); boost::shared_ptr<gtsam::Point3> p2 = unwrap_shared_ptr< gtsam::Point3 >(in[2], "ptr_gtsamPoint3");
pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2); pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2);
out[0] = wrap_shared_ptr(pairResult.first,"Point3", false); out[0] = wrap_shared_ptr(pairResult.first,"gtsam.Point3", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point3", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Point3", false);
} }
void MyTemplatePoint3_templatedMethodPoint2_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyTemplatePoint3_templatedMethod_67(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("templatedMethodPoint2",nargout,nargin-1,1); checkArguments("templatedMethod",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
Point2& t = *unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2"); gtsam::Point2& t = *unwrap_shared_ptr< gtsam::Point2 >(in[1], "ptr_gtsamPoint2");
obj->templatedMethodPoint2(t); obj->templatedMethod<gtsam::Point2>(t);
} }
void MyTemplatePoint3_templatedMethod_68(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint3_templatedMethodPoint3_68(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{ {
typedef boost::shared_ptr<MyTemplatePoint3> Shared; typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("templatedMethodPoint3",nargout,nargin-1,1); checkArguments("templatedMethod",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3"); Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
Point3& t = *unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3"); gtsam::Point3& t = *unwrap_shared_ptr< gtsam::Point3 >(in[1], "ptr_gtsamPoint3");
obj->templatedMethodPoint3(t); obj->templatedMethod<gtsam::Point3>(t);
} }
void MyFactorPosePoint2_collectorInsertAndMakeBase_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) void MyFactorPosePoint2_collectorInsertAndMakeBase_69(int nargout, mxArray *out[], int nargin, const mxArray *in[])
@ -894,55 +892,55 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
try { try {
switch(id) { switch(id) {
case 0: case 0:
Point2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); gtsamPoint2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1);
break; break;
case 1: case 1:
Point2_constructor_1(nargout, out, nargin-1, in+1); gtsamPoint2_constructor_1(nargout, out, nargin-1, in+1);
break; break;
case 2: case 2:
Point2_constructor_2(nargout, out, nargin-1, in+1); gtsamPoint2_constructor_2(nargout, out, nargin-1, in+1);
break; break;
case 3: case 3:
Point2_deconstructor_3(nargout, out, nargin-1, in+1); gtsamPoint2_deconstructor_3(nargout, out, nargin-1, in+1);
break; break;
case 4: case 4:
Point2_argChar_4(nargout, out, nargin-1, in+1); gtsamPoint2_argChar_4(nargout, out, nargin-1, in+1);
break; break;
case 5: case 5:
Point2_argUChar_5(nargout, out, nargin-1, in+1); gtsamPoint2_argUChar_5(nargout, out, nargin-1, in+1);
break; break;
case 6: case 6:
Point2_dim_6(nargout, out, nargin-1, in+1); gtsamPoint2_dim_6(nargout, out, nargin-1, in+1);
break; break;
case 7: case 7:
Point2_returnChar_7(nargout, out, nargin-1, in+1); gtsamPoint2_returnChar_7(nargout, out, nargin-1, in+1);
break; break;
case 8: case 8:
Point2_vectorConfusion_8(nargout, out, nargin-1, in+1); gtsamPoint2_vectorConfusion_8(nargout, out, nargin-1, in+1);
break; break;
case 9: case 9:
Point2_x_9(nargout, out, nargin-1, in+1); gtsamPoint2_x_9(nargout, out, nargin-1, in+1);
break; break;
case 10: case 10:
Point2_y_10(nargout, out, nargin-1, in+1); gtsamPoint2_y_10(nargout, out, nargin-1, in+1);
break; break;
case 11: case 11:
Point3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1); gtsamPoint3_collectorInsertAndMakeBase_11(nargout, out, nargin-1, in+1);
break; break;
case 12: case 12:
Point3_constructor_12(nargout, out, nargin-1, in+1); gtsamPoint3_constructor_12(nargout, out, nargin-1, in+1);
break; break;
case 13: case 13:
Point3_deconstructor_13(nargout, out, nargin-1, in+1); gtsamPoint3_deconstructor_13(nargout, out, nargin-1, in+1);
break; break;
case 14: case 14:
Point3_norm_14(nargout, out, nargin-1, in+1); gtsamPoint3_norm_14(nargout, out, nargin-1, in+1);
break; break;
case 15: case 15:
Point3_StaticFunctionRet_15(nargout, out, nargin-1, in+1); gtsamPoint3_StaticFunctionRet_15(nargout, out, nargin-1, in+1);
break; break;
case 16: case 16:
Point3_staticFunction_16(nargout, out, nargin-1, in+1); gtsamPoint3_staticFunction_16(nargout, out, nargin-1, in+1);
break; break;
case 17: case 17:
Test_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1); Test_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1);
@ -1056,10 +1054,10 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MyTemplatePoint2_return_ptrs_53(nargout, out, nargin-1, in+1); MyTemplatePoint2_return_ptrs_53(nargout, out, nargin-1, in+1);
break; break;
case 54: case 54:
MyTemplatePoint2_templatedMethodPoint2_54(nargout, out, nargin-1, in+1); MyTemplatePoint2_templatedMethod_54(nargout, out, nargin-1, in+1);
break; break;
case 55: case 55:
MyTemplatePoint2_templatedMethodPoint3_55(nargout, out, nargin-1, in+1); MyTemplatePoint2_templatedMethod_55(nargout, out, nargin-1, in+1);
break; break;
case 56: case 56:
MyTemplatePoint3_collectorInsertAndMakeBase_56(nargout, out, nargin-1, in+1); MyTemplatePoint3_collectorInsertAndMakeBase_56(nargout, out, nargin-1, in+1);
@ -1095,10 +1093,10 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MyTemplatePoint3_return_ptrs_66(nargout, out, nargin-1, in+1); MyTemplatePoint3_return_ptrs_66(nargout, out, nargin-1, in+1);
break; break;
case 67: case 67:
MyTemplatePoint3_templatedMethodPoint2_67(nargout, out, nargin-1, in+1); MyTemplatePoint3_templatedMethod_67(nargout, out, nargin-1, in+1);
break; break;
case 68: case 68:
MyTemplatePoint3_templatedMethodPoint3_68(nargout, out, nargin-1, in+1); MyTemplatePoint3_templatedMethod_68(nargout, out, nargin-1, in+1);
break; break;
case 69: case 69:
MyFactorPosePoint2_collectorInsertAndMakeBase_69(nargout, out, nargin-1, in+1); MyFactorPosePoint2_collectorInsertAndMakeBase_69(nargout, out, nargin-1, in+1);

View File

@ -3,6 +3,8 @@
class VectorNotEigen; class VectorNotEigen;
class ns::OtherClass; class ns::OtherClass;
namespace gtsam {
class Point2 { class Point2 {
Point2(); Point2();
Point2(double x, double y); Point2(double x, double y);
@ -23,12 +25,13 @@ class Point3 {
// static functions - use static keyword and uppercase // static functions - use static keyword and uppercase
static double staticFunction(); static double staticFunction();
static Point3 StaticFunctionRet(double z); static gtsam::Point3 StaticFunctionRet(double z);
// enabling serialization functionality // enabling serialization functionality
void serialize() const; // Just triggers a flag internally and removes actual function void serialize() const; // Just triggers a flag internally and removes actual function
}; };
}
// another comment // another comment
// another comment // another comment
@ -71,7 +74,7 @@ class Test {
Test* return_TestPtr(Test* value) const; Test* return_TestPtr(Test* value) const;
Test return_Test(Test* value) const; Test return_Test(Test* value) const;
Point2* return_Point2Ptr(bool value) const; gtsam::Point2* return_Point2Ptr(bool value) const;
pair<Test*,Test*> create_ptrs () const; pair<Test*,Test*> create_ptrs () const;
pair<Test ,Test*> create_MixedPtrs () const; pair<Test ,Test*> create_MixedPtrs () const;
@ -97,11 +100,11 @@ virtual class MyBase {
}; };
// A templated class // A templated class
template<T = {Point2, Point3}> template<T = {gtsam::Point2, gtsam::Point3}>
virtual class MyTemplate : MyBase { virtual class MyTemplate : MyBase {
MyTemplate(); MyTemplate();
template<ARG = {Point2, Point3}> template<ARG = {gtsam::Point2, gtsam::Point3}>
void templatedMethod(const ARG& t); void templatedMethod(const ARG& t);
// Stress test templates and pointer combinations // Stress test templates and pointer combinations

View File

@ -220,7 +220,7 @@ TEST( wrap, Geometry ) {
} }
EXPECT_LONGS_EQUAL(0, cls.static_methods.size()); EXPECT_LONGS_EQUAL(0, cls.static_methods.size());
EXPECT_LONGS_EQUAL(0, cls.namespaces.size()); EXPECT_LONGS_EQUAL(1, cls.namespaces.size());
#ifndef WRAP_DISABLE_SERIALIZE #ifndef WRAP_DISABLE_SERIALIZE
// check serialization flag // check serialization flag
@ -236,7 +236,7 @@ TEST( wrap, Geometry ) {
EXPECT_LONGS_EQUAL(1, cls.constructor.args_list.size()); EXPECT_LONGS_EQUAL(1, cls.constructor.args_list.size());
EXPECT_LONGS_EQUAL(1, cls.nrMethods()); EXPECT_LONGS_EQUAL(1, cls.nrMethods());
EXPECT_LONGS_EQUAL(2, cls.static_methods.size()); EXPECT_LONGS_EQUAL(2, cls.static_methods.size());
EXPECT_LONGS_EQUAL(0, cls.namespaces.size()); EXPECT_LONGS_EQUAL(1, cls.namespaces.size());
// first constructor takes 3 doubles // first constructor takes 3 doubles
ArgumentList c1 = cls.constructor.args_list.front(); ArgumentList c1 = cls.constructor.args_list.front();
@ -455,8 +455,8 @@ TEST( wrap, matlab_code_geometry ) {
string apath = "actual/"; string apath = "actual/";
EXPECT(files_equal(epath + "geometry_wrapper.cpp" , apath + "geometry_wrapper.cpp" )); EXPECT(files_equal(epath + "geometry_wrapper.cpp" , apath + "geometry_wrapper.cpp" ));
EXPECT(files_equal(epath + "Point2.m" , apath + "Point2.m" )); EXPECT(files_equal(epath + "+gtsam/Point2.m" , apath + "+gtsam/Point2.m" ));
EXPECT(files_equal(epath + "Point3.m" , apath + "Point3.m" )); EXPECT(files_equal(epath + "+gtsam/Point3.m" , apath + "+gtsam/Point3.m" ));
EXPECT(files_equal(epath + "Test.m" , apath + "Test.m" )); EXPECT(files_equal(epath + "Test.m" , apath + "Test.m" ));
EXPECT(files_equal(epath + "MyBase.m" , apath + "MyBase.m" )); EXPECT(files_equal(epath + "MyBase.m" , apath + "MyBase.m" ));
EXPECT(files_equal(epath + "MyTemplatePoint2.m" , apath + "MyTemplatePoint2.m" )); EXPECT(files_equal(epath + "MyTemplatePoint2.m" , apath + "MyTemplatePoint2.m" ));