Go to the documentation of this file. 1 #include <gtwrap/matlab.h>
13 std::streambuf *outbuf = std::cout.rdbuf(&mout);
15 bool anyDeleted =
false;
19 "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n"
20 "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n"
21 "module, so that your recompiled module is used instead of the old one." << endl;
22 std::cout.rdbuf(outbuf);
26 const mxArray *alreadyCreated = mexGetVariablePtr(
"global",
"gtsam_functions_rttiRegistry_created");
28 std::map<std::string, std::string> types;
32 mxArray *registry = mexGetVariable(
"global",
"gtsamwrap_rttiRegistry");
34 registry = mxCreateStructMatrix(1, 1, 0,
NULL);
35 typedef std::pair<std::string, std::string> StringPair;
36 for(
const StringPair& rtti_matlab: types) {
37 int fieldId = mxAddField(registry, rtti_matlab.first.c_str());
39 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
41 mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str());
42 mxSetFieldByNumber(registry, 0, fieldId, matlabName);
44 if(mexPutVariable(
"global",
"gtsamwrap_rttiRegistry", registry) != 0) {
45 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
47 mxDestroyArray(registry);
49 mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL);
50 if(mexPutVariable(
"global",
"gtsam_functions_rttiRegistry_created", newAlreadyCreated) != 0) {
51 mexErrMsgTxt(
"gtsam wrap: Error indexing RTTI types, inheritance will not work correctly");
53 mxDestroyArray(newAlreadyCreated);
57 void load2D_0(
int nargout, mxArray *
out[],
int nargin,
const mxArray *in[])
61 std::shared_ptr<Test>
model = unwrap_shared_ptr< Test >(in[1],
"ptr_Test");
69 void load2D_1(
int nargout, mxArray *
out[],
int nargin,
const mxArray *in[])
73 std::shared_ptr<gtsam::noiseModel::Diagonal>
model = unwrap_shared_ptr< gtsam::noiseModel::Diagonal >(in[1],
"ptr_gtsamnoiseModelDiagonal");
81 void load2D_2(
int nargout, mxArray *
out[],
int nargin,
const mxArray *in[])
93 out[0] = wrap< Vector >(aGlobalFunction());
99 out[0] = wrap< Vector >(overloadedGlobalFunction(
a));
106 out[0] = wrap< Vector >(overloadedGlobalFunction(
a,
b));
110 checkArguments(
"MultiTemplatedFunctionStringSize_tDouble",nargout,nargin,2);
111 T&
x = *unwrap_shared_ptr< T >(in[0],
"ptr_T");
117 checkArguments(
"MultiTemplatedFunctionDoubleSize_tDouble",nargout,nargin,2);
118 T&
x = *unwrap_shared_ptr< T >(in[0],
"ptr_T");
138 DefaultFuncInt(123,0);
143 string&
s = *unwrap_shared_ptr< string >(in[0],
"ptr_string");
144 string&
name = *unwrap_shared_ptr< string >(in[1],
"ptr_string");
145 DefaultFuncString(
s,
name);
150 string&
s = *unwrap_shared_ptr< string >(in[0],
"ptr_string");
151 DefaultFuncString(
s,
"");
156 DefaultFuncString(
"hello",
"");
161 gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[0],
"ptr_gtsamKeyFormatter");
162 DefaultFuncObj(keyFormatter);
177 DefaultFuncZero(
a,
b,
c,
d,
e);
186 DefaultFuncZero(
a,
b,
c,
d,
false);
194 DefaultFuncZero(
a,
b,
c,0,
false);
201 DefaultFuncZero(
a,
b,0.0,0,
false);
206 std::vector<int>&
i = *unwrap_shared_ptr< std::vector<int> >(in[0],
"ptr_stdvectorint");
207 std::vector<string>&
s = *unwrap_shared_ptr< std::vector<string> >(in[1],
"ptr_stdvectorstring");
208 DefaultFuncVector(
i,
s);
213 std::vector<int>&
i = *unwrap_shared_ptr< std::vector<int> >(in[0],
"ptr_stdvectorint");
214 DefaultFuncVector(
i,{
"borglab",
"gtsam"});
219 DefaultFuncVector({1, 2, 3},{
"borglab",
"gtsam"});
221 void setPose_23(
int nargout, mxArray *
out[],
int nargin,
const mxArray *in[])
224 gtsam::Pose3&
pose = *unwrap_shared_ptr< gtsam::Pose3 >(in[0],
"ptr_gtsamPose3");
227 void setPose_24(
int nargout, mxArray *
out[],
int nargin,
const mxArray *in[])
236 gtsam::Ordering& frontalKeys = *unwrap_shared_ptr< gtsam::Ordering >(in[1],
"ptr_gtsamOrdering");
244 gtsam::Rot3&
t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0],
"ptr_gtsamRot3");
245 TemplatedFunctionRot3(
t);
251 std::streambuf *outbuf = std::cout.rdbuf(&mout);
341 }
catch(
const std::exception&
e) {
342 mexErrMsgTxt((
"Exception from gtsam:\n" + std::string(
e.what()) +
"\n").c_str());
345 std::cout.rdbuf(outbuf);
void DefaultFuncObj_14(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void load2D_1(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Annotation for function names.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
void EliminateDiscrete_25(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void aGlobalFunction_3(int nargout, mxArray *out[], int nargin, const mxArray *in[])
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
mxArray * wrap< double >(const double &value)
void DefaultFuncZero_16(int nargout, mxArray *out[], int nargin, const mxArray *in[])
const GaussianFactorGraph factors
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 load2D_2(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncString_13(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncVector_20(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void TemplatedFunctionRot3_26(int nargout, mxArray *out[], int nargin, const mxArray *in[])
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MultiTemplatedFunctionStringSize_tDouble_6(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void checkArguments(const string &name, int nargout, int nargin, int expected)
size_t unwrap< size_t >(const mxArray *array)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
void DefaultFuncVector_21(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void _functions_RTTIRegister()
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for DiscreteFactorGraph.
int unwrap< int >(const mxArray *array)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
void DefaultFuncZero_19(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncZero_17(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)
void DefaultFuncString_12(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void setPose_23(int nargout, mxArray *out[], int nargin, const mxArray *in[])
A small structure to hold a non zero as a triplet (i,j,value).
noiseModel::Diagonal::shared_ptr model
std::ofstream out("Result.txt")
bool unwrap< bool >(const mxArray *array)
void load2D_0(int nargout, mxArray *out[], int nargin, const mxArray *in[])
GraphAndValues load2D(const std::string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
void overloadedGlobalFunction_5(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncObj_15(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void setPose_24(int nargout, mxArray *out[], int nargin, const mxArray *in[])
string unwrap< string >(const mxArray *array)
void DefaultFuncVector_22(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncInt_8(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncInt_10(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncInt_9(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void DefaultFuncZero_18(int nargout, mxArray *out[], int nargin, const mxArray *in[])
double unwrap< double >(const mxArray *array)
void DefaultFuncString_11(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void MultiTemplatedFunctionDoubleSize_tDouble_7(int nargout, mxArray *out[], int nargin, const mxArray *in[])
void overloadedGlobalFunction_4(int nargout, mxArray *out[], int nargin, const mxArray *in[])
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:19