From 42deeb7bf02d3abfc329f0945694cc07487abca4 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Sat, 18 Mar 2017 18:26:21 -0400 Subject: [PATCH] fix/update matlab wrapper tests when wrap serialization option is off --- wrap/tests/expected2/MyFactorPosePoint2.m | 6 +- wrap/tests/expected2/MyVector12.m | 36 +++++ wrap/tests/expected2/MyVector3.m | 36 +++++ wrap/tests/expected2/aGlobalFunction.m | 2 +- wrap/tests/expected2/geometry_wrapper.cpp | 126 ++++++++++++++++-- .../expected2/overloadedGlobalFunction.m | 4 +- 6 files changed, 192 insertions(+), 18 deletions(-) create mode 100644 wrap/tests/expected2/MyVector12.m create mode 100644 wrap/tests/expected2/MyVector3.m diff --git a/wrap/tests/expected2/MyFactorPosePoint2.m b/wrap/tests/expected2/MyFactorPosePoint2.m index 430206232..a61e54eb2 100644 --- a/wrap/tests/expected2/MyFactorPosePoint2.m +++ b/wrap/tests/expected2/MyFactorPosePoint2.m @@ -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(74, my_ptr); + geometry_wrapper(80, 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(75, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + my_ptr = geometry_wrapper(81, 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(76, obj.ptr_MyFactorPosePoint2); + geometry_wrapper(82, obj.ptr_MyFactorPosePoint2); end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected2/MyVector12.m b/wrap/tests/expected2/MyVector12.m new file mode 100644 index 000000000..4bd86e8a7 --- /dev/null +++ b/wrap/tests/expected2/MyVector12.m @@ -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(77, my_ptr); + elseif nargin == 0 + my_ptr = geometry_wrapper(78); + else + error('Arguments do not match any overload of MyVector12 constructor'); + end + obj.ptr_MyVector12 = my_ptr; + end + + function delete(obj) + geometry_wrapper(79, 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 diff --git a/wrap/tests/expected2/MyVector3.m b/wrap/tests/expected2/MyVector3.m new file mode 100644 index 000000000..82f3ed4bd --- /dev/null +++ b/wrap/tests/expected2/MyVector3.m @@ -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(74, my_ptr); + elseif nargin == 0 + my_ptr = geometry_wrapper(75); + else + error('Arguments do not match any overload of MyVector3 constructor'); + end + obj.ptr_MyVector3 = my_ptr; + end + + function delete(obj) + geometry_wrapper(76, 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 diff --git a/wrap/tests/expected2/aGlobalFunction.m b/wrap/tests/expected2/aGlobalFunction.m index d96662dc1..7246b478b 100644 --- a/wrap/tests/expected2/aGlobalFunction.m +++ b/wrap/tests/expected2/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(77, varargin{:}); + varargout{1} = geometry_wrapper(83, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/wrap/tests/expected2/geometry_wrapper.cpp b/wrap/tests/expected2/geometry_wrapper.cpp index 8526900a7..475025654 100644 --- a/wrap/tests/expected2/geometry_wrapper.cpp +++ b/wrap/tests/expected2/geometry_wrapper.cpp @@ -5,6 +5,8 @@ typedef MyTemplate MyTemplatePoint2; typedef MyTemplate MyTemplateMatrix; +typedef MyVector<3> MyVector3; +typedef MyVector<12> MyVector12; typedef MyFactor MyFactorPosePoint2; typedef std::set*> Collector_gtsamPoint2; @@ -19,6 +21,10 @@ typedef std::set*> Collector_MyTemplatePoint static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; typedef std::set*> Collector_MyTemplateMatrix; static Collector_MyTemplateMatrix collector_MyTemplateMatrix; +typedef std::set*> Collector_MyVector3; +static Collector_MyVector3 collector_MyVector3; +typedef std::set*> Collector_MyVector12; +static Collector_MyVector12 collector_MyVector12; typedef std::set*> Collector_MyFactorPosePoint2; static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; @@ -64,6 +70,18 @@ void _deleteAllObjects() collector_MyTemplateMatrix.erase(iter++); 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(); iter != collector_MyFactorPosePoint2.end(); ) { delete *iter; @@ -885,7 +903,73 @@ void MyTemplateMatrix_templatedMethod_73(int nargout, mxArray *out[], int nargin out[0] = wrap< Vector >(obj->templatedMethod(t)); } -void MyFactorPosePoint2_collectorInsertAndMakeBase_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector3_collectorInsertAndMakeBase_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyVector3.insert(self); +} + +void MyVector3_constructor_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new MyVector3()); + collector_MyVector3.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void MyVector3_deconstructor_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_MyVector3",nargout,nargin,1); + Shared *self = *reinterpret_cast(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_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyVector12.insert(self); +} + +void MyVector12_constructor_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new MyVector12()); + collector_MyVector12.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void MyVector12_deconstructor_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_MyVector12",nargout,nargin,1); + Shared *self = *reinterpret_cast(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_80(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -894,7 +978,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_74(int nargout, mxArray *out[ collector_MyFactorPosePoint2.insert(self); } -void MyFactorPosePoint2_constructor_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_constructor_81(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -909,7 +993,7 @@ void MyFactorPosePoint2_constructor_75(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void MyFactorPosePoint2_deconstructor_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_deconstructor_82(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); @@ -922,18 +1006,18 @@ void MyFactorPosePoint2_deconstructor_76(int nargout, mxArray *out[], int nargin } } -void aGlobalFunction_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void aGlobalFunction_83(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("aGlobalFunction",nargout,nargin,0); out[0] = wrap< Vector >(aGlobalFunction()); } -void overloadedGlobalFunction_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_84(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_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_85(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("overloadedGlobalFunction",nargout,nargin,2); int a = unwrap< int >(in[0]); @@ -1175,22 +1259,40 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) MyTemplateMatrix_templatedMethod_73(nargout, out, nargin-1, in+1); break; case 74: - MyFactorPosePoint2_collectorInsertAndMakeBase_74(nargout, out, nargin-1, in+1); + MyVector3_collectorInsertAndMakeBase_74(nargout, out, nargin-1, in+1); break; case 75: - MyFactorPosePoint2_constructor_75(nargout, out, nargin-1, in+1); + MyVector3_constructor_75(nargout, out, nargin-1, in+1); break; case 76: - MyFactorPosePoint2_deconstructor_76(nargout, out, nargin-1, in+1); + MyVector3_deconstructor_76(nargout, out, nargin-1, in+1); break; case 77: - aGlobalFunction_77(nargout, out, nargin-1, in+1); + MyVector12_collectorInsertAndMakeBase_77(nargout, out, nargin-1, in+1); break; case 78: - overloadedGlobalFunction_78(nargout, out, nargin-1, in+1); + MyVector12_constructor_78(nargout, out, nargin-1, in+1); break; case 79: - overloadedGlobalFunction_79(nargout, out, nargin-1, in+1); + MyVector12_deconstructor_79(nargout, out, nargin-1, in+1); + break; + case 80: + MyFactorPosePoint2_collectorInsertAndMakeBase_80(nargout, out, nargin-1, in+1); + break; + case 81: + MyFactorPosePoint2_constructor_81(nargout, out, nargin-1, in+1); + break; + case 82: + MyFactorPosePoint2_deconstructor_82(nargout, out, nargin-1, in+1); + break; + case 83: + aGlobalFunction_83(nargout, out, nargin-1, in+1); + break; + case 84: + overloadedGlobalFunction_84(nargout, out, nargin-1, in+1); + break; + case 85: + overloadedGlobalFunction_85(nargout, out, nargin-1, in+1); break; } } catch(const std::exception& e) { diff --git a/wrap/tests/expected2/overloadedGlobalFunction.m b/wrap/tests/expected2/overloadedGlobalFunction.m index 7dd7317ab..e5b4b21a9 100644 --- a/wrap/tests/expected2/overloadedGlobalFunction.m +++ b/wrap/tests/expected2/overloadedGlobalFunction.m @@ -1,8 +1,8 @@ function varargout = overloadedGlobalFunction(varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(78, varargin{:}); + varargout{1} = geometry_wrapper(84, varargin{:}); elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') - varargout{1} = geometry_wrapper(79, varargin{:}); + varargout{1} = geometry_wrapper(85, varargin{:}); else error('Arguments do not match any overload of function overloadedGlobalFunction'); end