diff --git a/python/handwritten/geometry_python.cpp b/python/handwritten/geometry_python.cpp deleted file mode 100644 index 61f1e3ee7..000000000 --- a/python/handwritten/geometry_python.cpp +++ /dev/null @@ -1,155 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 geometry_python.cpp - * @brief wraps geometry classes into the geometry submodule of gtsam - * @author Ellon Paiva Mendes (LAAS-CNRS) - **/ - - /** TODOs Summary: - * - */ - -#include - -#include - -#include -#include -#include - -using namespace boost::python; -using namespace gtsam; - -// Prototypes used to perform overloading -// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html -// Rot3 -gtsam::Rot3 (*AxisAngle_0)(const Vector3&, double) = &Rot3::AxisAngle; -gtsam::Rot3 (*AxisAngle_1)(const gtsam::Point3&, double) = &Rot3::AxisAngle; -gtsam::Rot3 (*Rodrigues_0)(const Vector3&) = &Rot3::Rodrigues; -gtsam::Rot3 (*Rodrigues_1)(double, double, double) = &Rot3::Rodrigues; -gtsam::Rot3 (*RzRyRx_0)(double, double, double) = &Rot3::RzRyRx; -gtsam::Rot3 (*RzRyRx_1)(const Vector&) = &Rot3::RzRyRx; -// Pose3 -BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(Pose3_equals_overloads_0, equals, 1, 2) -bool (Pose3::*equals_0)(const gtsam::Pose3&, double) const = &Pose3::equals; - - -BOOST_PYTHON_MODULE(libgeometry_python) -{ - -class_("Point3") - .def(init<>()) - .def(init()) - .def(init()) - .def("identity", &Point3::identity) - .staticmethod("identity") - .def("add", &Point3::add) - .def("cross", &Point3::cross) - .def("dist", &Point3::dist) - .def("distance", &Point3::distance) - .def("dot", &Point3::dot) - .def("equals", &Point3::equals) - .def("norm", &Point3::norm) - .def("normalize", &Point3::normalize) - .def("print", &Point3::print) - .def("sub", &Point3::sub) - .def("vector", &Point3::vector) - .def("x", &Point3::x) - .def("y", &Point3::y) - .def("z", &Point3::z) - .def(self * other()) - .def(other() * self) - .def(self + self) - .def(-self) - .def(self - self) - .def(self / other()) - .def(self_ns::str(self)) - .def(repr(self)) - .def(self == self) -; - -class_("Rot3") - .def(init<>()) - .def(init()) - .def(init()) - .def(init()) - .def(init()) - .def("AxisAngle", AxisAngle_0) - .def("AxisAngle", AxisAngle_1) - .staticmethod("AxisAngle") - .def("Expmap", &Rot3::Expmap) - .staticmethod("Expmap") - .def("ExpmapDerivative", &Rot3::ExpmapDerivative) - .staticmethod("ExpmapDerivative") - .def("Logmap", &Rot3::Logmap) - .staticmethod("Logmap") - .def("LogmapDerivative", &Rot3::LogmapDerivative) - .staticmethod("LogmapDerivative") - .def("Rodrigues", Rodrigues_0) - .def("Rodrigues", Rodrigues_1) - .staticmethod("Rodrigues") - .def("Rx", &Rot3::Rx) - .staticmethod("Rx") - .def("Ry", &Rot3::Ry) - .staticmethod("Ry") - .def("Rz", &Rot3::Rz) - .staticmethod("Rz") - .def("RzRyRx", RzRyRx_0) - .def("RzRyRx", RzRyRx_1) - .staticmethod("RzRyRx") - .def("identity", &Rot3::identity) - .staticmethod("identity") - .def("AdjointMap", &Rot3::AdjointMap) - .def("column", &Rot3::column) - .def("conjugate", &Rot3::conjugate) - .def("equals", &Rot3::equals) - .def("localCayley", &Rot3::localCayley) - .def("matrix", &Rot3::matrix) - .def("print", &Rot3::print) - .def("r1", &Rot3::r1) - .def("r2", &Rot3::r2) - .def("r3", &Rot3::r3) - .def("retractCayley", &Rot3::retractCayley) - .def("rpy", &Rot3::rpy) - .def("slerp", &Rot3::slerp) - .def("transpose", &Rot3::transpose) - .def("xyz", &Rot3::xyz) - .def(self * self) - .def(self * other()) - .def(self * other()) - .def(self_ns::str(self)) - .def(repr(self)) -; - -class_("Pose3") - .def(init<>()) - .def(init()) - .def(init()) - .def(init()) - .def("identity", &Pose3::identity) - .staticmethod("identity") - .def("bearing", &Pose3::bearing) - .def("equals", equals_0, Pose3_equals_overloads_0()) - .def("matrix", &Pose3::matrix) - .def("print", &Pose3::print) - .def("transform_from", &Pose3::transform_from) - .def("x", &Pose3::x) - .def("y", &Pose3::y) - .def("z", &Pose3::z) - .def(self * self) - .def(self * other()) - .def(self_ns::str(self)) - .def(repr(self)) -; - -} \ No newline at end of file diff --git a/python/handwritten/noiseModel_python.cpp b/python/handwritten/noiseModel_python.cpp deleted file mode 100644 index f9115b870..000000000 --- a/python/handwritten/noiseModel_python.cpp +++ /dev/null @@ -1,128 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 noiseModel_python.cpp - * @brief wraps the noise model classes into the noiseModel module - * @author Ellon Paiva Mendes (LAAS-CNRS) - **/ - - /** TODOs Summary: - * - * TODO(Ellon): Don't know yet it it's worth/needed to add 'Wrap structs' for each of the noise models. - * I think it's only worthy if we want to access virtual the virtual functions from python. - * TODO(Ellon): Wrap non-pure virtual methods of Base on BaseWrap - */ - -#include - -#include - -using namespace boost::python; -using namespace gtsam; -using namespace gtsam::noiseModel; - -// Wrap around pure virtual class Base. -// All pure virtual methods should be wrapped. Non-pure may be wrapped if we want to mimic the -// overloading through inheritance in Python. -// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/exposing.html#python.class_virtual_functions -struct BaseCallback : Base, wrapper -{ - void print (const std::string & name="") const { - this->get_override("print")(); - } - bool equals (const Base & expected, double tol=1e-9) const { - return this->get_override("equals")(); - } - Vector whiten (const Vector & v) const { - return this->get_override("whiten")(); - } - Matrix Whiten (const Matrix & v) const { - return this->get_override("Whiten")(); - } - Vector unwhiten (const Vector & v) const { - return this->get_override("unwhiten")(); - } - double distance (const Vector & v) const { - return this->get_override("distance")(); - } - void WhitenSystem (std::vector< Matrix > &A, Vector &b) const { - this->get_override("WhitenSystem")(); - } - void WhitenSystem (Matrix &A, Vector &b) const { - this->get_override("WhitenSystem")(); - } - void WhitenSystem (Matrix &A1, Matrix &A2, Vector &b) const { - this->get_override("WhitenSystem")(); - } - void WhitenSystem (Matrix &A1, Matrix &A2, Matrix &A3, Vector &b) const { - this->get_override("WhitenSystem")(); - } - - // TODO(Ellon): Wrap non-pure virtual methods should go here. - // See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/exposing.html#python.virtual_functions_with_default_implementations - -}; - -// Overloads for named constructors. Named constructors are static, so we declare them -// using BOOST_PYTHON_FUNCTION_OVERLOADS instead of BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS -// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html#python.default_arguments -BOOST_PYTHON_FUNCTION_OVERLOADS(Gaussian_SqrtInformation_overloads, Gaussian::SqrtInformation, 1, 2) -BOOST_PYTHON_FUNCTION_OVERLOADS(Gaussian_Information_overloads, Gaussian::Information, 1, 2) -BOOST_PYTHON_FUNCTION_OVERLOADS(Gaussian_Covariance_overloads, Gaussian::Covariance, 1, 2) -BOOST_PYTHON_FUNCTION_OVERLOADS(Diagonal_Sigmas_overloads, Diagonal::Sigmas, 1, 2) -BOOST_PYTHON_FUNCTION_OVERLOADS(Diagonal_Variances_overloads, Diagonal::Variances, 1, 2) -BOOST_PYTHON_FUNCTION_OVERLOADS(Diagonal_Precisions_overloads, Diagonal::Precisions, 1, 2) -BOOST_PYTHON_FUNCTION_OVERLOADS(Isotropic_Sigma_overloads, Isotropic::Sigma, 2, 3) -BOOST_PYTHON_FUNCTION_OVERLOADS(Isotropic_Variance_overloads, Isotropic::Variance, 2, 3) -BOOST_PYTHON_FUNCTION_OVERLOADS(Isotropic_Precision_overloads, Isotropic::Precision, 2, 3) - -BOOST_PYTHON_MODULE(libnoiseModel_python) -{ - -class_("Base") - .def("print", pure_virtual(&Base::print)) -; - -// NOTE: We should use "Base" in "bases<...>", and not "BaseCallback" (it was not clear at the begining) -class_, bases >("Gaussian", no_init) - .def("SqrtInformation",&Gaussian::SqrtInformation, Gaussian_SqrtInformation_overloads()) - .staticmethod("SqrtInformation") - .def("Information",&Gaussian::Information, Gaussian_Information_overloads()) - .staticmethod("Information") - .def("Covariance",&Gaussian::Covariance, Gaussian_Covariance_overloads()) - .staticmethod("Covariance") -; - -class_, bases >("Diagonal", no_init) - .def("Sigmas",&Diagonal::Sigmas, Diagonal_Sigmas_overloads()) - .staticmethod("Sigmas") - .def("Variances",&Diagonal::Variances, Diagonal_Variances_overloads()) - .staticmethod("Variances") - .def("Precisions",&Diagonal::Precisions, Diagonal_Precisions_overloads()) - .staticmethod("Precisions") -; - -class_, bases >("Isotropic", no_init) - .def("Sigma",&Isotropic::Sigma, Isotropic_Sigma_overloads()) - .staticmethod("Sigma") - .def("Variance",&Isotropic::Variance, Isotropic_Variance_overloads()) - .staticmethod("Variance") - .def("Precision",&Isotropic::Precision, Isotropic_Precision_overloads()) - .staticmethod("Precision") -; - -class_, bases >("Unit", no_init) - .def("Create",&Unit::Create) - .staticmethod("Create") -; - -} \ No newline at end of file diff --git a/python/handwritten/nonlinear_python.cpp b/python/handwritten/nonlinear_python.cpp deleted file mode 100644 index de164957c..000000000 --- a/python/handwritten/nonlinear_python.cpp +++ /dev/null @@ -1,139 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 nonlinear_python.cpp - * @brief wraps nonlinear classes into the nonlinear submodule of gtsam python - * @author Ellon Paiva Mendes (LAAS-CNRS) - **/ - - /** TODOs Summary: - * - */ - -#include - -#include -#include -#include - -#include - -using namespace boost::python; -using namespace gtsam; - -// Overloading macros -// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html -// ISAM2 -BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(ISAM2_update_overloads, ISAM2::update, 0, 7) - - -/** The function ValuesAt is a workaround to be able to call the correct templated version - * of Values::at. Without it, python would only try to match the last 'at' metho defined - * below. With this wrapper function we can call 'at' in python passing an extra type, - * which will define the type to be returned. Example: - * - * >>> import gtsam - * >>> v = gtsam.nonlinear.Values() - * >>> v.insert(1,gtsam.geometry.Point3()) - * >>> v.insert(2,gtsam.geometry.Rot3()) - * >>> v.insert(3,gtsam.geometry.Pose3()) - * >>> v.at(1,gtsam.geometry.Point3()) - * >>> v.at(2,gtsam.geometry.Rot3()) - * >>> v.at(3,gtsam.geometry.Pose3()) - * - * A more 'pythonic' way I think would be to not use this function and define different - * 'at' methods below using the name of the type in the function name, like: - * - * .def("point3_at", &Values::at, return_internal_reference<>()) - * .def("rot3_at", &Values::at, return_internal_reference<>()) - * .def("pose3_at", &Values::at, return_internal_reference<>()) - * - * and then they could be accessed from python as - * - * >>> import gtsam - * >>> v = gtsam.nonlinear.Values() - * >>> v.insert(1,gtsam.geometry.Point3()) - * >>> v.insert(2,gtsam.geometry.Rot3()) - * >>> v.insert(3,gtsam.geometry.Pose3()) - * >>> v.point3_at(1) - * >>> v.rot3_at(2) - * >>> v.pose3_at(3) - * - * In fact, I just saw the pythonic way sounds more clear, so I'm sticking with this and - * leaving the comments here for future reference. I'm using the PEP0008 for method naming. - * See: https://www.python.org/dev/peps/pep-0008/#function-and-method-arguments - */ -// template -// const T & ValuesAt( const Values & v, Key j, T /*type*/) -// { -// return v.at(j); -// } - -BOOST_PYTHON_MODULE(libnonlinear_python) -{ - -// Function pointers for overloads in Values -void (Values::*insert_0)(const gtsam::Values&) = &Values::insert; -void (Values::*insert_1)(Key, const gtsam::Point3&) = &Values::insert; -void (Values::*insert_2)(Key, const gtsam::Rot3&) = &Values::insert; -void (Values::*insert_3)(Key, const gtsam::Pose3&) = &Values::insert; - -class_("Values") - .def(init<>()) - .def(init()) - .def("clear", &Values::clear) - .def("dim", &Values::dim) - .def("empty", &Values::empty) - .def("equals", &Values::equals) - .def("erase", &Values::erase) - .def("insert_fixed", &Values::insertFixed) - .def("print", &Values::print) - .def("size", &Values::size) - .def("swap", &Values::swap) - .def("insert", insert_0) - .def("insert", insert_1) - .def("insert", insert_2) - .def("insert", insert_3) - // .def("at", &ValuesAt, return_internal_reference<>()) - // .def("at", &ValuesAt, return_internal_reference<>()) - // .def("at", &ValuesAt, return_internal_reference<>()) - .def("point3_at", &Values::at, return_internal_reference<>()) - .def("rot3_at", &Values::at, return_internal_reference<>()) - .def("pose3_at", &Values::at, return_internal_reference<>()) -; - -// Function pointers for overloads in NonlinearFactorGraph -void (NonlinearFactorGraph::*add_0)(const NonlinearFactorGraph::sharedFactor&) = &NonlinearFactorGraph::add; - -class_("NonlinearFactorGraph") - .def("size",&NonlinearFactorGraph::size) - .def("add", add_0) -; - -// TODO(Ellon): Export all properties of ISAM2Params -class_("ISAM2Params") -; - -// TODO(Ellon): Export useful methods/properties of ISAM2Result -class_("ISAM2Result") -; - -// Function pointers for overloads in ISAM2 -Values (ISAM2::*calculateEstimate_0)() const = &ISAM2::calculateEstimate; - -class_("ISAM2") - // TODO(Ellon): wrap all optional values of update - .def("update",&ISAM2::update, ISAM2_update_overloads()) - .def("calculate_estimate", calculateEstimate_0) -; - -} \ No newline at end of file diff --git a/python/handwritten/registernumpyeigen_python.cpp b/python/handwritten/registernumpyeigen_python.cpp deleted file mode 100644 index cb8980494..000000000 --- a/python/handwritten/registernumpyeigen_python.cpp +++ /dev/null @@ -1,54 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 libregisternumpyeigen_python.cpp - * @brief register conversion matrix between numpy and Eigen - * @author Ellon Paiva Mendes (LAAS-CNRS) - **/ - - #include - -#include - -#include -#include - -using namespace boost::python; -using namespace gtsam; - -BOOST_PYTHON_MODULE(libregisternumpyeigen_python) -{ - -import_array(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); - -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); -NumpyEigenConverter::register_converter(); - -} diff --git a/python/handwritten/slam_python.cpp b/python/handwritten/slam_python.cpp deleted file mode 100644 index c3c86661a..000000000 --- a/python/handwritten/slam_python.cpp +++ /dev/null @@ -1,86 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 slam_python.cpp - * @brief wraps slam classes into the slam submodule of gtsam python - * @author Ellon Paiva Mendes (LAAS-CNRS) - **/ - - /** TODOs Summary: - * - */ - -#include - -#include -#include -#include -#include -#include -#include - -using namespace boost::python; -using namespace gtsam; - -// Prototypes used to perform overloading -// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html -// *NONE* - -// Wrap around pure virtual class NonlinearFactor. -// All pure virtual methods should be wrapped. Non-pure may be wrapped if we want to mimic the -// overloading through inheritance in Python. -// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/exposing.html#python.class_virtual_functions -struct NonlinearFactorCallback : NonlinearFactor, wrapper -{ - double error (const Values & values) const { - return this->get_override("error")(values); - } - size_t dim () const { - return this->get_override("dim")(); - } - boost::shared_ptr linearize(const Values & values) const { - return this->get_override("linearize")(values); - } -}; - -// Macro used to define templated factors -#define BETWEENFACTOR(VALUE) \ - class_< BetweenFactor, bases, boost::shared_ptr< BetweenFactor > >("BetweenFactor"#VALUE) \ - .def(init()) \ - .def("measured", &BetweenFactor::measured, return_internal_reference<>()) \ -; - -#define PRIORFACTOR(VALUE) \ - class_< PriorFactor, bases, boost::shared_ptr< PriorFactor > >("PriorFactor"#VALUE) \ - .def(init()) \ - .def("prior", &PriorFactor::prior, return_internal_reference<>()) \ -; - -BOOST_PYTHON_MODULE(libslam_python) -{ - - class_("NonlinearFactor") - ; - - BETWEENFACTOR(Point3) - - BETWEENFACTOR(Rot3) - - BETWEENFACTOR(Pose3) - - PRIORFACTOR(Point3) - - PRIORFACTOR(Rot3) - - PRIORFACTOR(Pose3) - -} \ No newline at end of file