commit
21bbd631ef
|
@ -28,6 +28,7 @@
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
|
#include <sstream>
|
||||||
#include <iterator> // std::ostream_iterator
|
#include <iterator> // std::ostream_iterator
|
||||||
//#include <cstdint> // on Linux GCC: fails with error regarding needing C++0x std flags
|
//#include <cstdint> // on Linux GCC: fails with error regarding needing C++0x std flags
|
||||||
//#include <cinttypes> // same failure as above
|
//#include <cinttypes> // same failure as above
|
||||||
|
@ -314,6 +315,25 @@ vector<Class> Class::expandTemplate(Str templateArg,
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
vector<Class> Class::expandTemplate(Str templateArg,
|
||||||
|
const vector<int>& integers) const {
|
||||||
|
vector<Class> result;
|
||||||
|
BOOST_FOREACH(int i, integers) {
|
||||||
|
Qualified expandedClass = (Qualified) (*this);
|
||||||
|
stringstream ss; ss << i;
|
||||||
|
string instName = ss.str();
|
||||||
|
expandedClass.expand(instName);
|
||||||
|
const TemplateSubstitution ts(templateArg, instName, expandedClass);
|
||||||
|
Class inst = expandTemplate(ts);
|
||||||
|
inst.name_ = expandedClass.name();
|
||||||
|
inst.templateArgs.clear();
|
||||||
|
inst.typedefName = qualifiedName("::") + "<" + instName + ">";
|
||||||
|
result.push_back(inst);
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Class::addMethod(bool verbose, bool is_const, Str methodName,
|
void Class::addMethod(bool verbose, bool is_const, Str methodName,
|
||||||
const ArgumentList& argumentList, const ReturnValue& returnValue,
|
const ArgumentList& argumentList, const ReturnValue& returnValue,
|
||||||
|
|
|
@ -106,6 +106,10 @@ public:
|
||||||
std::vector<Class> expandTemplate(Str templateArg,
|
std::vector<Class> expandTemplate(Str templateArg,
|
||||||
const std::vector<Qualified>& instantiations) const;
|
const std::vector<Qualified>& instantiations) const;
|
||||||
|
|
||||||
|
// Create new classes with integer template arguments
|
||||||
|
std::vector<Class> expandTemplate(Str templateArg,
|
||||||
|
const std::vector<int>& integers) const;
|
||||||
|
|
||||||
/// Add potentially overloaded, potentially templated method
|
/// Add potentially overloaded, potentially templated method
|
||||||
void addMethod(bool verbose, bool is_const, Str methodName,
|
void addMethod(bool verbose, bool is_const, Str methodName,
|
||||||
const ArgumentList& argumentList, const ReturnValue& returnValue,
|
const ArgumentList& argumentList, const ReturnValue& returnValue,
|
||||||
|
|
|
@ -47,15 +47,17 @@ namespace fs = boost::filesystem;
|
||||||
// If a number of template arguments were given, generate a number of expanded
|
// If a number of template arguments were given, generate a number of expanded
|
||||||
// class names, e.g., PriorFactor -> PriorFactorPose2, and add those classes
|
// class names, e.g., PriorFactor -> PriorFactorPose2, and add those classes
|
||||||
static void handle_possible_template(vector<Class>& classes, const Class& cls,
|
static void handle_possible_template(vector<Class>& classes, const Class& cls,
|
||||||
const vector<Qualified>& instantiations) {
|
const Template& t) {
|
||||||
if (cls.templateArgs.empty() || instantiations.empty()) {
|
if (cls.templateArgs.empty() || t.empty()) {
|
||||||
classes.push_back(cls);
|
classes.push_back(cls);
|
||||||
} else {
|
} else {
|
||||||
if (cls.templateArgs.size() != 1)
|
if (cls.templateArgs.size() != 1)
|
||||||
throw std::runtime_error(
|
throw std::runtime_error(
|
||||||
"In-line template instantiations only handle a single template argument");
|
"In-line template instantiations only handle a single template argument");
|
||||||
vector<Class> classInstantiations = //
|
string arg = cls.templateArgs.front();
|
||||||
cls.expandTemplate(cls.templateArgs.front(), instantiations);
|
vector<Class> classInstantiations =
|
||||||
|
(t.nrValues() > 0) ? cls.expandTemplate(arg, t.argValues()) :
|
||||||
|
cls.expandTemplate(arg, t.intList());
|
||||||
BOOST_FOREACH(const Class& c, classInstantiations)
|
BOOST_FOREACH(const Class& c, classInstantiations)
|
||||||
classes.push_back(c);
|
classes.push_back(c);
|
||||||
}
|
}
|
||||||
|
@ -107,7 +109,7 @@ void Module::parseMarkup(const std::string& data) {
|
||||||
Rule class_p = class_g //
|
Rule class_p = class_g //
|
||||||
[assign_a(cls.namespaces_, namespaces)]
|
[assign_a(cls.namespaces_, namespaces)]
|
||||||
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls),
|
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls),
|
||||||
bl::var(classTemplate.argValues()))]
|
bl::var(classTemplate))]
|
||||||
[clear_a(classTemplate)] //
|
[clear_a(classTemplate)] //
|
||||||
[assign_a(cls,cls0)];
|
[assign_a(cls,cls0)];
|
||||||
|
|
||||||
|
|
|
@ -26,6 +26,7 @@ namespace wrap {
|
||||||
class Template {
|
class Template {
|
||||||
std::string argName_;
|
std::string argName_;
|
||||||
std::vector<Qualified> argValues_;
|
std::vector<Qualified> argValues_;
|
||||||
|
std::vector<int> intList_;
|
||||||
friend struct TemplateGrammar;
|
friend struct TemplateGrammar;
|
||||||
public:
|
public:
|
||||||
/// The only way to get values into a Template is via our friendly Grammar
|
/// The only way to get values into a Template is via our friendly Grammar
|
||||||
|
@ -34,13 +35,20 @@ public:
|
||||||
void clear() {
|
void clear() {
|
||||||
argName_.clear();
|
argName_.clear();
|
||||||
argValues_.clear();
|
argValues_.clear();
|
||||||
|
intList_.clear();
|
||||||
}
|
}
|
||||||
const std::string& argName() const {
|
const std::string& argName() const {
|
||||||
return argName_;
|
return argName_;
|
||||||
}
|
}
|
||||||
|
const std::vector<int>& intList() const {
|
||||||
|
return intList_;
|
||||||
|
}
|
||||||
const std::vector<Qualified>& argValues() const {
|
const std::vector<Qualified>& argValues() const {
|
||||||
return argValues_;
|
return argValues_;
|
||||||
}
|
}
|
||||||
|
bool empty() const {
|
||||||
|
return argValues_.empty() && intList_.empty();
|
||||||
|
}
|
||||||
size_t nrValues() const {
|
size_t nrValues() const {
|
||||||
return argValues_.size();
|
return argValues_.size();
|
||||||
}
|
}
|
||||||
|
@ -53,16 +61,52 @@ public:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html
|
||||||
|
struct IntListGrammar: public classic::grammar<IntListGrammar > {
|
||||||
|
|
||||||
|
typedef std::vector<int> IntList;
|
||||||
|
IntList& result_; ///< successful parse will be placed in here
|
||||||
|
|
||||||
|
/// Construct type grammar and specify where result is placed
|
||||||
|
IntListGrammar(IntList& result) :
|
||||||
|
result_(result) {
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Definition of type grammar
|
||||||
|
template<typename ScannerT>
|
||||||
|
struct definition {
|
||||||
|
|
||||||
|
classic::rule<ScannerT> integer_p, intList_p;
|
||||||
|
|
||||||
|
definition(IntListGrammar const& self) {
|
||||||
|
using namespace classic;
|
||||||
|
|
||||||
|
integer_p = int_p[push_back_a(self.result_)];
|
||||||
|
|
||||||
|
intList_p = '{' >> !integer_p >> *(',' >> integer_p) >> '}';
|
||||||
|
}
|
||||||
|
|
||||||
|
classic::rule<ScannerT> const& start() const {
|
||||||
|
return intList_p;
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
};
|
||||||
|
// IntListGrammar
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html
|
// http://boost-spirit.com/distrib/spirit_1_8_2/libs/spirit/doc/grammar.html
|
||||||
struct TemplateGrammar: public classic::grammar<TemplateGrammar> {
|
struct TemplateGrammar: public classic::grammar<TemplateGrammar> {
|
||||||
|
|
||||||
Template& result_; ///< successful parse will be placed in here
|
Template& result_; ///< successful parse will be placed in here
|
||||||
TypeListGrammar<'{', '}'> argValues_g; ///< TypeList parser
|
TypeListGrammar<'{', '}'> argValues_g; ///< TypeList parser
|
||||||
|
IntListGrammar intList_g; ///< TypeList parser
|
||||||
|
|
||||||
/// Construct type grammar and specify where result is placed
|
/// Construct type grammar and specify where result is placed
|
||||||
TemplateGrammar(Template& result) :
|
TemplateGrammar(Template& result) :
|
||||||
result_(result), argValues_g(result.argValues_) {
|
result_(result), argValues_g(result.argValues_), //
|
||||||
|
intList_g(result.intList_) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Definition of type grammar
|
/// Definition of type grammar
|
||||||
|
@ -76,7 +120,7 @@ struct TemplateGrammar: public classic::grammar<TemplateGrammar> {
|
||||||
using classic::assign_a;
|
using classic::assign_a;
|
||||||
templateArgValues_p = (str_p("template") >> '<'
|
templateArgValues_p = (str_p("template") >> '<'
|
||||||
>> (BasicRules<ScannerT>::name_p)[assign_a(self.result_.argName_)]
|
>> (BasicRules<ScannerT>::name_p)[assign_a(self.result_.argName_)]
|
||||||
>> '=' >> self.argValues_g >> '>');
|
>> '=' >> (self.argValues_g | self.intList_g) >> '>');
|
||||||
}
|
}
|
||||||
|
|
||||||
classic::rule<ScannerT> const& start() const {
|
classic::rule<ScannerT> const& start() const {
|
||||||
|
|
|
@ -79,6 +79,14 @@ class_<MyTemplateMatrix>("MyTemplateMatrix")
|
||||||
.def("templatedMethod", &MyTemplateMatrix::templatedMethod);
|
.def("templatedMethod", &MyTemplateMatrix::templatedMethod);
|
||||||
;
|
;
|
||||||
|
|
||||||
|
class_<MyVector3>("MyVector3")
|
||||||
|
.def("MyVector3", &MyVector3::MyVector3);
|
||||||
|
;
|
||||||
|
|
||||||
|
class_<MyVector12>("MyVector12")
|
||||||
|
.def("MyVector12", &MyVector12::MyVector12);
|
||||||
|
;
|
||||||
|
|
||||||
class_<MyFactorPosePoint2>("MyFactorPosePoint2")
|
class_<MyFactorPosePoint2>("MyFactorPosePoint2")
|
||||||
.def("MyFactorPosePoint2", &MyFactorPosePoint2::MyFactorPosePoint2);
|
.def("MyFactorPosePoint2", &MyFactorPosePoint2::MyFactorPosePoint2);
|
||||||
;
|
;
|
||||||
|
|
|
@ -12,9 +12,9 @@ classdef MyFactorPosePoint2 < handle
|
||||||
function obj = MyFactorPosePoint2(varargin)
|
function obj = MyFactorPosePoint2(varargin)
|
||||||
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
||||||
my_ptr = varargin{2};
|
my_ptr = varargin{2};
|
||||||
geometry_wrapper(76, my_ptr);
|
geometry_wrapper(82, my_ptr);
|
||||||
elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base')
|
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(77, varargin{1}, varargin{2}, varargin{3}, varargin{4});
|
my_ptr = geometry_wrapper(83, varargin{1}, varargin{2}, varargin{3}, varargin{4});
|
||||||
else
|
else
|
||||||
error('Arguments do not match any overload of MyFactorPosePoint2 constructor');
|
error('Arguments do not match any overload of MyFactorPosePoint2 constructor');
|
||||||
end
|
end
|
||||||
|
@ -22,7 +22,7 @@ classdef MyFactorPosePoint2 < handle
|
||||||
end
|
end
|
||||||
|
|
||||||
function delete(obj)
|
function delete(obj)
|
||||||
geometry_wrapper(78, obj.ptr_MyFactorPosePoint2);
|
geometry_wrapper(84, obj.ptr_MyFactorPosePoint2);
|
||||||
end
|
end
|
||||||
|
|
||||||
function display(obj), obj.print(''); end
|
function display(obj), obj.print(''); end
|
||||||
|
|
|
@ -0,0 +1,36 @@
|
||||||
|
%class MyVector12, see Doxygen page for details
|
||||||
|
%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
%
|
||||||
|
%-------Constructors-------
|
||||||
|
%MyVector12()
|
||||||
|
%
|
||||||
|
classdef MyVector12 < handle
|
||||||
|
properties
|
||||||
|
ptr_MyVector12 = 0
|
||||||
|
end
|
||||||
|
methods
|
||||||
|
function obj = MyVector12(varargin)
|
||||||
|
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
||||||
|
my_ptr = varargin{2};
|
||||||
|
geometry_wrapper(79, my_ptr);
|
||||||
|
elseif nargin == 0
|
||||||
|
my_ptr = geometry_wrapper(80);
|
||||||
|
else
|
||||||
|
error('Arguments do not match any overload of MyVector12 constructor');
|
||||||
|
end
|
||||||
|
obj.ptr_MyVector12 = my_ptr;
|
||||||
|
end
|
||||||
|
|
||||||
|
function delete(obj)
|
||||||
|
geometry_wrapper(81, obj.ptr_MyVector12);
|
||||||
|
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
|
||||||
|
end
|
||||||
|
|
||||||
|
methods(Static = true)
|
||||||
|
end
|
||||||
|
end
|
|
@ -0,0 +1,36 @@
|
||||||
|
%class MyVector3, see Doxygen page for details
|
||||||
|
%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html
|
||||||
|
%
|
||||||
|
%-------Constructors-------
|
||||||
|
%MyVector3()
|
||||||
|
%
|
||||||
|
classdef MyVector3 < handle
|
||||||
|
properties
|
||||||
|
ptr_MyVector3 = 0
|
||||||
|
end
|
||||||
|
methods
|
||||||
|
function obj = MyVector3(varargin)
|
||||||
|
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
||||||
|
my_ptr = varargin{2};
|
||||||
|
geometry_wrapper(76, my_ptr);
|
||||||
|
elseif nargin == 0
|
||||||
|
my_ptr = geometry_wrapper(77);
|
||||||
|
else
|
||||||
|
error('Arguments do not match any overload of MyVector3 constructor');
|
||||||
|
end
|
||||||
|
obj.ptr_MyVector3 = my_ptr;
|
||||||
|
end
|
||||||
|
|
||||||
|
function delete(obj)
|
||||||
|
geometry_wrapper(78, obj.ptr_MyVector3);
|
||||||
|
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
|
||||||
|
end
|
||||||
|
|
||||||
|
methods(Static = true)
|
||||||
|
end
|
||||||
|
end
|
|
@ -1,6 +1,6 @@
|
||||||
function varargout = aGlobalFunction(varargin)
|
function varargout = aGlobalFunction(varargin)
|
||||||
if length(varargin) == 0
|
if length(varargin) == 0
|
||||||
varargout{1} = geometry_wrapper(79, varargin{:});
|
varargout{1} = geometry_wrapper(85, varargin{:});
|
||||||
else
|
else
|
||||||
error('Arguments do not match any overload of function aGlobalFunction');
|
error('Arguments do not match any overload of function aGlobalFunction');
|
||||||
end
|
end
|
||||||
|
|
|
@ -10,6 +10,8 @@
|
||||||
|
|
||||||
typedef MyTemplate<gtsam::Point2> MyTemplatePoint2;
|
typedef MyTemplate<gtsam::Point2> MyTemplatePoint2;
|
||||||
typedef MyTemplate<Matrix> MyTemplateMatrix;
|
typedef MyTemplate<Matrix> MyTemplateMatrix;
|
||||||
|
typedef MyVector<3> MyVector3;
|
||||||
|
typedef MyVector<12> MyVector12;
|
||||||
typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
||||||
|
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2");
|
BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2");
|
||||||
|
@ -27,6 +29,10 @@ typedef std::set<boost::shared_ptr<MyTemplatePoint2>*> Collector_MyTemplatePoint
|
||||||
static Collector_MyTemplatePoint2 collector_MyTemplatePoint2;
|
static Collector_MyTemplatePoint2 collector_MyTemplatePoint2;
|
||||||
typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix;
|
typedef std::set<boost::shared_ptr<MyTemplateMatrix>*> Collector_MyTemplateMatrix;
|
||||||
static Collector_MyTemplateMatrix collector_MyTemplateMatrix;
|
static Collector_MyTemplateMatrix collector_MyTemplateMatrix;
|
||||||
|
typedef std::set<boost::shared_ptr<MyVector3>*> Collector_MyVector3;
|
||||||
|
static Collector_MyVector3 collector_MyVector3;
|
||||||
|
typedef std::set<boost::shared_ptr<MyVector12>*> Collector_MyVector12;
|
||||||
|
static Collector_MyVector12 collector_MyVector12;
|
||||||
typedef std::set<boost::shared_ptr<MyFactorPosePoint2>*> Collector_MyFactorPosePoint2;
|
typedef std::set<boost::shared_ptr<MyFactorPosePoint2>*> Collector_MyFactorPosePoint2;
|
||||||
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2;
|
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2;
|
||||||
|
|
||||||
|
@ -72,6 +78,18 @@ void _deleteAllObjects()
|
||||||
collector_MyTemplateMatrix.erase(iter++);
|
collector_MyTemplateMatrix.erase(iter++);
|
||||||
anyDeleted = true;
|
anyDeleted = true;
|
||||||
} }
|
} }
|
||||||
|
{ for(Collector_MyVector3::iterator iter = collector_MyVector3.begin();
|
||||||
|
iter != collector_MyVector3.end(); ) {
|
||||||
|
delete *iter;
|
||||||
|
collector_MyVector3.erase(iter++);
|
||||||
|
anyDeleted = true;
|
||||||
|
} }
|
||||||
|
{ for(Collector_MyVector12::iterator iter = collector_MyVector12.begin();
|
||||||
|
iter != collector_MyVector12.end(); ) {
|
||||||
|
delete *iter;
|
||||||
|
collector_MyVector12.erase(iter++);
|
||||||
|
anyDeleted = true;
|
||||||
|
} }
|
||||||
{ for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin();
|
{ for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin();
|
||||||
iter != collector_MyFactorPosePoint2.end(); ) {
|
iter != collector_MyFactorPosePoint2.end(); ) {
|
||||||
delete *iter;
|
delete *iter;
|
||||||
|
@ -914,7 +932,73 @@ void MyTemplateMatrix_templatedMethod_75(int nargout, mxArray *out[], int nargin
|
||||||
out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
|
out[0] = wrap< Vector >(obj->templatedMethod<Vector>(t));
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyFactorPosePoint2_collectorInsertAndMakeBase_76(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyVector3_collectorInsertAndMakeBase_76(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<MyVector3> Shared;
|
||||||
|
|
||||||
|
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||||
|
collector_MyVector3.insert(self);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MyVector3_constructor_77(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<MyVector3> Shared;
|
||||||
|
|
||||||
|
Shared *self = new Shared(new MyVector3());
|
||||||
|
collector_MyVector3.insert(self);
|
||||||
|
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||||
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
|
}
|
||||||
|
|
||||||
|
void MyVector3_deconstructor_78(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
typedef boost::shared_ptr<MyVector3> Shared;
|
||||||
|
checkArguments("delete_MyVector3",nargout,nargin,1);
|
||||||
|
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||||
|
Collector_MyVector3::iterator item;
|
||||||
|
item = collector_MyVector3.find(self);
|
||||||
|
if(item != collector_MyVector3.end()) {
|
||||||
|
delete self;
|
||||||
|
collector_MyVector3.erase(item);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MyVector12_collectorInsertAndMakeBase_79(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<MyVector12> Shared;
|
||||||
|
|
||||||
|
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||||
|
collector_MyVector12.insert(self);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MyVector12_constructor_80(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
mexAtExit(&_deleteAllObjects);
|
||||||
|
typedef boost::shared_ptr<MyVector12> Shared;
|
||||||
|
|
||||||
|
Shared *self = new Shared(new MyVector12());
|
||||||
|
collector_MyVector12.insert(self);
|
||||||
|
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||||
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
|
}
|
||||||
|
|
||||||
|
void MyVector12_deconstructor_81(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
|
{
|
||||||
|
typedef boost::shared_ptr<MyVector12> Shared;
|
||||||
|
checkArguments("delete_MyVector12",nargout,nargin,1);
|
||||||
|
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||||
|
Collector_MyVector12::iterator item;
|
||||||
|
item = collector_MyVector12.find(self);
|
||||||
|
if(item != collector_MyVector12.end()) {
|
||||||
|
delete self;
|
||||||
|
collector_MyVector12.erase(item);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MyFactorPosePoint2_collectorInsertAndMakeBase_82(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
|
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
|
||||||
|
@ -923,7 +1007,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_76(int nargout, mxArray *out[
|
||||||
collector_MyFactorPosePoint2.insert(self);
|
collector_MyFactorPosePoint2.insert(self);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyFactorPosePoint2_constructor_77(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyFactorPosePoint2_constructor_83(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
mexAtExit(&_deleteAllObjects);
|
mexAtExit(&_deleteAllObjects);
|
||||||
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
|
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
|
||||||
|
@ -938,7 +1022,7 @@ void MyFactorPosePoint2_constructor_77(int nargout, mxArray *out[], int nargin,
|
||||||
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||||
}
|
}
|
||||||
|
|
||||||
void MyFactorPosePoint2_deconstructor_78(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void MyFactorPosePoint2_deconstructor_84(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
|
typedef boost::shared_ptr<MyFactorPosePoint2> Shared;
|
||||||
checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1);
|
checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1);
|
||||||
|
@ -951,18 +1035,18 @@ void MyFactorPosePoint2_deconstructor_78(int nargout, mxArray *out[], int nargin
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void aGlobalFunction_79(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void aGlobalFunction_85(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
checkArguments("aGlobalFunction",nargout,nargin,0);
|
checkArguments("aGlobalFunction",nargout,nargin,0);
|
||||||
out[0] = wrap< Vector >(aGlobalFunction());
|
out[0] = wrap< Vector >(aGlobalFunction());
|
||||||
}
|
}
|
||||||
void overloadedGlobalFunction_80(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void overloadedGlobalFunction_86(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
checkArguments("overloadedGlobalFunction",nargout,nargin,1);
|
checkArguments("overloadedGlobalFunction",nargout,nargin,1);
|
||||||
int a = unwrap< int >(in[0]);
|
int a = unwrap< int >(in[0]);
|
||||||
out[0] = wrap< Vector >(overloadedGlobalFunction(a));
|
out[0] = wrap< Vector >(overloadedGlobalFunction(a));
|
||||||
}
|
}
|
||||||
void overloadedGlobalFunction_81(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
void overloadedGlobalFunction_87(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
{
|
{
|
||||||
checkArguments("overloadedGlobalFunction",nargout,nargin,2);
|
checkArguments("overloadedGlobalFunction",nargout,nargin,2);
|
||||||
int a = unwrap< int >(in[0]);
|
int a = unwrap< int >(in[0]);
|
||||||
|
@ -1210,22 +1294,40 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||||
MyTemplateMatrix_templatedMethod_75(nargout, out, nargin-1, in+1);
|
MyTemplateMatrix_templatedMethod_75(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 76:
|
case 76:
|
||||||
MyFactorPosePoint2_collectorInsertAndMakeBase_76(nargout, out, nargin-1, in+1);
|
MyVector3_collectorInsertAndMakeBase_76(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 77:
|
case 77:
|
||||||
MyFactorPosePoint2_constructor_77(nargout, out, nargin-1, in+1);
|
MyVector3_constructor_77(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 78:
|
case 78:
|
||||||
MyFactorPosePoint2_deconstructor_78(nargout, out, nargin-1, in+1);
|
MyVector3_deconstructor_78(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 79:
|
case 79:
|
||||||
aGlobalFunction_79(nargout, out, nargin-1, in+1);
|
MyVector12_collectorInsertAndMakeBase_79(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 80:
|
case 80:
|
||||||
overloadedGlobalFunction_80(nargout, out, nargin-1, in+1);
|
MyVector12_constructor_80(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
case 81:
|
case 81:
|
||||||
overloadedGlobalFunction_81(nargout, out, nargin-1, in+1);
|
MyVector12_deconstructor_81(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 82:
|
||||||
|
MyFactorPosePoint2_collectorInsertAndMakeBase_82(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 83:
|
||||||
|
MyFactorPosePoint2_constructor_83(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 84:
|
||||||
|
MyFactorPosePoint2_deconstructor_84(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 85:
|
||||||
|
aGlobalFunction_85(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 86:
|
||||||
|
overloadedGlobalFunction_86(nargout, out, nargin-1, in+1);
|
||||||
|
break;
|
||||||
|
case 87:
|
||||||
|
overloadedGlobalFunction_87(nargout, out, nargin-1, in+1);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
} catch(const std::exception& e) {
|
} catch(const std::exception& e) {
|
||||||
|
|
|
@ -1,8 +1,8 @@
|
||||||
function varargout = overloadedGlobalFunction(varargin)
|
function varargout = overloadedGlobalFunction(varargin)
|
||||||
if length(varargin) == 1 && isa(varargin{1},'numeric')
|
if length(varargin) == 1 && isa(varargin{1},'numeric')
|
||||||
varargout{1} = geometry_wrapper(80, varargin{:});
|
varargout{1} = geometry_wrapper(86, varargin{:});
|
||||||
elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double')
|
elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double')
|
||||||
varargout{1} = geometry_wrapper(81, varargin{:});
|
varargout{1} = geometry_wrapper(87, varargin{:});
|
||||||
else
|
else
|
||||||
error('Arguments do not match any overload of function overloadedGlobalFunction');
|
error('Arguments do not match any overload of function overloadedGlobalFunction');
|
||||||
end
|
end
|
||||||
|
|
|
@ -127,6 +127,12 @@ class MyFactor {
|
||||||
// and a typedef specializing it
|
// and a typedef specializing it
|
||||||
typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
typedef MyFactor<gtsam::Pose2, Matrix> MyFactorPosePoint2;
|
||||||
|
|
||||||
|
// A class with integer template arguments
|
||||||
|
template<N = {3,12}>
|
||||||
|
class MyVector {
|
||||||
|
MyVector();
|
||||||
|
};
|
||||||
|
|
||||||
// comments at the end!
|
// comments at the end!
|
||||||
|
|
||||||
// even more comments at the end!
|
// even more comments at the end!
|
||||||
|
|
|
@ -221,6 +221,29 @@ TEST( Class, TemplateSubstition ) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//******************************************************************************
|
||||||
|
TEST( Class, TemplateSubstitionIntList ) {
|
||||||
|
|
||||||
|
using classic::space_p;
|
||||||
|
|
||||||
|
// Create type grammar that will place result in cls
|
||||||
|
Class cls;
|
||||||
|
Template t;
|
||||||
|
ClassGrammar g(cls, t);
|
||||||
|
|
||||||
|
string markup(string("template<N = {3,4}>"
|
||||||
|
"class Point2 {"
|
||||||
|
" void myMethod(Matrix A) const;"
|
||||||
|
"};"));
|
||||||
|
|
||||||
|
EXPECT(parse(markup.c_str(), g, space_p).full);
|
||||||
|
|
||||||
|
vector<Class> classes = cls.expandTemplate(t.argName(), t.intList());
|
||||||
|
|
||||||
|
// check the number of new classes is 2
|
||||||
|
EXPECT_LONGS_EQUAL(2, classes.size());
|
||||||
|
}
|
||||||
|
|
||||||
//******************************************************************************
|
//******************************************************************************
|
||||||
TEST(Class, Template) {
|
TEST(Class, Template) {
|
||||||
|
|
||||||
|
|
|
@ -47,6 +47,15 @@ TEST( Template, grammar ) {
|
||||||
EXPECT(actual[2]==Qualified("Vector",Qualified::EIGEN));
|
EXPECT(actual[2]==Qualified("Vector",Qualified::EIGEN));
|
||||||
EXPECT(actual[3]==Qualified("Matrix",Qualified::EIGEN));
|
EXPECT(actual[3]==Qualified("Matrix",Qualified::EIGEN));
|
||||||
actual.clear();
|
actual.clear();
|
||||||
|
|
||||||
|
EXPECT(parse("template<N = {1,2,3,4}>", g, space_p).full);
|
||||||
|
EXPECT_LONGS_EQUAL(4, actual.intList().size());
|
||||||
|
EXPECT(actual.argName()=="N");
|
||||||
|
EXPECT_LONGS_EQUAL(1,actual.intList()[0]);
|
||||||
|
EXPECT_LONGS_EQUAL(2,actual.intList()[1]);
|
||||||
|
EXPECT_LONGS_EQUAL(3,actual.intList()[2]);
|
||||||
|
EXPECT_LONGS_EQUAL(4,actual.intList()[3]);
|
||||||
|
actual.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
//******************************************************************************
|
//******************************************************************************
|
||||||
|
|
|
@ -144,7 +144,7 @@ TEST( wrap, Small ) {
|
||||||
TEST( wrap, Geometry ) {
|
TEST( wrap, Geometry ) {
|
||||||
string markup_header_path = topdir + "/wrap/tests";
|
string markup_header_path = topdir + "/wrap/tests";
|
||||||
Module module(markup_header_path.c_str(), "geometry",enable_verbose);
|
Module module(markup_header_path.c_str(), "geometry",enable_verbose);
|
||||||
EXPECT_LONGS_EQUAL(7, module.classes.size());
|
EXPECT_LONGS_EQUAL(9, module.classes.size());
|
||||||
|
|
||||||
// forward declarations
|
// forward declarations
|
||||||
LONGS_EQUAL(2, module.forward_declarations.size());
|
LONGS_EQUAL(2, module.forward_declarations.size());
|
||||||
|
@ -155,7 +155,7 @@ TEST( wrap, Geometry ) {
|
||||||
strvec exp_includes; exp_includes += "folder/path/to/Test.h";
|
strvec exp_includes; exp_includes += "folder/path/to/Test.h";
|
||||||
EXPECT(assert_equal(exp_includes, module.includes));
|
EXPECT(assert_equal(exp_includes, module.includes));
|
||||||
|
|
||||||
LONGS_EQUAL(7, module.classes.size());
|
LONGS_EQUAL(9, module.classes.size());
|
||||||
|
|
||||||
// Key for ReturnType::return_category
|
// Key for ReturnType::return_category
|
||||||
// CLASS = 1,
|
// CLASS = 1,
|
||||||
|
@ -445,15 +445,17 @@ 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 + "+gtsam/Point2.m" , apath + "+gtsam/Point2.m" ));
|
EXPECT(files_equal(epath + "+gtsam/Point2.m" , apath + "+gtsam/Point2.m" ));
|
||||||
EXPECT(files_equal(epath + "+gtsam/Point3.m" , apath + "+gtsam/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 + "MyVector3.m" , apath + "MyVector3.m" ));
|
||||||
|
EXPECT(files_equal(epath + "MyVector12.m" , apath + "MyVector12.m" ));
|
||||||
EXPECT(files_equal(epath + "MyTemplatePoint2.m" , apath + "MyTemplatePoint2.m" ));
|
EXPECT(files_equal(epath + "MyTemplatePoint2.m" , apath + "MyTemplatePoint2.m" ));
|
||||||
EXPECT(files_equal(epath + "MyTemplateMatrix.m" , apath + "MyTemplateMatrix.m" ));
|
EXPECT(files_equal(epath + "MyTemplateMatrix.m" , apath + "MyTemplateMatrix.m" ));
|
||||||
EXPECT(files_equal(epath + "MyFactorPosePoint2.m" , apath + "MyFactorPosePoint2.m"));
|
EXPECT(files_equal(epath + "MyFactorPosePoint2.m" , apath + "MyFactorPosePoint2.m" ));
|
||||||
EXPECT(files_equal(epath + "aGlobalFunction.m" , apath + "aGlobalFunction.m" ));
|
EXPECT(files_equal(epath + "aGlobalFunction.m" , apath + "aGlobalFunction.m" ));
|
||||||
EXPECT(files_equal(epath + "overloadedGlobalFunction.m" , apath + "overloadedGlobalFunction.m" ));
|
EXPECT(files_equal(epath + "overloadedGlobalFunction.m", apath + "overloadedGlobalFunction.m"));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
Loading…
Reference in New Issue