Fixed issue with templateArgName overloading

release/4.3a0
dellaert 2014-11-12 19:09:30 +01:00
parent 9b9d9a6b54
commit 34a0913125
8 changed files with 384 additions and 40 deletions

View File

@ -65,12 +65,15 @@ typedef rule<BOOST_SPIRIT_CLASSIC_NS::phrase_scanner_t> Rule;
// If a number of template arguments were given, generate a number of expanded
// class names, e.g., PriorFactor -> PriorFactorPose2, and add those classes
static void handle_possible_template(vector<Class>& classes, const Class& cls,
const string& templateArgName, const vector<Qualified>& instantiations) {
if (instantiations.empty()) {
const vector<Qualified>& instantiations) {
if (cls.templateArgs.empty() || instantiations.empty()) {
classes.push_back(cls);
} else {
if (cls.templateArgs.size() != 1)
throw std::runtime_error(
"In-line template instantiations only handle a single template argument");
vector<Class> classInstantiations = //
cls.expandTemplate(templateArgName, instantiations);
cls.expandTemplate(cls.templateArgs.front(), instantiations);
BOOST_FOREACH(const Class& c, classInstantiations)
classes.push_back(c);
}
@ -312,7 +315,7 @@ void Module::parseMarkup(const std::string& data) {
[assign_a(deconstructor.name,cls.name)]
[assign_a(cls.deconstructor, deconstructor)]
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls),
bl::var(templateArgName), bl::var(templateInstantiations))]
bl::var(templateInstantiations))]
[assign_a(deconstructor,deconstructor0)]
[assign_a(constructor, constructor0)]
[assign_a(cls,cls0)]

View File

@ -12,9 +12,9 @@ classdef MyFactorPosePoint2 < handle
function obj = MyFactorPosePoint2(varargin)
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
my_ptr = varargin{2};
geometry_wrapper(53, my_ptr);
geometry_wrapper(67, my_ptr);
elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base')
my_ptr = geometry_wrapper(54, varargin{1}, varargin{2}, varargin{3}, varargin{4});
my_ptr = geometry_wrapper(68, varargin{1}, varargin{2}, varargin{3}, varargin{4});
else
error('Arguments do not match any overload of MyFactorPosePoint2 constructor');
end
@ -22,7 +22,7 @@ classdef MyFactorPosePoint2 < handle
end
function delete(obj)
geometry_wrapper(55, obj.ptr_MyFactorPosePoint2);
geometry_wrapper(69, obj.ptr_MyFactorPosePoint2);
end
function display(obj), obj.print(''); end

View File

@ -5,6 +5,13 @@
%MyTemplatePoint2()
%
%-------Methods-------
%accept_T(Point2 value) : returns void
%accept_Tptr(Point2 value) : returns void
%create_MixedPtrs() : returns pair< Point2, SharedPoint2 >
%create_ptrs() : returns pair< SharedPoint2, SharedPoint2 >
%return_T(Point2 value) : returns Point2
%return_Tptr(Point2 value) : returns Point2
%return_ptrs(Point2 p1, Point2 p2) : returns pair< SharedPoint2, SharedPoint2 >
%templatedMethod(Test t) : returns void
%
classdef MyTemplatePoint2 < MyBase
@ -37,11 +44,73 @@ classdef MyTemplatePoint2 < MyBase
%DISPLAY Calls print on the object
function disp(obj), obj.display; end
%DISP Calls print on the object
function varargout = accept_T(this, varargin)
% 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
if length(varargin) == 1 && isa(varargin{1},'Point2')
geometry_wrapper(47, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint2.accept_T');
end
end
function varargout = accept_Tptr(this, varargin)
% 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
if length(varargin) == 1 && isa(varargin{1},'Point2')
geometry_wrapper(48, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr');
end
end
function varargout = create_MixedPtrs(this, varargin)
% CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Point2, SharedPoint2 >
% 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{:});
end
function varargout = create_ptrs(this, varargin)
% CREATE_PTRS usage: create_ptrs() : returns pair< SharedPoint2, SharedPoint2 >
% 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{:});
end
function varargout = return_T(this, varargin)
% RETURN_T usage: return_T(Point2 value) : returns Point2
% 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')
varargout{1} = geometry_wrapper(51, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint2.return_T');
end
end
function varargout = return_Tptr(this, varargin)
% RETURN_TPTR usage: return_Tptr(Point2 value) : returns Point2
% 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')
varargout{1} = geometry_wrapper(52, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr');
end
end
function varargout = return_ptrs(this, varargin)
% RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< SharedPoint2, SharedPoint2 >
% 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')
[ varargout{1} varargout{2} ] = geometry_wrapper(53, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs');
end
end
function varargout = templatedMethod(this, varargin)
% TEMPLATEDMETHOD usage: templatedMethod(Test 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},'Test')
geometry_wrapper(47, this, varargin{:});
geometry_wrapper(54, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethod');
end

View File

@ -5,6 +5,13 @@
%MyTemplatePoint3()
%
%-------Methods-------
%accept_T(Point3 value) : returns void
%accept_Tptr(Point3 value) : returns void
%create_MixedPtrs() : returns pair< Point3, SharedPoint3 >
%create_ptrs() : returns pair< SharedPoint3, SharedPoint3 >
%return_T(Point3 value) : returns Point3
%return_Tptr(Point3 value) : returns Point3
%return_ptrs(Point3 p1, Point3 p2) : returns pair< SharedPoint3, SharedPoint3 >
%templatedMethod(Test t) : returns void
%
classdef MyTemplatePoint3 < MyBase
@ -17,11 +24,11 @@ classdef MyTemplatePoint3 < MyBase
if nargin == 2
my_ptr = varargin{2};
else
my_ptr = geometry_wrapper(49, varargin{2});
my_ptr = geometry_wrapper(56, varargin{2});
end
base_ptr = geometry_wrapper(48, my_ptr);
base_ptr = geometry_wrapper(55, my_ptr);
elseif nargin == 0
[ my_ptr, base_ptr ] = geometry_wrapper(50);
[ my_ptr, base_ptr ] = geometry_wrapper(57);
else
error('Arguments do not match any overload of MyTemplatePoint3 constructor');
end
@ -30,18 +37,80 @@ classdef MyTemplatePoint3 < MyBase
end
function delete(obj)
geometry_wrapper(51, obj.ptr_MyTemplatePoint3);
geometry_wrapper(58, obj.ptr_MyTemplatePoint3);
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 = accept_T(this, varargin)
% 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
if length(varargin) == 1 && isa(varargin{1},'Point3')
geometry_wrapper(59, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint3.accept_T');
end
end
function varargout = accept_Tptr(this, varargin)
% 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
if length(varargin) == 1 && isa(varargin{1},'Point3')
geometry_wrapper(60, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint3.accept_Tptr');
end
end
function varargout = create_MixedPtrs(this, varargin)
% CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Point3, SharedPoint3 >
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
[ varargout{1} varargout{2} ] = geometry_wrapper(61, this, varargin{:});
end
function varargout = create_ptrs(this, varargin)
% CREATE_PTRS usage: create_ptrs() : returns pair< SharedPoint3, SharedPoint3 >
% 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{:});
end
function varargout = return_T(this, varargin)
% RETURN_T usage: return_T(Point3 value) : returns Point3
% 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')
varargout{1} = geometry_wrapper(63, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint3.return_T');
end
end
function varargout = return_Tptr(this, varargin)
% RETURN_TPTR usage: return_Tptr(Point3 value) : returns Point3
% 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')
varargout{1} = geometry_wrapper(64, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint3.return_Tptr');
end
end
function varargout = return_ptrs(this, varargin)
% RETURN_PTRS usage: return_ptrs(Point3 p1, Point3 p2) : returns pair< SharedPoint3, SharedPoint3 >
% 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')
[ varargout{1} varargout{2} ] = geometry_wrapper(65, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint3.return_ptrs');
end
end
function varargout = templatedMethod(this, varargin)
% TEMPLATEDMETHOD usage: templatedMethod(Test 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},'Test')
geometry_wrapper(52, this, varargin{:});
geometry_wrapper(66, this, varargin{:});
else
error('Arguments do not match any overload of function MyTemplatePoint3.templatedMethod');
end

View File

@ -1,6 +1,6 @@
function varargout = aGlobalFunction(varargin)
if length(varargin) == 0
varargout{1} = geometry_wrapper(56, varargin{:});
varargout{1} = geometry_wrapper(70, varargin{:});
else
error('Arguments do not match any overload of function aGlobalFunction');
end

View File

@ -588,7 +588,83 @@ void MyTemplatePoint2_deconstructor_46(int nargout, mxArray *out[], int nargin,
}
}
void MyTemplatePoint2_templatedMethod_47(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint2_accept_T_47(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("accept_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
Point2& value = *unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2");
obj->accept_T(value);
}
void MyTemplatePoint2_accept_Tptr_48(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("accept_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
boost::shared_ptr<Point2> value = unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2");
obj->accept_Tptr(value);
}
void MyTemplatePoint2_create_MixedPtrs_49(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("create_MixedPtrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
pair< Point2, SharedPoint2 > pairResult = obj->create_MixedPtrs();
out[0] = wrap_shared_ptr(SharedPoint2(new Point2(pairResult.first)),"Point2", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point2", false);
}
void MyTemplatePoint2_create_ptrs_50(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("create_ptrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
pair< SharedPoint2, SharedPoint2 > pairResult = obj->create_ptrs();
out[0] = wrap_shared_ptr(pairResult.first,"Point2", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point2", false);
}
void MyTemplatePoint2_return_T_51(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("return_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
boost::shared_ptr<Point2> value = unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2");
out[0] = wrap_shared_ptr(SharedPoint2(new Point2(obj->return_T(value))),"Point2", false);
}
void MyTemplatePoint2_return_Tptr_52(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("return_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint2>(in[0], "ptr_MyTemplatePoint2");
boost::shared_ptr<Point2> value = unwrap_shared_ptr< Point2 >(in[1], "ptr_Point2");
out[0] = wrap_shared_ptr(obj->return_Tptr(value),"Point2", false);
}
void MyTemplatePoint2_return_ptrs_53(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<Point2> SharedPoint2;
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("return_ptrs",nargout,nargin-1,2);
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<Point2> p2 = unwrap_shared_ptr< Point2 >(in[2], "ptr_Point2");
pair< SharedPoint2, SharedPoint2 > pairResult = obj->return_ptrs(p1,p2);
out[0] = wrap_shared_ptr(pairResult.first,"Point2", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point2", false);
}
void MyTemplatePoint2_templatedMethod_54(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyTemplatePoint2> Shared;
checkArguments("templatedMethod",nargout,nargin-1,1);
@ -597,7 +673,7 @@ void MyTemplatePoint2_templatedMethod_47(int nargout, mxArray *out[], int nargin
obj->templatedMethod(t);
}
void MyTemplatePoint3_collectorInsertAndMakeBase_48(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint3_collectorInsertAndMakeBase_55(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
@ -610,7 +686,7 @@ void MyTemplatePoint3_collectorInsertAndMakeBase_48(int nargout, mxArray *out[],
*reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);
}
void MyTemplatePoint3_upcastFromVoid_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {
void MyTemplatePoint3_upcastFromVoid_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
boost::shared_ptr<void> *asVoid = *reinterpret_cast<boost::shared_ptr<void>**> (mxGetData(in[0]));
@ -619,7 +695,7 @@ void MyTemplatePoint3_upcastFromVoid_49(int nargout, mxArray *out[], int nargin,
*reinterpret_cast<Shared**>(mxGetData(out[0])) = self;
}
void MyTemplatePoint3_constructor_50(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint3_constructor_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
@ -634,7 +710,7 @@ void MyTemplatePoint3_constructor_50(int nargout, mxArray *out[], int nargin, co
*reinterpret_cast<SharedBase**>(mxGetData(out[1])) = new SharedBase(*self);
}
void MyTemplatePoint3_deconstructor_51(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint3_deconstructor_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("delete_MyTemplatePoint3",nargout,nargin,1);
@ -647,7 +723,83 @@ void MyTemplatePoint3_deconstructor_51(int nargout, mxArray *out[], int nargin,
}
}
void MyTemplatePoint3_templatedMethod_52(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint3_accept_T_59(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("accept_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
Point3& value = *unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3");
obj->accept_T(value);
}
void MyTemplatePoint3_accept_Tptr_60(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("accept_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
boost::shared_ptr<Point3> value = unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3");
obj->accept_Tptr(value);
}
void MyTemplatePoint3_create_MixedPtrs_61(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("create_MixedPtrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
pair< Point3, SharedPoint3 > pairResult = obj->create_MixedPtrs();
out[0] = wrap_shared_ptr(SharedPoint3(new Point3(pairResult.first)),"Point3", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point3", false);
}
void MyTemplatePoint3_create_ptrs_62(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("create_ptrs",nargout,nargin-1,0);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
pair< SharedPoint3, SharedPoint3 > pairResult = obj->create_ptrs();
out[0] = wrap_shared_ptr(pairResult.first,"Point3", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point3", false);
}
void MyTemplatePoint3_return_T_63(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("return_T",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
boost::shared_ptr<Point3> value = unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3");
out[0] = wrap_shared_ptr(SharedPoint3(new Point3(obj->return_T(value))),"Point3", false);
}
void MyTemplatePoint3_return_Tptr_64(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("return_Tptr",nargout,nargin-1,1);
Shared obj = unwrap_shared_ptr<MyTemplatePoint3>(in[0], "ptr_MyTemplatePoint3");
boost::shared_ptr<Point3> value = unwrap_shared_ptr< Point3 >(in[1], "ptr_Point3");
out[0] = wrap_shared_ptr(obj->return_Tptr(value),"Point3", false);
}
void MyTemplatePoint3_return_ptrs_65(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<Point3> SharedPoint3;
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("return_ptrs",nargout,nargin-1,2);
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<Point3> p2 = unwrap_shared_ptr< Point3 >(in[2], "ptr_Point3");
pair< SharedPoint3, SharedPoint3 > pairResult = obj->return_ptrs(p1,p2);
out[0] = wrap_shared_ptr(pairResult.first,"Point3", false);
out[1] = wrap_shared_ptr(pairResult.second,"Point3", false);
}
void MyTemplatePoint3_templatedMethod_66(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyTemplatePoint3> Shared;
checkArguments("templatedMethod",nargout,nargin-1,1);
@ -656,7 +808,7 @@ void MyTemplatePoint3_templatedMethod_52(int nargout, mxArray *out[], int nargin
obj->templatedMethod(t);
}
void MyFactorPosePoint2_collectorInsertAndMakeBase_53(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_collectorInsertAndMakeBase_67(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
@ -665,7 +817,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_53(int nargout, mxArray *out[
collector_MyFactorPosePoint2.insert(self);
}
void MyFactorPosePoint2_constructor_54(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_constructor_68(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
mexAtExit(&_deleteAllObjects);
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
@ -680,7 +832,7 @@ void MyFactorPosePoint2_constructor_54(int nargout, mxArray *out[], int nargin,
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
}
void MyFactorPosePoint2_deconstructor_55(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_deconstructor_69(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1);
@ -693,18 +845,18 @@ void MyFactorPosePoint2_deconstructor_55(int nargout, mxArray *out[], int nargin
}
}
void aGlobalFunction_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void aGlobalFunction_70(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("aGlobalFunction",nargout,nargin,0);
out[0] = wrap< Vector >(aGlobalFunction());
}
void overloadedGlobalFunction_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void overloadedGlobalFunction_71(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("overloadedGlobalFunction",nargout,nargin,1);
int a = unwrap< int >(in[0]);
out[0] = wrap< Vector >(overloadedGlobalFunction(a));
}
void overloadedGlobalFunction_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void overloadedGlobalFunction_72(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("overloadedGlobalFunction",nargout,nargin,2);
int a = unwrap< int >(in[0]);
@ -865,40 +1017,82 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MyTemplatePoint2_deconstructor_46(nargout, out, nargin-1, in+1);
break;
case 47:
MyTemplatePoint2_templatedMethod_47(nargout, out, nargin-1, in+1);
MyTemplatePoint2_accept_T_47(nargout, out, nargin-1, in+1);
break;
case 48:
MyTemplatePoint3_collectorInsertAndMakeBase_48(nargout, out, nargin-1, in+1);
MyTemplatePoint2_accept_Tptr_48(nargout, out, nargin-1, in+1);
break;
case 49:
MyTemplatePoint3_upcastFromVoid_49(nargout, out, nargin-1, in+1);
MyTemplatePoint2_create_MixedPtrs_49(nargout, out, nargin-1, in+1);
break;
case 50:
MyTemplatePoint3_constructor_50(nargout, out, nargin-1, in+1);
MyTemplatePoint2_create_ptrs_50(nargout, out, nargin-1, in+1);
break;
case 51:
MyTemplatePoint3_deconstructor_51(nargout, out, nargin-1, in+1);
MyTemplatePoint2_return_T_51(nargout, out, nargin-1, in+1);
break;
case 52:
MyTemplatePoint3_templatedMethod_52(nargout, out, nargin-1, in+1);
MyTemplatePoint2_return_Tptr_52(nargout, out, nargin-1, in+1);
break;
case 53:
MyFactorPosePoint2_collectorInsertAndMakeBase_53(nargout, out, nargin-1, in+1);
MyTemplatePoint2_return_ptrs_53(nargout, out, nargin-1, in+1);
break;
case 54:
MyFactorPosePoint2_constructor_54(nargout, out, nargin-1, in+1);
MyTemplatePoint2_templatedMethod_54(nargout, out, nargin-1, in+1);
break;
case 55:
MyFactorPosePoint2_deconstructor_55(nargout, out, nargin-1, in+1);
MyTemplatePoint3_collectorInsertAndMakeBase_55(nargout, out, nargin-1, in+1);
break;
case 56:
aGlobalFunction_56(nargout, out, nargin-1, in+1);
MyTemplatePoint3_upcastFromVoid_56(nargout, out, nargin-1, in+1);
break;
case 57:
overloadedGlobalFunction_57(nargout, out, nargin-1, in+1);
MyTemplatePoint3_constructor_57(nargout, out, nargin-1, in+1);
break;
case 58:
overloadedGlobalFunction_58(nargout, out, nargin-1, in+1);
MyTemplatePoint3_deconstructor_58(nargout, out, nargin-1, in+1);
break;
case 59:
MyTemplatePoint3_accept_T_59(nargout, out, nargin-1, in+1);
break;
case 60:
MyTemplatePoint3_accept_Tptr_60(nargout, out, nargin-1, in+1);
break;
case 61:
MyTemplatePoint3_create_MixedPtrs_61(nargout, out, nargin-1, in+1);
break;
case 62:
MyTemplatePoint3_create_ptrs_62(nargout, out, nargin-1, in+1);
break;
case 63:
MyTemplatePoint3_return_T_63(nargout, out, nargin-1, in+1);
break;
case 64:
MyTemplatePoint3_return_Tptr_64(nargout, out, nargin-1, in+1);
break;
case 65:
MyTemplatePoint3_return_ptrs_65(nargout, out, nargin-1, in+1);
break;
case 66:
MyTemplatePoint3_templatedMethod_66(nargout, out, nargin-1, in+1);
break;
case 67:
MyFactorPosePoint2_collectorInsertAndMakeBase_67(nargout, out, nargin-1, in+1);
break;
case 68:
MyFactorPosePoint2_constructor_68(nargout, out, nargin-1, in+1);
break;
case 69:
MyFactorPosePoint2_deconstructor_69(nargout, out, nargin-1, in+1);
break;
case 70:
aGlobalFunction_70(nargout, out, nargin-1, in+1);
break;
case 71:
overloadedGlobalFunction_71(nargout, out, nargin-1, in+1);
break;
case 72:
overloadedGlobalFunction_72(nargout, out, nargin-1, in+1);
break;
}
} catch(const std::exception& e) {

View File

@ -1,8 +1,8 @@
function varargout = overloadedGlobalFunction(varargin)
if length(varargin) == 1 && isa(varargin{1},'numeric')
varargout{1} = geometry_wrapper(57, varargin{:});
varargout{1} = geometry_wrapper(71, varargin{:});
elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double')
varargout{1} = geometry_wrapper(58, varargin{:});
varargout{1} = geometry_wrapper(72, varargin{:});
else
error('Arguments do not match any overload of function overloadedGlobalFunction');
end

View File

@ -103,6 +103,15 @@ virtual class MyTemplate : MyBase {
template<ARG = {Point2, Point3}>
void templatedMethod(const Test& t);
// Stress test templates and pointer combinations
void accept_T(const T& value) const;
void accept_Tptr(T* value) const;
T* return_Tptr(T* value) const;
T return_T(T* value) const;
pair<T*,T*> create_ptrs () const;
pair<T ,T*> create_MixedPtrs () const;
pair<T*,T*> return_ptrs (T* p1, T* p2) const;
};
// A doubly templated class