[inprogress] cython wrapper
parent
df8900a3d1
commit
ecde851d8c
|
@ -105,6 +105,21 @@ void Argument::proxy_check(FileWriter& proxyFile, const string& s) const {
|
|||
proxyFile.oss << " && size(" << s << ",2)==1";
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Argument::emit_cython_pxd(FileWriter& file) const {
|
||||
string typeName = type.qualifiedName("_");
|
||||
string cythonType = typeName;
|
||||
if (typeName=="Vector" || typeName == "Matrix") {
|
||||
cythonType = "Map[" + typeName + "Xd]&";
|
||||
} else {
|
||||
if (is_ptr) cythonType = "shared_ptr[" + typeName + "]&";
|
||||
if (is_ref) cythonType = cythonType + "&";
|
||||
if (is_const) cythonType = "const " + cythonType;
|
||||
}
|
||||
|
||||
file.oss << cythonType << " " << name;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
string ArgumentList::types() const {
|
||||
string str;
|
||||
|
@ -184,6 +199,14 @@ void ArgumentList::emit_prototype(FileWriter& file, const string& name) const {
|
|||
file.oss << ")";
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void ArgumentList::emit_cython_pxd(FileWriter& file) const {
|
||||
for (size_t j = 0; j<size(); ++j) {
|
||||
at(j).emit_cython_pxd(file);
|
||||
if (j<size()-1) file.oss << ", ";
|
||||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void ArgumentList::proxy_check(FileWriter& proxyFile) const {
|
||||
// Check nr of arguments
|
||||
|
|
|
@ -62,6 +62,12 @@ struct Argument {
|
|||
*/
|
||||
void proxy_check(FileWriter& proxyFile, const std::string& s) const;
|
||||
|
||||
/**
|
||||
* emit arguments for cython pxd
|
||||
* @param file output stream
|
||||
*/
|
||||
void emit_cython_pxd(FileWriter& file) const;
|
||||
|
||||
friend std::ostream& operator<<(std::ostream& os, const Argument& arg) {
|
||||
os << (arg.is_const ? "const " : "") << arg.type << (arg.is_ptr ? "*" : "")
|
||||
<< (arg.is_ref ? "&" : "");
|
||||
|
@ -103,6 +109,12 @@ struct ArgumentList: public std::vector<Argument> {
|
|||
*/
|
||||
void emit_prototype(FileWriter& file, const std::string& name) const;
|
||||
|
||||
/**
|
||||
* emit arguments for cython pxd
|
||||
* @param file output stream
|
||||
*/
|
||||
void emit_cython_pxd(FileWriter& file) const;
|
||||
|
||||
/**
|
||||
* emit checking arguments to MATLAB proxy
|
||||
* @param proxyFile output stream
|
||||
|
|
|
@ -660,3 +660,27 @@ void Class::python_wrapper(FileWriter& wrapperFile) const {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Class::cython_wrapper(FileWriter& pxdFile, FileWriter& pyxFile) const {
|
||||
pxdFile.oss << "cdef extern from \"" << includeFile << "\" namespace \""
|
||||
<< qualifiedNamespaces("::") << "\":" << endl;
|
||||
pxdFile.oss << "\tcdef cppclass " << qualifiedName("_") << " \"" << qualifiedName("::") << "\"";
|
||||
if (parentClass) pxdFile.oss << "(" << parentClass->qualifiedName("_") << ")";
|
||||
pxdFile.oss << ":\n";
|
||||
|
||||
pyxFile.oss << "cdef class " << name();
|
||||
if (parentClass) pyxFile.oss << "(" << parentClass->name() << ")";
|
||||
pyxFile.oss << ":\n";
|
||||
pyxFile.oss << "\tcdef shared_ptr[" << qualifiedName("_") << "] "
|
||||
<< "gt" << name() << "_\n";
|
||||
|
||||
constructor.cython_wrapper(pxdFile, pyxFile, qualifiedName("_"));
|
||||
|
||||
pxdFile.oss << "\n";
|
||||
pyxFile.oss << "\n";
|
||||
// for(const StaticMethod& m: static_methods | boost::adaptors::map_values)
|
||||
// m.cython_wrapper(pxdFile, pyxFile, name());
|
||||
// for(const Method& m: methods_ | boost::adaptors::map_values)
|
||||
// m.cython_wrapper(pxdFile, pyxFile, name());
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -74,6 +74,7 @@ public:
|
|||
Constructor constructor; ///< Class constructors
|
||||
Deconstructor deconstructor; ///< Deconstructor to deallocate C++ object
|
||||
bool verbose_; ///< verbose flag
|
||||
std::string includeFile;
|
||||
|
||||
/// Constructor creates an empty class
|
||||
Class(bool verbose = true) :
|
||||
|
@ -141,6 +142,9 @@ public:
|
|||
// emit python wrapper
|
||||
void python_wrapper(FileWriter& wrapperFile) const;
|
||||
|
||||
// emit cython wrapper
|
||||
void cython_wrapper(FileWriter& pxdFile, FileWriter& pyxFile) const;
|
||||
|
||||
friend std::ostream& operator<<(std::ostream& os, const Class& cls) {
|
||||
os << "class " << cls.name() << "{\n";
|
||||
os << cls.constructor << ";\n";
|
||||
|
|
|
@ -121,3 +121,13 @@ void Constructor::python_wrapper(FileWriter& wrapperFile, Str className) const {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Constructor::cython_wrapper(FileWriter& pxdFile, FileWriter& pyxFile, Str className) const {
|
||||
for (size_t i = 0; i < nrOverloads(); i++) {
|
||||
ArgumentList args = argumentList(i);
|
||||
pxdFile.oss << "\t\t" << className << "(";
|
||||
args.emit_cython_pxd(pxdFile);
|
||||
pxdFile.oss << ") " << "except +\n";
|
||||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -78,6 +78,9 @@ struct Constructor: public OverloadedFunction {
|
|||
// emit python wrapper
|
||||
void python_wrapper(FileWriter& wrapperFile, Str className) const;
|
||||
|
||||
// emit cython wrapper
|
||||
void cython_wrapper(FileWriter& pxdFile, FileWriter& pyxFile, Str className) const;
|
||||
|
||||
friend std::ostream& operator<<(std::ostream& os, const Constructor& m) {
|
||||
for (size_t i = 0; i < m.nrOverloads(); i++)
|
||||
os << m.name_ << m.argLists_[i];
|
||||
|
|
|
@ -100,6 +100,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
BasicRules<phrase_scanner_t> basic;
|
||||
|
||||
vector<string> namespaces; // current namespace tag
|
||||
string currentInclude;
|
||||
|
||||
// parse a full class
|
||||
Class cls0(verbose),cls(verbose);
|
||||
|
@ -107,6 +108,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
ClassGrammar class_g(cls,classTemplate);
|
||||
Rule class_p = class_g //
|
||||
[assign_a(cls.namespaces_, namespaces)]
|
||||
[assign_a(cls.includeFile, currentInclude)]
|
||||
[bl::bind(&handle_possible_template, bl::var(classes), bl::var(cls),
|
||||
bl::var(classTemplate))]
|
||||
[clear_a(classTemplate)] //
|
||||
|
@ -129,8 +131,11 @@ void Module::parseMarkup(const std::string& data) {
|
|||
|
||||
// Create grammar for global functions
|
||||
GlobalFunctionGrammar global_function_g(global_functions,namespaces);
|
||||
|
||||
Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[push_back_a(includes)] >> ch_p('>');
|
||||
|
||||
Rule include_p = str_p("#include") >> ch_p('<') >>
|
||||
(*(anychar_p - '>'))[push_back_a(includes)]
|
||||
[assign_a(currentInclude)] >>
|
||||
ch_p('>');
|
||||
|
||||
#ifdef __clang__
|
||||
#pragma clang diagnostic push
|
||||
|
@ -160,7 +165,7 @@ void Module::parseMarkup(const std::string& data) {
|
|||
[assign_a(cls,cls0)] // also clear class to avoid partial parse
|
||||
[assign_a(fwDec, fwDec0)];
|
||||
|
||||
Rule module_content_p = basic.comments_p | include_p | class_p
|
||||
Rule module_content_p = basic.comments_p | class_p
|
||||
| templateSingleInstantiation_p | forward_declaration_p
|
||||
| global_function_g | namespace_def_p;
|
||||
|
||||
|
@ -273,6 +278,28 @@ void Module::matlab_code(const string& toolboxPath) const {
|
|||
wrapperFile.emit(true);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Module::cython_code(const string& toolboxPath) const {
|
||||
|
||||
fs::create_directories(toolboxPath);
|
||||
|
||||
// create the unified .cpp switch file
|
||||
string pxdFileName = toolboxPath + "/" + name + "_wrapper" + ".pxd";
|
||||
string pyxFileName = toolboxPath + "/" + name + ".pyx";
|
||||
FileWriter pxdFile(pxdFileName, verbose, "#");
|
||||
FileWriter pyxFile(pyxFileName, verbose, "#");
|
||||
|
||||
// create proxy class and wrapper code
|
||||
for(const Class& cls: expandedClasses)
|
||||
cls.cython_wrapper(pxdFile, pyxFile);
|
||||
|
||||
// finish wrapper file
|
||||
pxdFile.oss << "\n";
|
||||
pxdFile.emit(true);
|
||||
pyxFile.oss << "\n";
|
||||
pyxFile.emit(true);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Module::generateIncludes(FileWriter& file) const {
|
||||
|
||||
|
|
|
@ -62,6 +62,9 @@ struct Module {
|
|||
/// MATLAB code generation:
|
||||
void matlab_code(const std::string& path) const;
|
||||
|
||||
/// Cython code generation:
|
||||
void cython_code(const std::string& path) const;
|
||||
|
||||
void generateIncludes(FileWriter& file) const;
|
||||
|
||||
void finish_wrapper(FileWriter& file,
|
||||
|
|
|
@ -128,6 +128,14 @@ public:
|
|||
return Qualified("void", VOID);
|
||||
}
|
||||
|
||||
/// Return a qualified namespace using given delimiter
|
||||
std::string qualifiedNamespaces(const std::string& delimiter = "") const {
|
||||
std::string result;
|
||||
for (std::size_t i = 0; i < namespaces_.size(); ++i)
|
||||
result += (namespaces_[i] + ((i<namespaces_.size()-1)?delimiter:""));
|
||||
return result;
|
||||
}
|
||||
|
||||
/// Return a qualified string using given delimiter
|
||||
std::string qualifiedName(const std::string& delimiter = "") const {
|
||||
std::string result;
|
||||
|
|
|
@ -15,7 +15,8 @@
|
|||
#include <boost/spirit/include/classic_clear_actor.hpp>
|
||||
#include <boost/spirit/include/classic_assign_actor.hpp>
|
||||
#include <boost/spirit/include/classic_confix.hpp>
|
||||
|
||||
#include <boost/spirit/include/classic_increment_actor.hpp>
|
||||
|
||||
namespace boost {
|
||||
namespace spirit {
|
||||
|
||||
|
|
|
@ -0,0 +1,309 @@
|
|||
namespace gtsam {
|
||||
|
||||
#include <gtsam/geometry/Point3.h>
|
||||
class Point3 {
|
||||
// Standard Constructors
|
||||
Point3();
|
||||
Point3(double x, double y, double z);
|
||||
Point3(Vector v);
|
||||
|
||||
// Testable
|
||||
void print(string s) const;
|
||||
bool equals(const gtsam::Point3& p, double tol) const;
|
||||
|
||||
// Group
|
||||
static gtsam::Point3 identity();
|
||||
|
||||
// Standard Interface
|
||||
Vector vector() const;
|
||||
double x() const;
|
||||
double y() const;
|
||||
double z() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const;
|
||||
};
|
||||
|
||||
#include <gtsam/geometry/Rot3.h>
|
||||
class Rot3 {
|
||||
// Standard Constructors and Named Constructors
|
||||
Rot3();
|
||||
Rot3(Matrix R);
|
||||
static gtsam::Rot3 Rx(double t);
|
||||
static gtsam::Rot3 Ry(double t);
|
||||
static gtsam::Rot3 Rz(double t);
|
||||
static gtsam::Rot3 RzRyRx(double x, double y, double z);
|
||||
static gtsam::Rot3 RzRyRx(Vector xyz);
|
||||
static gtsam::Rot3 Yaw(double t); // positive yaw is to right (as in aircraft heading)
|
||||
static gtsam::Rot3 Pitch(double t); // positive pitch is up (increasing aircraft altitude)
|
||||
static gtsam::Rot3 Roll(double t); // positive roll is to right (increasing yaw in aircraft)
|
||||
static gtsam::Rot3 Ypr(double y, double p, double r);
|
||||
static gtsam::Rot3 Quaternion(double w, double x, double y, double z);
|
||||
static gtsam::Rot3 Rodrigues(Vector v);
|
||||
|
||||
// Testable
|
||||
void print(string s) const;
|
||||
bool equals(const gtsam::Rot3& rot, double tol) const;
|
||||
|
||||
// Group
|
||||
static gtsam::Rot3 identity();
|
||||
gtsam::Rot3 inverse() const;
|
||||
gtsam::Rot3 compose(const gtsam::Rot3& p2) const;
|
||||
gtsam::Rot3 between(const gtsam::Rot3& p2) const;
|
||||
|
||||
// Manifold
|
||||
//gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options
|
||||
gtsam::Rot3 retract(Vector v) const;
|
||||
Vector localCoordinates(const gtsam::Rot3& p) const;
|
||||
|
||||
// Group Action on Point3
|
||||
gtsam::Point3 rotate(const gtsam::Point3& p) const;
|
||||
gtsam::Point3 unrotate(const gtsam::Point3& p) const;
|
||||
|
||||
// Standard Interface
|
||||
static gtsam::Rot3 Expmap(Vector v);
|
||||
static Vector Logmap(const gtsam::Rot3& p);
|
||||
Matrix matrix() const;
|
||||
Matrix transpose() const;
|
||||
gtsam::Point3 column(size_t index) const;
|
||||
Vector xyz() const;
|
||||
Vector ypr() const;
|
||||
Vector rpy() const;
|
||||
double roll() const;
|
||||
double pitch() const;
|
||||
double yaw() const;
|
||||
// Vector toQuaternion() const; // FIXME: Can't cast to Vector properly
|
||||
Vector quaternion() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const;
|
||||
};
|
||||
|
||||
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
class VectorValues {
|
||||
//Constructors
|
||||
VectorValues();
|
||||
VectorValues(const gtsam::VectorValues& other);
|
||||
|
||||
//Named Constructors
|
||||
static gtsam::VectorValues Zero(const gtsam::VectorValues& model);
|
||||
|
||||
//Standard Interface
|
||||
size_t size() const;
|
||||
size_t dim(size_t j) const;
|
||||
bool exists(size_t j) const;
|
||||
void print(string s) const;
|
||||
bool equals(const gtsam::VectorValues& expected, double tol) const;
|
||||
void insert(size_t j, Vector value);
|
||||
Vector vector() const;
|
||||
Vector at(size_t j) const;
|
||||
void update(const gtsam::VectorValues& values);
|
||||
|
||||
//Advanced Interface
|
||||
void setZero();
|
||||
|
||||
gtsam::VectorValues add(const gtsam::VectorValues& c) const;
|
||||
void addInPlace(const gtsam::VectorValues& c);
|
||||
gtsam::VectorValues subtract(const gtsam::VectorValues& c) const;
|
||||
gtsam::VectorValues scale(double a) const;
|
||||
void scaleInPlace(double a);
|
||||
|
||||
bool hasSameStructure(const gtsam::VectorValues& other) const;
|
||||
double dot(const gtsam::VectorValues& V) const;
|
||||
double norm() const;
|
||||
double squaredNorm() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const;
|
||||
};
|
||||
|
||||
namespace noiseModel {
|
||||
#include <gtsam/linear/NoiseModel.h>
|
||||
virtual class Base {
|
||||
};
|
||||
|
||||
virtual class Gaussian : gtsam::noiseModel::Base {
|
||||
static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R);
|
||||
static gtsam::noiseModel::Gaussian* Covariance(Matrix R);
|
||||
Matrix R() const;
|
||||
bool equals(gtsam::noiseModel::Base& expected, double tol);
|
||||
void print(string s) const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
|
||||
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);
|
||||
Matrix R() const;
|
||||
void print(string s) const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
|
||||
namespace mEstimator {
|
||||
virtual class Base {
|
||||
};
|
||||
|
||||
virtual class Null: gtsam::noiseModel::mEstimator::Base {
|
||||
Null();
|
||||
void print(string s) const;
|
||||
static gtsam::noiseModel::mEstimator::Null* Create();
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
|
||||
virtual class Fair: gtsam::noiseModel::mEstimator::Base {
|
||||
Fair(double c);
|
||||
void print(string s) const;
|
||||
static gtsam::noiseModel::mEstimator::Fair* Create(double c);
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
|
||||
virtual class Huber: gtsam::noiseModel::mEstimator::Base {
|
||||
Huber(double k);
|
||||
void print(string s) const;
|
||||
static gtsam::noiseModel::mEstimator::Huber* Create(double k);
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
} // namespace mEstimator
|
||||
|
||||
virtual class Robust : gtsam::noiseModel::Base {
|
||||
Robust(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise);
|
||||
static gtsam::noiseModel::Robust* Create(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise);
|
||||
void print(string s) const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serializable() const;
|
||||
};
|
||||
} // namespace noiseModel
|
||||
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
class Values {
|
||||
Values();
|
||||
Values(const gtsam::Values& other);
|
||||
|
||||
size_t size() const;
|
||||
bool empty() const;
|
||||
void clear();
|
||||
size_t dim() const;
|
||||
|
||||
void print(string s) const;
|
||||
bool equals(const gtsam::Values& other, double tol) const;
|
||||
|
||||
void insert(const gtsam::Values& values);
|
||||
void update(const gtsam::Values& values);
|
||||
void erase(size_t j);
|
||||
void swap(gtsam::Values& values);
|
||||
|
||||
bool exists(size_t j) const;
|
||||
// gtsam::KeyVector keys() const;
|
||||
|
||||
gtsam::VectorValues zeroVectors() const;
|
||||
|
||||
gtsam::Values retract(const gtsam::VectorValues& delta) const;
|
||||
gtsam::VectorValues localCoordinates(const gtsam::Values& cp) const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const;
|
||||
|
||||
// New in 4.0, we have to specialize every insert/update/at to generate wrappers
|
||||
// Instead of the old:
|
||||
// void insert(size_t j, const gtsam::Value& value);
|
||||
// void update(size_t j, const gtsam::Value& val);
|
||||
// gtsam::Value at(size_t j) const;
|
||||
|
||||
template<T = {gtsam::Point3, gtsam::Rot3, Vector, Matrix}>
|
||||
void insert(size_t j, const T& t);
|
||||
|
||||
template<T = {gtsam::Point3, gtsam::Rot3, Vector, Matrix}>
|
||||
void update(size_t j, const T& t);
|
||||
|
||||
template<T = {gtsam::Point3, gtsam::Rot3, Vector, Matrix}>
|
||||
T at(size_t j);
|
||||
|
||||
/// version for double
|
||||
void insertDouble(size_t j, double c);
|
||||
double atDouble(size_t j) const;
|
||||
};
|
||||
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
virtual class NonlinearFactor {
|
||||
// Factor base class
|
||||
size_t size() const;
|
||||
// gtsam::KeyVector keys() const;
|
||||
void print(string s) const;
|
||||
void printKeys(string s) const;
|
||||
// NonlinearFactor
|
||||
void equals(const gtsam::NonlinearFactor& other, double tol) const;
|
||||
double error(const gtsam::Values& c) const;
|
||||
size_t dim() const;
|
||||
bool active(const gtsam::Values& c) const;
|
||||
// gtsam::GaussianFactor* linearize(const gtsam::Values& c) const;
|
||||
gtsam::NonlinearFactor* clone() const;
|
||||
// gtsam::NonlinearFactor* rekey(const gtsam::KeyVector& newKeys) const; //FIXME: Conversion from KeyVector to std::vector does not happen
|
||||
};
|
||||
|
||||
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
class NonlinearFactorGraph {
|
||||
NonlinearFactorGraph();
|
||||
NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);
|
||||
|
||||
// FactorGraph
|
||||
void print(string s) const;
|
||||
bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const;
|
||||
size_t size() const;
|
||||
bool empty() const;
|
||||
void remove(size_t i);
|
||||
size_t nrFactors() const;
|
||||
gtsam::NonlinearFactor* at(size_t idx) const;
|
||||
void push_back(const gtsam::NonlinearFactorGraph& factors);
|
||||
void push_back(gtsam::NonlinearFactor* factor);
|
||||
void add(gtsam::NonlinearFactor* factor);
|
||||
bool exists(size_t idx) const;
|
||||
// gtsam::KeySet keys() const;
|
||||
|
||||
// NonlinearFactorGraph
|
||||
double error(const gtsam::Values& values) const;
|
||||
double probPrime(const gtsam::Values& values) const;
|
||||
// gtsam::Ordering orderingCOLAMD() const;
|
||||
// // Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const std::map<gtsam::Key,int>& constraints) const;
|
||||
// gtsam::GaussianFactorGraph* linearize(const gtsam::Values& values) const;
|
||||
gtsam::NonlinearFactorGraph clone() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const;
|
||||
};
|
||||
|
||||
|
||||
virtual class NoiseModelFactor: gtsam::NonlinearFactor {
|
||||
void equals(const gtsam::NoiseModelFactor& other, double tol) const;
|
||||
gtsam::noiseModel::Base* get_noiseModel() const; // deprecated by below
|
||||
gtsam::noiseModel::Base* noiseModel() const;
|
||||
Vector unwhitenedError(const gtsam::Values& x) const;
|
||||
Vector whitenedError(const gtsam::Values& x) const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
template<T = {gtsam::Point3, gtsam::Rot3}>
|
||||
virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
||||
BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
|
||||
T measured() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const;
|
||||
};
|
||||
|
||||
|
||||
|
||||
}
|
|
@ -5,6 +5,7 @@ virtual class ns::OtherClass;
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
class Point2 {
|
||||
Point2();
|
||||
Point2(double x, double y);
|
||||
|
@ -20,6 +21,7 @@ class Point2 {
|
|||
void serializable() const; // Sets flag and creates export, but does not make serialization functions
|
||||
};
|
||||
|
||||
#include <gtsam/geometry/Point3.h>
|
||||
class Point3 {
|
||||
Point3(double x, double y, double z);
|
||||
double norm() const;
|
||||
|
|
|
@ -477,6 +477,26 @@ TEST( wrap, python_code_geometry ) {
|
|||
EXPECT(files_equal(epath + "geometry_python.cpp", apath + "geometry_python.cpp" ));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( wrap, cython_code_geometry ) {
|
||||
// Parse into class object
|
||||
string header_path = topdir + "/wrap/tests";
|
||||
Module module(header_path,"geometry",enable_verbose);
|
||||
string path = topdir + "/wrap";
|
||||
|
||||
// clean out previous generated code
|
||||
fs::remove_all("actual-cython");
|
||||
|
||||
// emit MATLAB code
|
||||
// make_geometry will not compile, use make testwrap to generate real make
|
||||
module.cython_wrapper("actual-cython");
|
||||
string epath = path + "/tests/expected-cython/";
|
||||
string apath = "actual-cython/";
|
||||
|
||||
EXPECT(files_equal(epath + "geometry_cython.pxd", apath + "geometry_cython.pxd" ));
|
||||
EXPECT(files_equal(epath + "geometry.pyx", apath + "geometry.pyx" ));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -0,0 +1,59 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
||||
* See LICENSE for the license information
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/**
|
||||
* @file testWrap.cpp
|
||||
* @brief Unit test for wrap.c
|
||||
* @author Frank Dellaert
|
||||
**/
|
||||
|
||||
#include <wrap/utilities.h>
|
||||
#include <wrap/Module.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
#include <boost/filesystem.hpp>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
|
||||
using namespace std;
|
||||
using namespace boost::assign;
|
||||
using namespace wrap;
|
||||
namespace fs = boost::filesystem;
|
||||
static bool enable_verbose = true;
|
||||
#ifdef TOPSRCDIR
|
||||
static string topdir = TOPSRCDIR;
|
||||
#else
|
||||
static string topdir = "TOPSRCDIR_NOT_CONFIGURED"; // If TOPSRCDIR is not defined, we error
|
||||
#endif
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( wrap, cython_code_geometry ) {
|
||||
// Parse into class object
|
||||
string header_path = topdir + "/wrap/tests";
|
||||
Module module(header_path,"cythontest",enable_verbose);
|
||||
string path = topdir + "/wrap";
|
||||
|
||||
// clean out previous generated code
|
||||
fs::remove_all("actual-cython");
|
||||
|
||||
// emit MATLAB code
|
||||
// make_geometry will not compile, use make testwrap to generate real make
|
||||
module.cython_code("actual-cython");
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
|
@ -22,6 +22,16 @@
|
|||
|
||||
using namespace std;
|
||||
|
||||
/** Displays usage information */
|
||||
void usage() {
|
||||
cerr << "wrap parses an interface file and produces a MATLAB toolbox" << endl;
|
||||
cerr << "usage: wrap [--matlab|--cython] interfacePath moduleName toolboxPath headerPath" << endl;
|
||||
cerr << " interfacePath : *absolute* path to directory of module interface file" << endl;
|
||||
cerr << " moduleName : the name of the module, interface file must be called moduleName.h" << endl;
|
||||
cerr << " toolboxPath : the directory in which to generate the wrappers" << endl;
|
||||
cerr << " headerPath : path to matlab.h" << endl;
|
||||
}
|
||||
|
||||
/**
|
||||
* Top-level function to wrap a module
|
||||
* @param interfacePath path to where interface file lives, e.g., borg/gtsam
|
||||
|
@ -29,7 +39,8 @@ using namespace std;
|
|||
* @param toolboxPath path where the toolbox should be generated, e.g. borg/gtsam/build
|
||||
* @param headerPath is the path to matlab.h
|
||||
*/
|
||||
void generate_matlab_toolbox(
|
||||
void generate_toolbox(
|
||||
const string& language,
|
||||
const string& interfacePath,
|
||||
const string& moduleName,
|
||||
const string& toolboxPath,
|
||||
|
@ -39,18 +50,17 @@ void generate_matlab_toolbox(
|
|||
// This recursively creates Class objects, Method objects, etc...
|
||||
wrap::Module module(interfacePath, moduleName, false);
|
||||
|
||||
if (language == "--matlab")
|
||||
// Then emit MATLAB code
|
||||
module.matlab_code(toolboxPath);
|
||||
}
|
||||
|
||||
/** Displays usage information */
|
||||
void usage() {
|
||||
cerr << "wrap parses an interface file and produces a MATLAB toolbox" << endl;
|
||||
cerr << "usage: wrap interfacePath moduleName toolboxPath headerPath" << endl;
|
||||
cerr << " interfacePath : *absolute* path to directory of module interface file" << endl;
|
||||
cerr << " moduleName : the name of the module, interface file must be called moduleName.h" << endl;
|
||||
cerr << " toolboxPath : the directory in which to generate the wrappers" << endl;
|
||||
cerr << " headerPath : path to matlab.h" << endl;
|
||||
module.matlab_code(toolboxPath);
|
||||
else if (language == "--cython") {
|
||||
module.cython_code(toolboxPath);
|
||||
}
|
||||
else {
|
||||
cerr << "First argument invalid" << endl;
|
||||
cerr << endl;
|
||||
usage();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -58,7 +68,7 @@ void usage() {
|
|||
* Typically called from "make all" using appropriate arguments
|
||||
*/
|
||||
int main(int argc, const char* argv[]) {
|
||||
if (argc != 5) {
|
||||
if (argc != 6) {
|
||||
cerr << "Invalid arguments:\n";
|
||||
for (int i=0; i<argc; ++i)
|
||||
cerr << argv[i] << endl;
|
||||
|
@ -67,7 +77,7 @@ int main(int argc, const char* argv[]) {
|
|||
}
|
||||
else {
|
||||
try {
|
||||
generate_matlab_toolbox(argv[1],argv[2],argv[3],argv[4]);
|
||||
generate_toolbox(argv[1], argv[2],argv[3],argv[4],argv[5]);
|
||||
} catch(std::exception& e) {
|
||||
cerr << e.what() << endl;
|
||||
return 1;
|
||||
|
|
Loading…
Reference in New Issue