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> 42 std::streambuf *outbuf = std::cout.rdbuf(&mout);
44 bool anyDeleted =
false;
101 "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" 102 "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" 103 "module, so that your recompiled module is used instead of the old one." << endl;
104 std::cout.rdbuf(outbuf);
108 const mxArray *alreadyCreated = mexGetVariablePtr(
"global",
"gtsam_functions_rttiRegistry_created");
109 if(!alreadyCreated) {
110 std::map<std::string, std::string> types;
112 mxArray *registry = mexGetVariable(
"global",
"gtsamwrap_rttiRegistry");
114 registry = mxCreateStructMatrix(1, 1, 0,
NULL);
115 typedef std::pair<std::string, std::string> StringPair;
116 for(
const StringPair& rtti_matlab: types) {
117 int fieldId = mxAddField(registry, rtti_matlab.first.c_str());
119 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
120 mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str());
121 mxSetFieldByNumber(registry, 0, fieldId, matlabName);
123 if(mexPutVariable(
"global",
"gtsamwrap_rttiRegistry", registry) != 0)
124 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
125 mxDestroyArray(registry);
127 mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL);
128 if(mexPutVariable(
"global",
"gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0)
129 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
130 mxDestroyArray(newAlreadyCreated);
134 void load2D_0(
int nargout, mxArray *out[],
int nargin,
const mxArray *in[])
138 boost::shared_ptr<Test>
model = unwrap_shared_ptr< Test >(in[1],
"ptr_Test");
142 auto pairResult =
load2D(filename,model,maxID,addNoise,smart);
143 out[0] =
wrap_shared_ptr(pairResult.first,
"gtsam.NonlinearFactorGraph",
false);
146 void load2D_1(
int nargout, mxArray *out[],
int nargin,
const mxArray *in[])
150 boost::shared_ptr<gtsam::noiseModel::Diagonal>
model = unwrap_shared_ptr< gtsam::noiseModel::Diagonal >(in[1],
"ptr_gtsamnoiseModelDiagonal");
154 auto pairResult =
load2D(filename,model,maxID,addNoise,smart);
155 out[0] =
wrap_shared_ptr(pairResult.first,
"gtsam.NonlinearFactorGraph",
false);
158 void load2D_2(
int nargout, mxArray *out[],
int nargin,
const mxArray *in[])
162 boost::shared_ptr<gtsam::noiseModel::Diagonal>
model = unwrap_shared_ptr< gtsam::noiseModel::Diagonal >(in[1],
"ptr_gtsamnoiseModelDiagonal");
163 auto pairResult =
load2D(filename,model);
164 out[0] =
wrap_shared_ptr(pairResult.first,
"gtsam.NonlinearFactorGraph",
false);
170 out[0] = wrap< Vector >(aGlobalFunction());
176 out[0] = wrap< Vector >(overloadedGlobalFunction(a));
183 out[0] = wrap< Vector >(overloadedGlobalFunction(a,b));
187 checkArguments(
"MultiTemplatedFunctionStringSize_tDouble",nargout,nargin,2);
188 T&
x = *unwrap_shared_ptr< T >(in[0],
"ptr_T");
190 out[0] =
wrap< double >(MultiTemplatedFunctionStringSize_tDouble(x,y));
194 checkArguments(
"MultiTemplatedFunctionDoubleSize_tDouble",nargout,nargin,2);
195 T&
x = *unwrap_shared_ptr< T >(in[0],
"ptr_T");
197 out[0] =
wrap< double >(MultiTemplatedFunctionDoubleSize_tDouble(x,y));
208 string&
s = *unwrap_shared_ptr< string >(in[0],
"ptr_string");
209 string&
name = *unwrap_shared_ptr< string >(in[1],
"ptr_string");
210 DefaultFuncString(s,name);
215 gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[0],
"ptr_gtsamKeyFormatter");
216 DefaultFuncObj(keyFormatter);
221 gtsam::Rot3&
t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0],
"ptr_gtsamRot3");
222 TemplatedFunctionRot3(t);
225 void mexFunction(
int nargout, mxArray *out[],
int nargin,
const mxArray *in[])
228 std::streambuf *outbuf = std::cout.rdbuf(&mout);
237 load2D_0(nargout, out, nargin-1, in+1);
240 load2D_1(nargout, out, nargin-1, in+1);
243 load2D_2(nargout, out, nargin-1, in+1);
273 }
catch(
const std::exception&
e) {
274 mexErrMsgTxt((
"Exception from gtsam:\n" + std::string(e.what()) +
"\n").c_str());
277 std::cout.rdbuf(outbuf);
int unwrap< int >(const mxArray *array)
MyVector< 12 > MyVector12
void DefaultFuncString_9(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< Test > * > Collector_Test
MyFactor< gtsam::Pose2, gtsam::Matrix > MyFactorPosePoint2
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_FunRange collector_FunRange
std::set< boost::shared_ptr< MultipleTemplatesIntDouble > * > Collector_MultipleTemplatesIntDouble
noiseModel::Diagonal::shared_ptr model
void checkArguments(const string &name, int nargout, int nargin, int expected)
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
void _functions_RTTIRegister()
std::set< boost::shared_ptr< MyVector12 > * > Collector_MyVector12
void overloadedGlobalFunction_4(int nargout, mxArray *out[], int nargin, const mxArray *in[])
string unwrap< string >(const mxArray *array)
iterator iter(handle obj)
std::set< boost::shared_ptr< PrimitiveRefDouble > * > Collector_PrimitiveRefDouble
std::set< boost::shared_ptr< MyFactorPosePoint2 > * > Collector_MyFactorPosePoint2
size_t unwrap< size_t >(const mxArray *array)
std::set< boost::shared_ptr< MyVector12 > * > Collector_MyVector12
MultipleTemplates< int, float > MultipleTemplatesIntFloat
mxArray * wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const std::string &matlabName, bool isVirtual)
GeneralSFMFactor< SfmCamera, Point3 > MyFactor
std::set< boost::shared_ptr< MultipleTemplatesIntDouble > * > Collector_MultipleTemplatesIntDouble
void load2D_1(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void aGlobalFunction_3(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MyVector3 collector_MyVector3
std::set< boost::shared_ptr< FunRange > * > Collector_FunRange
std::set< boost::shared_ptr< MultipleTemplatesIntFloat > * > Collector_MultipleTemplatesIntFloat
std::set< boost::shared_ptr< MyVector3 > * > Collector_MyVector3
double unwrap< double >(const mxArray *array)
std::set< boost::shared_ptr< MyFactorPosePoint2 > * > Collector_MyFactorPosePoint2
static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble
void load2D_2(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void TemplatedFunctionRot3_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble
static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat
std::set< boost::shared_ptr< Test > * > Collector_Test
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
std::set< boost::shared_ptr< FunDouble > * > Collector_FunDouble
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::set< boost::shared_ptr< MultipleTemplatesIntFloat > * > Collector_MultipleTemplatesIntFloat
std::set< boost::shared_ptr< PrimitiveRefDouble > * > Collector_PrimitiveRefDouble
std::set< boost::shared_ptr< FunDouble > * > Collector_FunDouble
void overloadedGlobalFunction_5(int nargout, mxArray *out[], int nargin, const mxArray *in[])
mxArray * wrap< double >(const double &value)
void MultiTemplatedFunctionStringSize_tDouble_6(int nargout, mxArray *out[], int nargin, const mxArray *in[])
std::set< boost::shared_ptr< MyVector3 > * > Collector_MyVector3
static Collector_Test collector_Test
std::set< boost::shared_ptr< FunRange > * > Collector_FunRange
void DefaultFuncInt_8(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void load2D_0(int nargout, mxArray *out[], int nargin, const mxArray *in[])
MultipleTemplates< int, double > MultipleTemplatesIntDouble
static Collector_MyVector12 collector_MyVector12
void DefaultFuncObj_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2
static Collector_FunDouble collector_FunDouble
void MultiTemplatedFunctionDoubleSize_tDouble_7(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Annotation for function names.
bool unwrap< bool >(const mxArray *array)
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
PrimitiveRef< double > PrimitiveRefDouble