1 #include <gtwrap/matlab.h> 4 #include <folder/path/to/Test.h> 41 std::streambuf *outbuf = std::cout.rdbuf(&mout);
43 bool anyDeleted =
false;
113 "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" 114 "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" 115 "module, so that your recompiled module is used instead of the old one." << endl;
116 std::cout.rdbuf(outbuf);
120 const mxArray *alreadyCreated = mexGetVariablePtr(
"global",
"gtsam_class_rttiRegistry_created");
121 if(!alreadyCreated) {
122 std::map<std::string, std::string> types;
126 mxArray *registry = mexGetVariable(
"global",
"gtsamwrap_rttiRegistry");
128 registry = mxCreateStructMatrix(1, 1, 0,
NULL);
129 typedef std::pair<std::string, std::string> StringPair;
130 for(
const StringPair& rtti_matlab: types) {
131 int fieldId = mxAddField(registry, rtti_matlab.first.c_str());
133 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
135 mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str());
136 mxSetFieldByNumber(registry, 0, fieldId, matlabName);
138 if(mexPutVariable(
"global",
"gtsamwrap_rttiRegistry", registry) != 0) {
139 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
141 mxDestroyArray(registry);
143 mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL);
144 if(mexPutVariable(
"global",
"gtsam_class_rttiRegistry_created", newAlreadyCreated) != 0) {
145 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
147 mxDestroyArray(newAlreadyCreated);
154 typedef std::shared_ptr<FunRange> Shared;
156 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
163 typedef std::shared_ptr<FunRange> Shared;
165 Shared *
self =
new Shared(
new FunRange());
168 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
173 typedef std::shared_ptr<FunRange> Shared;
175 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
176 Collector_FunRange::iterator item;
187 auto obj = unwrap_shared_ptr<FunRange>(in[0],
"ptr_FunRange");
189 out[0] =
wrap_shared_ptr(std::make_shared<FunRange>(obj->range(d)),
"FunRange",
false);
201 typedef std::shared_ptr<Fun<double>> Shared;
203 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
209 typedef std::shared_ptr<Fun<double>> Shared;
211 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
212 Collector_FunDouble::iterator item;
222 checkArguments(
"multiTemplatedMethodStringSize_t",nargout,nargin-1,3);
223 auto obj = unwrap_shared_ptr<Fun<double>>(in[0],
"ptr_FunDouble");
233 auto obj = unwrap_shared_ptr<Fun<double>>(in[0],
"ptr_FunDouble");
240 auto obj = unwrap_shared_ptr<Fun<double>>(in[0],
"ptr_FunDouble");
248 checkArguments(
"Fun<double>.staticMethodWithThis",nargout,nargin,0);
254 checkArguments(
"Fun<double>.templatedStaticMethodInt",nargout,nargin,1);
262 typedef std::shared_ptr<Test> Shared;
264 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
271 typedef std::shared_ptr<Test> Shared;
273 Shared *
self =
new Shared(
new Test());
276 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
282 typedef std::shared_ptr<Test> Shared;
285 Matrix b = unwrap< Matrix >(in[1]);
286 Shared *
self =
new Shared(
new Test(a,b));
289 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
294 typedef std::shared_ptr<Test> Shared;
296 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
297 Collector_Test::iterator item;
308 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
310 obj->arg_EigenConstRef(value);
316 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
317 auto pairResult = obj->create_MixedPtrs();
318 out[0] =
wrap_shared_ptr(std::make_shared<Test>(pairResult.first),
"Test",
false);
325 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
326 auto pairResult = obj->create_ptrs();
334 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
341 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
348 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
349 gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[1],
"ptr_gtsamKeyFormatter");
356 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
363 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
370 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
373 std::shared_ptr<Point2> shared(obj->return_Point2Ptr(value));
381 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
382 std::shared_ptr<Test>
value = unwrap_shared_ptr< Test >(in[1],
"ptr_Test");
383 out[0] =
wrap_shared_ptr(std::make_shared<Test>(obj->return_Test(value)),
"Test",
false);
389 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
390 std::shared_ptr<Test>
value = unwrap_shared_ptr< Test >(in[1],
"ptr_Test");
397 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
405 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
413 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
414 Test&
t = *unwrap_shared_ptr< Test >(in[1],
"ptr_Test");
421 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
429 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
431 out[0] = wrap< Matrix >(obj->return_matrix1(value));
437 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
439 out[0] = wrap< Matrix >(obj->return_matrix2(value));
445 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
446 Vector v = unwrap< Vector >(in[1]);
447 Matrix A = unwrap< Matrix >(in[2]);
448 auto pairResult = obj->return_pair(v,A);
449 out[0] = wrap< Vector >(pairResult.first);
450 out[1] = wrap< Matrix >(pairResult.second);
456 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
457 Vector v = unwrap< Vector >(in[1]);
458 auto pairResult = obj->return_pair(v);
459 out[0] = wrap< Vector >(pairResult.first);
460 out[1] = wrap< Matrix >(pairResult.second);
466 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
467 std::shared_ptr<Test>
p1 = unwrap_shared_ptr< Test >(in[1],
"ptr_Test");
468 std::shared_ptr<Test>
p2 = unwrap_shared_ptr< Test >(in[2],
"ptr_Test");
469 auto pairResult = obj->return_ptrs(p1,p2);
477 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
485 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
493 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
495 out[0] = wrap< Vector >(obj->return_vector1(value));
501 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
503 out[0] = wrap< Vector >(obj->return_vector2(value));
509 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
510 std::shared_ptr<std::vector<testing::Test>> container = unwrap_shared_ptr< std::vector<testing::Test> >(in[1],
"ptr_stdvectorTest");
511 obj->set_container(*container);
517 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
518 std::shared_ptr<std::vector<testing::Test>> container = unwrap_shared_ptr< std::vector<testing::Test> >(in[1],
"ptr_stdvectorTest");
519 obj->set_container(*container);
525 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
526 std::shared_ptr<std::vector<testing::Test>> container = unwrap_shared_ptr< std::vector<testing::Test> >(in[1],
"ptr_stdvectorTest");
527 obj->set_container(*container);
533 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
534 out[0] =
wrap_shared_ptr(obj->model_ptr,
"gtsam.noiseModel.Base",
false);
540 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
541 std::shared_ptr<gtsam::noiseModel::Base> model_ptr = unwrap_shared_ptr< gtsam::noiseModel::Base >(in[1],
"ptr_gtsamnoiseModelBase");
542 obj->model_ptr = *model_ptr;
548 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
555 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
563 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
570 auto obj = unwrap_shared_ptr<Test>(in[0],
"ptr_Test");
578 typedef std::shared_ptr<PrimitiveRef<double>> Shared;
580 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
587 typedef std::shared_ptr<PrimitiveRef<double>> Shared;
589 Shared *
self =
new Shared(
new PrimitiveRef<double>());
592 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
597 typedef std::shared_ptr<PrimitiveRef<double>> Shared;
599 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
600 Collector_PrimitiveRefDouble::iterator item;
618 typedef std::shared_ptr<MyVector<3>> Shared;
620 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
627 typedef std::shared_ptr<MyVector<3>> Shared;
629 Shared *
self =
new Shared(
new MyVector<3>());
632 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
637 typedef std::shared_ptr<MyVector<3>> Shared;
639 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
640 Collector_MyVector3::iterator item;
651 typedef std::shared_ptr<MyVector<12>> Shared;
653 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
660 typedef std::shared_ptr<MyVector<12>> Shared;
662 Shared *
self =
new Shared(
new MyVector<12>());
665 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
670 typedef std::shared_ptr<MyVector<12>> Shared;
672 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
673 Collector_MyVector12::iterator item;
684 typedef std::shared_ptr<MultipleTemplates<int, double>> Shared;
686 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
692 typedef std::shared_ptr<MultipleTemplates<int, double>> Shared;
693 checkArguments(
"delete_MultipleTemplatesIntDouble",nargout,nargin,1);
694 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
695 Collector_MultipleTemplatesIntDouble::iterator item;
706 typedef std::shared_ptr<MultipleTemplates<int, float>> Shared;
708 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
714 typedef std::shared_ptr<MultipleTemplates<int, float>> Shared;
715 checkArguments(
"delete_MultipleTemplatesIntFloat",nargout,nargin,1);
716 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
717 Collector_MultipleTemplatesIntFloat::iterator item;
728 typedef std::shared_ptr<ForwardKinematics> Shared;
730 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
737 typedef std::shared_ptr<ForwardKinematics> Shared;
739 gtdynamics::Robot& robot = *unwrap_shared_ptr< gtdynamics::Robot >(in[0],
"ptr_gtdynamicsRobot");
740 string& start_link_name = *unwrap_shared_ptr< string >(in[1],
"ptr_string");
741 string& end_link_name = *unwrap_shared_ptr< string >(in[2],
"ptr_string");
742 gtsam::Values& joint_angles = *unwrap_shared_ptr< gtsam::Values >(in[3],
"ptr_gtsamValues");
743 gtsam::Pose3& l2Tp = *unwrap_shared_ptr< gtsam::Pose3 >(in[4],
"ptr_gtsamPose3");
744 Shared *
self =
new Shared(
new ForwardKinematics(robot,start_link_name,end_link_name,joint_angles,l2Tp));
747 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
753 typedef std::shared_ptr<ForwardKinematics> Shared;
755 gtdynamics::Robot& robot = *unwrap_shared_ptr< gtdynamics::Robot >(in[0],
"ptr_gtdynamicsRobot");
756 string& start_link_name = *unwrap_shared_ptr< string >(in[1],
"ptr_string");
757 string& end_link_name = *unwrap_shared_ptr< string >(in[2],
"ptr_string");
758 gtsam::Values& joint_angles = *unwrap_shared_ptr< gtsam::Values >(in[3],
"ptr_gtsamValues");
759 Shared *
self =
new Shared(
new ForwardKinematics(robot,start_link_name,end_link_name,joint_angles,
gtsam::Pose3()));
762 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
767 typedef std::shared_ptr<ForwardKinematics> Shared;
769 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
770 Collector_ForwardKinematics::iterator item;
781 typedef std::shared_ptr<TemplatedConstructor> Shared;
783 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
790 typedef std::shared_ptr<TemplatedConstructor> Shared;
792 Shared *
self =
new Shared(
new TemplatedConstructor());
795 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
801 typedef std::shared_ptr<TemplatedConstructor> Shared;
803 string&
arg = *unwrap_shared_ptr< string >(in[0],
"ptr_string");
804 Shared *
self =
new Shared(
new TemplatedConstructor(arg));
807 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
813 typedef std::shared_ptr<TemplatedConstructor> Shared;
816 Shared *
self =
new Shared(
new TemplatedConstructor(arg));
819 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
825 typedef std::shared_ptr<TemplatedConstructor> Shared;
828 Shared *
self =
new Shared(
new TemplatedConstructor(arg));
831 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
836 typedef std::shared_ptr<TemplatedConstructor> Shared;
838 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
839 Collector_TemplatedConstructor::iterator item;
850 typedef std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
852 Shared *
self = *
reinterpret_cast<Shared**
> (mxGetData(in[0]));
859 typedef std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
864 std::shared_ptr<gtsam::noiseModel::Base> noiseModel = unwrap_shared_ptr< gtsam::noiseModel::Base >(in[3],
"ptr_gtsamnoiseModelBase");
868 *
reinterpret_cast<Shared**
> (mxGetData(out[0])) =
self;
873 typedef std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
875 Shared *
self = *
reinterpret_cast<Shared**
>(mxGetData(in[0]));
876 Collector_MyFactorPosePoint2::iterator item;
887 auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0],
"ptr_MyFactorPosePoint2");
888 string&
s = *unwrap_shared_ptr< string >(in[1],
"ptr_string");
889 gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[2],
"ptr_gtsamKeyFormatter");
890 obj->print(s,keyFormatter);
896 auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0],
"ptr_MyFactorPosePoint2");
897 string&
s = *unwrap_shared_ptr< string >(in[1],
"ptr_string");
904 auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0],
"ptr_MyFactorPosePoint2");
912 std::streambuf *outbuf = std::cout.rdbuf(&mout);
1158 }
catch(
const std::exception&
e) {
1159 mexErrMsgTxt((
"Exception from gtsam:\n" + std::string(e.what()) +
"\n").c_str());
1162 std::cout.rdbuf(outbuf);
int unwrap< int >(const mxArray *array)
std::set< std::shared_ptr< PrimitiveRefDouble > * > Collector_PrimitiveRefDouble
void TemplatedConstructor_constructor_68(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< std::shared_ptr< MultipleTemplatesIntDouble > * > Collector_MultipleTemplatesIntDouble
void Test_return_TestPtr_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_get_name_47(int nargout, mxArray *out[], int nargin, const mxArray *in[])
PrimitiveRef< double > PrimitiveRefDouble
void PrimitiveRefDouble_constructor_50(int nargout, mxArray *out[], int nargin, const mxArray *in[])
mxArray * wrap_shared_ptr(std::shared_ptr< Class > shared_ptr, const std::string &matlabName, bool isVirtual)
std::set< std::shared_ptr< FunDouble > * > Collector_FunDouble
void Test_set_container_42(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_matrix1_31(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< std::shared_ptr< MyVector3 > * > Collector_MyVector3
void Test_set_name_48(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunRange_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::ofstream out("Result.txt")
void MultipleTemplatesIntFloat_deconstructor_62(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void checkArguments(const string &name, int nargout, int nargin, int expected)
static Collector_FunDouble collector_FunDouble
void FunDouble_collectorInsertAndMakeBase_5(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void _class_RTTIRegister()
void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_arg_EigenConstRef_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat
string unwrap< string >(const mxArray *array)
iterator iter(handle obj)
void Test_print_23(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_get_container_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[])
size_t unwrap< size_t >(const mxArray *array)
void Test_set_value_46(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunRange_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_lambda_20(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyVector12_deconstructor_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static const KeyFormatter DefaultKeyFormatter
GeneralSFMFactor< SfmCamera, Point3 > MyFactor
void TemplatedConstructor_constructor_69(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MultipleTemplates< int, float > MultipleTemplatesIntFloat
void FunDouble_templatedMethod_9(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< std::shared_ptr< MyVector12 > * > Collector_MyVector12
std::set< std::shared_ptr< FunRange > * > Collector_FunRange
static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble
void PrimitiveRefDouble_deconstructor_51(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunDouble_staticMethodWithThis_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunDouble_templatedStaticMethodInt_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
mxArray * wrap< size_t >(const size_t &value)
void PrimitiveRefDouble_collectorInsertAndMakeBase_49(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void ForwardKinematics_collectorInsertAndMakeBase_63(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_markdown_21(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_Test collector_Test
void TemplatedConstructor_deconstructor_72(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_FunRange collector_FunRange
void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_59(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunRange_range_3(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyVector12_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_get_model_ptr_43(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_print_78(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< std::shared_ptr< ForwardKinematics > * > Collector_ForwardKinematics
void MyFactorPosePoint2_deconstructor_75(int nargout, mxArray *out[], int nargin, const mxArray *in[])
double unwrap< double >(const mxArray *array)
const Symbol key1('v', 1)
void Test_return_bool_27(int nargout, mxArray *out[], int nargin, const mxArray *in[])
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, std::shared_ptr< T > > make_shared(Args &&... args)
static Collector_MyVector3 collector_MyVector3
std::set< std::shared_ptr< MyFactorPosePoint2 > * > Collector_MyFactorPosePoint2
MyFactor< gtsam::Pose2, gtsam::Matrix > MyFactorPosePoint2
void Test_collectorInsertAndMakeBase_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_set_model_ptr_44(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Array< int, Dynamic, 1 > v
void Test_return_matrix2_32(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunDouble_sets_8(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunRange_create_4(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyVector12_constructor_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_constructor_74(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyVector3_constructor_54(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_get_value_45(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void ForwardKinematics_constructor_65(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Array< double, 1, 3 > e(1./3., 0.5, 2.)
void Test_constructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MultipleTemplatesIntDouble_deconstructor_60(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< std::shared_ptr< Test > * > Collector_Test
void MyFactorPosePoint2_collectorInsertAndMakeBase_73(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
void Test_return_Point2Ptr_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_set_container_41(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_markdown_22(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_TemplatedConstructor collector_TemplatedConstructor
void MyVector3_collectorInsertAndMakeBase_53(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_create_ptrs_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
mxArray * wrap< int >(const int &value)
void TemplatedConstructor_collectorInsertAndMakeBase_67(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_print_77(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void TemplatedConstructor_constructor_71(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyVector3_deconstructor_55(int nargout, mxArray *out[], int nargin, const mxArray *in[])
mxArray * wrap< double >(const double &value)
MyVector< 12 > MyVector12
void Test_deconstructor_15(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_61(int nargout, mxArray *out[], int nargin, const mxArray *in[])
#define mxUINT32OR64_CLASS
void FunDouble_multiTemplatedMethod_7(int nargout, mxArray *out[], int nargin, const mxArray *in[])
ADT create(const Signature &signature)
void Test_constructor_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_ForwardKinematics collector_ForwardKinematics
mxArray * wrap< string >(const string &value)
void TemplatedConstructor_constructor_70(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunDouble_deconstructor_6(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_double_28(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< std::shared_ptr< TemplatedConstructor > * > Collector_TemplatedConstructor
void ForwardKinematics_deconstructor_66(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_set_container_40(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_field_29(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MyFactorPosePoint2_print_76(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Annotation for function names.
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
MultipleTemplates< int, double > MultipleTemplatesIntDouble
mxArray * wrap< bool >(const bool &value)
bool unwrap< bool >(const mxArray *array)
std::set< std::shared_ptr< MultipleTemplatesIntFloat > * > Collector_MultipleTemplatesIntFloat
void Test_return_int_30(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
void Test_create_MixedPtrs_17(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_pair_33(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_Test_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void FunRange_deconstructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void ForwardKinematics_constructor_64(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MyVector12 collector_MyVector12
const Symbol key2('v', 2)
void PrimitiveRefDouble_Brutal_52(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2