wrap_mods_inheritance branch - Can now pass derived classes in as base class arguments (i.e. pass gtsamPose2 where gtsamValues.insert expects gtsamValue)
parent
3c27daae18
commit
8a8b27005f
26
gtsam.h
26
gtsam.h
|
@ -65,14 +65,13 @@ namespace gtsam {
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
||||||
class Value {
|
class Value {
|
||||||
|
// No constructors because this is an abstract class
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
bool equals(const gtsam::Value& expected, double tol) const;
|
|
||||||
|
|
||||||
// Manifold
|
// Manifold
|
||||||
size_t dim() const;
|
size_t dim() const;
|
||||||
gtsam::Value retract(Vector v) const;
|
|
||||||
Vector localCoordinates(const gtsam::Value& t2) const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class LieVector : gtsam::Value {
|
class LieVector : gtsam::Value {
|
||||||
|
@ -107,7 +106,7 @@ class LieVector : gtsam::Value {
|
||||||
// geometry
|
// geometry
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
||||||
class Point2 {
|
class Point2 : gtsam::Value {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
Point2();
|
Point2();
|
||||||
Point2(double x, double y);
|
Point2(double x, double y);
|
||||||
|
@ -139,7 +138,7 @@ class Point2 {
|
||||||
Vector vector() const;
|
Vector vector() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class StereoPoint2 {
|
class StereoPoint2 : gtsam::Value {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
StereoPoint2();
|
StereoPoint2();
|
||||||
StereoPoint2(double uL, double uR, double v);
|
StereoPoint2(double uL, double uR, double v);
|
||||||
|
@ -168,7 +167,7 @@ class StereoPoint2 {
|
||||||
Vector vector() const;
|
Vector vector() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Point3 {
|
class Point3 : gtsam::Value {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
Point3();
|
Point3();
|
||||||
Point3(double x, double y, double z);
|
Point3(double x, double y, double z);
|
||||||
|
@ -201,7 +200,7 @@ class Point3 {
|
||||||
double z() const;
|
double z() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Rot2 {
|
class Rot2 : gtsam::Value {
|
||||||
// Standard Constructors and Named Constructors
|
// Standard Constructors and Named Constructors
|
||||||
Rot2();
|
Rot2();
|
||||||
Rot2(double theta);
|
Rot2(double theta);
|
||||||
|
@ -243,7 +242,7 @@ class Rot2 {
|
||||||
Matrix matrix() const;
|
Matrix matrix() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Rot3 {
|
class Rot3 : gtsam::Value {
|
||||||
// Standard Constructors and Named Constructors
|
// Standard Constructors and Named Constructors
|
||||||
Rot3();
|
Rot3();
|
||||||
Rot3(Matrix R);
|
Rot3(Matrix R);
|
||||||
|
@ -295,7 +294,7 @@ class Rot3 {
|
||||||
// Vector toQuaternion() const; // FIXME: Can't cast to Vector properly
|
// Vector toQuaternion() const; // FIXME: Can't cast to Vector properly
|
||||||
};
|
};
|
||||||
|
|
||||||
class Pose2 {
|
class Pose2 : gtsam::Value {
|
||||||
// Standard Constructor
|
// Standard Constructor
|
||||||
Pose2();
|
Pose2();
|
||||||
Pose2(double x, double y, double theta);
|
Pose2(double x, double y, double theta);
|
||||||
|
@ -341,7 +340,7 @@ class Pose2 {
|
||||||
Matrix matrix() const;
|
Matrix matrix() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Pose3 {
|
class Pose3 : gtsam::Value {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
Pose3();
|
Pose3();
|
||||||
Pose3(const gtsam::Pose3& pose);
|
Pose3(const gtsam::Pose3& pose);
|
||||||
|
@ -389,7 +388,7 @@ class Pose3 {
|
||||||
double range(const gtsam::Pose3& pose); // FIXME: shadows other range
|
double range(const gtsam::Pose3& pose); // FIXME: shadows other range
|
||||||
};
|
};
|
||||||
|
|
||||||
class Cal3_S2 {
|
class Cal3_S2 : gtsam::Value {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
Cal3_S2();
|
Cal3_S2();
|
||||||
Cal3_S2(double fx, double fy, double s, double u0, double v0);
|
Cal3_S2(double fx, double fy, double s, double u0, double v0);
|
||||||
|
@ -439,7 +438,7 @@ class Cal3_S2Stereo {
|
||||||
double baseline() const;
|
double baseline() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class CalibratedCamera {
|
class CalibratedCamera : gtsam::Value {
|
||||||
// Standard Constructors and Named Constructors
|
// Standard Constructors and Named Constructors
|
||||||
CalibratedCamera();
|
CalibratedCamera();
|
||||||
CalibratedCamera(const gtsam::Pose3& pose);
|
CalibratedCamera(const gtsam::Pose3& pose);
|
||||||
|
@ -469,7 +468,7 @@ class CalibratedCamera {
|
||||||
double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods
|
double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods
|
||||||
};
|
};
|
||||||
|
|
||||||
class SimpleCamera {
|
class SimpleCamera : gtsam::Value {
|
||||||
// Standard Constructors and Named Constructors
|
// Standard Constructors and Named Constructors
|
||||||
SimpleCamera();
|
SimpleCamera();
|
||||||
SimpleCamera(const gtsam::Pose3& pose);
|
SimpleCamera(const gtsam::Pose3& pose);
|
||||||
|
@ -942,6 +941,7 @@ class Values {
|
||||||
Values();
|
Values();
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
|
void insert(size_t j, const gtsam::Value& value);
|
||||||
bool exists(size_t j) const;
|
bool exists(size_t j) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -36,6 +36,8 @@ void Class::matlab_proxy(const string& classFile, const string& wrapperName, Fil
|
||||||
|
|
||||||
// get the name of actual matlab object
|
// get the name of actual matlab object
|
||||||
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
|
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
|
||||||
|
const string matlabBaseName = wrap::qualifiedName("", qualifiedParent);
|
||||||
|
const string cppBaseName = wrap::qualifiedName("::", qualifiedParent);
|
||||||
|
|
||||||
// emit class proxy code
|
// emit class proxy code
|
||||||
// we want our class to inherit the handle class for memory purposes
|
// we want our class to inherit the handle class for memory purposes
|
||||||
|
@ -65,15 +67,18 @@ void Class::matlab_proxy(const string& classFile, const string& wrapperName, Fil
|
||||||
BOOST_FOREACH(ArgumentList a, constructor.args_list)
|
BOOST_FOREACH(ArgumentList a, constructor.args_list)
|
||||||
{
|
{
|
||||||
const int id = functionNames.size();
|
const int id = functionNames.size();
|
||||||
constructor.proxy_fragment(proxyFile, wrapperName, matlabName, id, a);
|
constructor.proxy_fragment(proxyFile, wrapperName, matlabName, matlabBaseName, id, a);
|
||||||
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
const string wrapFunctionName = constructor.wrapper_fragment(wrapperFile,
|
||||||
cppName, matlabName, id, using_namespaces, includes, a);
|
cppName, matlabName, cppBaseName, id, using_namespaces, a);
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
functionNames.push_back(wrapFunctionName);
|
functionNames.push_back(wrapFunctionName);
|
||||||
}
|
}
|
||||||
proxyFile.oss << " else\n";
|
proxyFile.oss << " else\n";
|
||||||
proxyFile.oss << " error('Arguments do not match any overload of " << matlabName << " constructor');" << endl;
|
proxyFile.oss << " error('Arguments do not match any overload of " << matlabName << " constructor');" << endl;
|
||||||
proxyFile.oss << " end\n";
|
proxyFile.oss << " end\n";
|
||||||
|
if(!qualifiedParent.empty())
|
||||||
|
proxyFile.oss << " obj = obj@" << matlabBaseName << "(uint64(" << ptr_constructor_key << "), base_ptr);\n";
|
||||||
|
proxyFile.oss << " obj.ptr_" << matlabName << " = my_ptr;\n";
|
||||||
proxyFile.oss << " end\n\n";
|
proxyFile.oss << " end\n\n";
|
||||||
|
|
||||||
// Deconstructor
|
// Deconstructor
|
||||||
|
@ -81,8 +86,7 @@ void Class::matlab_proxy(const string& classFile, const string& wrapperName, Fil
|
||||||
const int id = functionNames.size();
|
const int id = functionNames.size();
|
||||||
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabName, id);
|
deconstructor.proxy_fragment(proxyFile, wrapperName, matlabName, id);
|
||||||
proxyFile.oss << "\n";
|
proxyFile.oss << "\n";
|
||||||
const string functionName = deconstructor.wrapper_fragment(wrapperFile,
|
const string functionName = deconstructor.wrapper_fragment(wrapperFile, cppName, matlabName, id, using_namespaces);
|
||||||
cppName, matlabName, id, using_namespaces, includes);
|
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
functionNames.push_back(functionName);
|
functionNames.push_back(functionName);
|
||||||
}
|
}
|
||||||
|
@ -124,40 +128,44 @@ string Class::qualifiedName(const string& delim) const {
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, int id) const {
|
string Class::pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const string& wrapperName, int id) const {
|
||||||
|
|
||||||
static const uint64_t ptr_constructor_key =
|
|
||||||
(uint64_t('G') << 56) |
|
|
||||||
(uint64_t('T') << 48) |
|
|
||||||
(uint64_t('S') << 40) |
|
|
||||||
(uint64_t('A') << 32) |
|
|
||||||
(uint64_t('M') << 24) |
|
|
||||||
(uint64_t('p') << 16) |
|
|
||||||
(uint64_t('t') << 8) |
|
|
||||||
(uint64_t('r'));
|
|
||||||
|
|
||||||
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
|
const string matlabName = qualifiedName(), cppName = qualifiedName("::");
|
||||||
const string wrapFunctionName = matlabName + "_collectorInsert_" + boost::lexical_cast<string>(id);
|
const string wrapFunctionName = matlabName + "_collectorInsertAndMakeBase_" + boost::lexical_cast<string>(id);
|
||||||
|
const string baseMatlabName = wrap::qualifiedName("", qualifiedParent);
|
||||||
|
const string baseCppName = wrap::qualifiedName("::", qualifiedParent);
|
||||||
|
|
||||||
// MATLAB constructor that assigns pointer to matlab object then calls c++
|
// MATLAB constructor that assigns pointer to matlab object then calls c++
|
||||||
// function to add the object to the collector.
|
// function to add the object to the collector.
|
||||||
proxyFile.oss << " if nargin == 2 && isa(varargin{1}, 'uint64') && ";
|
proxyFile.oss << " if nargin == 2 && isa(varargin{1}, 'uint64') && ";
|
||||||
proxyFile.oss << "varargin{1} == uint64(" << ptr_constructor_key << ")\n";
|
proxyFile.oss << "varargin{1} == uint64(" << ptr_constructor_key << ")\n";
|
||||||
proxyFile.oss << " obj.self = varargin{2};\n";
|
proxyFile.oss << " my_ptr = varargin{2};\n";
|
||||||
proxyFile.oss << " " << wrapperName << "(" << id << ", obj.self);\n";
|
if(qualifiedParent.empty()) // If this class has a base class, we'll get a base class pointer back
|
||||||
|
proxyFile.oss << " ";
|
||||||
|
else
|
||||||
|
proxyFile.oss << " base_ptr = ";
|
||||||
|
proxyFile.oss << wrapperName << "(" << id << ", my_ptr);\n"; // Call collector insert and get base class ptr
|
||||||
|
|
||||||
// C++ function to add pointer from MATLAB to collector. The pointer always
|
// C++ function to add pointer from MATLAB to collector. The pointer always
|
||||||
// comes from a C++ return value; this mechanism allows the object to be added
|
// comes from a C++ return value; this mechanism allows the object to be added
|
||||||
// to a collector in a different wrap module.
|
// to a collector in a different wrap module. If this class has a base class,
|
||||||
|
// a new pointer to the base class is allocated and returned.
|
||||||
wrapperFile.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
wrapperFile.oss << "void " << wrapFunctionName << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
|
||||||
wrapperFile.oss << "{\n";
|
wrapperFile.oss << "{\n";
|
||||||
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
|
wrapperFile.oss << " mexAtExit(&_deleteAllObjects);\n";
|
||||||
generateUsingNamespace(wrapperFile, using_namespaces);
|
generateUsingNamespace(wrapperFile, using_namespaces);
|
||||||
// Typedef boost::shared_ptr
|
// Typedef boost::shared_ptr
|
||||||
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
|
wrapperFile.oss << " typedef boost::shared_ptr<" << cppName << "> Shared;\n";
|
||||||
wrapperFile.oss << "\n";
|
wrapperFile.oss << "\n";
|
||||||
// Get self pointer passed in
|
// Get self pointer passed in
|
||||||
wrapperFile.oss << " Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));\n";
|
wrapperFile.oss << " Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));\n";
|
||||||
// Add to collector
|
// Add to collector
|
||||||
wrapperFile.oss << " collector_" << matlabName << ".insert(self);\n";
|
wrapperFile.oss << " collector_" << matlabName << ".insert(self);\n";
|
||||||
|
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
|
||||||
|
if(!qualifiedParent.empty()) {
|
||||||
|
wrapperFile.oss << "\n";
|
||||||
|
wrapperFile.oss << " typedef boost::shared_ptr<" << baseCppName << "> SharedBase;\n";
|
||||||
|
wrapperFile.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
|
||||||
|
wrapperFile.oss << " *reinterpret_cast<SharedBase**>(mxGetData(out[0])) = new SharedBase(*self);\n";
|
||||||
|
}
|
||||||
wrapperFile.oss << "}\n";
|
wrapperFile.oss << "}\n";
|
||||||
|
|
||||||
return wrapFunctionName;
|
return wrapFunctionName;
|
||||||
|
|
|
@ -37,7 +37,7 @@ string Constructor::matlab_wrapper_name(const string& className) const {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperName,
|
void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperName,
|
||||||
const string& className, const int id, const ArgumentList args) const {
|
const string& matlabName, const string& matlabBaseName, const int id, const ArgumentList args) const {
|
||||||
size_t nrArgs = args.size();
|
size_t nrArgs = args.size();
|
||||||
// check for number of arguments...
|
// check for number of arguments...
|
||||||
file.oss << " elseif nargin == " << nrArgs;
|
file.oss << " elseif nargin == " << nrArgs;
|
||||||
|
@ -50,7 +50,11 @@ void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperNam
|
||||||
first=false;
|
first=false;
|
||||||
}
|
}
|
||||||
// emit code for calling constructor
|
// emit code for calling constructor
|
||||||
file.oss << "\n obj.self = " << wrapperName << "(" << id;
|
if(matlabBaseName.empty())
|
||||||
|
file.oss << "\n my_ptr = ";
|
||||||
|
else
|
||||||
|
file.oss << "\n [ my_ptr, base_ptr ] = ";
|
||||||
|
file.oss << wrapperName << "(" << id;
|
||||||
// emit constructor arguments
|
// emit constructor arguments
|
||||||
for(size_t i=0;i<nrArgs;i++) {
|
for(size_t i=0;i<nrArgs;i++) {
|
||||||
file.oss << ", ";
|
file.oss << ", ";
|
||||||
|
@ -63,9 +67,9 @@ void Constructor::proxy_fragment(FileWriter& file, const std::string& wrapperNam
|
||||||
string Constructor::wrapper_fragment(FileWriter& file,
|
string Constructor::wrapper_fragment(FileWriter& file,
|
||||||
const string& cppClassName,
|
const string& cppClassName,
|
||||||
const string& matlabClassName,
|
const string& matlabClassName,
|
||||||
|
const string& cppBaseClassName,
|
||||||
int id,
|
int id,
|
||||||
const vector<string>& using_namespaces,
|
const vector<string>& using_namespaces,
|
||||||
const vector<string>& includes,
|
|
||||||
const ArgumentList& al) const {
|
const ArgumentList& al) const {
|
||||||
|
|
||||||
const string wrapFunctionName = matlabClassName + "_constructor_" + boost::lexical_cast<string>(id);
|
const string wrapFunctionName = matlabClassName + "_constructor_" + boost::lexical_cast<string>(id);
|
||||||
|
@ -89,6 +93,14 @@ string Constructor::wrapper_fragment(FileWriter& file,
|
||||||
file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl;
|
file.oss << " out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);" << endl;
|
||||||
file.oss << " *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;" << endl;
|
file.oss << " *reinterpret_cast<Shared**> (mxGetData(out[0])) = self;" << endl;
|
||||||
|
|
||||||
|
// If we have a base class, return the base class pointer (MATLAB will call the base class collectorInsertAndMakeBase to add this to the collector and recurse the heirarchy)
|
||||||
|
if(!cppBaseClassName.empty()) {
|
||||||
|
file.oss << "\n";
|
||||||
|
file.oss << " typedef boost::shared_ptr<" << cppBaseClassName << "> SharedBase;\n";
|
||||||
|
file.oss << " out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);\n";
|
||||||
|
file.oss << " *reinterpret_cast<SharedBase**>(mxGetData(out[1])) = new SharedBase(*self);\n";
|
||||||
|
}
|
||||||
|
|
||||||
file.oss << "}" << endl;
|
file.oss << "}" << endl;
|
||||||
|
|
||||||
return wrapFunctionName;
|
return wrapFunctionName;
|
||||||
|
|
|
@ -49,16 +49,16 @@ struct Constructor {
|
||||||
* if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end
|
* if nargin == 2, obj.self = new_Pose3_RP(varargin{1},varargin{2}); end
|
||||||
*/
|
*/
|
||||||
void proxy_fragment(FileWriter& file, const std::string& wrapperName,
|
void proxy_fragment(FileWriter& file, const std::string& wrapperName,
|
||||||
const std::string& className, const int id,
|
const std::string& className, const std::string& matlabBaseName, const int id,
|
||||||
const ArgumentList args) const;
|
const ArgumentList args) const;
|
||||||
|
|
||||||
/// cpp wrapper
|
/// cpp wrapper
|
||||||
std::string wrapper_fragment(FileWriter& file,
|
std::string wrapper_fragment(FileWriter& file,
|
||||||
const std::string& cppClassName,
|
const std::string& cppClassName,
|
||||||
const std::string& matlabClassName,
|
const std::string& matlabClassName,
|
||||||
|
const std::string& cppBaseClassName,
|
||||||
int id,
|
int id,
|
||||||
const std::vector<std::string>& using_namespaces,
|
const std::vector<std::string>& using_namespaces,
|
||||||
const std::vector<std::string>& includes,
|
|
||||||
const ArgumentList& al) const;
|
const ArgumentList& al) const;
|
||||||
|
|
||||||
/// constructor function
|
/// constructor function
|
||||||
|
|
|
@ -39,7 +39,7 @@ void Deconstructor::proxy_fragment(FileWriter& file,
|
||||||
const std::string& qualifiedMatlabName, int id) const {
|
const std::string& qualifiedMatlabName, int id) const {
|
||||||
|
|
||||||
file.oss << " function delete(obj)\n";
|
file.oss << " function delete(obj)\n";
|
||||||
file.oss << " " << wrapperName << "(" << id << ", obj.self);\n";
|
file.oss << " " << wrapperName << "(" << id << ", obj.ptr_" << qualifiedMatlabName << ");\n";
|
||||||
file.oss << " end\n";
|
file.oss << " end\n";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -48,7 +48,7 @@ string Deconstructor::wrapper_fragment(FileWriter& file,
|
||||||
const string& cppClassName,
|
const string& cppClassName,
|
||||||
const string& matlabClassName,
|
const string& matlabClassName,
|
||||||
int id,
|
int id,
|
||||||
const vector<string>& using_namespaces, const vector<string>& includes) const {
|
const vector<string>& using_namespaces) const {
|
||||||
|
|
||||||
const string matlabName = matlab_wrapper_name(matlabClassName);
|
const string matlabName = matlab_wrapper_name(matlabClassName);
|
||||||
|
|
||||||
|
|
|
@ -55,8 +55,7 @@ struct Deconstructor {
|
||||||
const std::string& cppClassName,
|
const std::string& cppClassName,
|
||||||
const std::string& matlabClassName,
|
const std::string& matlabClassName,
|
||||||
int id,
|
int id,
|
||||||
const std::vector<std::string>& using_namespaces,
|
const std::vector<std::string>& using_namespaces) const;
|
||||||
const std::vector<std::string>& includes) const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // \namespace wrap
|
} // \namespace wrap
|
||||||
|
|
|
@ -56,7 +56,7 @@ using namespace boost; // not usual, but for conciseness of generated code
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// "Unique" key to signal calling the matlab object constructor with a raw pointer
|
// "Unique" key to signal calling the matlab object constructor with a raw pointer
|
||||||
// Also present in Class.cpp
|
// Also present in utilities.h
|
||||||
static const uint64_t ptr_constructor_key =
|
static const uint64_t ptr_constructor_key =
|
||||||
(uint64_t('G') << 56) |
|
(uint64_t('G') << 56) |
|
||||||
(uint64_t('T') << 48) |
|
(uint64_t('T') << 48) |
|
||||||
|
@ -383,7 +383,7 @@ mxArray* wrap_shared_ptr(boost::shared_ptr< Class >* shared_ptr, const char *cla
|
||||||
template <typename Class>
|
template <typename Class>
|
||||||
boost::shared_ptr<Class> unwrap_shared_ptr(const mxArray* obj, const string& propertyName) {
|
boost::shared_ptr<Class> unwrap_shared_ptr(const mxArray* obj, const string& propertyName) {
|
||||||
|
|
||||||
mxArray* mxh = mxGetProperty(obj,0, propertyName);
|
mxArray* mxh = mxGetProperty(obj,0, propertyName.c_str());
|
||||||
if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh)
|
if (mxGetClassID(mxh) != mxUINT32OR64_CLASS || mxIsComplex(mxh)
|
||||||
|| mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error(
|
|| mxGetM(mxh) != 1 || mxGetN(mxh) != 1) error(
|
||||||
"Parameter is not an Shared type.");
|
"Parameter is not an Shared type.");
|
||||||
|
|
|
@ -137,12 +137,16 @@ void generateIncludes(FileWriter& file, const string& class_name,
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
string qualifiedName(const string& separator, const vector<string>& names, const string& finalName) {
|
string qualifiedName(const string& separator, const vector<string>& names, const string& finalName) {
|
||||||
string result;
|
string result;
|
||||||
for(size_t i = 0; i < names.size() - 1; ++i)
|
if(!names.empty()) {
|
||||||
result += (names[i] + separator);
|
for(size_t i = 0; i < names.size() - 1; ++i)
|
||||||
if(finalName.empty())
|
result += (names[i] + separator);
|
||||||
result += names.back();
|
if(finalName.empty())
|
||||||
else
|
result += names.back();
|
||||||
result += (names.back() + separator + finalName);
|
else
|
||||||
|
result += (names.back() + separator + finalName);
|
||||||
|
} else if(!finalName.empty()) {
|
||||||
|
result = finalName;
|
||||||
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#include <exception>
|
#include <exception>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <sstream>
|
#include <sstream>
|
||||||
|
#include <cstdint>
|
||||||
|
|
||||||
#include "FileWriter.h"
|
#include "FileWriter.h"
|
||||||
|
|
||||||
|
@ -66,6 +67,18 @@ public:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/** Special "magic number" passed into MATLAB constructor to indicate creating
|
||||||
|
* a MATLAB object from a shared_ptr allocated in C++
|
||||||
|
*/
|
||||||
|
static const uint64_t ptr_constructor_key =
|
||||||
|
(uint64_t('G') << 56) |
|
||||||
|
(uint64_t('T') << 48) |
|
||||||
|
(uint64_t('S') << 40) |
|
||||||
|
(uint64_t('A') << 32) |
|
||||||
|
(uint64_t('M') << 24) |
|
||||||
|
(uint64_t('p') << 16) |
|
||||||
|
(uint64_t('t') << 8) |
|
||||||
|
(uint64_t('r'));
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* read contents of a file into a std::string
|
* read contents of a file into a std::string
|
||||||
|
|
Loading…
Reference in New Issue