cython wrap unstable

release/4.3a0
Duy-Nguyen Ta 2017-03-18 15:52:08 -04:00
parent a6281e1932
commit d18e638b08
4 changed files with 57 additions and 30 deletions

View File

@ -1 +1,2 @@
from gtsam import *
from gtsam import *
from gtsam_unstable import *

View File

@ -0,0 +1,18 @@
from distutils.core import setup
from distutils.extension import Extension
from Cython.Build import cythonize
import eigency
setup(
ext_modules=cythonize(Extension(
"gtsam_unstable",
sources=["gtsam_unstable.pyx"],
include_dirs = ["${CMAKE_SOURCE_DIR}", "${CMAKE_BINARY_DIR}",
"${CMAKE_SOURCE_DIR}/gtsam/3rdparty/Eigen"
] + eigency.get_includes(include_eigen=False),
libraries=['gtsam', 'gtsam_unstable'],
library_dirs=["${GTSAM_DIR}/../../"],
language="c++",
extra_compile_args=["-std=c++11"])),
)

View File

@ -118,6 +118,20 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX)
wrap_and_install_library(gtsam_unstable.h "gtsam" "" "${mexFlags}")
endif(GTSAM_INSTALL_MATLAB_TOOLBOX)
# Cython wrap for gtsam_unstable
# Create the matlab toolbox for the gtsam library
if (GTSAM_INSTALL_CYTHON_TOOLBOX)
# Set up codegen
include(GtsamCythonWrap)
# Wrap
wrap_and_install_library_cython("../gtsam_unstable/gtsam_unstable.h" # interface_header
"from gtsam.gtsam cimport *" # extra imports
"../cython/gtsam_unstable" # path to setup.py.in
"${GTSAM_CYTHON_INSTALL_PATH}/gtsam" # install path
)
endif ()
# Build examples
add_subdirectory(examples)

View File

@ -276,7 +276,7 @@ class SimPolygon2D {
// Nonlinear factors from gtsam, for our Value types
#include <gtsam/slam/PriorFactor.h>
template<T = {gtsam::PoseRTV}>
virtual class PriorFactor : gtsam::NonlinearFactor {
virtual class PriorFactor : gtsam::NoiseModelFactor {
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
void serializable() const; // enabling serialization functionality
@ -285,7 +285,7 @@ virtual class PriorFactor : gtsam::NonlinearFactor {
#include <gtsam/slam/BetweenFactor.h>
template<T = {gtsam::PoseRTV}>
virtual class BetweenFactor : gtsam::NonlinearFactor {
virtual class BetweenFactor : gtsam::NoiseModelFactor {
BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
void serializable() const; // enabling serialization functionality
@ -363,13 +363,13 @@ virtual class SmartRangeFactor : gtsam::NoiseModelFactor {
void addRange(size_t key, double measuredRange);
gtsam::Point2 triangulate(const gtsam::Values& x) const;
void print(string s) const;
//void print(string s) const;
};
#include <gtsam/sam/RangeFactor.h>
template<POSE, POINT>
virtual class RangeFactor : gtsam::NonlinearFactor {
virtual class RangeFactor : gtsam::NoiseModelFactor {
RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
void serializable() const; // enabling serialization functionality
@ -380,7 +380,7 @@ typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> RangeFactorRTV;
#include <gtsam/nonlinear/NonlinearEquality.h>
template<T = {gtsam::PoseRTV}>
virtual class NonlinearEquality : gtsam::NonlinearFactor {
virtual class NonlinearEquality : gtsam::NoiseModelFactor {
// Constructor - forces exact evaluation
NonlinearEquality(size_t j, const T& feasible);
// Constructor - allows inexact evaluation
@ -391,7 +391,7 @@ virtual class NonlinearEquality : gtsam::NonlinearFactor {
#include <gtsam_unstable/dynamics/IMUFactor.h>
template<POSE = {gtsam::PoseRTV}>
virtual class IMUFactor : gtsam::NonlinearFactor {
virtual class IMUFactor : gtsam::NoiseModelFactor {
/** Standard constructor */
IMUFactor(Vector accel, Vector gyro,
double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
@ -409,7 +409,7 @@ virtual class IMUFactor : gtsam::NonlinearFactor {
#include <gtsam_unstable/dynamics/FullIMUFactor.h>
template<POSE = {gtsam::PoseRTV}>
virtual class FullIMUFactor : gtsam::NonlinearFactor {
virtual class FullIMUFactor : gtsam::NoiseModelFactor {
/** Standard constructor */
FullIMUFactor(Vector accel, Vector gyro,
double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
@ -425,13 +425,11 @@ virtual class FullIMUFactor : gtsam::NonlinearFactor {
size_t key2() const;
};
#include <gtsam_unstable/dynamics/DynamicsPriors.h>
virtual class DHeightPrior : gtsam::NonlinearFactor {
DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model);
};
virtual class DRollPrior : gtsam::NonlinearFactor {
/** allows for explicit roll parameterization - uses canonical coordinate */
DRollPrior(size_t key, double wx, const gtsam::noiseModel::Base* model);
@ -439,12 +437,10 @@ virtual class DRollPrior : gtsam::NonlinearFactor {
DRollPrior(size_t key, const gtsam::noiseModel::Base* model);
};
virtual class VelocityPrior : gtsam::NonlinearFactor {
VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model);
};
virtual class DGroundConstraint : gtsam::NonlinearFactor {
// Primary constructor allows for variable height of the "floor"
DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model);
@ -470,6 +466,7 @@ virtual class PendulumFactor1 : gtsam::NonlinearFactor {
Vector evaluateError(const gtsam::LieScalar& qk1, const gtsam::LieScalar& qk, const gtsam::LieScalar& v) const;
};
#include <gtsam_unstable/dynamics/Pendulum.h>
virtual class PendulumFactor2 : gtsam::NonlinearFactor {
/** Standard constructor */
PendulumFactor2(size_t vk1, size_t vk, size_t qKey, double dt, double L, double g);
@ -492,18 +489,17 @@ virtual class PendulumFactorPk1 : gtsam::NonlinearFactor {
};
#include <gtsam_unstable/dynamics/SimpleHelicopter.h>
virtual class Reconstruction : gtsam::NonlinearFactor {
virtual class Reconstruction : gtsam::NoiseModelFactor {
Reconstruction(size_t gKey1, size_t gKey, size_t xiKey, double h);
Vector evaluateError(const gtsam::Pose3& gK1, const gtsam::Pose3& gK, const gtsam::Vector6& xiK) const;
Vector evaluateError(const gtsam::Pose3& gK1, const gtsam::Pose3& gK, Vector xiK) const;
};
virtual class DiscreteEulerPoincareHelicopter : gtsam::NonlinearFactor {
virtual class DiscreteEulerPoincareHelicopter : gtsam::NoiseModelFactor {
DiscreteEulerPoincareHelicopter(size_t xiKey, size_t xiKey_1, size_t gKey,
double h, Matrix Inertia, Vector Fu, double m);
Vector evaluateError(const gtsam::Vector6& xiK, const gtsam::Vector6& xiK_1, const gtsam::Pose3& gK) const;
Vector evaluateError(Vector xiK, Vector xiK_1, const gtsam::Pose3& gK) const;
};
//*************************************************************************
@ -640,13 +636,13 @@ virtual class DiscreteEulerPoincareHelicopter : gtsam::NonlinearFactor {
// slam
//*************************************************************************
#include <gtsam_unstable/slam/RelativeElevationFactor.h>
virtual class RelativeElevationFactor: gtsam::NonlinearFactor {
virtual class RelativeElevationFactor: gtsam::NoiseModelFactor {
RelativeElevationFactor();
RelativeElevationFactor(size_t poseKey, size_t pointKey, double measured,
const gtsam::noiseModel::Base* model);
double measured() const;
void print(string s) const;
//void print(string s) const;
};
#include <gtsam_unstable/slam/DummyFactor.h>
@ -655,20 +651,20 @@ virtual class DummyFactor : gtsam::NonlinearFactor {
};
#include <gtsam_unstable/slam/InvDepthFactorVariant1.h>
virtual class InvDepthFactorVariant1 : gtsam::NonlinearFactor {
virtual class InvDepthFactorVariant1 : gtsam::NoiseModelFactor {
InvDepthFactorVariant1(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
};
#include <gtsam_unstable/slam/InvDepthFactorVariant2.h>
virtual class InvDepthFactorVariant2 : gtsam::NonlinearFactor {
virtual class InvDepthFactorVariant2 : gtsam::NoiseModelFactor {
InvDepthFactorVariant2(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::Point3& referencePoint, const gtsam::noiseModel::Base* model);
};
#include <gtsam_unstable/slam/InvDepthFactorVariant3.h>
virtual class InvDepthFactorVariant3a : gtsam::NonlinearFactor {
virtual class InvDepthFactorVariant3a : gtsam::NoiseModelFactor {
InvDepthFactorVariant3a(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
};
virtual class InvDepthFactorVariant3b : gtsam::NonlinearFactor {
virtual class InvDepthFactorVariant3b : gtsam::NoiseModelFactor {
InvDepthFactorVariant3b(size_t poseKey1, size_t poseKey2, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
};
@ -685,7 +681,7 @@ class Mechanization_bRn2 {
static gtsam::Mechanization_bRn2 initialize(Matrix U, Matrix F, double g_e);
gtsam::Mechanization_bRn2 correct(Vector dx) const;
gtsam::Mechanization_bRn2 integrate(Vector u, double dt) const;
void print(string s) const;
//void print(string s) const;
};
#include <gtsam_unstable/slam/AHRS.h>
@ -695,19 +691,17 @@ class AHRS {
pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> integrate(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector u, double dt);
pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aid(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, bool Farrel);
pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aidGeneral(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, Vector f_expected, const gtsam::Rot3& increment);
void print(string s) const;
//void print(string s) const;
};
// Tectonic SAM Factors
#include <gtsam_unstable/slam/TSAMFactors.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
//typedef gtsam::NoiseModelFactor2<gtsam::Pose2, gtsam::Point2> NLPosePose;
virtual class DeltaFactor : gtsam::NoiseModelFactor {
DeltaFactor(size_t i, size_t j, const gtsam::Point2& measured,
const gtsam::noiseModel::Base* noiseModel);
void print(string s) const;
//void print(string s) const;
};
//typedef gtsam::NoiseModelFactor4<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2,
@ -715,7 +709,7 @@ virtual class DeltaFactor : gtsam::NoiseModelFactor {
virtual class DeltaFactorBase : gtsam::NoiseModelFactor {
DeltaFactorBase(size_t b1, size_t i, size_t b2, size_t j,
const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel);
void print(string s) const;
//void print(string s) const;
};
//typedef gtsam::NoiseModelFactor4<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2,
@ -723,7 +717,7 @@ virtual class DeltaFactorBase : gtsam::NoiseModelFactor {
virtual class OdometryFactorBase : gtsam::NoiseModelFactor {
OdometryFactorBase(size_t b1, size_t i, size_t b2, size_t j,
const gtsam::Pose2& measured, const gtsam::noiseModel::Base* noiseModel);
void print(string s) const;
//void print(string s) const;
};
#include <gtsam/geometry/Cal3DS2.h>