matlab.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
25 #include <gtsam/base/Vector.h>
26 #include <gtsam/base/Matrix.h>
27 #include <gtsam/geometry/Point2.h>
28 #include <gtsam/geometry/Point3.h>
29 
30 using gtsam::Vector;
31 using gtsam::Matrix;
32 using gtsam::Point2;
33 using gtsam::Point3;
34 
35 extern "C" {
36 #include <mex.h>
37 }
38 
39 #include <boost/shared_ptr.hpp>
40 #include <boost/make_shared.hpp>
41 
42 #include <list>
43 #include <string>
44 #include <sstream>
45 #include <typeinfo>
46 #include <set>
47 #include <streambuf>
48 
49 using namespace std;
50 using namespace boost; // not usual, but for conciseness of generated code
51 
52 // start GTSAM Specifics /////////////////////////////////////////////////
53 // to enable Matrix and Vector constructor for SharedGaussian:
54 #define GTSAM_MAGIC_GAUSSIAN
55 // end GTSAM Specifics /////////////////////////////////////////////////
56 
57 #if defined(__LP64__) || defined(_WIN64)
58 // 64-bit
59 #define mxUINT32OR64_CLASS mxUINT64_CLASS
60 #else
61 #define mxUINT32OR64_CLASS mxUINT32_CLASS
62 #endif
63 
64 // "Unique" key to signal calling the matlab object constructor with a raw pointer
65 // to a shared pointer of the same C++ object type as the MATLAB type.
66 // Also present in utilities.h
68  (boost::uint64_t('G') << 56) |
69  (boost::uint64_t('T') << 48) |
70  (boost::uint64_t('S') << 40) |
71  (boost::uint64_t('A') << 32) |
72  (boost::uint64_t('M') << 24) |
73  (boost::uint64_t('p') << 16) |
74  (boost::uint64_t('t') << 8) |
75  (boost::uint64_t('r'));
76 
77 //*****************************************************************************
78 // Utilities
79 //*****************************************************************************
80 
81 void error(const char* str) {
82  mexErrMsgIdAndTxt("wrap:error", str);
83 }
84 
85 mxArray *scalar(mxClassID classid) {
86  mwSize dims[1]; dims[0]=1;
87  return mxCreateNumericArray(1, dims, classid, mxREAL);
88 }
89 
90 void checkScalar(const mxArray* array, const char* str) {
91  int m = mxGetM(array), n = mxGetN(array);
92  if (m!=1 || n!=1)
93  mexErrMsgIdAndTxt("wrap: not a scalar in ", str);
94 }
95 
96 // Replacement streambuf for cout that writes to the MATLAB console
97 // Thanks to http://stackoverflow.com/a/249008
98 class mstream : public std::streambuf {
99 protected:
100  virtual std::streamsize xsputn(const char *s, std::streamsize n) {
101  mexPrintf("%.*s",n,s);
102  return n;
103  }
104  virtual int overflow(int c = EOF) {
105  if (c != EOF) {
106  mexPrintf("%.1s",&c);
107  }
108  return 1;
109  }
110 };
111 
112 //*****************************************************************************
113 // Check arguments
114 //*****************************************************************************
115 
116 void checkArguments(const string& name, int nargout, int nargin, int expected) {
117  stringstream err;
118  err << name << " expects " << expected << " arguments, not " << nargin;
119  if (nargin!=expected)
120  error(err.str().c_str());
121 }
122 
123 //*****************************************************************************
124 // wrapping C++ basis types in MATLAB arrays
125 //*****************************************************************************
126 
127 // default wrapping throws an error: only basis types are allowed in wrap
128 template <typename Class>
129 mxArray* wrap(const Class& value) {
130  error("wrap internal error: attempted wrap of invalid type");
131  return 0;
132 }
133 
134 // specialization to string
135 // wraps into a character array
136 template<>
137 mxArray* wrap<string>(const string& value) {
138  return mxCreateString(value.c_str());
139 }
140 
141 // specialization to char
142 template<>
143 mxArray* wrap<char>(const char& value) {
144  mxArray *result = scalar(mxUINT32OR64_CLASS);
145  *(char*)mxGetData(result) = value;
146  return result;
147 }
148 
149 // specialization to unsigned char
150 template<>
151 mxArray* wrap<unsigned char>(const unsigned char& value) {
152  mxArray *result = scalar(mxUINT32OR64_CLASS);
153  *(unsigned char*)mxGetData(result) = value;
154  return result;
155 }
156 
157 // specialization to bool
158 template<>
159 mxArray* wrap<bool>(const bool& value) {
160  mxArray *result = scalar(mxUINT32OR64_CLASS);
161  *(bool*)mxGetData(result) = value;
162  return result;
163 }
164 
165 // specialization to size_t
166 template<>
167 mxArray* wrap<size_t>(const size_t& value) {
168  mxArray *result = scalar(mxUINT32OR64_CLASS);
169  *(size_t*)mxGetData(result) = value;
170  return result;
171 }
172 
173 // specialization to int
174 template<>
175 mxArray* wrap<int>(const int& value) {
176  mxArray *result = scalar(mxUINT32OR64_CLASS);
177  *(int*)mxGetData(result) = value;
178  return result;
179 }
180 
181 // specialization to double -> just double
182 template<>
183 mxArray* wrap<double>(const double& value) {
184  return mxCreateDoubleScalar(value);
185 }
186 
187 // wrap a const Eigen vector into a double vector
188 mxArray* wrap_Vector(const gtsam::Vector& v) {
189  int m = v.size();
190  mxArray *result = mxCreateDoubleMatrix(m, 1, mxREAL);
191  double *data = mxGetPr(result);
192  for (int i=0;i<m;i++) data[i]=v(i);
193  return result;
194 }
195 
196 // specialization to Eigen vector -> double vector
197 template<>
198 mxArray* wrap<gtsam::Vector >(const gtsam::Vector& v) {
199  return wrap_Vector(v);
200 }
201 
202 // specialization to Eigen vector -> double vector
203 template<>
204 mxArray* wrap<gtsam::Point2 >(const gtsam::Point2& v) {
205  return wrap_Vector(v);
206 }
207 
208 // specialization to Eigen vector -> double vector
209 template<>
210 mxArray* wrap<gtsam::Point3 >(const gtsam::Point3& v) {
211  return wrap_Vector(v);
212 }
213 
214 // wrap a const Eigen MATRIX into a double matrix
215 mxArray* wrap_Matrix(const gtsam::Matrix& A) {
216  int m = A.rows(), n = A.cols();
217 #ifdef DEBUG_WRAP
218  mexPrintf("wrap_Matrix called with A = \n", m,n);
219  gtsam::print(A);
220 #endif
221  mxArray *result = mxCreateDoubleMatrix(m, n, mxREAL);
222  double *data = mxGetPr(result);
223  // converts from column-major to row-major
224  for (int j=0;j<n;j++) for (int i=0;i<m;i++,data++) *data = A(i,j);
225  return result;
226 }
227 
228 // specialization to Eigen MATRIX -> double matrix
229 template<>
230 mxArray* wrap<gtsam::Matrix >(const gtsam::Matrix& A) {
231  return wrap_Matrix(A);
232 }
233 
234 //*****************************************************************************
235 // unwrapping MATLAB arrays into C++ basis types
236 //*****************************************************************************
237 
238 // default unwrapping throws an error
239 // as wrap only supports passing a reference or one of the basic types
240 template <typename T>
241 T unwrap(const mxArray* array) {
242  error("wrap internal error: attempted unwrap of invalid type");
243  return T();
244 }
245 
246 // specialization to string
247 // expects a character array
248 // Warning: relies on mxChar==char
249 template<>
250 string unwrap<string>(const mxArray* array) {
251  char *data = mxArrayToString(array);
252  if (data==NULL) error("unwrap<string>: not a character array");
253  string str(data);
254  mxFree(data);
255  return str;
256 }
257 
258 // Check for 64-bit, as Mathworks says mxGetScalar only good for 32 bit
259 template <typename T>
260 T myGetScalar(const mxArray* array) {
261  switch (mxGetClassID(array)) {
262  case mxINT64_CLASS:
263  return (T) *(boost::int64_t*) mxGetData(array);
264  case mxUINT64_CLASS:
265  return (T) *(boost::uint64_t*) mxGetData(array);
266  default:
267  // hope for the best!
268  return (T) mxGetScalar(array);
269  }
270 }
271 
272 // specialization to bool
273 template<>
274 bool unwrap<bool>(const mxArray* array) {
275  checkScalar(array,"unwrap<bool>");
276  return myGetScalar<bool>(array);
277 }
278 
279 // specialization to char
280 template<>
281 char unwrap<char>(const mxArray* array) {
282  checkScalar(array,"unwrap<char>");
283  return myGetScalar<char>(array);
284 }
285 
286 // specialization to unsigned char
287 template<>
288 unsigned char unwrap<unsigned char>(const mxArray* array) {
289  checkScalar(array,"unwrap<unsigned char>");
290  return myGetScalar<unsigned char>(array);
291 }
292 
293 // specialization to int
294 template<>
295 int unwrap<int>(const mxArray* array) {
296  checkScalar(array,"unwrap<int>");
297  return myGetScalar<int>(array);
298 }
299 
300 // specialization to size_t
301 template<>
302 size_t unwrap<size_t>(const mxArray* array) {
303  checkScalar(array, "unwrap<size_t>");
304  return myGetScalar<size_t>(array);
305 }
306 
307 // specialization to double
308 template<>
309 double unwrap<double>(const mxArray* array) {
310  checkScalar(array,"unwrap<double>");
311  return myGetScalar<double>(array);
312 }
313 
314 // specialization to Eigen vector
315 template<>
317  int m = mxGetM(array), n = mxGetN(array);
318  if (mxIsDouble(array)==false || n!=1) error("unwrap<vector>: not a vector");
319 #ifdef DEBUG_WRAP
320  mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n);
321 #endif
322  double* data = (double*)mxGetData(array);
323  gtsam::Vector v(m);
324  for (int i=0;i<m;i++,data++) v(i) = *data;
325 #ifdef DEBUG_WRAP
326  gtsam::print(v);
327 #endif
328  return v;
329 }
330 
331 // specialization to Point2
332 template<>
334  int m = mxGetM(array), n = mxGetN(array);
335  if (mxIsDouble(array)==false || n!=1) error("unwrap<vector>: not a vector");
336 #ifdef DEBUG_WRAP
337  mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n);
338 #endif
339  double* data = (double*)mxGetData(array);
340  gtsam::Vector v(m);
341  for (int i=0;i<m;i++,data++) v(i) = *data;
342 #ifdef DEBUG_WRAP
343  gtsam::print(v);
344 #endif
345  return v;
346 }
347 
348 // specialization to Point3
349 template<>
351  int m = mxGetM(array), n = mxGetN(array);
352  if (mxIsDouble(array)==false || n!=1) error("unwrap<vector>: not a vector");
353 #ifdef DEBUG_WRAP
354  mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n);
355 #endif
356  double* data = (double*)mxGetData(array);
357  gtsam::Vector v(m);
358  for (int i=0;i<m;i++,data++) v(i) = *data;
359 #ifdef DEBUG_WRAP
360  gtsam::print(v);
361 #endif
362  return v;
363 }
364 
365 
366 // specialization to Eigen matrix
367 template<>
369  if (mxIsDouble(array)==false) error("unwrap<matrix>: not a matrix");
370  int m = mxGetM(array), n = mxGetN(array);
371 #ifdef DEBUG_WRAP
372  mexPrintf("unwrap< gtsam::Matrix > called with %dx%d argument\n", m,n);
373 #endif
374  double* data = (double*)mxGetData(array);
375  gtsam::Matrix A(m,n);
376  // converts from row-major to column-major
377  for (int j=0;j<n;j++) for (int i=0;i<m;i++,data++) A(i,j) = *data;
378 #ifdef DEBUG_WRAP
379  gtsam::print(A);
380 #endif
381  return A;
382 }
383 
384 /*
385  [create_object] creates a MATLAB proxy class object with a mexhandle
386  in the self property. Matlab does not allow the creation of matlab
387  objects from within mex files, hence we resort to an ugly trick: we
388  invoke the proxy class constructor by calling MATLAB with a special
389  uint64 value ptr_constructor_key and the pointer itself. MATLAB
390  allocates the object. Then, the special constructor in our wrap code
391  that is activated when the ptr_constructor_key is passed in passes
392  the pointer back into a C++ function to add the pointer to its
393  collector. We go through this extra "C++ to MATLAB to C++ step" in
394  order to be able to add to the collector could be in a different wrap
395  module.
396 */
397 mxArray* create_object(const std::string& classname, void *pointer, bool isVirtual, const char *rttiName) {
398  mxArray *result;
399  mxArray *input[3];
400  int nargin = 2;
401  // First input argument is pointer constructor key
402  input[0] = mxCreateNumericMatrix(1, 1, mxUINT64_CLASS, mxREAL);
403  *reinterpret_cast<boost::uint64_t*>(mxGetData(input[0])) = ptr_constructor_key;
404  // Second input argument is the pointer
405  input[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
406  *reinterpret_cast<void**>(mxGetData(input[1])) = pointer;
407  // If the class is virtual, use the RTTI name to look up the derived matlab type
408  const char *derivedClassName;
409  if(isVirtual) {
410  const mxArray *rttiRegistry = mexGetVariablePtr("global", "gtsamwrap_rttiRegistry");
411  if(!rttiRegistry)
412  mexErrMsgTxt(
413  "gtsam wrap: RTTI registry is missing - it could have been cleared from the workspace."
414  " You can issue 'clear all' to completely clear the workspace, and next time a wrapped object is"
415  " created the RTTI registry will be recreated.");
416  const mxArray *derivedNameMx = mxGetField(rttiRegistry, 0, rttiName);
417  if(!derivedNameMx)
418  mexErrMsgTxt((
419  "gtsam wrap: The derived class type " + string(rttiName) + " was not found in the RTTI registry. "
420  "Try calling 'clear all' twice consecutively - we have seen things not get unloaded properly the "
421  "first time. If this does not work, this may indicate an inconsistency in your wrap interface file. "
422  "The most likely cause for this is that a base class was marked virtual in the wrap interface "
423  "definition header file for gtsam or for your module, but a derived type was returned by a C++ "
424  "function and that derived type was not marked virtual (or was not specified in the wrap interface "
425  "definition header at all).").c_str());
426  size_t strLen = mxGetN(derivedNameMx);
427  char *buf = new char[strLen+1];
428  if(mxGetString(derivedNameMx, buf, strLen+1))
429  mexErrMsgTxt("gtsam wrap: Internal error reading RTTI table, try 'clear all' to clear your workspace and reinitialize the toolbox.");
430  derivedClassName = buf;
431  input[2] = mxCreateString("void");
432  nargin = 3;
433  } else {
434  derivedClassName = classname.c_str();
435  }
436  // Call special pointer constructor, which sets 'self'
437  mexCallMATLAB(1,&result, nargin, input, derivedClassName);
438  // Deallocate our memory
439  mxDestroyArray(input[0]);
440  mxDestroyArray(input[1]);
441  if(isVirtual) {
442  mxDestroyArray(input[2]);
443  delete[] derivedClassName;
444  }
445  return result;
446 }
447 
448 /*
449  When the user calls a method that returns a shared pointer, we create
450  an ObjectHandle from the shared_pointer and return it as a proxy
451  class to matlab.
452 */
453 template <typename Class>
454 mxArray* wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const std::string& matlabName, bool isVirtual) {
455  // Create actual class object from out pointer
456  mxArray* result;
457  if(isVirtual) {
458  boost::shared_ptr<void> void_ptr(shared_ptr);
459  result = create_object(matlabName, &void_ptr, isVirtual, typeid(*shared_ptr).name());
460  } else {
461  boost::shared_ptr<Class> *heapPtr = new boost::shared_ptr<Class>(shared_ptr);
462  result = create_object(matlabName, heapPtr, isVirtual, "");
463  }
464  return result;
465 }
466 
467 template <typename Class>
468 boost::shared_ptr<Class> unwrap_shared_ptr(const mxArray* obj, const string& propertyName) {
469 
470  mxArray* mxh = mxGetProperty(obj,0, propertyName.c_str());
471  if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh)
472  || mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error(
473  "Parameter is not an Shared type.");
474 
475  boost::shared_ptr<Class>* spp = *reinterpret_cast<boost::shared_ptr<Class>**> (mxGetData(mxh));
476  return *spp;
477 }
478 
480 //template <>
481 //Vector unwrap_shared_ptr<Vector>(const mxArray* obj, const string& propertyName) {
482 // bool unwrap_shared_ptr_Vector_attempted = false;
483 // BOOST_STATIC_ASSERT(unwrap_shared_ptr_Vector_attempted, "Vector cannot be unwrapped as a shared pointer");
484 // return Vector();
485 //}
486 
488 //template <>
489 //Matrix unwrap_shared_ptr<Matrix>(const mxArray* obj, const string& propertyName) {
490 // bool unwrap_shared_ptr_Matrix_attempted = false;
491 // BOOST_STATIC_ASSERT(unwrap_shared_ptr_Matrix_attempted, "Matrix cannot be unwrapped as a shared pointer");
492 // return Matrix();
493 //}
494 
int unwrap< int >(const mxArray *array)
Definition: matlab.h:295
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Matrix3f m
int array[24]
gtsam::Vector unwrap< gtsam::Vector >(const mxArray *array)
Definition: matlab.h:316
Matrix expected
Definition: testMatrix.cpp:974
char unwrap< char >(const mxArray *array)
Definition: matlab.h:281
void checkArguments(const string &name, int nargout, int nargin, int expected)
Definition: matlab.h:116
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
Definition: numpy.h:543
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::Point3 unwrap< gtsam::Point3 >(const mxArray *array)
Definition: matlab.h:350
Definition: Half.h:150
string unwrap< string >(const mxArray *array)
Definition: matlab.h:250
size_t unwrap< size_t >(const mxArray *array)
Definition: matlab.h:302
unsigned char unwrap< unsigned char >(const mxArray *array)
Definition: matlab.h:288
mxArray * wrap_shared_ptr(boost::shared_ptr< Class > shared_ptr, const std::string &matlabName, bool isVirtual)
Definition: matlab.h:454
mxArray * wrap< size_t >(const size_t &value)
Definition: matlab.h:167
const char * c_str(Args &&...args)
Definition: internals.h:314
T unwrap(const mxArray *array)
Definition: matlab.h:241
boost::shared_ptr< Class > unwrap_shared_ptr(const mxArray *obj, const string &propertyName)
Definition: matlab.h:468
mxArray * create_object(const std::string &classname, void *pointer, bool isVirtual, const char *rttiName)
Definition: matlab.h:397
Eigen::VectorXd Vector
Definition: Vector.h:38
double unwrap< double >(const mxArray *array)
Definition: matlab.h:309
Values result
virtual int overflow(int c=EOF)
Definition: matlab.h:104
Definition: pytypes.h:928
signed __int64 int64_t
Definition: ms_stdint.h:94
mxArray * wrap_Vector(const gtsam::Vector &v)
Definition: matlab.h:188
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
Eigen::Triplet< double > T
int data[]
mxArray * wrap< char >(const char &value)
Definition: matlab.h:143
virtual std::streamsize xsputn(const char *s, std::streamsize n)
Definition: matlab.h:100
RealScalar s
#define NULL
Definition: ccolamd.c:609
mxArray * wrap< unsigned char >(const unsigned char &value)
Definition: matlab.h:151
gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray *array)
Definition: matlab.h:368
mxArray * wrap< int >(const int &value)
Definition: matlab.h:175
typedef and functions to augment Eigen&#39;s VectorXd
mxArray * wrap< double >(const double &value)
Definition: matlab.h:183
#define mxUINT32OR64_CLASS
Definition: matlab.h:61
static const boost::uint64_t ptr_constructor_key
Definition: matlab.h:67
void checkScalar(const mxArray *array, const char *str)
Definition: matlab.h:90
mxArray * wrap(const Class &value)
Definition: matlab.h:129
mxArray * wrap< string >(const string &value)
Definition: matlab.h:137
3D Point
gtsam::Point2 unwrap< gtsam::Point2 >(const mxArray *array)
Definition: matlab.h:333
Annotation for function names.
Definition: attr.h:36
Vector3 Point3
Definition: Point3.h:35
mxArray * wrap< bool >(const bool &value)
Definition: matlab.h:159
bool unwrap< bool >(const mxArray *array)
Definition: matlab.h:274
2D Point
mxArray * scalar(mxClassID classid)
Definition: matlab.h:85
mxArray * wrap_Matrix(const gtsam::Matrix &A)
Definition: matlab.h:215
void error(const char *str)
Definition: matlab.h:81
Definition: matlab.h:98
std::ptrdiff_t j
T myGetScalar(const mxArray *array)
Definition: matlab.h:260


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:46