unify gtsam.h for matlab and cython wrapper

release/4.3a0
Duy-Nguyen Ta 2017-03-18 15:33:01 -04:00
parent 6148f822ae
commit a6281e1932
5 changed files with 162 additions and 2878 deletions

File diff suppressed because it is too large Load Diff

View File

@ -25,7 +25,7 @@ class Point2 {
Point2();
Point2(double x, double y);
Point2(Vector v);
Point2(const gtsam::Point2& l);
//Point2(const gtsam::Point2& l);
// Testable
void print(string s) const;
@ -51,7 +51,7 @@ class Point3 {
Point3();
Point3(double x, double y, double z);
Point3(Vector v);
Point3(const gtsam::Point3& l);
//Point3(const gtsam::Point3& l);
// Testable
void print(string s) const;
@ -75,7 +75,7 @@ class Rot2 {
// Standard Constructors and Named Constructors
Rot2();
Rot2(double theta);
Rot2(const gtsam::Rot2& l);
//Rot2(const gtsam::Rot2& l);
static gtsam::Rot2 fromAngle(double theta);
static gtsam::Rot2 fromDegrees(double theta);
@ -121,7 +121,7 @@ class Rot3 {
// Standard Constructors and Named Constructors
Rot3();
Rot3(Matrix R);
Rot3(const gtsam::Rot3& l);
//Rot3(const gtsam::Rot3& l);
static gtsam::Rot3 Rx(double t);
static gtsam::Rot3 Ry(double t);
@ -177,7 +177,7 @@ class Rot3 {
class Pose2 {
// Standard Constructor
Pose2();
Pose2(const gtsam::Pose2& pose);
//Pose2(const gtsam::Pose2& pose);
Pose2(double x, double y, double theta);
Pose2(double theta, const gtsam::Point2& t);
Pose2(const gtsam::Rot2& r, const gtsam::Point2& t);
@ -227,7 +227,7 @@ class Pose2 {
class Pose3 {
// Standard Constructors
Pose3();
Pose3(const gtsam::Pose3& pose);
//Pose3(const gtsam::Pose3& pose);
Pose3(const gtsam::Rot3& r, const gtsam::Point3& t);
Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose)
Pose3(Matrix t);
@ -344,7 +344,7 @@ virtual class Base {
virtual class Null: gtsam::noiseModel::mEstimator::Base {
Null();
Null(const gtsam::noiseModel::mEstimator::Null& other);
//Null(const gtsam::noiseModel::mEstimator::Null& other);
void print(string s) const;
static gtsam::noiseModel::mEstimator::Null* Create();
@ -354,7 +354,7 @@ virtual class Null: gtsam::noiseModel::mEstimator::Base {
virtual class Fair: gtsam::noiseModel::mEstimator::Base {
Fair(double c);
Fair(const gtsam::noiseModel::mEstimator::Fair& other);
//Fair(const gtsam::noiseModel::mEstimator::Fair& other);
void print(string s) const;
static gtsam::noiseModel::mEstimator::Fair* Create(double c);
@ -364,7 +364,7 @@ virtual class Fair: gtsam::noiseModel::mEstimator::Base {
virtual class Huber: gtsam::noiseModel::mEstimator::Base {
Huber(double k);
Huber(const gtsam::noiseModel::mEstimator::Huber& other);
//Huber(const gtsam::noiseModel::mEstimator::Huber& other);
void print(string s) const;
static gtsam::noiseModel::mEstimator::Huber* Create(double k);
@ -375,7 +375,7 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base {
virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
Tukey(double k);
Tukey(const gtsam::noiseModel::mEstimator::Tukey& other);
//Tukey(const gtsam::noiseModel::mEstimator::Tukey& other);
void print(string s) const;
static gtsam::noiseModel::mEstimator::Tukey* Create(double k);
@ -388,7 +388,7 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
virtual class Robust : gtsam::noiseModel::Base {
Robust(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise);
Robust(const gtsam::noiseModel::Robust& other);
//Robust(const gtsam::noiseModel::Robust& other);
static gtsam::noiseModel::Robust* Create(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise);
void print(string s) const;
@ -405,7 +405,7 @@ class Sampler {
Sampler(gtsam::noiseModel::Diagonal* model, int seed);
Sampler(Vector sigmas, int seed);
Sampler(int seed);
Sampler(const gtsam::Sampler& other);
//Sampler(const gtsam::Sampler& other);
//Standard Interface
@ -483,7 +483,7 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3,
Vector b, const gtsam::noiseModel::Diagonal* model);
//JacobianFactor(const gtsam::GaussianFactorGraph& graph);
JacobianFactor(const gtsam::JacobianFactor& other);
//JacobianFactor(const gtsam::JacobianFactor& other);
//Testable
void print(string s) const;
@ -529,7 +529,7 @@ virtual class HessianFactor : gtsam::GaussianFactor {
Vector g1, Matrix G22, Matrix G23, Vector g2, Matrix G33, Vector g3,
double f);
//HessianFactor(const gtsam::GaussianFactorGraph& factors);
HessianFactor(const gtsam::HessianFactor& other);
//HessianFactor(const gtsam::HessianFactor& other);
//Testable
size_t size() const;
@ -551,7 +551,7 @@ virtual class HessianFactor : gtsam::GaussianFactor {
#include <gtsam/nonlinear/Values.h>
class Values {
Values();
Values(const gtsam::Values& other);
//Values(const gtsam::Values& other);
size_t size() const;
bool empty() const;
@ -638,7 +638,7 @@ virtual class NonlinearFactor {
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
class NonlinearFactorGraph {
NonlinearFactorGraph();
NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);
//NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);
// FactorGraph
void print(string s) const;
@ -679,7 +679,7 @@ virtual class NoiseModelFactor: gtsam::NonlinearFactor {
template<T = {Vector, gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3}>
virtual class PriorFactor : gtsam::NoiseModelFactor {
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
PriorFactor(const This& other);
//PriorFactor(const This& other);
T prior() const;
// enabling serialization functionality
@ -691,7 +691,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor {
template<T = {Vector, gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3}>
virtual class BetweenFactor : gtsam::NoiseModelFactor {
BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
BetweenFactor(const This& other);
//BetweenFactor(const This& other);
T measured() const;
// enabling serialization functionality

282
gtsam.h
View File

@ -89,6 +89,18 @@
* - Add "void serializable()" to a class if you only want the class to be serialized as a
* part of a container (such as noisemodel). This version does not require a publicly
* accessible default constructor.
* Forward declarations and class definitions for Cython:
* - Need to specify the base class (both this forward class and base class are declared in an external cython header)
* This is so Cython can generate proper inheritance.
* Example when wrapping a gtsam-based project:
* // forward declarations
* virtual class gtsam::NonlinearFactor
* virtual class gtsam::NoiseModelFactor : gtsam::NonlinearFactor
* // class definition
* #include <MyFactor.h>
* virtual class MyFactor : gtsam::NoiseModelFactor {...};
* - *DO NOT* re-define overriden function already declared in the external (forward-declared) base class
* - This will cause an ambiguity problem in Cython pxd header file
*/
/**
@ -102,51 +114,106 @@
* - TODO: Add generalized serialization support via boost.serialization with hooks to matlab save/load
*/
namespace std {
#include <vector>
template<T>
class vector
{
//Do we need these?
//Capacity
/*size_t size() const;
size_t max_size() const;
//void resize(size_t sz);
size_t capacity() const;
bool empty() const;
void reserve(size_t n);
//Element access
T* at(size_t n);
T* front();
T* back();
//Modifiers
void assign(size_t n, const T& u);
void push_back(const T& x);
void pop_back();*/
};
//typedef std::vector
#include<list>
template<T>
class list
{
};
}
namespace gtsam {
// Actually a FastList<Key>
#include <gtsam/inference/Key.h>
class KeyList {
KeyList();
KeyList(const gtsam::KeyList& other);
// Note: no print function
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
size_t front() const;
size_t back() const;
void push_back(size_t key);
void push_front(size_t key);
void pop_back();
void pop_front();
void sort();
void remove(size_t key);
void serialize() const;
};
// Actually a FastSet<Key>
class KeySet {
KeySet();
KeySet(const gtsam::KeySet& other);
KeySet(const gtsam::KeyVector& other);
KeySet(const gtsam::KeyList& other);
// Testable
void print(string s) const;
bool equals(const gtsam::KeySet& other) const;
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
void insert(size_t key);
void merge(gtsam::KeySet& other);
bool erase(size_t key); // returns true if value was removed
bool count(size_t key) const; // returns true if value exists
void serialize() const;
};
// Actually a vector<Key>
class KeyVector {
KeyVector();
KeyVector(const gtsam::KeyVector& other);
// Note: no print function
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
size_t at(size_t i) const;
size_t front() const;
size_t back() const;
void push_back(size_t key) const;
void serialize() const;
};
// Actually a FastMap<Key,int>
class KeyGroupMap {
KeyGroupMap();
// Note: no print function
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
size_t at(size_t key) const;
int erase(size_t key);
bool insert2(size_t key, int val);
};
//*************************************************************************
// base
//*************************************************************************
/** gtsam namespace functions */
#include <gtsam/base/Matrix.h>
bool linear_independent(Matrix A, Matrix B, double tol);
#include <gtsam/base/Value.h>
virtual class Value {
// No constructors because this is an abstract class
@ -254,6 +321,7 @@ class LieMatrix {
// geometry
//*************************************************************************
#include <gtsam/geometry/Point2.h>
class Point2 {
// Standard Constructors
Point2();
@ -262,7 +330,7 @@ class Point2 {
// Testable
void print(string s) const;
bool equals(const gtsam::Point2& pose, double tol) const;
bool equals(const gtsam::Point2& point, double tol) const;
// Group
static gtsam::Point2 identity();
@ -279,6 +347,7 @@ class Point2 {
};
// std::vector<gtsam::Point2>
#include <gtsam/geometry/Point2.h>
class Point2Vector
{
// Constructors
@ -304,6 +373,7 @@ class Point2Vector
void pop_back();
};
#include <gtsam/geometry/StereoPoint2.h>
class StereoPoint2 {
// Standard Constructors
StereoPoint2();
@ -337,6 +407,7 @@ class StereoPoint2 {
void serialize() const;
};
#include <gtsam/geometry/Point3.h>
class Point3 {
// Standard Constructors
Point3();
@ -360,6 +431,7 @@ class Point3 {
void serialize() const;
};
#include <gtsam/geometry/Rot2.h>
class Rot2 {
// Standard Constructors and Named Constructors
Rot2();
@ -403,6 +475,7 @@ class Rot2 {
void serialize() const;
};
#include <gtsam/geometry/Rot3.h>
class Rot3 {
// Standard Constructors and Named Constructors
Rot3();
@ -457,10 +530,11 @@ class Rot3 {
void serialize() const;
};
#include <gtsam/geometry/Pose2.h>
class Pose2 {
// Standard Constructor
Pose2();
Pose2(const gtsam::Pose2& pose);
Pose2(const gtsam::Pose2& other);
Pose2(double x, double y, double theta);
Pose2(double theta, const gtsam::Point2& t);
Pose2(const gtsam::Rot2& r, const gtsam::Point2& t);
@ -505,10 +579,11 @@ class Pose2 {
void serialize() const;
};
#include <gtsam/geometry/Pose3.h>
class Pose3 {
// Standard Constructors
Pose3();
Pose3(const gtsam::Pose3& pose);
Pose3(const gtsam::Pose3& other);
Pose3(const gtsam::Rot3& r, const gtsam::Point3& t);
Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose)
Pose3(Matrix t);
@ -554,6 +629,7 @@ class Pose3 {
};
// std::vector<gtsam::Pose3>
#include <gtsam/geometry/Pose3.h>
class Pose3Vector
{
Pose3Vector();
@ -606,6 +682,7 @@ class EssentialMatrix {
double error(Vector vA, Vector vB);
};
#include <gtsam/geometry/Cal3_S2.h>
class Cal3_S2 {
// Standard Constructors
Cal3_S2();
@ -662,7 +739,6 @@ virtual class Cal3DS2_Base {
// Action on Point2
gtsam::Point2 uncalibrate(const gtsam::Point2& p) const;
gtsam::Point2 calibrate(const gtsam::Point2& p, double tol) const;
gtsam::Point2 calibrate(const gtsam::Point2& p) const;
// enabling serialization functionality
void serialize() const;
@ -754,7 +830,6 @@ class Cal3Bundler {
// Action on Point2
gtsam::Point2 calibrate(const gtsam::Point2& p, double tol) const;
gtsam::Point2 calibrate(const gtsam::Point2& p) const;
gtsam::Point2 uncalibrate(const gtsam::Point2& p) const;
// Standard Interface
@ -772,6 +847,7 @@ class Cal3Bundler {
void serialize() const;
};
#include <gtsam/geometry/CalibratedCamera.h>
class CalibratedCamera {
// Standard Constructors and Named Constructors
CalibratedCamera();
@ -801,6 +877,7 @@ class CalibratedCamera {
void serialize() const;
};
#include <gtsam/geometry/PinholeCamera.h>
template<CALIBRATION>
class PinholeCamera {
// Standard Constructors and Named Constructors
@ -838,6 +915,7 @@ class PinholeCamera {
void serialize() const;
};
#include <gtsam/geometry/SimpleCamera.h>
virtual class SimpleCamera {
// Standard Constructors and Named Constructors
SimpleCamera();
@ -882,6 +960,7 @@ typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
#include <gtsam/geometry/StereoCamera.h>
class StereoCamera {
// Standard Constructors and Named Constructors
StereoCamera();
@ -959,7 +1038,6 @@ virtual class SymbolicFactorGraph {
// Standard interface
gtsam::KeySet keys() const;
void push_back(gtsam::SymbolicFactor* factor);
void push_back(const gtsam::SymbolicFactorGraph& graph);
void push_back(const gtsam::SymbolicBayesNet& bayesNet);
void push_back(const gtsam::SymbolicBayesTree& bayesTree);
@ -1034,14 +1112,14 @@ class SymbolicBayesTree {
//Constructors
SymbolicBayesTree();
SymbolicBayesTree(const gtsam::SymbolicBayesTree& other);
SymbolicBayesTree(const gtsam::SymbolicBayesTree& other);
// Testable
void print(string s);
bool equals(const gtsam::SymbolicBayesTree& other, double tol) const;
//Standard Interface
//size_t findParentClique(const gtsam::IndexVector& parents) const;
//size_t findParentClique(const gtsam::IndexVector& parents) const;
size_t size();
void saveGraph(string s) const;
void clear();
@ -1496,7 +1574,7 @@ virtual class GaussianBayesNet {
size_t size() const;
// FactorGraph derived interface
size_t size() const;
// size_t size() const;
gtsam::GaussianConditional* at(size_t idx) const;
gtsam::KeySet keys() const;
bool exists(size_t idx) const;
@ -1543,6 +1621,7 @@ virtual class GaussianBayesTree {
gtsam::GaussianBayesNet* jointBayesNet(size_t key1, size_t key2) const;
};
#include <gtsam/linear/Errors.h>
class Errors {
//Constructors
Errors();
@ -1553,6 +1632,7 @@ class Errors {
bool equals(const gtsam::Errors& expected, double tol) const;
};
#include <gtsam/linear/GaussianISAM.h>
class GaussianISAM {
//Constructor
GaussianISAM();
@ -1589,7 +1669,7 @@ virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParamete
void setReset(int value);
void setEpsilon_rel(double value);
void setEpsilon_abs(double value);
void print();
void print() const;
};
#include <gtsam/linear/SubgraphSolver.h>
@ -1683,6 +1763,7 @@ class Ordering {
void serialize() const;
};
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
class NonlinearFactorGraph {
NonlinearFactorGraph();
NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);
@ -1713,6 +1794,7 @@ class NonlinearFactorGraph {
void serialize() const;
};
#include <gtsam/nonlinear/NonlinearFactor.h>
virtual class NonlinearFactor {
// Factor base class
size_t size() const;
@ -1720,7 +1802,7 @@ virtual class NonlinearFactor {
void print(string s) const;
void printKeys(string s) const;
// NonlinearFactor
void equals(const gtsam::NonlinearFactor& other, double tol) const;
bool 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;
@ -1729,8 +1811,9 @@ virtual class NonlinearFactor {
// gtsam::NonlinearFactor* rekey(const gtsam::KeyVector& newKeys) const; //FIXME: Conversion from KeyVector to std::vector does not happen
};
#include <gtsam/nonlinear/NonlinearFactor.h>
virtual class NoiseModelFactor: gtsam::NonlinearFactor {
void equals(const gtsam::NoiseModelFactor& other, double tol) const;
bool 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;
@ -1809,95 +1892,6 @@ class Values {
double atDouble(size_t j) const;
};
// Actually a FastList<Key>
#include <gtsam/inference/Key.h>
class KeyList {
KeyList();
KeyList(const gtsam::KeyList& other);
// Note: no print function
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
size_t front() const;
size_t back() const;
void push_back(size_t key);
void push_front(size_t key);
void pop_back();
void pop_front();
void sort();
void remove(size_t key);
void serialize() const;
};
// Actually a FastSet<Key>
class KeySet {
KeySet();
KeySet(const gtsam::KeySet& other);
KeySet(const gtsam::KeyVector& other);
KeySet(const gtsam::KeyList& other);
// Testable
void print(string s) const;
bool equals(const gtsam::KeySet& other) const;
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
void insert(size_t key);
void merge(gtsam::KeySet& other);
bool erase(size_t key); // returns true if value was removed
bool count(size_t key) const; // returns true if value exists
void serialize() const;
};
// Actually a vector<Key>
class KeyVector {
KeyVector();
KeyVector(const gtsam::KeyVector& other);
// Note: no print function
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
size_t at(size_t i) const;
size_t front() const;
size_t back() const;
void push_back(size_t key) const;
void serialize() const;
};
// Actually a FastMap<Key,int>
class KeyGroupMap {
KeyGroupMap();
// Note: no print function
// common STL methods
size_t size() const;
bool empty() const;
void clear();
// structure specific methods
size_t at(size_t key) const;
int erase(size_t key);
bool insert2(size_t key, int val);
};
#include <gtsam/nonlinear/Marginals.h>
class Marginals {
Marginals(const gtsam::NonlinearFactorGraph& graph,
@ -1954,8 +1948,6 @@ virtual class LinearContainerFactor : gtsam::NonlinearFactor {
//*************************************************************************
// Nonlinear optimizers
//*************************************************************************
#include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/NonlinearOptimizerParams.h>
virtual class NonlinearOptimizerParams {
NonlinearOptimizerParams();
@ -2020,6 +2012,7 @@ virtual class DoglegParams : gtsam::NonlinearOptimizerParams {
void setVerbosityDL(string verbosityDL) const;
};
#include <gtsam/nonlinear/NonlinearOptimizer.h>
virtual class NonlinearOptimizer {
gtsam::Values optimize();
gtsam::Values optimizeSafely();
@ -2029,17 +2022,20 @@ virtual class NonlinearOptimizer {
void iterate() const;
};
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
virtual class GaussNewtonOptimizer : gtsam::NonlinearOptimizer {
GaussNewtonOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues);
GaussNewtonOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::GaussNewtonParams& params);
};
#include <gtsam/nonlinear/DoglegOptimizer.h>
virtual class DoglegOptimizer : gtsam::NonlinearOptimizer {
DoglegOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues);
DoglegOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::DoglegParams& params);
double getDelta() const;
};
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer {
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues);
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::LevenbergMarquardtParams& params);
@ -2163,7 +2159,11 @@ class ISAM2 {
gtsam::Values getLinearizationPoint() const;
gtsam::Values calculateEstimate() const;
gtsam::Value calculateEstimate(size_t key) const;
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
gtsam::Cal3Bundler, gtsam::EssentialMatrix,
gtsam::SimpleCamera, Vector, Matrix}>
VALUE calculateEstimate(size_t key) const;
gtsam::Values calculateBestEstimate() const;
Matrix marginalCovariance(size_t key) const;
gtsam::VectorValues getDelta() const;
@ -2493,6 +2493,7 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams {
Matrix getAccelerometerCovariance() const;
Matrix getIntegrationCovariance() const;
bool getUse2ndOrderCoriolis() const;
void print(string s) const;
};
#include <gtsam/navigation/ImuFactor.h>
@ -2570,7 +2571,6 @@ virtual class CombinedImuFactor: gtsam::NonlinearFactor {
class PreintegratedAhrsMeasurements {
// Standard Constructor
PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance);
PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance);
PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs);
// Testable

View File

@ -172,9 +172,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX)
include(GtsamCythonWrap)
# Wrap
wrap_and_install_library_cython("../cython/gtsam.h" # interface_header
wrap_and_install_library_cython("../gtsam.h" # interface_header
"" # extra imports
"../cython" # path to setup.py.in
"../cython/gtsam" # path to setup.py.in
"${GTSAM_CYTHON_INSTALL_PATH}/gtsam" # install path
)
endif ()
endif ()