Handle special case of single overload with all numeric arguments

release/4.3a0
dellaert 2014-05-25 15:21:49 -04:00
parent a38504dc6a
commit 9a102e8c59
5 changed files with 45 additions and 103 deletions

View File

@ -78,28 +78,42 @@ void Method::proxy_wrapper_fragments(FileWriter& file, FileWriter& wrapperFile,
}
}
// Handle special case of single overload with numeric
// Check arguments for all overloads
for (size_t overload = 0; overload < argLists.size(); ++overload) {
// Handle special case of single overload with all numeric arguments
if (argLists.size() == 1 && argLists[0].allScalar()) {
// Output proxy matlab code
file.oss << " " << (overload == 0 ? "" : "else");
file.oss << " ";
const int id = (int) functionNames.size();
argLists[overload].emit_conditional_call(file, returnVals[overload],
wrapperName, id);
argLists[0].emit_call(file, returnVals[0], wrapperName, id);
// Output C++ wrapper code
const string wrapFunctionName = wrapper_fragment(wrapperFile, cppClassName,
matlabUniqueName, overload, id, typeAttributes);
matlabUniqueName, 0, id, typeAttributes);
// Add to function list
functionNames.push_back(wrapFunctionName);
} else {
// Check arguments for all overloads
for (size_t overload = 0; overload < argLists.size(); ++overload) {
// Output proxy matlab code
file.oss << " " << (overload == 0 ? "" : "else");
const int id = (int) functionNames.size();
argLists[overload].emit_conditional_call(file, returnVals[overload],
wrapperName, id);
// Output C++ wrapper code
const string wrapFunctionName = wrapper_fragment(wrapperFile,
cppClassName, matlabUniqueName, overload, id, typeAttributes);
// Add to function list
functionNames.push_back(wrapFunctionName);
}
file.oss << " else\n";
file.oss
<< " error('Arguments do not match any overload of function "
<< matlabQualName << "." << name << "');" << endl;
file.oss << " end\n";
}
file.oss << " else\n";
file.oss << " error('Arguments do not match any overload of function "
<< matlabQualName << "." << name << "');" << endl;
file.oss << " end\n";
file.oss << " end\n";
}

View File

@ -44,71 +44,43 @@ classdef Point2 < handle
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
if length(varargin) == 1 && isa(varargin{1},'char')
geometry_wrapper(4, this, varargin{:});
else
error('Arguments do not match any overload of function Point2.argChar');
end
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
if length(varargin) == 1 && isa(varargin{1},'char')
geometry_wrapper(5, this, varargin{:});
else
error('Arguments do not match any overload of function Point2.argUChar');
end
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
if length(varargin) == 0
varargout{1} = geometry_wrapper(6, this, varargin{:});
else
error('Arguments do not match any overload of function Point2.dim');
end
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
if length(varargin) == 0
varargout{1} = geometry_wrapper(7, this, varargin{:});
else
error('Arguments do not match any overload of function Point2.returnChar');
end
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
if length(varargin) == 0
varargout{1} = geometry_wrapper(8, this, varargin{:});
else
error('Arguments do not match any overload of function Point2.vectorConfusion');
end
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
if length(varargin) == 0
varargout{1} = geometry_wrapper(9, this, varargin{:});
else
error('Arguments do not match any overload of function Point2.x');
end
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
if length(varargin) == 0
varargout{1} = geometry_wrapper(10, this, varargin{:});
else
error('Arguments do not match any overload of function Point2.y');
end
varargout{1} = geometry_wrapper(10, this, varargin{:});
end
end

View File

@ -43,11 +43,7 @@ classdef Point3 < handle
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
if length(varargin) == 0
varargout{1} = geometry_wrapper(14, this, varargin{:});
else
error('Arguments do not match any overload of function Point3.norm');
end
varargout{1} = geometry_wrapper(14, this, varargin{:});
end
function varargout = string_serialize(this, varargin)

View File

@ -66,41 +66,25 @@ classdef Test < handle
function varargout = create_MixedPtrs(this, varargin)
% CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, SharedTest >
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 0
[ varargout{1} varargout{2} ] = geometry_wrapper(24, this, varargin{:});
else
error('Arguments do not match any overload of function Test.create_MixedPtrs');
end
[ varargout{1} varargout{2} ] = geometry_wrapper(24, this, varargin{:});
end
function varargout = create_ptrs(this, varargin)
% CREATE_PTRS usage: create_ptrs() : returns pair< SharedTest, SharedTest >
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 0
[ varargout{1} varargout{2} ] = geometry_wrapper(25, this, varargin{:});
else
error('Arguments do not match any overload of function Test.create_ptrs');
end
[ varargout{1} varargout{2} ] = geometry_wrapper(25, this, varargin{:});
end
function varargout = print(this, varargin)
% PRINT usage: print() : returns void
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 0
geometry_wrapper(26, this, varargin{:});
else
error('Arguments do not match any overload of function Test.print');
end
geometry_wrapper(26, this, varargin{:});
end
function varargout = return_Point2Ptr(this, varargin)
% RETURN_POINT2PTR usage: return_Point2Ptr(bool 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},'logical')
varargout{1} = geometry_wrapper(27, this, varargin{:});
else
error('Arguments do not match any overload of function Test.return_Point2Ptr');
end
varargout{1} = geometry_wrapper(27, this, varargin{:});
end
function varargout = return_Test(this, varargin)
@ -126,21 +110,13 @@ classdef Test < handle
function varargout = return_bool(this, varargin)
% RETURN_BOOL usage: return_bool(bool value) : returns bool
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'logical')
varargout{1} = geometry_wrapper(30, this, varargin{:});
else
error('Arguments do not match any overload of function Test.return_bool');
end
varargout{1} = geometry_wrapper(30, this, varargin{:});
end
function varargout = return_double(this, varargin)
% RETURN_DOUBLE usage: return_double(double value) : returns double
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = geometry_wrapper(31, this, varargin{:});
else
error('Arguments do not match any overload of function Test.return_double');
end
varargout{1} = geometry_wrapper(31, this, varargin{:});
end
function varargout = return_field(this, varargin)
@ -156,11 +132,7 @@ classdef Test < handle
function varargout = return_int(this, varargin)
% RETURN_INT usage: return_int(int value) : returns int
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'numeric')
varargout{1} = geometry_wrapper(33, this, varargin{:});
else
error('Arguments do not match any overload of function Test.return_int');
end
varargout{1} = geometry_wrapper(33, this, varargin{:});
end
function varargout = return_matrix1(this, varargin)
@ -206,11 +178,7 @@ classdef Test < handle
function varargout = return_size_t(this, varargin)
% RETURN_SIZE_T usage: return_size_t(size_t value) : returns size_t
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'numeric')
varargout{1} = geometry_wrapper(38, this, varargin{:});
else
error('Arguments do not match any overload of function Test.return_size_t');
end
varargout{1} = geometry_wrapper(38, this, varargin{:});
end
function varargout = return_string(this, varargin)

View File

@ -40,11 +40,7 @@ classdef ClassA < handle
function varargout = memberFunction(this, varargin)
% MEMBERFUNCTION usage: memberFunction() : returns double
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 0
varargout{1} = testNamespaces_wrapper(9, this, varargin{:});
else
error('Arguments do not match any overload of function ns2.ClassA.memberFunction');
end
varargout{1} = testNamespaces_wrapper(9, this, varargin{:});
end
function varargout = nsArg(this, varargin)
@ -60,11 +56,7 @@ classdef ClassA < handle
function varargout = nsReturn(this, varargin)
% NSRETURN usage: nsReturn(double q) : returns ns2::ns3::ClassB
% Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
if length(varargin) == 1 && isa(varargin{1},'double')
varargout{1} = testNamespaces_wrapper(11, this, varargin{:});
else
error('Arguments do not match any overload of function ns2.ClassA.nsReturn');
end
varargout{1} = testNamespaces_wrapper(11, this, varargin{:});
end
end