1 #include <gtwrap/matlab.h> 4 #include <boost/archive/text_iarchive.hpp> 5 #include <boost/archive/text_oarchive.hpp> 6 #include <boost/serialization/export.hpp> 8 #include <folder/path/to/Test.h> 59 std::streambuf *outbuf = std::cout.rdbuf(&mout);
61 bool anyDeleted =
false;
154 "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" 155 "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" 156 "module, so that your recompiled module is used instead of the old one." << endl;
157 std::cout.rdbuf(outbuf);
161 const mxArray *alreadyCreated = mexGetVariablePtr(
"global",
"gtsam_inheritance_rttiRegistry_created");
162 if(!alreadyCreated) {
163 std::map<std::string, std::string> types;
164 types.insert(std::make_pair(
typeid(MyBase).
name(),
"MyBase"));
167 types.insert(std::make_pair(
typeid(ForwardKinematicsFactor).
name(),
"ForwardKinematicsFactor"));
169 mxArray *registry = mexGetVariable(
"global",
"gtsamwrap_rttiRegistry");
171 registry = mxCreateStructMatrix(1, 1, 0,
NULL);
172 typedef std::pair<std::string, std::string> StringPair;
173 for(
const StringPair& rtti_matlab: types) {
174 int fieldId = mxAddField(registry, rtti_matlab.first.c_str());
176 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
177 mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str());
178 mxSetFieldByNumber(registry, 0, fieldId, matlabName);
180 if(mexPutVariable(
"global",
"gtsamwrap_rttiRegistry", registry) != 0)
181 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
182 mxDestroyArray(registry);
184 mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL);
185 if(mexPutVariable(
"global",
"gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0)
186 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
187 mxDestroyArray(newAlreadyCreated);
194 typedef boost::shared_ptr<gtsam::Point2> Shared;
196 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
203 typedef boost::shared_ptr<MyBase> Shared;
205 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
211 typedef boost::shared_ptr<MyBase> Shared;
213 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
214 Collector_MyBase::iterator item;
224 typedef boost::shared_ptr<gtsam::Point2> Shared;
226 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
227 Collector_gtsamPoint2::iterator item;
238 typedef boost::shared_ptr<MyTemplate<gtsam::Point2>> Shared;
240 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
243 typedef boost::shared_ptr<MyBase> SharedBase;
245 *
reinterpret_cast<SharedBase**
>(mxGetData(out[0])) =
new SharedBase(*
self);
251 typedef boost::shared_ptr<MyTemplate<gtsam::Point2>> Shared;
253 Shared *
self =
new Shared(
new MyTemplate<gtsam::Point2>());
256 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
258 typedef boost::shared_ptr<MyBase> SharedBase;
260 *
reinterpret_cast<SharedBase**
>(mxGetData(out[1])) =
new SharedBase(*
self);
265 typedef boost::shared_ptr<MyTemplate<gtsam::Point2>> Shared;
267 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
268 Collector_MyTemplatePoint2::iterator item;
279 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
281 obj->accept_T(value);
287 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
289 obj->accept_Tptr(value);
295 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
296 auto pairResult = obj->create_MixedPtrs();
297 out[0] = wrap< Point2 >(pairResult.first);
299 boost::shared_ptr<Point2> shared(pairResult.second);
307 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
308 auto pairResult = obj->create_ptrs();
310 boost::shared_ptr<Point2> shared(pairResult.first);
314 boost::shared_ptr<Point2> shared(pairResult.second);
322 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
324 out[0] = wrap< Point2 >(obj->return_T(value));
330 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
333 boost::shared_ptr<Point2> shared(obj->return_Tptr(value));
341 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
342 Point2 p1 = unwrap< Point2 >(in[1]);
343 Point2 p2 = unwrap< Point2 >(in[2]);
344 auto pairResult = obj->return_ptrs(p1,p2);
346 boost::shared_ptr<Point2> shared(pairResult.first);
350 boost::shared_ptr<Point2> shared(pairResult.second);
358 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
359 Matrix t = unwrap< Matrix >(in[1]);
366 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
367 Point2 t = unwrap< Point2 >(in[1]);
374 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
375 Point3 t = unwrap< Point3 >(in[1]);
382 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Point2>>(in[0],
"ptr_MyTemplatePoint2");
383 Vector t = unwrap< Vector >(in[1]);
390 Point2 K = unwrap< Point2 >(in[0]);
397 typedef boost::shared_ptr<gtsam::Point3> Shared;
405 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
411 typedef boost::shared_ptr<MyTemplate<gtsam::Matrix>> Shared;
413 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
416 typedef boost::shared_ptr<MyBase> SharedBase;
418 *
reinterpret_cast<SharedBase**
>(mxGetData(out[0])) =
new SharedBase(*
self);
424 typedef boost::shared_ptr<MyTemplate<gtsam::Matrix>> Shared;
426 Shared *
self =
new Shared(
new MyTemplate<gtsam::Matrix>());
429 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
431 typedef boost::shared_ptr<MyBase> SharedBase;
433 *
reinterpret_cast<SharedBase**
>(mxGetData(out[1])) =
new SharedBase(*
self);
438 typedef boost::shared_ptr<MyTemplate<gtsam::Matrix>> Shared;
440 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
441 Collector_MyTemplateMatrix::iterator item;
452 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
454 obj->accept_T(value);
460 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
462 obj->accept_Tptr(value);
468 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
469 auto pairResult = obj->create_MixedPtrs();
470 out[0] = wrap< Matrix >(pairResult.first);
472 boost::shared_ptr<Matrix> shared(pairResult.second);
480 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
481 auto pairResult = obj->create_ptrs();
483 boost::shared_ptr<Matrix> shared(pairResult.first);
487 boost::shared_ptr<Matrix> shared(pairResult.second);
495 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
497 out[0] = wrap< Matrix >(obj->return_T(value));
503 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
506 boost::shared_ptr<Matrix> shared(obj->return_Tptr(value));
514 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
515 Matrix p1 = unwrap< Matrix >(in[1]);
516 Matrix p2 = unwrap< Matrix >(in[2]);
517 auto pairResult = obj->return_ptrs(p1,p2);
519 boost::shared_ptr<Matrix> shared(pairResult.first);
523 boost::shared_ptr<Matrix> shared(pairResult.second);
531 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
532 Matrix t = unwrap< Matrix >(in[1]);
539 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
540 Point2 t = unwrap< Point2 >(in[1]);
547 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
548 Point3 t = unwrap< Point3 >(in[1]);
555 auto obj = unwrap_shared_ptr<MyTemplate<gtsam::Matrix>>(in[0],
"ptr_MyTemplateMatrix");
556 Vector t = unwrap< Vector >(in[1]);
563 Matrix K = unwrap< Matrix >(in[0]);
570 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
571 boost::shared_ptr<std::vector<testing::Test>> container = unwrap_shared_ptr< std::vector<testing::Test> >(in[1],
"ptr_stdvectorTest");
572 obj->set_container(*container);
578 typedef boost::shared_ptr<ForwardKinematicsFactor> Shared;
580 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
583 typedef boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3>> SharedBase;
585 *
reinterpret_cast<SharedBase**
>(mxGetData(out[0])) =
new SharedBase(*
self);
590 typedef boost::shared_ptr<ForwardKinematicsFactor> Shared;
591 checkArguments(
"delete_ForwardKinematicsFactor",nargout,nargin,1);
592 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
593 Collector_ForwardKinematicsFactor::iterator item;
602 void mexFunction(
int nargout, mxArray *out[],
int nargin,
const mxArray *in[])
605 std::streambuf *outbuf = std::cout.rdbuf(&mout);
728 }
catch(
const std::exception&
e) {
729 mexErrMsgTxt((
"Exception from gtsam:\n" + std::string(e.what()) +
"\n").c_str());
732 std::cout.rdbuf(outbuf);
int unwrap< int >(const mxArray *array)
static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble
void MyTemplatePoint2_return_Tptr_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, boost::shared_ptr< T > > make_shared(Args &&...args)
std::set< boost::shared_ptr< gtsam::Point2 > * > Collector_gtsamPoint2
std::set< boost::shared_ptr< Test > * > Collector_Test
std::set< boost::shared_ptr< PrimitiveRefDouble > * > Collector_PrimitiveRefDouble
void MyTemplatePoint2_collectorInsertAndMakeBase_3(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_FunRange collector_FunRange
void gtsamPoint3_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MyVector12 collector_MyVector12
std::set< boost::shared_ptr< FunDouble > * > Collector_FunDouble
void MyTemplatePoint2_return_T_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void checkArguments(const string &name, int nargout, int nargin, int expected)
void MyTemplateMatrix_create_MixedPtrs_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< ForwardKinematicsFactor > * > Collector_ForwardKinematicsFactor
void ForwardKinematicsFactor_collectorInsertAndMakeBase_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_FunDouble collector_FunDouble
void MyTemplateMatrix_return_T_27(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MultipleTemplates< int, float > MultipleTemplatesIntFloat
void MyTemplatePoint2_templatedMethod_15(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplateMatrix_templatedMethod_32(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MyTemplate< gtsam::Point2 > MyTemplatePoint2
PrimitiveRef< double > PrimitiveRefDouble
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
iterator iter(handle obj)
static Collector_MyBase collector_MyBase
std::set< boost::shared_ptr< gtsam::Point3 > * > Collector_gtsamPoint3
void MyTemplateMatrix_accept_T_23(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< MyVector3 > * > Collector_MyVector3
void MyTemplateMatrix_Level_34(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< MyVector12 > * > Collector_MyVector12
static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor
mxArray * wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const std::string &matlabName, bool isVirtual)
void MyTemplatePoint2_Level_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MyTemplatePoint2 collector_MyTemplatePoint2
GeneralSFMFactor< SfmCamera, Point3 > MyFactor
void MyTemplatePoint2_return_ptrs_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat
std::set< boost::shared_ptr< MultipleTemplatesIntDouble > * > Collector_MultipleTemplatesIntDouble
void MyTemplatePoint2_accept_Tptr_8(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MultipleTemplates< int, double > MultipleTemplatesIntDouble
MyFactor< gtsam::Pose2, gtsam::Matrix > MyFactorPosePoint2
void MyTemplatePoint2_templatedMethod_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplateMatrix_deconstructor_22(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyBase_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_Test collector_Test
std::set< boost::shared_ptr< MultipleTemplatesIntDouble > * > Collector_MultipleTemplatesIntDouble
MyTemplate< gtsam::Matrix > MyTemplateMatrix
void MyTemplatePoint2_create_MixedPtrs_9(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MyVector< 12 > MyVector12
std::set< boost::shared_ptr< MultipleTemplatesIntFloat > * > Collector_MultipleTemplatesIntFloat
void gtsamPoint2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[])
double unwrap< double >(const mxArray *array)
void MyBase_deconstructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< MyFactorPosePoint2 > * > Collector_MyFactorPosePoint2
void MyTemplatePoint2_constructor_5(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint2_templatedMethod_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplatePoint2_create_ptrs_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2
std::set< boost::shared_ptr< MyTemplateMatrix > * > Collector_MyTemplateMatrix
static Collector_gtsamPoint3 collector_gtsamPoint3
void MyTemplateMatrix_templatedMethod_33(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void ForwardKinematicsFactor_deconstructor_37(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplateMatrix_templatedMethod_31(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< FunDouble > * > Collector_FunDouble
std::set< boost::shared_ptr< FunRange > * > Collector_FunRange
std::set< boost::shared_ptr< MyVector12 > * > Collector_MyVector12
void MyTemplatePoint2_deconstructor_6(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::set< boost::shared_ptr< PrimitiveRefDouble > * > Collector_PrimitiveRefDouble
void MyTemplateMatrix_accept_Tptr_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplateMatrix_return_ptrs_29(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< MyFactorPosePoint2 > * > Collector_MyFactorPosePoint2
std::set< boost::shared_ptr< gtsam::Point2 > * > Collector_gtsamPoint2
void MyTemplateMatrix_templatedMethod_30(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void _inheritance_RTTIRegister()
BOOST_CLASS_EXPORT_GUID(gtsam::Point2,"gtsamPoint2")
std::set< boost::shared_ptr< MyVector3 > * > Collector_MyVector3
void MyTemplatePoint2_templatedMethod_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
#define mxUINT32OR64_CLASS
std::set< boost::shared_ptr< MultipleTemplatesIntFloat > * > Collector_MultipleTemplatesIntFloat
static Collector_gtsamPoint2 collector_gtsamPoint2
std::set< boost::shared_ptr< FunRange > * > Collector_FunRange
std::set< boost::shared_ptr< gtsam::Point3 > * > Collector_gtsamPoint3
static Collector_MyTemplateMatrix collector_MyTemplateMatrix
void Test_set_container_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplateMatrix_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
std::set< boost::shared_ptr< MyTemplatePoint2 > * > Collector_MyTemplatePoint2
std::set< boost::shared_ptr< Test > * > Collector_Test
void MyTemplateMatrix_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
void MyTemplateMatrix_create_ptrs_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::set< boost::shared_ptr< MyBase > * > Collector_MyBase
void gtsamPoint2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyTemplateMatrix_return_Tptr_28(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MyVector3 collector_MyVector3
static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble
void MyTemplatePoint2_accept_T_7(int nargout, mxArray *out[], int nargin, const mxArray *in[])