Added a check that all wrapped classes involved in a heirarchy are marked virtual
parent
e337ab8b1d
commit
0c384dc35a
10
gtsam.h
10
gtsam.h
|
@ -702,17 +702,17 @@ class VariableIndex {
|
|||
|
||||
#include <gtsam/linear/NoiseModel.h>
|
||||
namespace noiseModel {
|
||||
class Base {
|
||||
virtual class Base {
|
||||
};
|
||||
|
||||
class Gaussian : gtsam::noiseModel::Base {
|
||||
virtual class Gaussian : gtsam::noiseModel::Base {
|
||||
static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R);
|
||||
static gtsam::noiseModel::Gaussian* Covariance(Matrix R);
|
||||
// Matrix R() const; // FIXME: cannot parse!!!
|
||||
void print(string s) const;
|
||||
};
|
||||
|
||||
class Diagonal : gtsam::noiseModel::Gaussian {
|
||||
virtual class Diagonal : gtsam::noiseModel::Gaussian {
|
||||
static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas);
|
||||
static gtsam::noiseModel::Diagonal* Variances(Vector variances);
|
||||
static gtsam::noiseModel::Diagonal* Precisions(Vector precisions);
|
||||
|
@ -720,14 +720,14 @@ class Diagonal : gtsam::noiseModel::Gaussian {
|
|||
void print(string s) const;
|
||||
};
|
||||
|
||||
class Isotropic : gtsam::noiseModel::Gaussian {
|
||||
virtual class Isotropic : gtsam::noiseModel::Gaussian {
|
||||
static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma);
|
||||
static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace);
|
||||
static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision);
|
||||
void print(string s) const;
|
||||
};
|
||||
|
||||
class Unit : gtsam::noiseModel::Gaussian {
|
||||
virtual class Unit : gtsam::noiseModel::Gaussian {
|
||||
static gtsam::noiseModel::Unit* Create(size_t dim);
|
||||
void print(string s) const;
|
||||
};
|
||||
|
|
|
@ -359,8 +359,16 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co
|
|||
BOOST_FOREACH(const Class& cls, classes) {
|
||||
if(!typeAttributes.insert(make_pair(cls.qualifiedName("::"), ReturnValue::TypeAttributes(cls.isVirtual))).second)
|
||||
throw DuplicateDefinition("class " + cls.qualifiedName("::"));
|
||||
|
||||
}
|
||||
// Check attributes
|
||||
BOOST_FOREACH(const Class& cls, classes) {
|
||||
// Check that class is virtual if it has a parent
|
||||
if(!cls.qualifiedParent.empty() && !cls.isVirtual)
|
||||
throw AttributeError(cls.qualifiedName("::"), "Has a base class so needs to be declared virtual, change to 'virtual class "+cls.name+" ...'");
|
||||
// Check that parent is virtual as well
|
||||
if(!cls.qualifiedParent.empty() && !typeAttributes.at(wrap::qualifiedName("::", cls.qualifiedParent)).isVirtual)
|
||||
throw AttributeError(wrap::qualifiedName("::", cls.qualifiedParent),
|
||||
"Is the base class of " + cls.qualifiedName("::") + ", so needs to be declared virtual");
|
||||
}
|
||||
|
||||
// Check that all classes have been defined somewhere
|
||||
|
@ -391,7 +399,7 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co
|
|||
}
|
||||
|
||||
// generate mexAtExit cleanup function
|
||||
wrapperFile.oss << "void _deleteAllObjects()\n";
|
||||
wrapperFile.oss << "\nvoid _deleteAllObjects()\n";
|
||||
wrapperFile.oss << "{\n";
|
||||
BOOST_FOREACH(const Class& cls, classes) {
|
||||
const string matlabName = cls.qualifiedName();
|
||||
|
@ -413,6 +421,7 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co
|
|||
}
|
||||
|
||||
// finish wrapper file
|
||||
wrapperFile.oss << "\n";
|
||||
finish_wrapper(wrapperFile, functionNames);
|
||||
|
||||
wrapperFile.emit(true);
|
||||
|
|
|
@ -69,6 +69,16 @@ public:
|
|||
virtual const char* what() const throw() { return what_.c_str(); }
|
||||
};
|
||||
|
||||
class AttributeError : public std::exception {
|
||||
private:
|
||||
const std::string what_;
|
||||
public:
|
||||
AttributeError(const std::string& name, const std::string& problem) :
|
||||
what_("Class " + name + ": " + problem) {}
|
||||
~AttributeError() throw() {}
|
||||
virtual const char* what() const throw() { return what_.c_str(); }
|
||||
};
|
||||
|
||||
/** Special "magic number" passed into MATLAB constructor to indicate creating
|
||||
* a MATLAB object from a shared_ptr allocated in C++
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue