From ec934770f3dc7702a738c8276bbb2598d3d9a6bd Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 15 Nov 2013 06:59:02 +0000 Subject: [PATCH 001/105] Initial stages of python wrapping. Issues with method overloading, boost optionals. Testing with Point2 only now --- CMakeLists.txt | 5 +++++ python/CMakeLists.txt | 25 +++++++++++++++++++++++++ python/base/DerivedValue.cpp | 9 +++++++++ python/base/Value.cpp | 10 ++++++++++ python/geometry/Point2.cpp | 23 +++++++++++++++++++++++ python/geometry/exportGeometry.cpp | 10 ++++++++++ 6 files changed, 82 insertions(+) create mode 100644 python/CMakeLists.txt create mode 100644 python/base/DerivedValue.cpp create mode 100644 python/base/Value.cpp create mode 100644 python/geometry/Point2.cpp create mode 100644 python/geometry/exportGeometry.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 0380b8a2f..bbf7de2e9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,6 +30,7 @@ message(STATUS "GTSAM_SOURCE_ROOT_DIR: [${GTSAM_SOURCE_ROOT_DIR}]") # Load build type flags and default to Debug mode include(GtsamBuildTypes) +include(GtsamPythonWrap) # Use macros for creating tests/timing scripts include(GtsamTesting) @@ -344,6 +345,10 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX) add_subdirectory(matlab) endif() +if(GTSAM_BUILD_PYTHON) + add_subdirectory(python) +endif() + # Build gtsam_unstable if (GTSAM_BUILD_UNSTABLE) add_subdirectory(gtsam_unstable) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt new file mode 100644 index 000000000..be739d7b4 --- /dev/null +++ b/python/CMakeLists.txt @@ -0,0 +1,25 @@ +include_directories("${PROJECT_SOURCE_DIR}/gtsam") + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../cmake) + +#include_directories(${EIGEN_INCLUDE_DIRS}) + +file(GLOB base_src "base/*.cpp") +file(GLOB geometry_src "geometry/*.cpp") +file(GLOB inference_src "inference/*.cpp") +file(GLOB linear_src "linear/*.cpp") +file(GLOB nonlinear_src "nonlinear/*.cpp") +file(GLOB slam_src "slam/*.cpp") +file(GLOB symbolic_src "symbolic/*.cpp") + +#wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src}) +wrap_python("geometry" ${PROJECT_SOURCE_DIR}/python/gtsam ${geometry_src}) + +#add_python_export_library(${PROJECT_NAME}_test ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} +# ${AUTOGEN_TEST_FILES} +#) \ No newline at end of file diff --git a/python/base/DerivedValue.cpp b/python/base/DerivedValue.cpp new file mode 100644 index 000000000..b389d14fc --- /dev/null +++ b/python/base/DerivedValue.cpp @@ -0,0 +1,9 @@ +#include +#include "gtsam/base/DerivedValue.h" + +using namespace boost::python; +using namespace gtsam; + +/*void exportDerivedValue(){ + class_ >("DerivedValue", no_init); +}*/ \ No newline at end of file diff --git a/python/base/Value.cpp b/python/base/Value.cpp new file mode 100644 index 000000000..052334dbf --- /dev/null +++ b/python/base/Value.cpp @@ -0,0 +1,10 @@ +#include +#include "gtsam/base/Value.h" + +using namespace boost::python; +using namespace gtsam; + +// Virtual class, no init +void exportValue(){ + class_("Value", no_init); +} \ No newline at end of file diff --git a/python/geometry/Point2.cpp b/python/geometry/Point2.cpp new file mode 100644 index 000000000..0f87a6e48 --- /dev/null +++ b/python/geometry/Point2.cpp @@ -0,0 +1,23 @@ +#include +#include "gtsam/geometry/Point2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_FUNCTION_OVERLOADS(equals_overloads, &Point2::equals, 1, 2) + +void exportPoint2(){ + + class_("Point2", init<>()) + .def(init()) + .def("print", &Point2::print) + .def("equals", &Point2::equals) + .def("inverse", &Point2::inverse) + .def("compose", &Point2::compose) + .def("between", &Point2::between) + .def("dim", &Point2::dim) + .def("retract", &Point2::retract) + .def("x", &Point2::x) + .def("y", &Point2::y) + ; +} \ No newline at end of file diff --git a/python/geometry/exportGeometry.cpp b/python/geometry/exportGeometry.cpp new file mode 100644 index 000000000..55bf7a83b --- /dev/null +++ b/python/geometry/exportGeometry.cpp @@ -0,0 +1,10 @@ +#include +#include + +void exportPoint2(); + +BOOST_PYTHON_MODULE(libgeometry){ + using namespace boost::python; + + exportPoint2(); +} \ No newline at end of file From 245578082924a3eeeb821bac7d41a93950fce802 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 15 Nov 2013 22:59:36 +0000 Subject: [PATCH 002/105] Rot2, Pose2, Point2 now all work fairly well in Python. See Pose2.cpp for examples on method overloading and auto-declarations --- python/geometry/Point2.cpp | 11 +++-- python/geometry/Pose2.cpp | 72 ++++++++++++++++++++++++++++++ python/geometry/Rot2.cpp | 48 ++++++++++++++++++++ python/geometry/exportGeometry.cpp | 5 ++- 4 files changed, 131 insertions(+), 5 deletions(-) create mode 100644 python/geometry/Pose2.cpp create mode 100644 python/geometry/Rot2.cpp diff --git a/python/geometry/Point2.cpp b/python/geometry/Point2.cpp index 0f87a6e48..0d1e7092b 100644 --- a/python/geometry/Point2.cpp +++ b/python/geometry/Point2.cpp @@ -4,20 +4,23 @@ using namespace boost::python; using namespace gtsam; -BOOST_PYTHON_FUNCTION_OVERLOADS(equals_overloads, &Point2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Point2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Point2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Point2::compose, 1, 3) void exportPoint2(){ class_("Point2", init<>()) .def(init()) - .def("print", &Point2::print) - .def("equals", &Point2::equals) + .def("print", &Point2::print, print_overloads(args("s"))) + .def("equals", &Point2::equals, equals_overloads(args("q","tol"))) .def("inverse", &Point2::inverse) - .def("compose", &Point2::compose) + .def("compose", &Point2::compose, compose_overloads(args("q", "H1", "H2"))) .def("between", &Point2::between) .def("dim", &Point2::dim) .def("retract", &Point2::retract) .def("x", &Point2::x) .def("y", &Point2::y) ; + } \ No newline at end of file diff --git a/python/geometry/Pose2.cpp b/python/geometry/Pose2.cpp new file mode 100644 index 000000000..577a8da2c --- /dev/null +++ b/python/geometry/Pose2.cpp @@ -0,0 +1,72 @@ +#include +#include "gtsam/geometry/Pose2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Pose2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Pose2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Pose2::compose, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Pose2::between, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_to_overloads, Pose2::transform_to, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_from_overloads, Pose2::transform_from, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(bearing_overloads, Pose2::bearing, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, Pose2::range, 1, 3) + +// Manually wrap + +void exportPose2(){ + + double (Pose2::*range1)(const Pose2&, boost::optional, boost::optional) const + = &Pose2::range; + double (Pose2::*range2)(const Point2&, boost::optional, boost::optional) const + = &Pose2::range; + + Rot2 (Pose2::*bearing1)(const Pose2&, boost::optional, boost::optional) const + = &Pose2::bearing; + Rot2 (Pose2::*bearing2)(const Point2&, boost::optional, boost::optional) const + = &Pose2::bearing; + + class_("Pose2", init<>()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &Pose2::print, print_overloads(args("s"))) + + .def("equals", &Pose2::equals, equals_overloads(args("pose","tol"))) + .def("inverse", &Pose2::inverse) + .def("compose", &Pose2::compose, compose_overloads(args("p2", "H1", "H2"))) + .def("between", &Pose2::between, between_overloads(args("p2", "H1", "H2"))) + .def("dim", &Pose2::dim) + .def("retract", &Pose2::retract) + + .def("transform_to", &Pose2::transform_to, + transform_to_overloads(args("point", "H1", "H2"))) + .def("transform_from", &Pose2::transform_from, + transform_to_overloads(args("point", "H1", "H2"))) + + .def("x", &Pose2::x) + .def("y", &Pose2::y) + .def("theta", &Pose2::theta) + // See documentation on call policy for more information + // https://wiki.python.org/moin/boost.python/CallPolicy + .def("t", &Pose2::t, return_value_policy()) + .def("r", &Pose2::r, return_value_policy()) + .def("translation", &Pose2::translation, return_value_policy()) + .def("rotation", &Pose2::rotation, return_value_policy()) + + .def("bearing", bearing1, bearing_overloads()) + .def("bearing", bearing2, bearing_overloads()) + + // Function overload example + .def("range", range1, range_overloads()) + .def("range", range2, range_overloads()) + + + .def("Expmap", &Pose2::Expmap) + .staticmethod("Expmap") + + .def(self * self) // __mult__ + ; + +} \ No newline at end of file diff --git a/python/geometry/Rot2.cpp b/python/geometry/Rot2.cpp new file mode 100644 index 000000000..06a6a7072 --- /dev/null +++ b/python/geometry/Rot2.cpp @@ -0,0 +1,48 @@ +#include +#include "gtsam/geometry/Rot2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Rot2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Rot2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Rot2::compose, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(relativeBearing_overloads, Rot2::relativeBearing, 1, 3) + +void exportRot2(){ + + class_("Rot2", init<>()) + .def(init()) + + .def("fromAngle", &Rot2::fromAngle) + .staticmethod("fromAngle") + + .def("fromDegrees", &Rot2::fromDegrees) + .staticmethod("fromDegrees") + + .def("fromCosSin", &Rot2::fromCosSin) + .staticmethod("fromCosSin") + + .def("atan2", &Rot2::atan2) + .staticmethod("atan2") + + .def("print", &Rot2::print, print_overloads(args("s"))) + .def("equals", &Rot2::equals, equals_overloads(args("q","tol"))) + .def("inverse", &Rot2::inverse) + .def("compose", &Rot2::compose, compose_overloads(args("q", "H1", "H2"))) + .def("between", &Rot2::between) + .def("dim", &Rot2::dim) + .def("retract", &Rot2::retract) + + .def("Expmap", &Rot2::Expmap) + .staticmethod("Expmap") + + .def("theta", &Rot2::theta) + .def("degrees", &Rot2::degrees) + .def("c", &Rot2::c) + .def("s", &Rot2::s) + + .def(self * self) // __mult__ + ; + +} \ No newline at end of file diff --git a/python/geometry/exportGeometry.cpp b/python/geometry/exportGeometry.cpp index 55bf7a83b..3887f7ca1 100644 --- a/python/geometry/exportGeometry.cpp +++ b/python/geometry/exportGeometry.cpp @@ -2,9 +2,12 @@ #include void exportPoint2(); +void exportRot2(); +void exportPose2(); BOOST_PYTHON_MODULE(libgeometry){ using namespace boost::python; - exportPoint2(); + exportRot2(); + exportPose2(); } \ No newline at end of file From d0efbadac8bce645402a32bfd7750443860a4f34 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 19 Nov 2013 04:28:38 +0000 Subject: [PATCH 003/105] Example on how to wrap templated classes such as factors --- python/CMakeLists.txt | 2 +- python/base/DerivedValue.cpp | 9 --------- python/base/Value.cpp | 10 ---------- python/slam/BearingFactor.cpp | 13 +++++++++++++ python/slam/BetweenFactor.cpp | 14 ++++++++++++++ python/slam/PriorFactor.cpp | 14 ++++++++++++++ python/slam/exportSlam.cpp | 24 ++++++++++++++++++++++++ 7 files changed, 66 insertions(+), 20 deletions(-) delete mode 100644 python/base/DerivedValue.cpp delete mode 100644 python/base/Value.cpp create mode 100644 python/slam/BearingFactor.cpp create mode 100644 python/slam/BetweenFactor.cpp create mode 100644 python/slam/PriorFactor.cpp create mode 100644 python/slam/exportSlam.cpp diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index be739d7b4..e503bdb45 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -19,7 +19,7 @@ file(GLOB symbolic_src "symbolic/*.cpp") #wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src}) wrap_python("geometry" ${PROJECT_SOURCE_DIR}/python/gtsam ${geometry_src}) - +wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src}) #add_python_export_library(${PROJECT_NAME}_test ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} # ${AUTOGEN_TEST_FILES} #) \ No newline at end of file diff --git a/python/base/DerivedValue.cpp b/python/base/DerivedValue.cpp deleted file mode 100644 index b389d14fc..000000000 --- a/python/base/DerivedValue.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include -#include "gtsam/base/DerivedValue.h" - -using namespace boost::python; -using namespace gtsam; - -/*void exportDerivedValue(){ - class_ >("DerivedValue", no_init); -}*/ \ No newline at end of file diff --git a/python/base/Value.cpp b/python/base/Value.cpp deleted file mode 100644 index 052334dbf..000000000 --- a/python/base/Value.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include -#include "gtsam/base/Value.h" - -using namespace boost::python; -using namespace gtsam; - -// Virtual class, no init -void exportValue(){ - class_("Value", no_init); -} \ No newline at end of file diff --git a/python/slam/BearingFactor.cpp b/python/slam/BearingFactor.cpp new file mode 100644 index 000000000..63d4bb3ed --- /dev/null +++ b/python/slam/BearingFactor.cpp @@ -0,0 +1,13 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +template +void exposeBearingFactor(const std::string& name){ + class_(name, init<>()) + ; +} \ No newline at end of file diff --git a/python/slam/BetweenFactor.cpp b/python/slam/BetweenFactor.cpp new file mode 100644 index 000000000..3674614da --- /dev/null +++ b/python/slam/BetweenFactor.cpp @@ -0,0 +1,14 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +template +void exposeBetweenFactor(const std::string& name){ + class_(name, init<>()) + .def(init()) + ; +} \ No newline at end of file diff --git a/python/slam/PriorFactor.cpp b/python/slam/PriorFactor.cpp new file mode 100644 index 000000000..e1ee27602 --- /dev/null +++ b/python/slam/PriorFactor.cpp @@ -0,0 +1,14 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +template +void exposePriorFactor(const std::string& name){ + class_(name, init<>()) + .def(init()) + ; +} \ No newline at end of file diff --git a/python/slam/exportSlam.cpp b/python/slam/exportSlam.cpp new file mode 100644 index 000000000..fdd1d1549 --- /dev/null +++ b/python/slam/exportSlam.cpp @@ -0,0 +1,24 @@ +#include +#include + +#include +#include +#include +#include + +template void exportPriorFactor(const std::string& name); +template void exportBetweenFactor(const std::string& name); + +BOOST_PYTHON_MODULE(libgeometry){ + using namespace boost::python; + + typedef gtsam::PriorFactor Point2PriorFactor; + typedef gtsam::PriorFactor Pose2PriorFactor; + + exportPriorFactor("Point2PriorFactor"); + exportPriorFactor("Pose2PriorFactor"); + + typedef gtsam::BetweenFactor Pose2BetweenFactor; + + exportBetweenFactor("Pose2BetweenFactor"); +} \ No newline at end of file From 414e6b58f91027e4050457e65ee1fbf30fab58a6 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Wed, 20 Nov 2013 02:30:44 +0000 Subject: [PATCH 004/105] Finally fixed templates, moved into single library for simplicity, add noisemodels, nonlinear --- python/CMakeLists.txt | 6 +- python/exportgtsam.cpp | 63 +++++++++++++++++++ python/geometry/exportGeometry.cpp | 13 ---- python/linear/NoiseModel.cpp | 13 ++++ .../nonlinear/LevenbergMarquardtOptimizer.cpp | 12 ++++ python/nonlinear/NonlinearFactorGraph.cpp | 18 ++++++ python/nonlinear/Values.cpp | 19 ++++++ python/slam/BearingFactor.cpp | 2 +- python/slam/BetweenFactor.cpp | 2 +- python/slam/PriorFactor.cpp | 8 +-- python/slam/exportSlam.cpp | 24 ------- 11 files changed, 135 insertions(+), 45 deletions(-) create mode 100644 python/exportgtsam.cpp delete mode 100644 python/geometry/exportGeometry.cpp create mode 100644 python/linear/NoiseModel.cpp create mode 100644 python/nonlinear/LevenbergMarquardtOptimizer.cpp create mode 100644 python/nonlinear/NonlinearFactorGraph.cpp create mode 100644 python/nonlinear/Values.cpp delete mode 100644 python/slam/exportSlam.cpp diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index e503bdb45..cd9861dc0 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -18,8 +18,10 @@ file(GLOB slam_src "slam/*.cpp") file(GLOB symbolic_src "symbolic/*.cpp") #wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src}) -wrap_python("geometry" ${PROJECT_SOURCE_DIR}/python/gtsam ${geometry_src}) -wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src}) +wrap_python("gtsam" ${PROJECT_SOURCE_DIR}/python/gtsam exportgtsam.cpp + ${geometry_src} ${linear_src} ${nonlinear_src} ${slam_src}) +#wrap_python("nonlinear" ${PROJECT_SOURCE_DIR}/python/gtsam ${nonlinear_src}) +#wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src}) #add_python_export_library(${PROJECT_NAME}_test ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} # ${AUTOGEN_TEST_FILES} #) \ No newline at end of file diff --git a/python/exportgtsam.cpp b/python/exportgtsam.cpp new file mode 100644 index 000000000..51e0ae1f3 --- /dev/null +++ b/python/exportgtsam.cpp @@ -0,0 +1,63 @@ +#include +#include + +#include +#include +#include +#include +#include + +using namespace boost::python; +using namespace gtsam; +using namespace std; + +// Geometery +void exportPoint2(); +void exportRot2(); +void exportPose2(); + +// Linear +void exportNoiseModels(); + +// Nonlinear +void exportValues(); +void exportNonlinearFactorGraph(); +void exportLevenbergMarquardtOptimizer(); + +// Slam +template< class FACTOR, class VALUE > +void exportPriorFactor(const std::string& name){ + class_< FACTOR >(name.c_str(), init<>()) + .def(init< Key, VALUE&, SharedNoiseModel >()) + ; +} + +template +void exportBetweenFactor(const std::string& name){ + class_(name.c_str(), init<>()) + .def(init()) + ; +} + +typedef gtsam::PriorFactor Point2PriorFactor; +typedef gtsam::PriorFactor Pose2PriorFactor; +typedef gtsam::BetweenFactor Pose2BetweenFactor; + +//-----------------------------------// + +BOOST_PYTHON_MODULE(libgtsam){ + using namespace boost::python; + exportPoint2(); + exportRot2(); + exportPose2(); + + exportNoiseModels(); + + exportValues(); + exportNonlinearFactorGraph(); + exportLevenbergMarquardtOptimizer(); + + exportPriorFactor< Point2PriorFactor, Point2 >("Point2PriorFactor"); + exportPriorFactor< Pose2PriorFactor, Pose2 >("Pose2PriorFactor"); + exportBetweenFactor< Pose2BetweenFactor, Pose2 >("Pose2BetweenFactor"); +} \ No newline at end of file diff --git a/python/geometry/exportGeometry.cpp b/python/geometry/exportGeometry.cpp deleted file mode 100644 index 3887f7ca1..000000000 --- a/python/geometry/exportGeometry.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#include -#include - -void exportPoint2(); -void exportRot2(); -void exportPose2(); - -BOOST_PYTHON_MODULE(libgeometry){ - using namespace boost::python; - exportPoint2(); - exportRot2(); - exportPose2(); -} \ No newline at end of file diff --git a/python/linear/NoiseModel.cpp b/python/linear/NoiseModel.cpp new file mode 100644 index 000000000..89ee26e9a --- /dev/null +++ b/python/linear/NoiseModel.cpp @@ -0,0 +1,13 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +void exportNoiseModels(){ + // Diagonal Noise Model, no constructor + class_("DiagonalNoiseModel", no_init) + .def("Sigmas", &noiseModel::Diagonal::Sigmas) + .staticmethod("Sigmas") + ; +} \ No newline at end of file diff --git a/python/nonlinear/LevenbergMarquardtOptimizer.cpp b/python/nonlinear/LevenbergMarquardtOptimizer.cpp new file mode 100644 index 000000000..b7e38359f --- /dev/null +++ b/python/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -0,0 +1,12 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +void exportLevenbergMarquardtOptimizer(){ + class_("LevenbergMarquardtOptimizer", + init()) + .def("optimize", &LevenbergMarquardtOptimizer::optimize, return_value_policy()) + ; +} \ No newline at end of file diff --git a/python/nonlinear/NonlinearFactorGraph.cpp b/python/nonlinear/NonlinearFactorGraph.cpp new file mode 100644 index 000000000..16aa4c6e4 --- /dev/null +++ b/python/nonlinear/NonlinearFactorGraph.cpp @@ -0,0 +1,18 @@ +#include +#include "gtsam/nonlinear/NonlinearFactorGraph.h" +#include + +using namespace boost::python; +using namespace gtsam; + + +void exportNonlinearFactorGraph(){ + + typedef boost::shared_ptr shared_factor; + + void (NonlinearFactorGraph::*push_back1)(const shared_factor& factor) = &NonlinearFactorGraph::push_back; + + class_("NonlinearFactorGraph", init<>()) + .def("push_back", push_back1) + ; +} \ No newline at end of file diff --git a/python/nonlinear/Values.cpp b/python/nonlinear/Values.cpp new file mode 100644 index 000000000..c1451cef1 --- /dev/null +++ b/python/nonlinear/Values.cpp @@ -0,0 +1,19 @@ +#include +#include + +using namespace boost::python; +using namespace gtsam; + +void exportValues(){ + + const Value& (Values::*at1)(Key) const = &Values::at; + bool (Values::*exists1)(Key) const = &Values::exists; + void (Values::*insert1)(Key, const Value&) = &Values::insert; + + class_("Values", init<>()) + .def(init()) + .def("at", at1, return_value_policy()) + .def("exists", exists1) + .def("insert", insert1, return_value_policy()) + ; +} \ No newline at end of file diff --git a/python/slam/BearingFactor.cpp b/python/slam/BearingFactor.cpp index 63d4bb3ed..b13d1f281 100644 --- a/python/slam/BearingFactor.cpp +++ b/python/slam/BearingFactor.cpp @@ -7,7 +7,7 @@ using namespace gtsam; using namespace std; template -void exposeBearingFactor(const std::string& name){ +void exportBearingFactor(const std::string& name){ class_(name, init<>()) ; } \ No newline at end of file diff --git a/python/slam/BetweenFactor.cpp b/python/slam/BetweenFactor.cpp index 3674614da..2732e4e7e 100644 --- a/python/slam/BetweenFactor.cpp +++ b/python/slam/BetweenFactor.cpp @@ -7,7 +7,7 @@ using namespace gtsam; using namespace std; template -void exposeBetweenFactor(const std::string& name){ +void exportBetweenFactor(const std::string& name){ class_(name, init<>()) .def(init()) ; diff --git a/python/slam/PriorFactor.cpp b/python/slam/PriorFactor.cpp index e1ee27602..1984fe144 100644 --- a/python/slam/PriorFactor.cpp +++ b/python/slam/PriorFactor.cpp @@ -6,9 +6,9 @@ using namespace gtsam; using namespace std; -template -void exposePriorFactor(const std::string& name){ - class_(name, init<>()) - .def(init()) +template< class FACTOR, class VALUE > +void exportPriorFactor(const std::string& name){ + class_< FACTOR >(name.c_str(), init<>()) + .def(init< Key, VALUE&, SharedNoiseModel >()) ; } \ No newline at end of file diff --git a/python/slam/exportSlam.cpp b/python/slam/exportSlam.cpp deleted file mode 100644 index fdd1d1549..000000000 --- a/python/slam/exportSlam.cpp +++ /dev/null @@ -1,24 +0,0 @@ -#include -#include - -#include -#include -#include -#include - -template void exportPriorFactor(const std::string& name); -template void exportBetweenFactor(const std::string& name); - -BOOST_PYTHON_MODULE(libgeometry){ - using namespace boost::python; - - typedef gtsam::PriorFactor Point2PriorFactor; - typedef gtsam::PriorFactor Pose2PriorFactor; - - exportPriorFactor("Point2PriorFactor"); - exportPriorFactor("Pose2PriorFactor"); - - typedef gtsam::BetweenFactor Pose2BetweenFactor; - - exportBetweenFactor("Pose2BetweenFactor"); -} \ No newline at end of file From def2f1a91ca237ea1265873cb2afcfaf6d5ae7f4 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Wed, 20 Nov 2013 05:31:21 +0000 Subject: [PATCH 005/105] Installation script for python Distutils for python package. Installs to default python dist-packages location call : python setup.py install --- python/gtsam/__init__.py | 1 + python/setup.py | 15 +++++++++++++++ 2 files changed, 16 insertions(+) create mode 100644 python/gtsam/__init__.py create mode 100644 python/setup.py diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py new file mode 100644 index 000000000..2e9b00af1 --- /dev/null +++ b/python/gtsam/__init__.py @@ -0,0 +1 @@ +from libgtsam import * \ No newline at end of file diff --git a/python/setup.py b/python/setup.py new file mode 100644 index 000000000..abbafda4b --- /dev/null +++ b/python/setup.py @@ -0,0 +1,15 @@ +#!/usr/bin/env python + +#http://docs.python.org/2/distutils/setupscript.html#setup-script + +from distutils.core import setup + +setup(name='GTSAM', + version='3.0', + description='Python Distribution Utilities', + author='Dellaert et. al', + author_email='Andrew.Melim@gatech.edu', + url='http://www.python.org/sigs/distutils-sig/', + packages=['gtsam'], + package_data={'gtsam' : ['libgtsam.so']}, + ) From 4e00f70e82f37248b623906608959f6f737effa5 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 15 Sep 2014 15:19:26 -0400 Subject: [PATCH 006/105] Updating cmake build --- cmake/GtsamPythonWrap.cmake | 3 ++- python/CMakeLists.txt | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/cmake/GtsamPythonWrap.cmake b/cmake/GtsamPythonWrap.cmake index d065a7828..fbad77a82 100644 --- a/cmake/GtsamPythonWrap.cmake +++ b/cmake/GtsamPythonWrap.cmake @@ -50,7 +50,8 @@ function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY) # On OSX and Linux, the python library must end in the extension .so. Build this # filename here. - get_property(PYLIB_OUTPUT_FILE TARGET ${TARGET_NAME} PROPERTY LOCATION) + #get_property(PYLIB_OUTPUT_FILE TARGET ${TARGET_NAME} PROPERTY LOCATION) + set(PYLIB_OUTPUT_FILE $) get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE) set(PYLIB_SO_NAME ${PYLIB_OUTPUT_NAME}.so) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index cd9861dc0..6693beba5 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -18,7 +18,7 @@ file(GLOB slam_src "slam/*.cpp") file(GLOB symbolic_src "symbolic/*.cpp") #wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src}) -wrap_python("gtsam" ${PROJECT_SOURCE_DIR}/python/gtsam exportgtsam.cpp +wrap_python("pygtsam" ${PROJECT_SOURCE_DIR}/python/gtsam exportgtsam.cpp ${geometry_src} ${linear_src} ${nonlinear_src} ${slam_src}) #wrap_python("nonlinear" ${PROJECT_SOURCE_DIR}/python/gtsam ${nonlinear_src}) #wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src}) From 20f5c465076ab6e51c67642ba98cc5a6267f6d62 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Wed, 17 Dec 2014 10:44:56 -0800 Subject: [PATCH 007/105] Reworked python directory structure. Added readme on constructing python module. Added first unit test for point2. Everything needed to get it passing is also here, including some renaming of variables and emitted library names Conflicts: cmake/GtsamPythonWrap.cmake python/handwritten/examples/OdometeryExample.py wrap/Module.cpp --- cmake/GtsamPythonWrap.cmake | 52 +++++++++++++----- python/README.txt | 12 ++++ python/gtsam/__init__.py | 2 +- python/gtsam/libgtsam_python.so | Bin 0 -> 63367 bytes python/gtsam_tests/testPoint2.py | 13 +++++ python/{ => handwritten}/CMakeLists.txt | 0 .../handwritten/examples/OdometeryExample.py | 7 +++ python/{ => handwritten}/exportgtsam.cpp | 0 python/{ => handwritten}/geometry/Point2.cpp | 0 python/{ => handwritten}/geometry/Pose2.cpp | 0 python/{ => handwritten}/geometry/Rot2.cpp | 0 .../{ => handwritten}/linear/NoiseModel.cpp | 0 .../nonlinear/LevenbergMarquardtOptimizer.cpp | 0 .../nonlinear/NonlinearFactorGraph.cpp | 0 python/{ => handwritten}/nonlinear/Values.cpp | 0 .../{ => handwritten}/slam/BearingFactor.cpp | 0 .../{ => handwritten}/slam/BetweenFactor.cpp | 0 python/{ => handwritten}/slam/PriorFactor.cpp | 0 python/setup.py | 2 +- 19 files changed, 71 insertions(+), 17 deletions(-) create mode 100644 python/README.txt create mode 100755 python/gtsam/libgtsam_python.so create mode 100644 python/gtsam_tests/testPoint2.py rename python/{ => handwritten}/CMakeLists.txt (100%) create mode 100644 python/handwritten/examples/OdometeryExample.py rename python/{ => handwritten}/exportgtsam.cpp (100%) rename python/{ => handwritten}/geometry/Point2.cpp (100%) rename python/{ => handwritten}/geometry/Pose2.cpp (100%) rename python/{ => handwritten}/geometry/Rot2.cpp (100%) rename python/{ => handwritten}/linear/NoiseModel.cpp (100%) rename python/{ => handwritten}/nonlinear/LevenbergMarquardtOptimizer.cpp (100%) rename python/{ => handwritten}/nonlinear/NonlinearFactorGraph.cpp (100%) rename python/{ => handwritten}/nonlinear/Values.cpp (100%) rename python/{ => handwritten}/slam/BearingFactor.cpp (100%) rename python/{ => handwritten}/slam/BetweenFactor.cpp (100%) rename python/{ => handwritten}/slam/PriorFactor.cpp (100%) mode change 100644 => 100755 python/setup.py diff --git a/cmake/GtsamPythonWrap.cmake b/cmake/GtsamPythonWrap.cmake index fbad77a82..581b068ad 100644 --- a/cmake/GtsamPythonWrap.cmake +++ b/cmake/GtsamPythonWrap.cmake @@ -36,24 +36,46 @@ function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY) ENDIF() ENDIF(APPLE) + if(MSVC) + add_library(${moduleName}_python MODULE ${ARGN}) + set_target_properties(${moduleName}_python PROPERTIES + OUTPUT_NAME ${moduleName}_python + CLEAN_DIRECT_OUTPUT 1 + VERSION 1 + SOVERSION 0 + SUFFIX ".pyd") + target_link_libraries(${moduleName}_python ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp - # Create a static library version - add_library(${TARGET_NAME} SHARED ${ARGN}) + set(PYLIB_OUTPUT_FILE $) + message(${PYLIB_OUTPUT_FILE}) + get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE) + set(PYLIB_SO_NAME ${PYLIB_OUTPUT_NAME}.pyd) - target_link_libraries(${TARGET_NAME} ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} gtsam-shared) - set_target_properties(${TARGET_NAME} PROPERTIES - OUTPUT_NAME ${TARGET_NAME} - CLEAN_DIRECT_OUTPUT 1 - VERSION 1 - SOVERSION 0) + ELSE() + # Create a shared library + add_library(${moduleName}_python SHARED ${generated_cpp_file}) + set_target_properties(${moduleName}_python PROPERTIES + OUTPUT_NAME ${moduleName}_python + CLEAN_DIRECT_OUTPUT 1) + target_link_libraries(${moduleName}_python ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp + # On OSX and Linux, the python library must end in the extension .so. Build this + # filename here. + get_property(PYLIB_OUTPUT_FILE TARGET ${moduleName}_python PROPERTY LOCATION) + set(PYLIB_OUTPUT_FILE $) + message(${PYLIB_OUTPUT_FILE}) + get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE) + set(PYLIB_SO_NAME lib${moduleName}_python.so) + ENDIF(MSVC) - # On OSX and Linux, the python library must end in the extension .so. Build this - # filename here. - #get_property(PYLIB_OUTPUT_FILE TARGET ${TARGET_NAME} PROPERTY LOCATION) - set(PYLIB_OUTPUT_FILE $) - get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE) - set(PYLIB_SO_NAME ${PYLIB_OUTPUT_NAME}.so) + # Installs the library in the gtsam folder, which is used by setup.py to create the gtsam package + set(PYTHON_MODULE_DIRECTORY ${CMAKE_SOURCE_DIR}/python/gtsam) + # Cause the library to be output in the correct directory. + add_custom_command(TARGET ${moduleName}_python + POST_BUILD + COMMAND cp -v ${PYLIB_OUTPUT_FILE} ${PYTHON_MODULE_DIRECTORY}/${PYLIB_SO_NAME} + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} + COMMENT "Copying library files to python directory" ) # Cause the library to be output in the correct directory. add_custom_command(TARGET ${TARGET_NAME} @@ -65,4 +87,4 @@ function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY) get_directory_property(AMCF ADDITIONAL_MAKE_CLEAN_FILES) list(APPEND AMCF ${PYTHON_MODULE_DIRECTORY}/${PYLIB_SO_NAME}) set_directory_properties(PROPERTIES ADDITIONAL_MAKE_CLEAN_FILES "${AMCF}") -endfunction(wrap_python) \ No newline at end of file +endfunction(wrap_python) diff --git a/python/README.txt b/python/README.txt new file mode 100644 index 000000000..5235300c2 --- /dev/null +++ b/python/README.txt @@ -0,0 +1,12 @@ +This directory contains the basic setup script and directory structure for the gtsam python module. +During the build of gtsam, when GTSAM_BUILD_PYTHON is enabled, the following instructions will run. +* Wrap parses gtsam.h and constructs a cpp file called ${moduleName}_python.cpp +* This file is then compiled and linked with BoostPython, generating a shared library which can then be imported by python +* The shared library is then copied to python/gtsam +* The user can use the setup.py script to build and install a python package, allowing easy importing into a python project. Examples: + * python setup.py sdist ---- Builds a tarball of the python package which can then be distributed + * python setup.py install ---- Installs the package into the python dist-packages folder. Can then be imported from any python file. +* To run the unit tests, you must first install the package on your path (TODO: Make this easier) + + +TODO: There are many issues with this build system, but these are the basics. diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 2e9b00af1..f1b07905b 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1 +1 @@ -from libgtsam import * \ No newline at end of file +from libgtsam_python import * diff --git a/python/gtsam/libgtsam_python.so b/python/gtsam/libgtsam_python.so new file mode 100755 index 0000000000000000000000000000000000000000..bd87730d7ac1534f9e835fa6997a6b0e77af8485 GIT binary patch literal 63367 zcmeIb34B|{wLgBnC^1=V6B2M(1sDiR97*1R6gjaHi8#T;CIkXp%a#(G*p?#6j!jt% z4iw{<_)!XBX=_8^0i`r;DNR|53n8I>eKch&ElUh#kqK>5%A;ZR?|WvEMpsu!2=3$k z|DW7Mnwjs+oH=vm%$YND@0G7|Rn1FJOUuy2m7#r0OGCW6jss2}XzMqK2m+^8rj5t< z(b^HLtR$$z|zyUQmXjdDge7$fALqzvw*ennkwT-MO=l$hrQ|Z8zNW^O--d{@FjMrWcK8jDl$@8z)pDNtiK5%G4>v44WXJn2 z?9ATO_mAw6?T1=DbIy7G<(bF6cFR2{o;LY{Q}4)_6@2FQxdd-)UU-tNaasRppJ`QD+{rHOS`v3G%`jnE#{(95pRd0Uzqn}^D z>Muw9ZOy9bSI@a))3k+uxVL$F&C|Dxp83+&zs&je+)J}R@mw?ct?JC> zKRvX;f6Q;rY3n|CnPdDcO<(u;t^PlqbJl0izxmkb|5{%7>gmPfr<63^dGW4aXS)7t z)w#R2p4FVYDdUdOGpqA1`s490Xzz4i&|dPR?`laM3wLo7#p*8Upc`XkECe#wG{l{HOrjNQ-_-KvlzUg%SqR# z;NOhTw=&J?9CWHVzCK02N>j-Bh{Md=9iIYkJKntfN~<}3O$xa^bFw-AuODqr=iC(X zxhutZoix#$&UTC!SWUVPA8%g%%G1pGd_IMo&p6SX&dwvu@#hXQ#}7#{Udv~gmoG~p zpCNSCOs~E;${fEUg&e$)7)T{u+f&FtEd~DtDfIT56mlC*(cdL0=+~ZNK3?ai7_Zk; z$nCe7zh-iqG1(mdNeVf%q|o!e6#Q4D=x<4ic7K{>&d)p9=J2_x9FNl`Y8wL_kbW5XeuURGb38|se;@OO=nM%u{R01Q=ntcRB?rJZ zztTA!YYR_GnQS~<(+0IXt@*NiBmbg%YZ)xMWOPx2q%DH zV%NXG58>69@$`G72)NcGBz#Ep%feyp8Q5pStwIi03;fs9IG@9U&kljlhW#Y|HG#VY z{zogP<6O;w6#{?cSV3P9I9~8`BJ_4po2upBhKjgAkzE@n@bbgLK|e&`{l{>8hz1DP zWrEHwtW(5)zrbhmY^^+3;6iSa&KEEy$D&>B4l66^6y+a4zlcs(m;+}C+`;r`s#a~_ zGlcbm$`1%Wp-$|&4uWO47>0*4V4g4HCo|oSx%A**&#-SsmR|7(?&K3B7pd&Zm`Btvr=edzn@)0`t_^IkG72chu7@B$Mn~ua%n`fVZL~Mc)9UWF3WNtUF|Voo zu2np}PUPN=^^5qtRm=-?hh6`GzeMHxMZY9{+UGDnZ@02?PWG*7A0bJ2m%wKT{8%<$ zrfb^_{5Qa!Q+b;hmt0Z)r>Ajz*f3s4f=}Y7PRy6}qWq6APnnzr|B_BE{97ttO`AVl zkMTe|S=tj@TV|dH0~P>a(h?k72C|B>~}=@Et5rmgB+0aPwO(+;enHhKJ0+d zL(((4-V*vVEXJjf!`cp39)mCR|5$-9PN9dZAXuVr74sBqu0E& zY$k74GmLK<3^KJlEZUWNRXdH-A2QItft8=G4IA*F&=aGdunBxJxe56|T=8db)P@vU(pnf_(Qb|=Qamg{k7iuW%C!rrNh;ZQngF=QqHvxr0k5;UI>-?{NYF_(3wy+*coXIv!j7_5Xj?GQ+}RQc1sj_h^d_Ia!r$r- zc_V?4XHi0*U9M7phrgjM;&)XueW)?yCpBX)j|6BaFm6yNFHPvRhYSKPZ16TWLrH_3dTdyT z5f61+G+4sRU_jfeOLaapKA($9IP5;i-Muj$pD`Xbn^nnpLFcN~XZuY}KK@H1E4Pj7WlYB9l z=FnL5exX4(7tHgue!iRkB!Y*Uo*2hiMBc}`9g=kBZ%1m0WS{)TBO+_k?X#u5OR!$$H-OEXvB%z9o!_q zEW(~Uic>a~U|+^adr~dGUso&D<(gXurNbtAT*+3b^IBIowff*hgxgv$c>0Qt4jooH z93T%P(y3$XpX5+{T~2w+MmObaQ{{Rk6>5w|tJK#N4hF(zzQ>-$3maLzfZ2qEl_Xxt z;ZSUgqT|VWEuEt#_=c|7lA?@@akw20GEmKYB~?hrD=%Kae2av6kgPzlbv$uVHW(=B z3B?`C#KpSyV&|k)zd1hCA+klujUh*4r%7YUlu)TL-pPNBBam>@idJu=EyTU>`AcG32X3un2R*TJ{J_Lh zb!nl?RV2=53@0oxPlhf0W!T%d_*)}kSG%hugw0Sh9cFyP?Ks3?6FdD;J2Mt1OXV?P zq05Evy@cPjqRkuf>E4D_ZP;Z)2DLaENpgXt#2qUd8gKy8;%!|)TayJ1RG}s&T2>tn z6m#!5;SdCkGw1}&TOSDhA38fy1cMHI6>Y;2rJ1(j?~f@<_~qUnN-e*HMK4eB>N@% z(!6iqn|Gw_Ly~w5N4xQ}KfcuN3uAFxmqe_#CVqYpQ#F247r!^gZ+Jn-SXR6%a1)5% z8FQ8Jv`d^_CEXXJV{bZoDYUU$GjRfX04JL4sF&SUBynR^W4GJ*dL^TYIv_WtdpXJ} zrV}8#g=5o|A*~1H6y!>9`_@PIgd?~?M@oSEZ-&~q?Ul0rH|5mRfusXh^==9ZYr-Mv+<7M%Jnn+y4Z0Hh29M?|M8#iMkQgun(f1g&lg%%T< zaf(SVtJvfQCe41sEz17BOsn%*qt4ZuCaP;{r8CE@dY8YWBC1ylTQF zxCM?447tbbK$Z~P32*hmlGU*1HR4FT3=m_ri*$w2jR=GH#DF;qzn<9Ek zz}MF7*PEN_*%J=p&RMb#A2V+@ev_Ua4Z&$JaZruB0}0j)_v_I>EuIiyPnOti@mm*3 zw=2|PFlzKZ-}9iE3>o5{a$HBNxp7aa&AQJU@$RYh*eZ+%EW&u$#8o}7TJg*=v1^L; zeQU*N?m=mR-Oj8zzv17W%!m}Y1G_E$(2wrxZ1uMA$27cc9mzy%B1J)O6IQ_X8i($} zC?r#j+dPNe8`k4DY~}L_#sQ+Cm8_UQpizWnv^ewCoMycoRyNOsnJ-=G?_3=S`CK*SCc_+SqQvX-(I`W4{NbRt!7sW(wnWtbM0)POB%hc zzGlBiDu63lza53_t`J`YbZ>LW@AY-+7#p-n_Re7EsK*Hlp~TNi_(%zvxf#Z7?7li3@mby+2&`-i8mBcRvwsXF`#rV%c|1_W4QMQw7|{-I zeN(#~qY{5eD`B%$TO&RGT3E+DJ}gNJX`pK_MH}q7HUrUpAtjekIiLv+6l*NTk(u*h z!VYya++@m;C&@pd-ozT$4$o)OQ=zo; zmYd~NUHGQ9MthRYH_DSi=yIqX>UzW;q+}M4bt6_~jJ9xzvKdRFF-{Ye@hb^j-OMo? zwQo;oD$hbD_V1f#Wvr#L|6AODi)6kQJ8ZEJ;y#kz-V}xjr=zqW94N3C6c-oRD4Xkuqd>q6V{QZ$D~c1~ z_CK+1IO1zK^;E)2s36^b39}NEYT&r;r;QL?n|eHYjSW2ATfuIVm8WOk1!pL%&1wv^ z_-A#r)nljKHVe05R?K3Y%&Ko|YWDHCHh=D1y%4O=uky^9t2@A=j5!L5wYf`|R?P9} z_JTqVFI|elMdC#Y4KG;W;@|vtXfp7tG=eCD5f3{GuPH`Tz4j-b?D?B{u$hK2|{0CwAhEnQ__{V05KH9?c@3ps7tw zlQqqvJtwfX!<+C5TBi1jQvMu~NA+L$$w~}JhW56=A}8O3SC`VYoua(_y(alSQ&&CJ z(zK1@Jt2u#*D+YzWWb%GynLTYmj8};??%2KY{Z8Lt&E_=Wm>+Ugx8_iZ}+f5_=<{l z2|rhY2zM*Ecx8y?=85;ZsJx2H_e}{e#V41Q*0eIE{I3K?fqV~-%G0}Avb4DuTyaOt|es$Q{Wvb@J0o{ zPNCl@-j5`?srdCud7o0gU%`K-;OiCq4h0`j@QW1uSq1;Lf^SpshZX!41s_oGVFm9~ z@GPZY_b7O-f?ulOc?w>u;8q3yzJkwC@Ea7|rrv1?-rd{+v*Ou@TiR5Z=4;Oz=t zt>AYl_)-PGQNimJ+^^t41+P=^4h3JX;MXhoLkixn;F}bDy@C%a_<(|6tKj!3_$me8 zq~HMse^$Y7SMY5LzCyuYQScfCA69T(!J`WPa|Pe6;6GMyr(*Xy6}(!(#ZLgR+@%WM zsFbf$aQSX5Wj8ALeM9SXii!MhZEoPuAk;9&*tSMUuAzFxt9so(<&K1spv zQ*byqv1_A(-xNbNZIgokM8Ss?e5ryztKc~bzD>a&Q1Dk2{AvXsR&ep^GRuuBxNwOW zzDvRHSLp0k@b4+O_CqU6k?ikO@GJ#itl+r{zE;8W6dbSc$1baaUl2nzZH9tJ6x^oZ z*DH9Lf?ufMP6gkn;BE!4R`6;CKSjZpD)^}iUZ>zI6}(ZwI}|*q;6G6C4h6qk!Mhav zRt3La!GEgY{R)1ig0ENbB?>;E;1?_SeF}cQf^Sst*$Tc%!M~;8Lkhl7!Jk#|76sp? z;1vq~ih{cod|1KfDR@-DzpLQ86nue#XWeCGDe^ZiQ}DdI&2d`_+^W#|4~5QB1^-V4 zzh1!`6g-*&A5ie~l=7OwkBTo<@H3S1c>`9K!p{%HcDMvs6+DBL;9oNoJX67K3T{#G zG6knL8M~?#d_oM>w51BJ+UGh2$4_m@4brOs5udG2Uix578 z#rRk5pp``kKbgh&SKgqNMF>BQ#rT(X(8?l&7qA%rnlWf)5yEG&82_>jT3Li}8;kL; zvOz105bj_x{^cCBvIyaYEXKdwgH{$Hyokm4SM{KkMF=luG5)o5(8?l&m#`TBsvESj z2;pTc#=jZ|tt>)#Ig9bH;GmU72)~)d_*ciEl|=|YoyGW9*PxX}2tSj>_}BG=Ru&=r zEEeNm{exB(A>7Gg{A>N7l|=}zU@`tRFlc2F!soCU|GIC`$|8i%WikG>anQ;lgu7Xc ze{CAHvIyZG7UN$-gH{$H{A?EEU+(S?vfRCv$#bom``V$1C3-xppSyc=*3(KML`RE{ zLy^%F^6{N>j1w_RH&UUI;Za;C98T#pN^fK7DU?p9^bku=pfreUBO6&dozi4dM+R8> z(>X|6DBaJ}A5xm!uaPd6exK6B{z#Ce-=Z{`(vdor{tKnagpO3R^z)P^(>dZ~>EBU$ zBBgCC{S>9i^&PRY^rMuXOzB*f{u!mol#XaD{Q#xOWgXe|C4dv|qI52$hgte|N|T8l z*~Zd0QJPHa$Pi24Kxs0mBO6)z8cLHX9T{Nh%P2jK()}zQqBNP#kuH|Ll+t7}M}jO} zPw6~L*Rk}4lqSfM^P?}8Sh?S*Jr}R;j&Shx_rO8x| zXe@mSrH`TXt}m$n$5Gl!>0y>WoYKcqdK*hmq4aT-9%AVUls=x)8(BJ?(qs}x23Y#j z3Zze0KBZ5hbdaUrqVx<(*Rk|pC{3nrq?)Clr!={;BTkn79i_>I z9kH?WQ1`~1 z6Q#)njtsH%4U{I+H?onXuc0)VypaKxzKqhvlmEw03*&fRzUiAthyVdd`#+EKb{}hit z9*+)+Xjd7P>5gYK#-j`4QPM?0?=TT=b9t&0F1RTca27N)L!iWb>96Nj86UxL(mAdyLgLb zm(!}H{qyPNbjA7Yo?TXgYLOGc+>_KLFn9QQ;Qu(lpf$Sf;*s+~Am^Aa4cEv5#N*Zb zE6#^v-465dD4B4VeW+qd#d#IA=he8c{@}iJ4Qes-YEZ4}+mK&P$-ay57Yw$p$#+t5 zToiXJ@oEvT>Uq=Mvz>CSO709LZj>(q z;6XNc$}a+RDmokKTd0RlSchPM*vKSk-fRzAakG+MVo2yH$M;vs`!I zxw+`i?X1yUPv4R(caJ;E-M2Qs4(+;o*6}#75d6#P)dpD-d6F0ukz+d@6~l@A7=7yDySoEo65|Il!J=ci+wVq&n1cH3>2L z%)hA8zp#iVN`}e3w~~b1oL@)X?FUu5C{91|E8_z)-aP~{uE{3{ zhr*x;J18WP_0@t93FdSfDlV7+DH^zB z?J(IaWXR?DK`xsDN`l=e8uxT>aX*qMGOUGyO~y%9H^!oYKtKIh3kuLZlTN9gbn8lw(xqj0P2FzMYJY%SSIon@J< zv$Zf%vp?d!WoSZgm%`M#mYOe2B_taj-_MeKcOX{2Tp=e=XlSO`w9)XiDW{>;@#u_vy^yZfp~-Pbf2wBO>GfiRn~{zC*!K z*M_<*{b5e-c%?=^((_e+xQ5#5`HZ~E6YfiEJKWtp{H42>d70VnzN@kx#gv6WzZ~7> z-in0{^H-q;{%hPlyQqH8%cJPPD~Y+pPtR`Hm!ly9$)9C9^%qU_I`f|Hr?pg5NK$!r zba7=KbA~K)nRMXoGe5qcmZXI8ee?5_>dEF_o zFiIlt^;uMZJ8vdq*~k++37)ov!7;L>C>*nwt8?AmTk}RZR~EosEKZc=4NuSJ=mzirTHhy@w$9B(X$ooi7h{pJ44!*c&wE%N zMpplgTG$%h&cZjy(O(0S(Lb=3pN<|z^kHIWAym1AzM1g@h06Uf=itnId{tpln-OQP zK(J@w?0s2a)i6V*qGawx`B^Am1L+P??Pc(wGN6Rea$=K~v5`M~!1*kV^Z6QBjGiR; z46tx}^g9S+<7FvFBQgC$j@ko~_jKf|@-F98mW^zrW_m4eD)o;tss9^8{ZFWGG+seo z|6ry5>&P><|Bso8?f**Fx1m0^j@UAuNKJHIfo!>uMrQV-6!c_7pC`0uZXRl#56X79Zgp7|U1#RAjeb?y zdr^`Hi1p01CBV1wity`qM!(oWL|y@RFMup#jVv~DUSK)fqdQPKE`fe*jG6hF`RZvn zX`mh+g&zJL3D9_w0@xweOJUDIY7nT46pJv8rzp?&K0H*b4UySynb;j~frYzrf3d-Az<<}*b z@BTE?gC(zLSKBlU=8dSf#hHcAL6BYU)64s>eLhmv{b^d{{O(WFBlX>%X0$<>54C@c zGn4yIwrankgL8N9;;gRIXb9WzTtXDz_1(*nI3g%-wUS zGCx_`y_M)-UF~;orK5RTtmXXu5XUW-fG@1fzaqQs?)lR{?}hIRvqh5{hh#{`oyVZ29htxw-D%nyinX!ja_G2owWdsm&c7eSX=< znkWs06aJ3sQY`N$VfD77=~o?op|;96WrEe2e^)^_O@E9dY9+<+`XA6%wYYh%wK9B^7NLF9=^?)q!S5P{94*S zH|NjDS@Qvv>|Hj4726(tB3{f!#md}07v;Ni)_k9eUHkmP-nOi&zUF*eWQrR>ZWSFm zZ6AH!jUBlSYYe(iTXV|75<_zX>O27}3~e%Iz~@3Xa&ob1Va-8As~CM5^QQnE@N_?e zwMk2>Dku8qKyu)eu=4jKCGOs;{G~p3;Uw0zw%HhxI=S^lI1$@6m~hjl+Yx+~{5>DLZj^=CRe z%87Qo3mfs@z16$>&K~V?@9x>Q{8453;P_}!#S-XGa z?P}ESGYReXbH(}$ie+V;>h6eY7;LOD-J7j)H6*{RZ>2T569nK4k{Y!3Fyx;RCz}a zYp3{rxYWXJ-x)pgZSedP2=r|9n+x=uxImxf9Xkm$cRWs(nDmWdL_PXLRCf17iQifl z-5x!SIPG~ldNaZi+Jo(QQx(XM;Q6x2Y>D2464BQ|Id05pKGs4L4g=4gp3kw?_LfC& zrw&2w{o)9A>uA4?HgVj4)ZKlJm{~ic4a7jN*1XlcwFSavav#4mzJfWBwM_MwNgO@Kr}d^;Un zp!H|KB->BbY(k$QfzP0l^Rv2lr$sEw$j-3C+gz53oVk;b)AlZrgyTg!9l0N)!}qGb z<+*T_|A$-+x4ZmXIcwf!<^o&Rnbh;{@o8iYPN|B#7(#)K}?mv$>Z+G;A>%?mnDuLvndh2k28fr?7U= zC_j3o&E@F}uYEg$DU6+Z&&9BWuH0RtbF*TdWnx%V)#C^2o88>ZKqg&a0X*;nk0(T$ zD81y~I#28X=CK_>QdKAFk?2ON4I;f=;(0sP@%=8ulNDY5Cdme|ktbLwDCFWT}qsgzgRO@8LwrNw@=Mw73ZCsIpJN%|??dUqLX$nxfI>>5ksZ(Aq4p)OxJ z+sp3^p(9cjhIez58Zf8-m0pY-vtJp*k3*#5Z!bS1l2k1Q$o`Gl+oUndJR<3T!*6pM zxQZvon7^;{PNkN1M8+9(K2-wt9)4|f^hLz;het3o`x`juoB_T2rojo0bvB;!wAM@^Jt`_x|#6rt$&8N`#pfw2v?!A)VWtiEsnLix6%`7(w_p!ka0LqpTMZ z*5W)Za~#5df?tF;BlIDB5#btynYara;Mo16r(3N)CVlAyBH|>Z?;XFh8r2 zKN)d(5q>#vH*lgaFT!sIUT5H++M)U12;54A84oqFaXSsr@A0Ahs}W|tnu!Mwvvb#` zFUrolE~7Hr+MT(2LUta8VGi+CgfgGw^DN5WM&-9Am#@sWrJp?^+d4lx4_d;iG5Hoj zacwwqQRPegRRJ#pZbjV4AN8wQ;w?aCeG&XQI8=Fy55^65^TT zW&bKj9&VDyQpkgM?Cgo@H^vebr1vDxBO&i7>aU~vFQG9MzAhd0yGfopDpY3YR%B<* zLj`KDipCRm`eQ2pGeddXrMv-FKK=&q zj6LN49{FzM&l2^~zl8c^rS_Y&g;u?Wn0%~R%Fk( z&Qg(W>mD~hyFV@clL^^2Ko!|m6hTp@i20!NIOwm(I<$glGdngv+q!ZB8xtW`Hh14f zxnYzGsO7?m_%{+|PTbF)rcHWH{bF!^{nRBvdtfl^3H?AVPtb6?Y>|smBs&Nyt%YdO{D5G?Y zc*IqO&z+$AEckg0@yx3wKMP{~q{GAr1@=s=ip47?R`7Tw87Lx#i^l5%7|=4TyQdSt zKSyI3O859PWuN z2E--XCH?VX{oMsW$T)v52OfQSbhI7qk-lfFN@Kc?6uU-8)3Oe;oTkkNUp!u@RZ{$p z>1nxB5jn|nL0YqAm3BGeL<8689Y>`day-%{mQ`tM(kwk`+RbV4Y@#!vruL~cZ5yFT z9aM9~<=PD*k-O~3H`BDArCB~o({>7MYAFg{V)<=42%Ys_y7pE&(rD-8v?E+6T%Dd4 zwES0E#t+jhi2f_h(w}a*EqwxG=ZdQsNBj#dJ(0$m`9scs@h>Z;Fb6 zQe<-=dO!jPByd0i2PAMn0tX~;KmrFOa6keFByd0i2PCj}3CQ1-tFGf^%tL|Gos|DaA+ZFg1Q^aR@zJf=lL~WJnhq()62=YWYhHY5EOH zy0Uqo-6+yIB0VV5lSF#cMLZ(!C6ryx(|FU9UGjG)j}Ylx5z2c?@^>cbJdiGV@8o~J zDy9lon;VmM(SA>sPfado175uPZ*5)sZ5 zp_bwr9<-*&`D(CS2fkXZ1Eukc+NWD*oX383+gemmR^XUvFXunPZ9ka<_~D{(XAAxc z2*OB+hmA7U8i@D{R)yrxoBYqTm~Usjdlm0rrF91^z~Tc?f@YMsM_?u1tX_eudoM(clk8 zbpB^c7!CYPddSo`SDfjMZ+1z4L5ADJf-Bcuxo(T%?6;iASCI9k zKOw{G*+VI~|0v4H`f{Cj0w>zCzVuIIDE$!>VV7}!((+Hffvhk60U5G;ktieim*r%5 z9`eZ7kZI{}$gm6fbP@kVL-J1;T|Rtd-zY8p8yQOfMz$~O%l@|->Pvq~hSI;H`sAY- z>vsSnnMl7!`jax0ej{kUcAdWz~6aKRd|4Ry95U@%@BD@J9^e@ze1ks&?vqF%=KA4ewbHDovCe&N3Lyp~bk#`d2@ zu^gqo+)r#0^^N6?=@(I#Sd{G#t+yhjX+!&1|Ia9^)|bC)KP>87C1FNY)2t$t!Mli% z?#GJVY2{gW^1vwuR?1ECFXgfm#nkqlKj8J9Kj8J*d&)e@zGZzGegssluMJpv=>Z-{ zJIqt@`77&xfef|2^kaqxd5td0R4%I$r)UQ9iI(ht-Q8A#wYs}mpsn9aeR|J;ir9GZ z*te{oA47OVl9M5sciFaDbd6~LU|CRP8j`GSIrr51c@Of`46%_s3dwKbBjuJS3X^>> zYv1`aFEGDI6cmB6{lwhFR0g;+jvtkvzr7*XN3{n1{SLYACE}T}eRm>m(d0Unh>z3c z`jd!{kF76>cvftmoroW#$#ozRpP)(mo`_G>q}@)$Cu!0iC*qSeX=fAhZ0)oz72)v= zSQ=>;)!Ym%SCjTG5kFXy_AC*{Gd9A`B;tp_?pRfb#WV1fqqHk(W`>5J*^%}_$;i+S z)ubIzV2m!5alooVES`bCcp>MlnwgGEZ(No69L&`IF{;+5I6Z5euEobi`ZEsT zX`mn6U_~rGFBTw9c%8tdzF#PCr@*a9)Aen9sJzuchs+=0c?SFmf#(|V*9EQ#Jkh>R z*LDdxNIVUU5&dBUeu%)g8SoPXK4id41-{XMdjvjUz?TWU-+;FWyvu-J1>9_0ZeZn; z^$pKbvGLmGg+P?+L4j-a3W(^F0ym!XzXY6(qu>WgcD>E;Wc{C*&fAsu4@7Z|9$!q; zlIKyXewDEDIa-(SLnIw~mmy6{?l0w=$%lRjDa~YFTrBXVcUu{0Y0ou{;D}gh9g1q1%qWot9-_^na^1xvnv~pz_GCNU1D5j2;2tT zjL&OQ;O_`JLw8si1*f1B!RE`1&Rr?+p%nNRz?nW6#{DjcfcTex|48~buLC!e+b-b8 z3EtFT5^gM*@o5E4di9FXD|C}xGl35(>!Y;KEx?J-euLhABJgbn{6^fsVC4n)wSfUMI)f?jCxMe5Y6ktU0c1ue44ldj8Rp$X z42M#PejUr%)LsBi{5#t?P$}>*OurfZ&w&rZo^;)1WhLFBeEp&3<$sw1e;qhPopj}3 z2_gB*KYsQdQQ~&sX8imZIPtHw@`7_j`3xu|;ll!#<9-(KDO$4s>=NZ|5lpmP&& zCVwGMB-wS;bdJlvBW4x&4B*smP|Uld1^z36TLmurelQHaS-)ljCplLOIm>o`2b`@( zS8~GV3i`(!!TGTo_HknYFG%lD(Des~^SJsw0-X3a+LJ4fH0N^zaH~o{#D4{x z_#YPhcL@C0qxk&YW|+Slfm6HvVm`tRVAn3-B!Am&R+ffYVArRjye9OvT;LuEoaFPI zu&Xfd>^dK~nVeSwr*?iHya4Nq`lt*=TrD0KH_C&}59JA|t zz^S}(-t7QxMnC6xbG$eOelEk4_si!4r*;R#yoRM<*Uy2|xYu3D(q_20MSw3Fi9N4ctu5zX4AC zY&4AHLI}jH{Pn=uI0iU_R>9}y6y@IqZl?c7oW$ina0MqI=jklqM1Px@Us4ax18&C8 zEuwt27+;Uz=L3N|1s!M}yUv1RN#nj&%=d8u_W-AM`-Od&DezwcH*5Dz;JNTCc8mEX zifivO`tV~7jXX|+NF2!=*mBZm)|J#L5N$M58RBORlv#585aCxaWdN0 z6y@I(^mAA7f-i~kmz~P{W%U2A18&ytkARchjQf%2fRla>8|=XGr0LOw4#fbOl|KVGmCqIBPv^z86)DPhr@%L)z+VAQ{i-(f>r>!^z;g}wH3eMX z>V%$`3VxmdPJ9jtJ75v`3jz-s=3@gK46}I@1a1{|)nF}fqQ6ln&TS%dlFeLh`6=*9 z;6!Je;8V_*3xU%-vWb3SnPb=GqI{hwpCj}bI>9p-Y5q`+?lZpQ!bQs7fy@QF{Ooi7%+(f?cp+>HKKQGTPa zdsq(GbzG5oc}@Kpn}P;tx@INr?X#O_jYU7zj6Y=neSeC3ly#IDkn)alm(~!9gd=VEdlC)!eWA1GF4n6&HMP2~`TQaOil#8+q(@rx zhUP%4KdhNRy6y|;E1CoK-e%nw353GBx2;3Na|pp^f5h)AC@C*>fU-#;ogSFr4?Eyb zu17+h8h>EI*VfX~i7HBp|L_reMnV+T^?8dc7P@rTqDnB!IhS!?IG{IrTYb%bt@3<4 zJh8k$*H?6O=s`T#5oq-`H$^)2cAKVGUa+WQp=T~?*DjnZDGA*>XWqOTSFK)KF{jD} z`Y}Z@{)&>r?hWgafcP`<`tr8ch6o-W@fdz}Xi<$#kNtE}SwpiIe{H@2oaw7W-XQq$ z)D-E9YKnDxVT*UAAKk^DqHk^R$6!ahx48|^k_4JDE`;Kjg6Jx32(;pPm58f)K|67| z!1TwGzNsHGDi1fUz;tK}`CW{=1m^6;vX`P;r7Ydt?27*em40DujrbuaM3>0fn)0Wn zAc2~22}!io2azLW@AY-+VSi+gf-I4`B25=0TJH_}J&Ttt@Ihu` z{=hOMw@B+sdAPZ$!LPSAHCHx^fYf~BTe5kVoQ;b=Qc`+4+ z;c$_4DrdUY)Ve(2s-9Q9z;4$G2-IH+U2BJI{Ol<+Ho=PY#r~kfrq}5HmLP0t$RE_h zF#X;Ye%GEST%09GVNAif%IeE$R6{E~i<6~gQ0zn{-4~ke$+KfDOy$^^g7TK8R`eXJ z5}&p)WibDRygjT%4iZ!|Un&%{5jUud7c8o=>vo6G2Y4!h)?~ex)81YzmouH~flJi4 z2Rmac9k7~6QPA5I@>GMmO&2O#y3*gdIuP=?YRZ{s7PsD9$7LhmfbC80v7Bah@*DM* zfUm9DPwNK;m~>xn=m*oEZLu7@z5WU# z))Y^5d!oFUG~xTf5xdMU?1kMnaB87A2LcK)!faq`HH?6(#&+v%|T`1S(o(cG*D16VVf{9)wj zg&6kIcG%EB$l+*e^)heY-{Eg)i@-F+Cq#9pz6g7> znnn_GoOiWL}ZFfJpx`9Ml^EZLQ?7lYc2@c&)*3 zCT)6%)R>6Nm*h9?O=?D8Gqp=bj&giiz=}Z2r11xcin-F^0xZ z9nwSx1$zXxU8hmCmtwyW+nwuSEMTq{QbcJp&0Myk)r~kRO5OlVgYmz;_K2NlO_=%d zcALHsTgosFzWn6Nc|8qAC!Q_XE84svpYE*>gd&N{xw0=$6x>(p*VqoF!ZF^R@nhun zk>`DJXkwb1LeEpH(l;fM2IWkp#=WQGEVG@WvOZw3z#&yNw~?WwjRtmsFt>J{wu&yc znCxv=nQFQEH!T!NCa*YUC*o`DzHOS4Ec;x3UVwcMrWh2m!&~3fZnu{r&g@Bizirgb zn1X$c`Sf*{b*#B~(s5pMz#Gx$;RLEO&{mK0)FdNcrmTBxixc$0;m2Ao{EztV-1N}N zC7sUw*CE_s=?-;3%-ucd@x269pc# z;d8l6H{nTUoR`vrIDE!|vyM|Ox^aX4K@|JG%PExGt;AhUkte>mVpLLj>?t=0-;9g;XF;oy#p!qo-Nv5oUmfrTGQc5!l89N&6Jv$O-IVtOear! zy8p8m)~N-1ar{7z`8%G)xNm@SvcwIMI!pK97N(ra=0}Az-C9@g<4r7kiPz_&Tam4J z>pUFvHjq0{U7*_-CE@@VXPR)}aGv&+v^REGkf^;5&)45{#vIP#Rc(IUa5s!9*i5PX zCO+cVn`Vi6y=TvbTxx#H)zov@Z%1MOZL>6I@f)C6F~fVF0Q==bjHL;-?eTc|D@kz- z*`j$Tm0^q)aydFeTf{j*F%RRRt+PD^!in|}=Wi$PRDKdM6 z#pLl=qY9hK(qX=D70ypw6U=5U4XZ()VsqATvpTk|Q;$^l*RH5jK;E#9xwGQbTF%hD zto_WEF5q6ISfK44|BgF-``cIH70HAATDX6j?y1EMzu42=c=VZ`?XLAE9`AFVkIBLC zOoQWVJkx+v13Ey7ui^4p1|L?*^IBKazF;x#@VC&jL38Kg!CgG6&6HQ%f^1mTh9_W+ z`e_&j<6Y)d8Yq3f6cdQwp3qmcz&&Axk{&iUXl>GwVHqB^2+%Z*&-xZ+Hz9N^shZv9 z^C#D=mQy!~$Efx8rck8Ki|t2WgIcj@GC*iQ6=( zIN#I`-thQPt;c5&S*<6@dE4_^x98&^)7w~ku7c&2c~1OI1&^EsxbGHMFf*++ZA!{} zF9vImbsczmN4)WYU%8|onj|kAZ*v&8N_d(^KJnRJ Date: Wed, 17 Dec 2014 10:49:02 -0800 Subject: [PATCH 008/105] Remove library --- python/gtsam/libgtsam_python.so | Bin 63367 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100755 python/gtsam/libgtsam_python.so diff --git a/python/gtsam/libgtsam_python.so b/python/gtsam/libgtsam_python.so deleted file mode 100755 index bd87730d7ac1534f9e835fa6997a6b0e77af8485..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 63367 zcmeIb34B|{wLgBnC^1=V6B2M(1sDiR97*1R6gjaHi8#T;CIkXp%a#(G*p?#6j!jt% z4iw{<_)!XBX=_8^0i`r;DNR|53n8I>eKch&ElUh#kqK>5%A;ZR?|WvEMpsu!2=3$k z|DW7Mnwjs+oH=vm%$YND@0G7|Rn1FJOUuy2m7#r0OGCW6jss2}XzMqK2m+^8rj5t< z(b^HLtR$$z|zyUQmXjdDge7$fALqzvw*ennkwT-MO=l$hrQ|Z8zNW^O--d{@FjMrWcK8jDl$@8z)pDNtiK5%G4>v44WXJn2 z?9ATO_mAw6?T1=DbIy7G<(bF6cFR2{o;LY{Q}4)_6@2FQxdd-)UU-tNaasRppJ`QD+{rHOS`v3G%`jnE#{(95pRd0Uzqn}^D z>Muw9ZOy9bSI@a))3k+uxVL$F&C|Dxp83+&zs&je+)J}R@mw?ct?JC> zKRvX;f6Q;rY3n|CnPdDcO<(u;t^PlqbJl0izxmkb|5{%7>gmPfr<63^dGW4aXS)7t z)w#R2p4FVYDdUdOGpqA1`s490Xzz4i&|dPR?`laM3wLo7#p*8Upc`XkECe#wG{l{HOrjNQ-_-KvlzUg%SqR# z;NOhTw=&J?9CWHVzCK02N>j-Bh{Md=9iIYkJKntfN~<}3O$xa^bFw-AuODqr=iC(X zxhutZoix#$&UTC!SWUVPA8%g%%G1pGd_IMo&p6SX&dwvu@#hXQ#}7#{Udv~gmoG~p zpCNSCOs~E;${fEUg&e$)7)T{u+f&FtEd~DtDfIT56mlC*(cdL0=+~ZNK3?ai7_Zk; z$nCe7zh-iqG1(mdNeVf%q|o!e6#Q4D=x<4ic7K{>&d)p9=J2_x9FNl`Y8wL_kbW5XeuURGb38|se;@OO=nM%u{R01Q=ntcRB?rJZ zztTA!YYR_GnQS~<(+0IXt@*NiBmbg%YZ)xMWOPx2q%DH zV%NXG58>69@$`G72)NcGBz#Ep%feyp8Q5pStwIi03;fs9IG@9U&kljlhW#Y|HG#VY z{zogP<6O;w6#{?cSV3P9I9~8`BJ_4po2upBhKjgAkzE@n@bbgLK|e&`{l{>8hz1DP zWrEHwtW(5)zrbhmY^^+3;6iSa&KEEy$D&>B4l66^6y+a4zlcs(m;+}C+`;r`s#a~_ zGlcbm$`1%Wp-$|&4uWO47>0*4V4g4HCo|oSx%A**&#-SsmR|7(?&K3B7pd&Zm`Btvr=edzn@)0`t_^IkG72chu7@B$Mn~ua%n`fVZL~Mc)9UWF3WNtUF|Voo zu2np}PUPN=^^5qtRm=-?hh6`GzeMHxMZY9{+UGDnZ@02?PWG*7A0bJ2m%wKT{8%<$ zrfb^_{5Qa!Q+b;hmt0Z)r>Ajz*f3s4f=}Y7PRy6}qWq6APnnzr|B_BE{97ttO`AVl zkMTe|S=tj@TV|dH0~P>a(h?k72C|B>~}=@Et5rmgB+0aPwO(+;enHhKJ0+d zL(((4-V*vVEXJjf!`cp39)mCR|5$-9PN9dZAXuVr74sBqu0E& zY$k74GmLK<3^KJlEZUWNRXdH-A2QItft8=G4IA*F&=aGdunBxJxe56|T=8db)P@vU(pnf_(Qb|=Qamg{k7iuW%C!rrNh;ZQngF=QqHvxr0k5;UI>-?{NYF_(3wy+*coXIv!j7_5Xj?GQ+}RQc1sj_h^d_Ia!r$r- zc_V?4XHi0*U9M7phrgjM;&)XueW)?yCpBX)j|6BaFm6yNFHPvRhYSKPZ16TWLrH_3dTdyT z5f61+G+4sRU_jfeOLaapKA($9IP5;i-Muj$pD`Xbn^nnpLFcN~XZuY}KK@H1E4Pj7WlYB9l z=FnL5exX4(7tHgue!iRkB!Y*Uo*2hiMBc}`9g=kBZ%1m0WS{)TBO+_k?X#u5OR!$$H-OEXvB%z9o!_q zEW(~Uic>a~U|+^adr~dGUso&D<(gXurNbtAT*+3b^IBIowff*hgxgv$c>0Qt4jooH z93T%P(y3$XpX5+{T~2w+MmObaQ{{Rk6>5w|tJK#N4hF(zzQ>-$3maLzfZ2qEl_Xxt z;ZSUgqT|VWEuEt#_=c|7lA?@@akw20GEmKYB~?hrD=%Kae2av6kgPzlbv$uVHW(=B z3B?`C#KpSyV&|k)zd1hCA+klujUh*4r%7YUlu)TL-pPNBBam>@idJu=EyTU>`AcG32X3un2R*TJ{J_Lh zb!nl?RV2=53@0oxPlhf0W!T%d_*)}kSG%hugw0Sh9cFyP?Ks3?6FdD;J2Mt1OXV?P zq05Evy@cPjqRkuf>E4D_ZP;Z)2DLaENpgXt#2qUd8gKy8;%!|)TayJ1RG}s&T2>tn z6m#!5;SdCkGw1}&TOSDhA38fy1cMHI6>Y;2rJ1(j?~f@<_~qUnN-e*HMK4eB>N@% z(!6iqn|Gw_Ly~w5N4xQ}KfcuN3uAFxmqe_#CVqYpQ#F247r!^gZ+Jn-SXR6%a1)5% z8FQ8Jv`d^_CEXXJV{bZoDYUU$GjRfX04JL4sF&SUBynR^W4GJ*dL^TYIv_WtdpXJ} zrV}8#g=5o|A*~1H6y!>9`_@PIgd?~?M@oSEZ-&~q?Ul0rH|5mRfusXh^==9ZYr-Mv+<7M%Jnn+y4Z0Hh29M?|M8#iMkQgun(f1g&lg%%T< zaf(SVtJvfQCe41sEz17BOsn%*qt4ZuCaP;{r8CE@dY8YWBC1ylTQF zxCM?447tbbK$Z~P32*hmlGU*1HR4FT3=m_ri*$w2jR=GH#DF;qzn<9Ek zz}MF7*PEN_*%J=p&RMb#A2V+@ev_Ua4Z&$JaZruB0}0j)_v_I>EuIiyPnOti@mm*3 zw=2|PFlzKZ-}9iE3>o5{a$HBNxp7aa&AQJU@$RYh*eZ+%EW&u$#8o}7TJg*=v1^L; zeQU*N?m=mR-Oj8zzv17W%!m}Y1G_E$(2wrxZ1uMA$27cc9mzy%B1J)O6IQ_X8i($} zC?r#j+dPNe8`k4DY~}L_#sQ+Cm8_UQpizWnv^ewCoMycoRyNOsnJ-=G?_3=S`CK*SCc_+SqQvX-(I`W4{NbRt!7sW(wnWtbM0)POB%hc zzGlBiDu63lza53_t`J`YbZ>LW@AY-+7#p-n_Re7EsK*Hlp~TNi_(%zvxf#Z7?7li3@mby+2&`-i8mBcRvwsXF`#rV%c|1_W4QMQw7|{-I zeN(#~qY{5eD`B%$TO&RGT3E+DJ}gNJX`pK_MH}q7HUrUpAtjekIiLv+6l*NTk(u*h z!VYya++@m;C&@pd-ozT$4$o)OQ=zo; zmYd~NUHGQ9MthRYH_DSi=yIqX>UzW;q+}M4bt6_~jJ9xzvKdRFF-{Ye@hb^j-OMo? zwQo;oD$hbD_V1f#Wvr#L|6AODi)6kQJ8ZEJ;y#kz-V}xjr=zqW94N3C6c-oRD4Xkuqd>q6V{QZ$D~c1~ z_CK+1IO1zK^;E)2s36^b39}NEYT&r;r;QL?n|eHYjSW2ATfuIVm8WOk1!pL%&1wv^ z_-A#r)nljKHVe05R?K3Y%&Ko|YWDHCHh=D1y%4O=uky^9t2@A=j5!L5wYf`|R?P9} z_JTqVFI|elMdC#Y4KG;W;@|vtXfp7tG=eCD5f3{GuPH`Tz4j-b?D?B{u$hK2|{0CwAhEnQ__{V05KH9?c@3ps7tw zlQqqvJtwfX!<+C5TBi1jQvMu~NA+L$$w~}JhW56=A}8O3SC`VYoua(_y(alSQ&&CJ z(zK1@Jt2u#*D+YzWWb%GynLTYmj8};??%2KY{Z8Lt&E_=Wm>+Ugx8_iZ}+f5_=<{l z2|rhY2zM*Ecx8y?=85;ZsJx2H_e}{e#V41Q*0eIE{I3K?fqV~-%G0}Avb4DuTyaOt|es$Q{Wvb@J0o{ zPNCl@-j5`?srdCud7o0gU%`K-;OiCq4h0`j@QW1uSq1;Lf^SpshZX!41s_oGVFm9~ z@GPZY_b7O-f?ulOc?w>u;8q3yzJkwC@Ea7|rrv1?-rd{+v*Ou@TiR5Z=4;Oz=t zt>AYl_)-PGQNimJ+^^t41+P=^4h3JX;MXhoLkixn;F}bDy@C%a_<(|6tKj!3_$me8 zq~HMse^$Y7SMY5LzCyuYQScfCA69T(!J`WPa|Pe6;6GMyr(*Xy6}(!(#ZLgR+@%WM zsFbf$aQSX5Wj8ALeM9SXii!MhZEoPuAk;9&*tSMUuAzFxt9so(<&K1spv zQ*byqv1_A(-xNbNZIgokM8Ss?e5ryztKc~bzD>a&Q1Dk2{AvXsR&ep^GRuuBxNwOW zzDvRHSLp0k@b4+O_CqU6k?ikO@GJ#itl+r{zE;8W6dbSc$1baaUl2nzZH9tJ6x^oZ z*DH9Lf?ufMP6gkn;BE!4R`6;CKSjZpD)^}iUZ>zI6}(ZwI}|*q;6G6C4h6qk!Mhav zRt3La!GEgY{R)1ig0ENbB?>;E;1?_SeF}cQf^Sst*$Tc%!M~;8Lkhl7!Jk#|76sp? z;1vq~ih{cod|1KfDR@-DzpLQ86nue#XWeCGDe^ZiQ}DdI&2d`_+^W#|4~5QB1^-V4 zzh1!`6g-*&A5ie~l=7OwkBTo<@H3S1c>`9K!p{%HcDMvs6+DBL;9oNoJX67K3T{#G zG6knL8M~?#d_oM>w51BJ+UGh2$4_m@4brOs5udG2Uix578 z#rRk5pp``kKbgh&SKgqNMF>BQ#rT(X(8?l&7qA%rnlWf)5yEG&82_>jT3Li}8;kL; zvOz105bj_x{^cCBvIyaYEXKdwgH{$Hyokm4SM{KkMF=luG5)o5(8?l&m#`TBsvESj z2;pTc#=jZ|tt>)#Ig9bH;GmU72)~)d_*ciEl|=|YoyGW9*PxX}2tSj>_}BG=Ru&=r zEEeNm{exB(A>7Gg{A>N7l|=}zU@`tRFlc2F!soCU|GIC`$|8i%WikG>anQ;lgu7Xc ze{CAHvIyZG7UN$-gH{$H{A?EEU+(S?vfRCv$#bom``V$1C3-xppSyc=*3(KML`RE{ zLy^%F^6{N>j1w_RH&UUI;Za;C98T#pN^fK7DU?p9^bku=pfreUBO6&dozi4dM+R8> z(>X|6DBaJ}A5xm!uaPd6exK6B{z#Ce-=Z{`(vdor{tKnagpO3R^z)P^(>dZ~>EBU$ zBBgCC{S>9i^&PRY^rMuXOzB*f{u!mol#XaD{Q#xOWgXe|C4dv|qI52$hgte|N|T8l z*~Zd0QJPHa$Pi24Kxs0mBO6)z8cLHX9T{Nh%P2jK()}zQqBNP#kuH|Ll+t7}M}jO} zPw6~L*Rk}4lqSfM^P?}8Sh?S*Jr}R;j&Shx_rO8x| zXe@mSrH`TXt}m$n$5Gl!>0y>WoYKcqdK*hmq4aT-9%AVUls=x)8(BJ?(qs}x23Y#j z3Zze0KBZ5hbdaUrqVx<(*Rk|pC{3nrq?)Clr!={;BTkn79i_>I z9kH?WQ1`~1 z6Q#)njtsH%4U{I+H?onXuc0)VypaKxzKqhvlmEw03*&fRzUiAthyVdd`#+EKb{}hit z9*+)+Xjd7P>5gYK#-j`4QPM?0?=TT=b9t&0F1RTca27N)L!iWb>96Nj86UxL(mAdyLgLb zm(!}H{qyPNbjA7Yo?TXgYLOGc+>_KLFn9QQ;Qu(lpf$Sf;*s+~Am^Aa4cEv5#N*Zb zE6#^v-465dD4B4VeW+qd#d#IA=he8c{@}iJ4Qes-YEZ4}+mK&P$-ay57Yw$p$#+t5 zToiXJ@oEvT>Uq=Mvz>CSO709LZj>(q z;6XNc$}a+RDmokKTd0RlSchPM*vKSk-fRzAakG+MVo2yH$M;vs`!I zxw+`i?X1yUPv4R(caJ;E-M2Qs4(+;o*6}#75d6#P)dpD-d6F0ukz+d@6~l@A7=7yDySoEo65|Il!J=ci+wVq&n1cH3>2L z%)hA8zp#iVN`}e3w~~b1oL@)X?FUu5C{91|E8_z)-aP~{uE{3{ zhr*x;J18WP_0@t93FdSfDlV7+DH^zB z?J(IaWXR?DK`xsDN`l=e8uxT>aX*qMGOUGyO~y%9H^!oYKtKIh3kuLZlTN9gbn8lw(xqj0P2FzMYJY%SSIon@J< zv$Zf%vp?d!WoSZgm%`M#mYOe2B_taj-_MeKcOX{2Tp=e=XlSO`w9)XiDW{>;@#u_vy^yZfp~-Pbf2wBO>GfiRn~{zC*!K z*M_<*{b5e-c%?=^((_e+xQ5#5`HZ~E6YfiEJKWtp{H42>d70VnzN@kx#gv6WzZ~7> z-in0{^H-q;{%hPlyQqH8%cJPPD~Y+pPtR`Hm!ly9$)9C9^%qU_I`f|Hr?pg5NK$!r zba7=KbA~K)nRMXoGe5qcmZXI8ee?5_>dEF_o zFiIlt^;uMZJ8vdq*~k++37)ov!7;L>C>*nwt8?AmTk}RZR~EosEKZc=4NuSJ=mzirTHhy@w$9B(X$ooi7h{pJ44!*c&wE%N zMpplgTG$%h&cZjy(O(0S(Lb=3pN<|z^kHIWAym1AzM1g@h06Uf=itnId{tpln-OQP zK(J@w?0s2a)i6V*qGawx`B^Am1L+P??Pc(wGN6Rea$=K~v5`M~!1*kV^Z6QBjGiR; z46tx}^g9S+<7FvFBQgC$j@ko~_jKf|@-F98mW^zrW_m4eD)o;tss9^8{ZFWGG+seo z|6ry5>&P><|Bso8?f**Fx1m0^j@UAuNKJHIfo!>uMrQV-6!c_7pC`0uZXRl#56X79Zgp7|U1#RAjeb?y zdr^`Hi1p01CBV1wity`qM!(oWL|y@RFMup#jVv~DUSK)fqdQPKE`fe*jG6hF`RZvn zX`mh+g&zJL3D9_w0@xweOJUDIY7nT46pJv8rzp?&K0H*b4UySynb;j~frYzrf3d-Az<<}*b z@BTE?gC(zLSKBlU=8dSf#hHcAL6BYU)64s>eLhmv{b^d{{O(WFBlX>%X0$<>54C@c zGn4yIwrankgL8N9;;gRIXb9WzTtXDz_1(*nI3g%-wUS zGCx_`y_M)-UF~;orK5RTtmXXu5XUW-fG@1fzaqQs?)lR{?}hIRvqh5{hh#{`oyVZ29htxw-D%nyinX!ja_G2owWdsm&c7eSX=< znkWs06aJ3sQY`N$VfD77=~o?op|;96WrEe2e^)^_O@E9dY9+<+`XA6%wYYh%wK9B^7NLF9=^?)q!S5P{94*S zH|NjDS@Qvv>|Hj4726(tB3{f!#md}07v;Ni)_k9eUHkmP-nOi&zUF*eWQrR>ZWSFm zZ6AH!jUBlSYYe(iTXV|75<_zX>O27}3~e%Iz~@3Xa&ob1Va-8As~CM5^QQnE@N_?e zwMk2>Dku8qKyu)eu=4jKCGOs;{G~p3;Uw0zw%HhxI=S^lI1$@6m~hjl+Yx+~{5>DLZj^=CRe z%87Qo3mfs@z16$>&K~V?@9x>Q{8453;P_}!#S-XGa z?P}ESGYReXbH(}$ie+V;>h6eY7;LOD-J7j)H6*{RZ>2T569nK4k{Y!3Fyx;RCz}a zYp3{rxYWXJ-x)pgZSedP2=r|9n+x=uxImxf9Xkm$cRWs(nDmWdL_PXLRCf17iQifl z-5x!SIPG~ldNaZi+Jo(QQx(XM;Q6x2Y>D2464BQ|Id05pKGs4L4g=4gp3kw?_LfC& zrw&2w{o)9A>uA4?HgVj4)ZKlJm{~ic4a7jN*1XlcwFSavav#4mzJfWBwM_MwNgO@Kr}d^;Un zp!H|KB->BbY(k$QfzP0l^Rv2lr$sEw$j-3C+gz53oVk;b)AlZrgyTg!9l0N)!}qGb z<+*T_|A$-+x4ZmXIcwf!<^o&Rnbh;{@o8iYPN|B#7(#)K}?mv$>Z+G;A>%?mnDuLvndh2k28fr?7U= zC_j3o&E@F}uYEg$DU6+Z&&9BWuH0RtbF*TdWnx%V)#C^2o88>ZKqg&a0X*;nk0(T$ zD81y~I#28X=CK_>QdKAFk?2ON4I;f=;(0sP@%=8ulNDY5Cdme|ktbLwDCFWT}qsgzgRO@8LwrNw@=Mw73ZCsIpJN%|??dUqLX$nxfI>>5ksZ(Aq4p)OxJ z+sp3^p(9cjhIez58Zf8-m0pY-vtJp*k3*#5Z!bS1l2k1Q$o`Gl+oUndJR<3T!*6pM zxQZvon7^;{PNkN1M8+9(K2-wt9)4|f^hLz;het3o`x`juoB_T2rojo0bvB;!wAM@^Jt`_x|#6rt$&8N`#pfw2v?!A)VWtiEsnLix6%`7(w_p!ka0LqpTMZ z*5W)Za~#5df?tF;BlIDB5#btynYara;Mo16r(3N)CVlAyBH|>Z?;XFh8r2 zKN)d(5q>#vH*lgaFT!sIUT5H++M)U12;54A84oqFaXSsr@A0Ahs}W|tnu!Mwvvb#` zFUrolE~7Hr+MT(2LUta8VGi+CgfgGw^DN5WM&-9Am#@sWrJp?^+d4lx4_d;iG5Hoj zacwwqQRPegRRJ#pZbjV4AN8wQ;w?aCeG&XQI8=Fy55^65^TT zW&bKj9&VDyQpkgM?Cgo@H^vebr1vDxBO&i7>aU~vFQG9MzAhd0yGfopDpY3YR%B<* zLj`KDipCRm`eQ2pGeddXrMv-FKK=&q zj6LN49{FzM&l2^~zl8c^rS_Y&g;u?Wn0%~R%Fk( z&Qg(W>mD~hyFV@clL^^2Ko!|m6hTp@i20!NIOwm(I<$glGdngv+q!ZB8xtW`Hh14f zxnYzGsO7?m_%{+|PTbF)rcHWH{bF!^{nRBvdtfl^3H?AVPtb6?Y>|smBs&Nyt%YdO{D5G?Y zc*IqO&z+$AEckg0@yx3wKMP{~q{GAr1@=s=ip47?R`7Tw87Lx#i^l5%7|=4TyQdSt zKSyI3O859PWuN z2E--XCH?VX{oMsW$T)v52OfQSbhI7qk-lfFN@Kc?6uU-8)3Oe;oTkkNUp!u@RZ{$p z>1nxB5jn|nL0YqAm3BGeL<8689Y>`day-%{mQ`tM(kwk`+RbV4Y@#!vruL~cZ5yFT z9aM9~<=PD*k-O~3H`BDArCB~o({>7MYAFg{V)<=42%Ys_y7pE&(rD-8v?E+6T%Dd4 zwES0E#t+jhi2f_h(w}a*EqwxG=ZdQsNBj#dJ(0$m`9scs@h>Z;Fb6 zQe<-=dO!jPByd0i2PAMn0tX~;KmrFOa6keFByd0i2PCj}3CQ1-tFGf^%tL|Gos|DaA+ZFg1Q^aR@zJf=lL~WJnhq()62=YWYhHY5EOH zy0Uqo-6+yIB0VV5lSF#cMLZ(!C6ryx(|FU9UGjG)j}Ylx5z2c?@^>cbJdiGV@8o~J zDy9lon;VmM(SA>sPfado175uPZ*5)sZ5 zp_bwr9<-*&`D(CS2fkXZ1Eukc+NWD*oX383+gemmR^XUvFXunPZ9ka<_~D{(XAAxc z2*OB+hmA7U8i@D{R)yrxoBYqTm~Usjdlm0rrF91^z~Tc?f@YMsM_?u1tX_eudoM(clk8 zbpB^c7!CYPddSo`SDfjMZ+1z4L5ADJf-Bcuxo(T%?6;iASCI9k zKOw{G*+VI~|0v4H`f{Cj0w>zCzVuIIDE$!>VV7}!((+Hffvhk60U5G;ktieim*r%5 z9`eZ7kZI{}$gm6fbP@kVL-J1;T|Rtd-zY8p8yQOfMz$~O%l@|->Pvq~hSI;H`sAY- z>vsSnnMl7!`jax0ej{kUcAdWz~6aKRd|4Ry95U@%@BD@J9^e@ze1ks&?vqF%=KA4ewbHDovCe&N3Lyp~bk#`d2@ zu^gqo+)r#0^^N6?=@(I#Sd{G#t+yhjX+!&1|Ia9^)|bC)KP>87C1FNY)2t$t!Mli% z?#GJVY2{gW^1vwuR?1ECFXgfm#nkqlKj8J9Kj8J*d&)e@zGZzGegssluMJpv=>Z-{ zJIqt@`77&xfef|2^kaqxd5td0R4%I$r)UQ9iI(ht-Q8A#wYs}mpsn9aeR|J;ir9GZ z*te{oA47OVl9M5sciFaDbd6~LU|CRP8j`GSIrr51c@Of`46%_s3dwKbBjuJS3X^>> zYv1`aFEGDI6cmB6{lwhFR0g;+jvtkvzr7*XN3{n1{SLYACE}T}eRm>m(d0Unh>z3c z`jd!{kF76>cvftmoroW#$#ozRpP)(mo`_G>q}@)$Cu!0iC*qSeX=fAhZ0)oz72)v= zSQ=>;)!Ym%SCjTG5kFXy_AC*{Gd9A`B;tp_?pRfb#WV1fqqHk(W`>5J*^%}_$;i+S z)ubIzV2m!5alooVES`bCcp>MlnwgGEZ(No69L&`IF{;+5I6Z5euEobi`ZEsT zX`mn6U_~rGFBTw9c%8tdzF#PCr@*a9)Aen9sJzuchs+=0c?SFmf#(|V*9EQ#Jkh>R z*LDdxNIVUU5&dBUeu%)g8SoPXK4id41-{XMdjvjUz?TWU-+;FWyvu-J1>9_0ZeZn; z^$pKbvGLmGg+P?+L4j-a3W(^F0ym!XzXY6(qu>WgcD>E;Wc{C*&fAsu4@7Z|9$!q; zlIKyXewDEDIa-(SLnIw~mmy6{?l0w=$%lRjDa~YFTrBXVcUu{0Y0ou{;D}gh9g1q1%qWot9-_^na^1xvnv~pz_GCNU1D5j2;2tT zjL&OQ;O_`JLw8si1*f1B!RE`1&Rr?+p%nNRz?nW6#{DjcfcTex|48~buLC!e+b-b8 z3EtFT5^gM*@o5E4di9FXD|C}xGl35(>!Y;KEx?J-euLhABJgbn{6^fsVC4n)wSfUMI)f?jCxMe5Y6ktU0c1ue44ldj8Rp$X z42M#PejUr%)LsBi{5#t?P$}>*OurfZ&w&rZo^;)1WhLFBeEp&3<$sw1e;qhPopj}3 z2_gB*KYsQdQQ~&sX8imZIPtHw@`7_j`3xu|;ll!#<9-(KDO$4s>=NZ|5lpmP&& zCVwGMB-wS;bdJlvBW4x&4B*smP|Uld1^z36TLmurelQHaS-)ljCplLOIm>o`2b`@( zS8~GV3i`(!!TGTo_HknYFG%lD(Des~^SJsw0-X3a+LJ4fH0N^zaH~o{#D4{x z_#YPhcL@C0qxk&YW|+Slfm6HvVm`tRVAn3-B!Am&R+ffYVArRjye9OvT;LuEoaFPI zu&Xfd>^dK~nVeSwr*?iHya4Nq`lt*=TrD0KH_C&}59JA|t zz^S}(-t7QxMnC6xbG$eOelEk4_si!4r*;R#yoRM<*Uy2|xYu3D(q_20MSw3Fi9N4ctu5zX4AC zY&4AHLI}jH{Pn=uI0iU_R>9}y6y@IqZl?c7oW$ina0MqI=jklqM1Px@Us4ax18&C8 zEuwt27+;Uz=L3N|1s!M}yUv1RN#nj&%=d8u_W-AM`-Od&DezwcH*5Dz;JNTCc8mEX zifivO`tV~7jXX|+NF2!=*mBZm)|J#L5N$M58RBORlv#585aCxaWdN0 z6y@I(^mAA7f-i~kmz~P{W%U2A18&ytkARchjQf%2fRla>8|=XGr0LOw4#fbOl|KVGmCqIBPv^z86)DPhr@%L)z+VAQ{i-(f>r>!^z;g}wH3eMX z>V%$`3VxmdPJ9jtJ75v`3jz-s=3@gK46}I@1a1{|)nF}fqQ6ln&TS%dlFeLh`6=*9 z;6!Je;8V_*3xU%-vWb3SnPb=GqI{hwpCj}bI>9p-Y5q`+?lZpQ!bQs7fy@QF{Ooi7%+(f?cp+>HKKQGTPa zdsq(GbzG5oc}@Kpn}P;tx@INr?X#O_jYU7zj6Y=neSeC3ly#IDkn)alm(~!9gd=VEdlC)!eWA1GF4n6&HMP2~`TQaOil#8+q(@rx zhUP%4KdhNRy6y|;E1CoK-e%nw353GBx2;3Na|pp^f5h)AC@C*>fU-#;ogSFr4?Eyb zu17+h8h>EI*VfX~i7HBp|L_reMnV+T^?8dc7P@rTqDnB!IhS!?IG{IrTYb%bt@3<4 zJh8k$*H?6O=s`T#5oq-`H$^)2cAKVGUa+WQp=T~?*DjnZDGA*>XWqOTSFK)KF{jD} z`Y}Z@{)&>r?hWgafcP`<`tr8ch6o-W@fdz}Xi<$#kNtE}SwpiIe{H@2oaw7W-XQq$ z)D-E9YKnDxVT*UAAKk^DqHk^R$6!ahx48|^k_4JDE`;Kjg6Jx32(;pPm58f)K|67| z!1TwGzNsHGDi1fUz;tK}`CW{=1m^6;vX`P;r7Ydt?27*em40DujrbuaM3>0fn)0Wn zAc2~22}!io2azLW@AY-+VSi+gf-I4`B25=0TJH_}J&Ttt@Ihu` z{=hOMw@B+sdAPZ$!LPSAHCHx^fYf~BTe5kVoQ;b=Qc`+4+ z;c$_4DrdUY)Ve(2s-9Q9z;4$G2-IH+U2BJI{Ol<+Ho=PY#r~kfrq}5HmLP0t$RE_h zF#X;Ye%GEST%09GVNAif%IeE$R6{E~i<6~gQ0zn{-4~ke$+KfDOy$^^g7TK8R`eXJ z5}&p)WibDRygjT%4iZ!|Un&%{5jUud7c8o=>vo6G2Y4!h)?~ex)81YzmouH~flJi4 z2Rmac9k7~6QPA5I@>GMmO&2O#y3*gdIuP=?YRZ{s7PsD9$7LhmfbC80v7Bah@*DM* zfUm9DPwNK;m~>xn=m*oEZLu7@z5WU# z))Y^5d!oFUG~xTf5xdMU?1kMnaB87A2LcK)!faq`HH?6(#&+v%|T`1S(o(cG*D16VVf{9)wj zg&6kIcG%EB$l+*e^)heY-{Eg)i@-F+Cq#9pz6g7> znnn_GoOiWL}ZFfJpx`9Ml^EZLQ?7lYc2@c&)*3 zCT)6%)R>6Nm*h9?O=?D8Gqp=bj&giiz=}Z2r11xcin-F^0xZ z9nwSx1$zXxU8hmCmtwyW+nwuSEMTq{QbcJp&0Myk)r~kRO5OlVgYmz;_K2NlO_=%d zcALHsTgosFzWn6Nc|8qAC!Q_XE84svpYE*>gd&N{xw0=$6x>(p*VqoF!ZF^R@nhun zk>`DJXkwb1LeEpH(l;fM2IWkp#=WQGEVG@WvOZw3z#&yNw~?WwjRtmsFt>J{wu&yc znCxv=nQFQEH!T!NCa*YUC*o`DzHOS4Ec;x3UVwcMrWh2m!&~3fZnu{r&g@Bizirgb zn1X$c`Sf*{b*#B~(s5pMz#Gx$;RLEO&{mK0)FdNcrmTBxixc$0;m2Ao{EztV-1N}N zC7sUw*CE_s=?-;3%-ucd@x269pc# z;d8l6H{nTUoR`vrIDE!|vyM|Ox^aX4K@|JG%PExGt;AhUkte>mVpLLj>?t=0-;9g;XF;oy#p!qo-Nv5oUmfrTGQc5!l89N&6Jv$O-IVtOear! zy8p8m)~N-1ar{7z`8%G)xNm@SvcwIMI!pK97N(ra=0}Az-C9@g<4r7kiPz_&Tam4J z>pUFvHjq0{U7*_-CE@@VXPR)}aGv&+v^REGkf^;5&)45{#vIP#Rc(IUa5s!9*i5PX zCO+cVn`Vi6y=TvbTxx#H)zov@Z%1MOZL>6I@f)C6F~fVF0Q==bjHL;-?eTc|D@kz- z*`j$Tm0^q)aydFeTf{j*F%RRRt+PD^!in|}=Wi$PRDKdM6 z#pLl=qY9hK(qX=D70ypw6U=5U4XZ()VsqATvpTk|Q;$^l*RH5jK;E#9xwGQbTF%hD zto_WEF5q6ISfK44|BgF-``cIH70HAATDX6j?y1EMzu42=c=VZ`?XLAE9`AFVkIBLC zOoQWVJkx+v13Ey7ui^4p1|L?*^IBKazF;x#@VC&jL38Kg!CgG6&6HQ%f^1mTh9_W+ z`e_&j<6Y)d8Yq3f6cdQwp3qmcz&&Axk{&iUXl>GwVHqB^2+%Z*&-xZ+Hz9N^shZv9 z^C#D=mQy!~$Efx8rck8Ki|t2WgIcj@GC*iQ6=( zIN#I`-thQPt;c5&S*<6@dE4_^x98&^)7w~ku7c&2c~1OI1&^EsxbGHMFf*++ZA!{} zF9vImbsczmN4)WYU%8|onj|kAZ*v&8N_d(^KJnRJ Date: Wed, 17 Dec 2014 10:47:17 -0800 Subject: [PATCH 009/105] Markdown readme --- python/{README.txt => README.md} | 3 +++ 1 file changed, 3 insertions(+) rename python/{README.txt => README.md} (94%) diff --git a/python/README.txt b/python/README.md similarity index 94% rename from python/README.txt rename to python/README.md index 5235300c2..4d908e52c 100644 --- a/python/README.txt +++ b/python/README.md @@ -1,3 +1,6 @@ +Python Wrapper and Packaging +============================ + This directory contains the basic setup script and directory structure for the gtsam python module. During the build of gtsam, when GTSAM_BUILD_PYTHON is enabled, the following instructions will run. * Wrap parses gtsam.h and constructs a cpp file called ${moduleName}_python.cpp From 2dbe7fa2e924e789298e62a311064337096288ed Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 11 Nov 2015 21:39:08 +0100 Subject: [PATCH 010/105] Add numpy_eigen as a 3rd party library. This commit adds a simple version of numpy_eigen, copied from gtborg/numpy_eigen commit 255c09efb82496, and with a fix released in the commit 9a75383733b3dc4bc2bb0649053949ad2bec9326 of Scheizer-Messer/numpy_eigen (https://github.com/ethz-asl/Schweizer-Messer/tree/master/numpy_eigen) Conflicts: CMakeLists.txt gtsam/CMakeLists.txt --- CMakeLists.txt | 8 +- cmake/GtsamPythonWrap.cmake | 1 - gtsam/3rdparty/numpy_eigen/README.md | 6 + .../numpy_eigen/NumpyEigenConverter.hpp | 316 ++++++++++++++++++ .../numpy_eigen/boost_python_headers.hpp | 250 ++++++++++++++ .../include/numpy_eigen/copy_routines.hpp | 148 ++++++++ .../include/numpy_eigen/type_traits.hpp | 153 +++++++++ 7 files changed, 878 insertions(+), 4 deletions(-) create mode 100644 gtsam/3rdparty/numpy_eigen/README.md create mode 100755 gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp create mode 100755 gtsam/3rdparty/numpy_eigen/include/numpy_eigen/boost_python_headers.hpp create mode 100755 gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp create mode 100755 gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index bbf7de2e9..263e47321 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,7 +30,6 @@ message(STATUS "GTSAM_SOURCE_ROOT_DIR: [${GTSAM_SOURCE_ROOT_DIR}]") # Load build type flags and default to Debug mode include(GtsamBuildTypes) -include(GtsamPythonWrap) # Use macros for creating tests/timing scripts include(GtsamTesting) @@ -65,6 +64,7 @@ option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TB option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" ON) option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" ON) option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) +option(GTSAM_BUILD_PYTHON "Build Python wrapper statically (increases build time)" OFF) # Options relating to MATLAB wrapper # TODO: Check for matlab mex binary before handling building of binaries @@ -345,8 +345,10 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX) add_subdirectory(matlab) endif() -if(GTSAM_BUILD_PYTHON) - add_subdirectory(python) +# Python wrap +if (GTSAM_BUILD_PYTHON) + include(GtsamPythonWrap) + wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "") endif() # Build gtsam_unstable diff --git a/cmake/GtsamPythonWrap.cmake b/cmake/GtsamPythonWrap.cmake index 581b068ad..cfbe89c1f 100644 --- a/cmake/GtsamPythonWrap.cmake +++ b/cmake/GtsamPythonWrap.cmake @@ -1,5 +1,4 @@ #Setup cache options -option(GTSAM_BUILD_PYTHON "Build Python wrapper statically (increases build time)" OFF) set(GTSAM_BUILD_PYTHON_FLAGS "" CACHE STRING "Extra flags for running Matlab PYTHON compilation") set(GTSAM_PYTHON_INSTALL_PATH "" CACHE PATH "Python toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/borg/python") if(NOT GTSAM_PYTHON_INSTALL_PATH) diff --git a/gtsam/3rdparty/numpy_eigen/README.md b/gtsam/3rdparty/numpy_eigen/README.md new file mode 100644 index 000000000..bd5a3f44d --- /dev/null +++ b/gtsam/3rdparty/numpy_eigen/README.md @@ -0,0 +1,6 @@ +numpy_eigen +=========== + +A boost python converter that handles the copy of matrices from the Eigen linear algebra library in C++ to numpy in Python. + +This is a minimal version based on the original from Paul Furgale (https://github.com/ethz-asl/Schweizer-Messer/tree/master/numpy_eigen) \ No newline at end of file diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp new file mode 100755 index 000000000..67b04537c --- /dev/null +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp @@ -0,0 +1,316 @@ +/** + * @file NumpyEigenConverter.hpp + * @author Paul Furgale + * @date Fri Feb 4 11:17:25 2011 + * + * @brief Classes to support conversion from numpy arrays in Python + * to Eigen3 matrices in c++ + * + * + */ + +#ifndef NUMPY_EIGEN_CONVERTER_HPP +#define NUMPY_EIGEN_CONVERTER_HPP + +#include "boost_python_headers.hpp" +#include + +#define PY_ARRAY_UNIQUE_SYMBOL NP_Eigen_AS +#include + +#include "type_traits.hpp" +#include +#include "copy_routines.hpp" + + + +/** + * @class NumpyEigenConverter + * @tparam the Eigen3 matrix type this class is specialized for + * + * adapted from http://misspent.wordpress.com/2009/09/27/how-to-write-boost-python-converters/ + * General help available http://docs.scipy.org/doc/numpy/reference/c-api.array.html + * + * To use: + * + * #include + * + * + * BOOST_PYTHON_MODULE(libmy_module_python) + * { + * // The converters will cause a segfault unless import_array() is called before the first one + * import_array(); + * NumpyEigenConverter >::register_converter(); + * NumpyEigenConverter >::register_converter(); + * } + * + */ +template +struct NumpyEigenConverter +{ + + typedef EIGEN_MATRIX_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + enum { + RowsAtCompileTime = matrix_t::RowsAtCompileTime, + ColsAtCompileTime = matrix_t::ColsAtCompileTime, + MaxRowsAtCompileTime = matrix_t::MaxRowsAtCompileTime, + MaxColsAtCompileTime = matrix_t::MaxColsAtCompileTime, + NpyType = TypeToNumPy::NpyType, + //Flags = ei_compute_matrix_flags<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::ret, + //CoeffReadCost = NumTraits::ReadCost, + Options = matrix_t::Options + //InnerStrideAtCompileTime = 1, + //OuterStrideAtCompileTime = (Options&RowMajor) ? ColsAtCompileTime : RowsAtCompileTime + }; + + static std::string castSizeOption(int option) + { + if(option == Eigen::Dynamic) + return "Dynamic"; + else + return boost::lexical_cast(option); + } + + static std::string toString() + { + return std::string() + "Eigen::Matrix<" + TypeToNumPy::typeString() + ", " + + castSizeOption(RowsAtCompileTime) + ", " + + castSizeOption(ColsAtCompileTime) + ", " + + boost::lexical_cast((int)Options) + ", " + + castSizeOption(MaxRowsAtCompileTime) + ", " + + castSizeOption(MaxColsAtCompileTime) + ">"; + } + + // The "Convert from C to Python" API + static PyObject * convert(const matrix_t & M) + { + PyObject * P = NULL; + if(RowsAtCompileTime == 1 || ColsAtCompileTime == 1) + { + // Create a 1D array + npy_intp dimensions[1]; + dimensions[0] = M.size(); + P = PyArray_SimpleNew(1, dimensions, TypeToNumPy::NpyType); + numpyTypeDemuxer< CopyEigenToNumpyVector >(&M,P); + } + else + { + // create a 2D array. + npy_intp dimensions[2]; + dimensions[0] = M.rows(); + dimensions[1] = M.cols(); + P = PyArray_SimpleNew(2, dimensions, TypeToNumPy::NpyType); + numpyTypeDemuxer< CopyEigenToNumpyMatrix >(&M,P); + } + + // incrementing the reference seems to cause a memory leak. + // boost::python::incref(P); + // This agrees with the sample code found here: + // http://mail.python.org/pipermail/cplusplus-sig/2008-October/013825.html + return P; + } + + static bool isDimensionValid(int requestedSize, int sizeAtCompileTime, int maxSizeAtCompileTime) + { + bool valid = true; + if(sizeAtCompileTime == Eigen::Dynamic) + { + // Check for dynamic fixed size + // http://eigen.tuxfamily.org/dox-devel/TutorialMatrixClass.html#TutorialMatrixOptTemplParams + if(!(maxSizeAtCompileTime == Eigen::Dynamic || requestedSize <= maxSizeAtCompileTime)) + { + valid = false; + } + } + else if(sizeAtCompileTime != requestedSize) + { + valid = false; + } + return valid; + } + + static void checkMatrixSizes(PyObject * obj_ptr) + { + int rows = PyArray_DIM(obj_ptr, 0); + int cols = PyArray_DIM(obj_ptr, 1); + + bool rowsValid = isDimensionValid(rows, RowsAtCompileTime, MaxRowsAtCompileTime); + bool colsValid = isDimensionValid(cols, ColsAtCompileTime, MaxColsAtCompileTime); + if(!rowsValid || !colsValid) + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + } + + static void checkRowVectorSizes(PyObject * obj_ptr, int cols) + { + if(!isDimensionValid(cols, ColsAtCompileTime, MaxColsAtCompileTime)) + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + } + + static void checkColumnVectorSizes(PyObject * obj_ptr, int rows) + { + // Check if the type can accomidate one column. + if(ColsAtCompileTime == Eigen::Dynamic || ColsAtCompileTime == 1) + { + if(!isDimensionValid(rows, RowsAtCompileTime, MaxRowsAtCompileTime)) + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + } + else + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + + } + + static void checkVectorSizes(PyObject * obj_ptr) + { + int size = PyArray_DIM(obj_ptr, 0); + + // If the number of rows is fixed at 1, assume that is the sense of the vector. + // Otherwise, assume it is a column. + if(RowsAtCompileTime == 1) + { + checkRowVectorSizes(obj_ptr, size); + } + else + { + checkColumnVectorSizes(obj_ptr, size); + } + } + + + static void* convertible(PyObject *obj_ptr) + { + // Check for a null pointer. + if(!obj_ptr) + { + //THROW_TYPE_ERROR("PyObject pointer was null"); + return 0; + } + + // Make sure this is a numpy array. + if (!PyArray_Check(obj_ptr)) + { + //THROW_TYPE_ERROR("Conversion is only defined for numpy array and matrix types"); + return 0; + } + + // Check the type of the array. + int npyType = PyArray_ObjectType(obj_ptr, 0); + + if(!TypeToNumPy::canConvert(npyType)) + { + //THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + // << ". Mismatched types."); + return 0; + } + + + + // Check the array dimensions. + int nd = PyArray_NDIM(obj_ptr); + + if(nd != 1 && nd != 2) + { + THROW_TYPE_ERROR("Conversion is only valid for arrays with 1 or 2 dimensions. Argument has " << nd << " dimensions"); + } + + if(nd == 1) + { + checkVectorSizes(obj_ptr); + } + else + { + // Two-dimensional matrix type. + checkMatrixSizes(obj_ptr); + } + + + return obj_ptr; + } + + + static void construct(PyObject *obj_ptr, boost::python::converter::rvalue_from_python_stage1_data *data) + { + boost::python::converter::rvalue_from_python_storage * matData = reinterpret_cast * >(data); + void* storage = matData->storage.bytes; + + // Make sure storage is 16byte aligned. With help from code from Memory.h + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + matrix_t * Mp = new (aligned) matrix_t(); + // Stash the memory chunk pointer for later use by boost.python + // This signals boost::python that the new value must be deleted eventually + data->convertible = storage; + + + // std::cout << "Creating aligned pointer " << aligned << " from storage " << storage << std::endl; + // std::cout << "matrix size: " << sizeof(matrix_t) << std::endl; + // std::cout << "referent size: " << boost::python::detail::referent_size< matrix_t & >::value << std::endl; + // std::cout << "sizeof(storage): " << sizeof(matData->storage) << std::endl; + // std::cout << "sizeof(bytes): " << sizeof(matData->storage.bytes) << std::endl; + + + + matrix_t & M = *Mp; + + int nd = PyArray_NDIM(obj_ptr); + if(nd == 1) + { + int size = PyArray_DIM(obj_ptr, 0); + // This is a vector type + if(RowsAtCompileTime == 1) + { + // Row Vector + M.resize(1,size); + } + else + { + // Column Vector + M.resize(size,1); + } + numpyTypeDemuxer< CopyNumpyToEigenVector >(&M,obj_ptr); + } + else + { + int rows = PyArray_DIM(obj_ptr, 0); + int cols = PyArray_DIM(obj_ptr, 1); + + M.resize(rows,cols); + numpyTypeDemuxer< CopyNumpyToEigenMatrix >(&M,obj_ptr); + } + + + + + } + + + // The registration function. + static void register_converter() + { + boost::python::to_python_converter(); + boost::python::converter::registry::push_back( + &NumpyEigenConverter::convertible, + &NumpyEigenConverter::construct, + boost::python::type_id()); + + } + +}; + + + + +#endif /* NUMPY_EIGEN_CONVERTER_HPP */ diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/boost_python_headers.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/boost_python_headers.hpp new file mode 100755 index 000000000..5499d2917 --- /dev/null +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/boost_python_headers.hpp @@ -0,0 +1,250 @@ +/** + * @file boost_python_headers.hpp + * @author Paul Furgale + * @date Mon Dec 12 10:36:03 2011 + * + * @brief A header that specializes boost-python to work with fixed-sized Eigen types. + * + * The original version of this library did not include these specializations and this caused + * assert failures when running on Ubuntu 10.04 32-bit. More information about fixed-size + * vectorizable types in Eigen is available here: + * http://eigen.tuxfamily.org/dox-devel/TopicFixedSizeVectorizable.html + * + * This code has been tested on Ubunutu 10.04 64 and 32 bit, OSX Snow Leopard and OSX Lion. + * + * This code is derived from boost/python/converter/arg_from_python.hpp + * Copyright David Abrahams 2002. + * Distributed under the Boost Software License, Version 1.0. (See http://www.boost.org/LICENSE_1_0.txt) + * + */ +#ifndef NUMPY_EIGEN_CONVERTERS_HPP +#define NUMPY_EIGEN_CONVERTERS_HPP + +#include +#include +#include +#include +#include +#include + + +namespace boost { namespace python { namespace detail { + template + struct referent_size; + + // This bit of code makes sure we have 16 extra bytes to do the pointer alignment for fixed-sized Eigen types + template + struct referent_size< Eigen::Matrix& > + { + // Add 16 bytes so we can get alignment + BOOST_STATIC_CONSTANT( std::size_t, value = sizeof(Eigen::Matrix) + 16); + }; + + // This bit of code makes sure we have 16 extra bytes to do the pointer alignment for fixed-sized Eigen types + template + struct referent_size< Eigen::Matrix const & > + { + // Add 16 bytes so we can get alignment + BOOST_STATIC_CONSTANT( std::size_t, value = sizeof(Eigen::Matrix) + 16); + }; + + // This bit of code makes sure we have 16 extra bytes to do the pointer alignment for fixed-sized Eigen types + template + struct referent_size< Eigen::Matrix > + { + // Add 16 bytes so we can get alignment + BOOST_STATIC_CONSTANT( std::size_t, value = sizeof(Eigen::Matrix) + 16); + }; + + + }}} + +namespace boost { namespace python { namespace converter { + + + template + struct rvalue_from_python_data< Eigen::Matrix const &> : rvalue_from_python_storage< Eigen::Matrix const & > + { + typedef typename Eigen::Matrix T; +# if (!defined(__MWERKS__) || __MWERKS__ >= 0x3000) \ + && (!defined(__EDG_VERSION__) || __EDG_VERSION__ >= 245) \ + && (!defined(__DECCXX_VER) || __DECCXX_VER > 60590014) \ + && !defined(BOOST_PYTHON_SYNOPSIS) /* Synopsis' OpenCXX has trouble parsing this */ + // This must always be a POD struct with m_data its first member. + BOOST_STATIC_ASSERT(BOOST_PYTHON_OFFSETOF(rvalue_from_python_storage,stage1) == 0); +# endif + + // The usual constructor + rvalue_from_python_data(rvalue_from_python_stage1_data const & _stage1) + { + this->stage1 = _stage1; + } + + + // This constructor just sets m_convertible -- used by + // implicitly_convertible<> to perform the final step of the + // conversion, where the construct() function is already known. + rvalue_from_python_data(void* convertible) + { + this->stage1.convertible = convertible; + } + + // Destroys any object constructed in the storage. + ~rvalue_from_python_data() + { + // Realign the pointer and destroy + if (this->stage1.convertible == this->storage.bytes) + { + void * storage = reinterpret_cast(this->storage.bytes); + T * aligned = reinterpret_cast(reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16)); + + //std::cout << "Destroying " << (void*)aligned << std::endl; + aligned->T::~T(); + } + } + private: + typedef typename add_reference::type>::type ref_type; + }; + + + + + + // Used when T is a plain value (non-pointer, non-reference) type or + // a (non-volatile) const reference to a plain value type. + template + struct arg_rvalue_from_python< Eigen::Matrix > + { + typedef Eigen::Matrix const & T; + typedef typename boost::add_reference< + T + // We can't add_const here, or it would be impossible to pass + // auto_ptr args from Python to C++ + >::type result_type; + + arg_rvalue_from_python(PyObject * obj) : m_data(converter::rvalue_from_python_stage1(obj, registered::converters)) + , m_source(obj) + { + + } + bool convertible() const + { + return m_data.stage1.convertible != 0; + } + + +# if BOOST_MSVC < 1301 || _MSC_FULL_VER > 13102196 + typename arg_rvalue_from_python:: +# endif + result_type operator()() + { + if (m_data.stage1.construct != 0) + m_data.stage1.construct(m_source, &m_data.stage1); + + // Here is the magic... + // Realign the pointer + void * storage = reinterpret_cast(m_data.storage.bytes); + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + return python::detail::void_ptr_to_reference(aligned, (result_type(*)())0); + } + + private: + rvalue_from_python_data m_data; + PyObject* m_source; + }; + + + // Used when T is a plain value (non-pointer, non-reference) type or + // a (non-volatile) const reference to a plain value type. + template + struct arg_rvalue_from_python< Eigen::Matrix const & > + { + typedef Eigen::Matrix const & T; + typedef typename boost::add_reference< + T + // We can't add_const here, or it would be impossible to pass + // auto_ptr args from Python to C++ + >::type result_type; + + arg_rvalue_from_python(PyObject * obj) : m_data(converter::rvalue_from_python_stage1(obj, registered::converters)) + , m_source(obj) + { + + } + bool convertible() const + { + return m_data.stage1.convertible != 0; + } + + +# if BOOST_MSVC < 1301 || _MSC_FULL_VER > 13102196 + typename arg_rvalue_from_python:: +# endif + result_type operator()() + { + if (m_data.stage1.construct != 0) + m_data.stage1.construct(m_source, &m_data.stage1); + + // Here is the magic... + // Realign the pointer + void * storage = reinterpret_cast(m_data.storage.bytes); + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + return python::detail::void_ptr_to_reference(aligned, (result_type(*)())0); + } + + private: + rvalue_from_python_data m_data; + PyObject* m_source; + }; + + // Used when T is a plain value (non-pointer, non-reference) type or + // a (non-volatile) const reference to a plain value type. + template + struct arg_rvalue_from_python< Eigen::Matrix const > + { + typedef Eigen::Matrix const & T; + typedef typename boost::add_reference< + T + // We can't add_const here, or it would be impossible to pass + // auto_ptr args from Python to C++ + >::type result_type; + + arg_rvalue_from_python(PyObject * obj) : m_data(converter::rvalue_from_python_stage1(obj, registered::converters)) + , m_source(obj) + { + + } + bool convertible() const + { + return m_data.stage1.convertible != 0; + } + + +# if BOOST_MSVC < 1301 || _MSC_FULL_VER > 13102196 + typename arg_rvalue_from_python:: +# endif + result_type operator()() + { + if (m_data.stage1.construct != 0) + m_data.stage1.construct(m_source, &m_data.stage1); + + // Here is the magic... + // Realign the pointer + void * storage = reinterpret_cast(m_data.storage.bytes); + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + return python::detail::void_ptr_to_reference(aligned, (result_type(*)())0); + } + + private: + rvalue_from_python_data m_data; + PyObject* m_source; + }; + + + }}} + + +#endif /* NUMPY_EIGEN_CONVERTERS_HPP */ diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp new file mode 100755 index 000000000..8ac94e8b7 --- /dev/null +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp @@ -0,0 +1,148 @@ +#ifndef NUMPY_EIGEN_COPY_ROUTINES_HPP +#define NUMPY_EIGEN_COPY_ROUTINES_HPP + + +template +struct CopyNumpyToEigenMatrix +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, PyObject * P_) + { + // Assumes M is already initialized. + for(int r = 0; r < M_->rows(); r++) + { + for(int c = 0; c < M_->cols(); c++) + { + T * p = static_cast(PyArray_GETPTR2(P_, r, c)); + (*M_)(r,c) = static_cast(*p); + } + } + } + +}; + +template +struct CopyEigenToNumpyMatrix +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, PyObject * P_) + { + // Assumes M is already initialized. + for(int r = 0; r < M_->rows(); r++) + { + for(int c = 0; c < M_->cols(); c++) + { + T * p = static_cast(PyArray_GETPTR2(P_, r, c)); + *p = static_cast((*M_)(r,c)); + } + } + } + +}; + +template +struct CopyEigenToNumpyVector +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, PyObject * P_) + { + // Assumes M is already initialized. + for(int i = 0; i < M_->size(); i++) + { + T * p = static_cast(PyArray_GETPTR1(P_, i)); + *p = static_cast((*M_)(i)); + } + } + +}; + + +template +struct CopyNumpyToEigenVector +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, PyObject * P_) + { + // Assumes M is already initialized. + for(int i = 0; i < M_->size(); i++) + { + T * p = static_cast(PyArray_GETPTR1(P_, i)); + (*M_)(i) = static_cast(*p); + } + } + +}; + + + + +// Crazy syntax in this function was found here: +// http://stackoverflow.com/questions/1840253/c-template-member-function-of-template-class-called-from-template-function/1840318#1840318 +template< typename FUNCTOR_T> +inline void numpyTypeDemuxer(typename FUNCTOR_T::matrix_t * M, PyObject * P) +{ + FUNCTOR_T f; + int npyType = PyArray_ObjectType(P, 0); + switch(npyType) + { + case NPY_BOOL: + f.template exec(M,P); + break; + case NPY_BYTE: + f.template exec(M,P); + break; + case NPY_UBYTE: + f.template exec(M,P); + break; + case NPY_SHORT: + f.template exec(M,P); + break; + case NPY_USHORT: + f.template exec(M,P); + break; + case NPY_INT: + f.template exec(M,P); + break; + case NPY_UINT: + f.template exec(M,P); + break; + case NPY_LONG: + f.template exec(M,P); + break; + case NPY_ULONG: + f.template exec(M,P); + break; + case NPY_LONGLONG: + f.template exec(M,P); + break; + case NPY_ULONGLONG: + f.template exec(M,P); + break; + case NPY_FLOAT: + f.template exec(M,P); + break; + case NPY_DOUBLE: + f.template exec(M,P); + break; + case NPY_LONGDOUBLE: + f.template exec(M,P); + break; + default: + THROW_TYPE_ERROR("Unsupported type: " << npyTypeToString(npyType)); + } +} + + +#endif /* NUMPY_EIGEN_COPY_ROUTINES_HPP */ diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp new file mode 100755 index 000000000..3b75c6b99 --- /dev/null +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp @@ -0,0 +1,153 @@ +#ifndef NUMPY_EIGEN_TYPE_TRAITS_HPP +#define NUMPY_EIGEN_TYPE_TRAITS_HPP + +#define THROW_TYPE_ERROR(msg) \ + { \ + std::stringstream type_error_ss; \ + type_error_ss << msg; \ + PyErr_SetString(PyExc_TypeError, type_error_ss.str().c_str()); \ + throw boost::python::error_already_set(); \ + } + + +//////////////////////////////////////////////// +// TypeToNumPy +// Defines helper functions based on the Eigen3 matrix type that +// decide what conversions can happen Eigen3 --> NumPy +// Also, converts a type to a NumPy enum. +template struct TypeToNumPy; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_INT }; + static const char * npyString() { return "NPY_INT"; } + static const char * typeString() { return "int"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_LONG; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_UBYTE }; + static const char * npyString() { return "NPY_UBYTE"; } + static const char * typeString() { return "unsigned char"; } + static bool canConvert(int type) + { + return type == NPY_UBYTE || type == NPY_BYTE || type == NPY_CHAR; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_BYTE }; + static const char * npyString() { return "NPY_BYTE"; } + static const char * typeString() { return "char"; } + static bool canConvert(int type) + { + return type == NPY_UBYTE || type == NPY_BYTE || type == NPY_CHAR; + } +}; + + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_FLOAT }; + static const char * npyString() { return "NPY_FLOAT"; } + static const char * typeString() { return "float"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_FLOAT || type == NPY_LONG; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_DOUBLE }; + static const char * npyString() { return "NPY_DOUBLE"; } + static const char * typeString() { return "double"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_FLOAT || type == NPY_DOUBLE || type == NPY_LONG; + } +}; + + + +inline const char * npyTypeToString(int npyType) +{ + switch(npyType) + { + case NPY_BOOL: + return "NPY_BOOL"; + case NPY_BYTE: + return "NPY_BYTE"; + case NPY_UBYTE: + return "NPY_UBYTE"; + case NPY_SHORT: + return "NPY_SHORT"; + case NPY_USHORT: + return "NPY_USHORT"; + case NPY_INT: + return "NPY_INT"; + case NPY_UINT: + return "NPY_UINT"; + case NPY_LONG: + return "NPY_LONG"; + case NPY_ULONG: + return "NPY_ULONG"; + case NPY_LONGLONG: + return "NPY_LONGLONG"; + case NPY_ULONGLONG: + return "NPY_ULONGLONG"; + case NPY_FLOAT: + return "NPY_FLOAT"; + case NPY_DOUBLE: + return "NPY_DOUBLE"; + case NPY_LONGDOUBLE: + return "NPY_LONGDOUBLE"; + case NPY_CFLOAT: + return "NPY_CFLOAT"; + case NPY_CDOUBLE: + return "NPY_CDOUBLE"; + case NPY_CLONGDOUBLE: + return "NPY_CLONGDOUBLE"; + case NPY_OBJECT: + return "NPY_OBJECT"; + case NPY_STRING: + return "NPY_STRING"; + case NPY_UNICODE: + return "NPY_UNICODE"; + case NPY_VOID: + return "NPY_VOID"; + case NPY_NTYPES: + return "NPY_NTYPES"; + case NPY_NOTYPE: + return "NPY_NOTYPE"; + case NPY_CHAR: + return "NPY_CHAR"; + default: + return "Unknown type"; + } +} + +inline std::string npyArrayTypeString(PyObject * obj_ptr) +{ + std::stringstream ss; + int nd = PyArray_NDIM(obj_ptr); + ss << "numpy.array<" << npyTypeToString(PyArray_ObjectType(obj_ptr, 0)) << ">["; + if(nd > 0) + { + ss << PyArray_DIM(obj_ptr, 0); + for(int i = 1; i < nd; i++) + { + ss << ", " << PyArray_DIM(obj_ptr, i); + } + } + ss << "]"; + return ss.str(); +} + + +#endif /* NUMPY_EIGEN_TYPE_TRAITS_HPP */ From 96d6b79f5e6d51f88a50ade43b94bc8e15eb03f6 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 17 Nov 2015 16:19:57 +0100 Subject: [PATCH 011/105] Start organizing python module Organize gtsam modules into submodules. Start with a handwritten noiseModel module. Conflicts: CMakeLists.txt --- CMakeLists.txt | 2 +- python/gtsam/__init__.py | 2 +- python/gtsam/noiseModel/.gitignore | 1 + python/gtsam/noiseModel/__init__.py | 1 + python/handwritten/noiseModel_python.cpp | 111 +++++++++++++++++++++++ 5 files changed, 115 insertions(+), 2 deletions(-) create mode 100644 python/gtsam/noiseModel/.gitignore create mode 100644 python/gtsam/noiseModel/__init__.py create mode 100644 python/handwritten/noiseModel_python.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 263e47321..a99f36027 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -348,7 +348,7 @@ endif() # Python wrap if (GTSAM_BUILD_PYTHON) include(GtsamPythonWrap) - wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "") + # wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "") endif() # Build gtsam_unstable diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index f1b07905b..2f9356acc 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1 +1 @@ -from libgtsam_python import * +import noiseModel diff --git a/python/gtsam/noiseModel/.gitignore b/python/gtsam/noiseModel/.gitignore new file mode 100644 index 000000000..e054d5cfe --- /dev/null +++ b/python/gtsam/noiseModel/.gitignore @@ -0,0 +1 @@ +/libnoiseModel_python.so diff --git a/python/gtsam/noiseModel/__init__.py b/python/gtsam/noiseModel/__init__.py new file mode 100644 index 000000000..492937407 --- /dev/null +++ b/python/gtsam/noiseModel/__init__.py @@ -0,0 +1 @@ +from libnoiseModel_python import * \ No newline at end of file diff --git a/python/handwritten/noiseModel_python.cpp b/python/handwritten/noiseModel_python.cpp new file mode 100644 index 000000000..e23a5b630 --- /dev/null +++ b/python/handwritten/noiseModel_python.cpp @@ -0,0 +1,111 @@ +#include + +#include + +#include + +using namespace boost::python; +using namespace gtsam; +using namespace gtsam::noiseModel; + +// Wrap around pure virtual class Base +// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/exposing.html#python.class_virtual_functions +struct BaseWrap : 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")(); + } + +}; + +BOOST_PYTHON_MODULE(libnoiseModel_python) +{ + +// NOTE: Don't know if it's really necessary to register the matrices convertion here. +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(); + +class_("Base") + .def("print", pure_virtual(&Base::print)) +; + +class_, bases >("Gaussian", no_init) + .def("SqrtInformation",&Gaussian::SqrtInformation) + .staticmethod("SqrtInformation") + .def("Information",&Gaussian::Information) + .staticmethod("Information") + .def("Covariance",&Gaussian::Covariance) + .staticmethod("Covariance") +; + +class_ >("Diagonal", no_init) + .def("Sigmas",&Diagonal::Sigmas) + .staticmethod("Sigmas") + .def("Variances",&Diagonal::Variances) + .staticmethod("Variances") + .def("Precisions",&Diagonal::Precisions) + .staticmethod("Precisions") +; + +class_ >("Isotropic", no_init) + .def("Sigma",&Isotropic::Sigma) + .staticmethod("Sigma") + .def("Variance",&Isotropic::Variance) + .staticmethod("Variance") + .def("Precision",&Isotropic::Precision) + .staticmethod("Precision") +; + +class_ >("Unit", no_init) + .def("Create",&Unit::Create) + .staticmethod("Create") +; + +} \ No newline at end of file From 977d4aa54fa886daeb58872006add1eb1867c5a1 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 17 Nov 2015 16:29:16 +0100 Subject: [PATCH 012/105] Add 'bases' for noiseModel classes While here, add comments and TODOs --- python/handwritten/noiseModel_python.cpp | 34 +++++++++++++++++++++--- 1 file changed, 30 insertions(+), 4 deletions(-) diff --git a/python/handwritten/noiseModel_python.cpp b/python/handwritten/noiseModel_python.cpp index e23a5b630..f33bc0e8b 100644 --- a/python/handwritten/noiseModel_python.cpp +++ b/python/handwritten/noiseModel_python.cpp @@ -1,3 +1,27 @@ +/* ---------------------------------------------------------------------------- + + * 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 @@ -43,6 +67,8 @@ struct BaseWrap : Base, wrapper this->get_override("WhitenSystem")(); } + // TODO(Ellon) Wrap non-pure virtual methods 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 + }; BOOST_PYTHON_MODULE(libnoiseModel_python) @@ -76,7 +102,7 @@ class_("Base") .def("print", pure_virtual(&Base::print)) ; -class_, bases >("Gaussian", no_init) +class_, bases >("Gaussian", no_init) .def("SqrtInformation",&Gaussian::SqrtInformation) .staticmethod("SqrtInformation") .def("Information",&Gaussian::Information) @@ -85,7 +111,7 @@ class_, bases >("Gaussian", no_init) .staticmethod("Covariance") ; -class_ >("Diagonal", no_init) +class_, bases >("Diagonal", no_init) .def("Sigmas",&Diagonal::Sigmas) .staticmethod("Sigmas") .def("Variances",&Diagonal::Variances) @@ -94,7 +120,7 @@ class_ >("Diagonal", no_init) .staticmethod("Precisions") ; -class_ >("Isotropic", no_init) +class_, bases >("Isotropic", no_init) .def("Sigma",&Isotropic::Sigma) .staticmethod("Sigma") .def("Variance",&Isotropic::Variance) @@ -103,7 +129,7 @@ class_ >("Isotropic", no_init) .staticmethod("Precision") ; -class_ >("Unit", no_init) +class_, bases >("Unit", no_init) .def("Create",&Unit::Create) .staticmethod("Create") ; From a0064f3aaba6a8cfed667c32bba3bd2cf433d0b3 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 17 Nov 2015 17:42:53 +0100 Subject: [PATCH 013/105] Add geometry submodule of python module --- python/gtsam/__init__.py | 1 + python/gtsam/geometry/.gitignore | 1 + python/gtsam/geometry/__init__.py | 1 + python/handwritten/geometry_python.cpp | 179 +++++++++++++++++++++++++ 4 files changed, 182 insertions(+) create mode 100644 python/gtsam/geometry/.gitignore create mode 100644 python/gtsam/geometry/__init__.py create mode 100644 python/handwritten/geometry_python.cpp diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 2f9356acc..df9839fb0 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1 +1,2 @@ import noiseModel +import geometry diff --git a/python/gtsam/geometry/.gitignore b/python/gtsam/geometry/.gitignore new file mode 100644 index 000000000..7e7c8fdb2 --- /dev/null +++ b/python/gtsam/geometry/.gitignore @@ -0,0 +1 @@ +/libgeometry_python.so diff --git a/python/gtsam/geometry/__init__.py b/python/gtsam/geometry/__init__.py new file mode 100644 index 000000000..32a465828 --- /dev/null +++ b/python/gtsam/geometry/__init__.py @@ -0,0 +1 @@ +from libgeometry_python import * \ No newline at end of file diff --git a/python/handwritten/geometry_python.cpp b/python/handwritten/geometry_python.cpp new file mode 100644 index 000000000..9e6a9e55c --- /dev/null +++ b/python/handwritten/geometry_python.cpp @@ -0,0 +1,179 @@ +/* ---------------------------------------------------------------------------- + + * 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) +{ + +// NOTE: Don't know if it's really necessary to register the matrices convertion here. +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(); + +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 From ff1cd140bbc7ee40968c40cebde7bc460194b8bf Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 17 Nov 2015 17:59:43 +0100 Subject: [PATCH 014/105] Register convertion between numpy and eigen in a separated submodule --- python/gtsam/__init__.py | 1 + python/gtsam/registernumpyeigen/.gitignore | 1 + python/gtsam/registernumpyeigen/__init__.py | 1 + python/handwritten/geometry_python.cpp | 24 --------- python/handwritten/noiseModel_python.cpp | 24 --------- .../handwritten/registernumpyeigen_python.cpp | 54 +++++++++++++++++++ 6 files changed, 57 insertions(+), 48 deletions(-) create mode 100644 python/gtsam/registernumpyeigen/.gitignore create mode 100644 python/gtsam/registernumpyeigen/__init__.py create mode 100644 python/handwritten/registernumpyeigen_python.cpp diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index df9839fb0..3e2899db0 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,2 +1,3 @@ +import registernumpyeigen import noiseModel import geometry diff --git a/python/gtsam/registernumpyeigen/.gitignore b/python/gtsam/registernumpyeigen/.gitignore new file mode 100644 index 000000000..7ed4e4844 --- /dev/null +++ b/python/gtsam/registernumpyeigen/.gitignore @@ -0,0 +1 @@ +/libregisternumpyeigen_python.so diff --git a/python/gtsam/registernumpyeigen/__init__.py b/python/gtsam/registernumpyeigen/__init__.py new file mode 100644 index 000000000..ac6856e8c --- /dev/null +++ b/python/gtsam/registernumpyeigen/__init__.py @@ -0,0 +1 @@ +from libregisternumpyeigen_python import * \ No newline at end of file diff --git a/python/handwritten/geometry_python.cpp b/python/handwritten/geometry_python.cpp index 9e6a9e55c..61f1e3ee7 100644 --- a/python/handwritten/geometry_python.cpp +++ b/python/handwritten/geometry_python.cpp @@ -47,30 +47,6 @@ bool (Pose3::*equals_0)(const gtsam::Pose3&, double) const = &Pose3::equals; BOOST_PYTHON_MODULE(libgeometry_python) { -// NOTE: Don't know if it's really necessary to register the matrices convertion here. -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(); - class_("Point3") .def(init<>()) .def(init()) diff --git a/python/handwritten/noiseModel_python.cpp b/python/handwritten/noiseModel_python.cpp index f33bc0e8b..34ec8393f 100644 --- a/python/handwritten/noiseModel_python.cpp +++ b/python/handwritten/noiseModel_python.cpp @@ -74,30 +74,6 @@ struct BaseWrap : Base, wrapper BOOST_PYTHON_MODULE(libnoiseModel_python) { -// NOTE: Don't know if it's really necessary to register the matrices convertion here. -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(); - class_("Base") .def("print", pure_virtual(&Base::print)) ; diff --git a/python/handwritten/registernumpyeigen_python.cpp b/python/handwritten/registernumpyeigen_python.cpp new file mode 100644 index 000000000..cb8980494 --- /dev/null +++ b/python/handwritten/registernumpyeigen_python.cpp @@ -0,0 +1,54 @@ +/* ---------------------------------------------------------------------------- + + * 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(); + +} From 7cfd57339a514d6f92523221da47a59193ffda9f Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 17 Nov 2015 18:36:49 +0100 Subject: [PATCH 015/105] Add nonlinear submodule of gtsam python module --- python/gtsam/__init__.py | 2 + python/gtsam/nonlinear/.gitignore | 1 + python/gtsam/nonlinear/__init__.py | 1 + python/handwritten/nonlinear_python.cpp | 54 +++++++++++++++++++++++++ 4 files changed, 58 insertions(+) create mode 100644 python/gtsam/nonlinear/.gitignore create mode 100644 python/gtsam/nonlinear/__init__.py create mode 100644 python/handwritten/nonlinear_python.cpp diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 3e2899db0..0493a252f 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,3 +1,5 @@ import registernumpyeigen import noiseModel import geometry +import nonlinear + diff --git a/python/gtsam/nonlinear/.gitignore b/python/gtsam/nonlinear/.gitignore new file mode 100644 index 000000000..d2353be92 --- /dev/null +++ b/python/gtsam/nonlinear/.gitignore @@ -0,0 +1 @@ +/libnonlinear_python.so diff --git a/python/gtsam/nonlinear/__init__.py b/python/gtsam/nonlinear/__init__.py new file mode 100644 index 000000000..74a227d48 --- /dev/null +++ b/python/gtsam/nonlinear/__init__.py @@ -0,0 +1 @@ +from libnonlinear_python import * \ No newline at end of file diff --git a/python/handwritten/nonlinear_python.cpp b/python/handwritten/nonlinear_python.cpp new file mode 100644 index 000000000..09b56ea85 --- /dev/null +++ b/python/handwritten/nonlinear_python.cpp @@ -0,0 +1,54 @@ +/* ---------------------------------------------------------------------------- + + * 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 + +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 +void (Values::*insert_0)(const gtsam::Values&) = &Values::insert; +void (Values::*insert_1)(Key, const gtsam::Pose3&) = &Values::insert; + +BOOST_PYTHON_MODULE(libnonlinear_python) +{ + +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("insertFixed", &Values::insertFixed) + .def("print", &Values::print) + .def("size", &Values::size) + .def("swap", &Values::swap) + .def("insert", insert_0) + .def("insert", insert_1) +; + +} \ No newline at end of file From e0b8d876953c48b924cc279431b16067fba52b3f Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 18 Nov 2015 11:48:25 +0100 Subject: [PATCH 016/105] Wrap Values::insert and Values::at for Point3, Rot3, and Pose3 --- python/handwritten/nonlinear_python.cpp | 54 ++++++++++++++++++++++++- 1 file changed, 53 insertions(+), 1 deletion(-) diff --git a/python/handwritten/nonlinear_python.cpp b/python/handwritten/nonlinear_python.cpp index 09b56ea85..40c97d4ed 100644 --- a/python/handwritten/nonlinear_python.cpp +++ b/python/handwritten/nonlinear_python.cpp @@ -30,7 +30,51 @@ 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 void (Values::*insert_0)(const gtsam::Values&) = &Values::insert; -void (Values::*insert_1)(Key, const gtsam::Pose3&) = &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; + +/** 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) { @@ -49,6 +93,14 @@ class_("Values") .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<>()) ; } \ No newline at end of file From 72d73c67215bfd9eef6fb175f331f900869c7a5c Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 18 Nov 2015 13:18:01 +0100 Subject: [PATCH 017/105] Add slam as submodule of gtsam python module --- python/gtsam/__init__.py | 2 +- python/gtsam/slam/.gitignore | 1 + python/gtsam/slam/__init__.py | 1 + python/handwritten/slam_python.cpp | 52 ++++++++++++++++++++++++++++++ 4 files changed, 55 insertions(+), 1 deletion(-) create mode 100644 python/gtsam/slam/.gitignore create mode 100644 python/gtsam/slam/__init__.py create mode 100644 python/handwritten/slam_python.cpp diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 0493a252f..92c2d1f65 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -2,4 +2,4 @@ import registernumpyeigen import noiseModel import geometry import nonlinear - +import slam diff --git a/python/gtsam/slam/.gitignore b/python/gtsam/slam/.gitignore new file mode 100644 index 000000000..4fbe984da --- /dev/null +++ b/python/gtsam/slam/.gitignore @@ -0,0 +1 @@ +/libslam_python.so diff --git a/python/gtsam/slam/__init__.py b/python/gtsam/slam/__init__.py new file mode 100644 index 000000000..8c327e67f --- /dev/null +++ b/python/gtsam/slam/__init__.py @@ -0,0 +1 @@ +from libslam_python import * \ No newline at end of file diff --git a/python/handwritten/slam_python.cpp b/python/handwritten/slam_python.cpp new file mode 100644 index 000000000..f2c56cae4 --- /dev/null +++ b/python/handwritten/slam_python.cpp @@ -0,0 +1,52 @@ +/* ---------------------------------------------------------------------------- + + * 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 + +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 + +// Macro used to define a BetweenFactor given the type. +#define BETWEENFACTOR(VALUE) \ + class_< BetweenFactor >("BetweenFactor"#VALUE) \ + .def(init()) \ + .def("measured", &BetweenFactor::measured, return_internal_reference<>()) \ +; + +BOOST_PYTHON_MODULE(libslam_python) +{ + + BETWEENFACTOR(Point3) + + BETWEENFACTOR(Rot3) + + BETWEENFACTOR(Pose3) + +} \ No newline at end of file From 6684f69d0a69c9a72d989114cacdb73629fad138 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 18 Nov 2015 17:28:44 +0100 Subject: [PATCH 018/105] Fix inheritance problem on python wrapping of noise models --- python/handwritten/noiseModel_python.cpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/python/handwritten/noiseModel_python.cpp b/python/handwritten/noiseModel_python.cpp index 34ec8393f..5ed919dd4 100644 --- a/python/handwritten/noiseModel_python.cpp +++ b/python/handwritten/noiseModel_python.cpp @@ -24,17 +24,17 @@ #include -#include - #include using namespace boost::python; using namespace gtsam; using namespace gtsam::noiseModel; -// Wrap around pure virtual class Base +// 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 BaseWrap : Base, wrapper +struct BaseCallback : Base, wrapper { void print (const std::string & name="") const { this->get_override("print")(); @@ -67,18 +67,20 @@ struct BaseWrap : Base, wrapper this->get_override("WhitenSystem")(); } - // TODO(Ellon) Wrap non-pure virtual methods 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 + // 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 }; BOOST_PYTHON_MODULE(libnoiseModel_python) { -class_("Base") +class_("Base") .def("print", pure_virtual(&Base::print)) ; -class_, bases >("Gaussian", no_init) +// 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) .staticmethod("SqrtInformation") .def("Information",&Gaussian::Information) From 9a97248ee4576bd5f58bdd87f704c9d6ec43e003 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 18 Nov 2015 17:35:27 +0100 Subject: [PATCH 019/105] Put classes in namespaces close to gtsam's C++ interface --- python/gtsam/__init__.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 92c2d1f65..39d0d08ef 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,5 +1,5 @@ import registernumpyeigen import noiseModel -import geometry -import nonlinear -import slam +from geometry import * +from nonlinear import * +from slam import * From 828b230e17534cdecc4d6def714b79dcb7caada1 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 18 Nov 2015 18:05:22 +0100 Subject: [PATCH 020/105] Add overloads for named constructors on noiseModel module --- python/handwritten/noiseModel_python.cpp | 31 +++++++++++++++++------- 1 file changed, 22 insertions(+), 9 deletions(-) diff --git a/python/handwritten/noiseModel_python.cpp b/python/handwritten/noiseModel_python.cpp index 5ed919dd4..f9115b870 100644 --- a/python/handwritten/noiseModel_python.cpp +++ b/python/handwritten/noiseModel_python.cpp @@ -72,6 +72,19 @@ struct BaseCallback : Base, wrapper }; +// 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) { @@ -81,29 +94,29 @@ class_("Base") // 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) + .def("SqrtInformation",&Gaussian::SqrtInformation, Gaussian_SqrtInformation_overloads()) .staticmethod("SqrtInformation") - .def("Information",&Gaussian::Information) + .def("Information",&Gaussian::Information, Gaussian_Information_overloads()) .staticmethod("Information") - .def("Covariance",&Gaussian::Covariance) + .def("Covariance",&Gaussian::Covariance, Gaussian_Covariance_overloads()) .staticmethod("Covariance") ; class_, bases >("Diagonal", no_init) - .def("Sigmas",&Diagonal::Sigmas) + .def("Sigmas",&Diagonal::Sigmas, Diagonal_Sigmas_overloads()) .staticmethod("Sigmas") - .def("Variances",&Diagonal::Variances) + .def("Variances",&Diagonal::Variances, Diagonal_Variances_overloads()) .staticmethod("Variances") - .def("Precisions",&Diagonal::Precisions) + .def("Precisions",&Diagonal::Precisions, Diagonal_Precisions_overloads()) .staticmethod("Precisions") ; class_, bases >("Isotropic", no_init) - .def("Sigma",&Isotropic::Sigma) + .def("Sigma",&Isotropic::Sigma, Isotropic_Sigma_overloads()) .staticmethod("Sigma") - .def("Variance",&Isotropic::Variance) + .def("Variance",&Isotropic::Variance, Isotropic_Variance_overloads()) .staticmethod("Variance") - .def("Precision",&Isotropic::Precision) + .def("Precision",&Isotropic::Precision, Isotropic_Precision_overloads()) .staticmethod("Precision") ; From 72a800f70f43d10ea76071a8228e3331d794e9ac Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Thu, 19 Nov 2015 10:09:15 +0100 Subject: [PATCH 021/105] Add inheritance to from NonlinearFactor to BetweenFactor. Nonlinear factor is pure virtual, so we need to declare a wrapper, even if we don't export anything from it. Also, we don't make explicit all the chain of inheritance from BetweenFactor, since it looks like exporting inheritance directly from NonlinearFactor allows adding it to NonlinearFactorGraph. --- python/handwritten/slam_python.cpp | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/python/handwritten/slam_python.cpp b/python/handwritten/slam_python.cpp index f2c56cae4..67aaf50c6 100644 --- a/python/handwritten/slam_python.cpp +++ b/python/handwritten/slam_python.cpp @@ -32,10 +32,28 @@ 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 a BetweenFactor given the type. #define BETWEENFACTOR(VALUE) \ - class_< BetweenFactor >("BetweenFactor"#VALUE) \ + class_< BetweenFactor, bases, boost::shared_ptr< BetweenFactor > >("BetweenFactor"#VALUE) \ .def(init()) \ .def("measured", &BetweenFactor::measured, return_internal_reference<>()) \ ; @@ -43,6 +61,9 @@ using namespace gtsam; BOOST_PYTHON_MODULE(libslam_python) { + class_("NonlinearFactor") + ; + BETWEENFACTOR(Point3) BETWEENFACTOR(Rot3) From b10f7386c518aaeb44af00f2b5fff464a2404444 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Thu, 19 Nov 2015 11:02:51 +0100 Subject: [PATCH 022/105] Wrap prior factors --- python/handwritten/slam_python.cpp | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/python/handwritten/slam_python.cpp b/python/handwritten/slam_python.cpp index 67aaf50c6..c3c86661a 100644 --- a/python/handwritten/slam_python.cpp +++ b/python/handwritten/slam_python.cpp @@ -21,6 +21,7 @@ #include +#include #include #include #include @@ -51,13 +52,19 @@ struct NonlinearFactorCallback : NonlinearFactor, wrapper } }; -// Macro used to define a BetweenFactor given the type. +// 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) { @@ -70,4 +77,10 @@ BOOST_PYTHON_MODULE(libslam_python) BETWEENFACTOR(Pose3) + PRIORFACTOR(Point3) + + PRIORFACTOR(Rot3) + + PRIORFACTOR(Pose3) + } \ No newline at end of file From 7680b533acfa4054e02530e6506e88e2287a9126 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Thu, 19 Nov 2015 11:03:35 +0100 Subject: [PATCH 023/105] Wrap basic functions of NonlinearFactorGraph and ISAM2 While here, change method names for python convention on PEP0008 --- python/handwritten/nonlinear_python.cpp | 45 +++++++++++++++++++++---- 1 file changed, 39 insertions(+), 6 deletions(-) diff --git a/python/handwritten/nonlinear_python.cpp b/python/handwritten/nonlinear_python.cpp index 40c97d4ed..de164957c 100644 --- a/python/handwritten/nonlinear_python.cpp +++ b/python/handwritten/nonlinear_python.cpp @@ -22,17 +22,19 @@ #include #include +#include +#include + #include using namespace boost::python; using namespace gtsam; -// Prototypes used to perform overloading +// Overloading macros // See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html -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; +// 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 @@ -79,6 +81,12 @@ void (Values::*insert_3)(Key, const gtsam::Pose3&) = &Values::insert; 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()) @@ -87,7 +95,7 @@ class_("Values") .def("empty", &Values::empty) .def("equals", &Values::equals) .def("erase", &Values::erase) - .def("insertFixed", &Values::insertFixed) + .def("insert_fixed", &Values::insertFixed) .def("print", &Values::print) .def("size", &Values::size) .def("swap", &Values::swap) @@ -103,4 +111,29 @@ class_("Values") .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 From ffae37a67522206eaeedda0060dc4766e5581108 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Thu, 19 Nov 2015 14:59:30 +0100 Subject: [PATCH 024/105] Revert python module to use old handwritten files Just noticed several handwritten files here. I'm reverting the python module to use these handwritten files to later add the files I was wrapping to the same framework. Classes from geometry were wrapped for an old C++ interface, so several boost python's .def(...) were commented out. Conflicts: python/gtsam/.gitignore --- CMakeLists.txt | 10 ++- python/CMakeLists.txt | 13 ++++ python/gtsam/.gitignore | 1 + python/gtsam/__init__.py | 6 +- .../examples/OdometeryExample.py | 0 python/handwritten/CMakeLists.txt | 65 ++++++++++++------- python/handwritten/exportgtsam.cpp | 2 +- python/handwritten/geometry/Point2.cpp | 4 +- python/handwritten/geometry/Pose2.cpp | 34 +++++----- python/handwritten/geometry/Rot2.cpp | 10 +-- 10 files changed, 92 insertions(+), 53 deletions(-) create mode 100644 python/CMakeLists.txt create mode 100644 python/gtsam/.gitignore rename python/{handwritten => gtsam}/examples/OdometeryExample.py (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index a99f36027..2719a77ab 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -347,8 +347,16 @@ endif() # Python wrap if (GTSAM_BUILD_PYTHON) - include(GtsamPythonWrap) + # NOTE: The automatic generation of python wrapper from the gtsampy.h interface is + # not working yet, so we're using a handwritten wrapper files on python/handwritten. + # Once the python wrapping from the interface file is working, you can _swap_ the + # comments on the next lines + + # include(GtsamPythonWrap) # wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "") + + add_subdirectory(python) + endif() # Build gtsam_unstable diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt new file mode 100644 index 000000000..0fcb1fc28 --- /dev/null +++ b/python/CMakeLists.txt @@ -0,0 +1,13 @@ +# Obtain Dependencies +# Boost Python +find_package(Boost COMPONENTS python REQUIRED) +include_directories(${Boost_INCLUDE_DIRS}) + +# Find Python +find_package(PythonLibs 2.7 REQUIRED) +include_directories(${PYTHON_INCLUDE_DIRS}) + +# Numpy_Eigen +include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) + +add_subdirectory(handwritten) \ No newline at end of file diff --git a/python/gtsam/.gitignore b/python/gtsam/.gitignore new file mode 100644 index 000000000..8f89b0f14 --- /dev/null +++ b/python/gtsam/.gitignore @@ -0,0 +1 @@ +/libgtsam_python.so diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 39d0d08ef..4b18783d3 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,5 +1 @@ -import registernumpyeigen -import noiseModel -from geometry import * -from nonlinear import * -from slam import * +from libgtsam_python import * \ No newline at end of file diff --git a/python/handwritten/examples/OdometeryExample.py b/python/gtsam/examples/OdometeryExample.py similarity index 100% rename from python/handwritten/examples/OdometeryExample.py rename to python/gtsam/examples/OdometeryExample.py diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 6693beba5..753e33831 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -1,27 +1,48 @@ -include_directories("${PROJECT_SOURCE_DIR}/gtsam") +# Macro to get list of subdirectories +MACRO(SUBDIRLIST result curdir) + FILE(GLOB children RELATIVE ${curdir} ${curdir}/*) + SET(dirlist "") + FOREACH(child ${children}) + IF(IS_DIRECTORY ${curdir}/${child}) + LIST(APPEND dirlist ${child}) + ENDIF() + ENDFOREACH() + SET(${result} ${dirlist}) +ENDMACRO() -#set the default path for built executables to the "bin" directory -set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) -#set the default path for built libraries to the "lib" directory -set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) +# get subdirectories list +SUBDIRLIST(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}) -list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../cmake) +# get the sources needed to compile gtsam python module +SET(gtsam_python_srcs "") +FOREACH(subdir ${SUBDIRS}) + file(GLOB ${subdir}_src "${subdir}/*.cpp") + LIST(APPEND gtsam_python_srcs ${${subdir}_src}) +ENDFOREACH() -#include_directories(${EIGEN_INCLUDE_DIRS}) +# Create the library +set(moduleName gtsam) +set(gtsamLib gtsam) +add_library(${moduleName}_python SHARED exportgtsam.cpp ${gtsam_python_srcs}) -file(GLOB base_src "base/*.cpp") -file(GLOB geometry_src "geometry/*.cpp") -file(GLOB inference_src "inference/*.cpp") -file(GLOB linear_src "linear/*.cpp") -file(GLOB nonlinear_src "nonlinear/*.cpp") -file(GLOB slam_src "slam/*.cpp") -file(GLOB symbolic_src "symbolic/*.cpp") +set_target_properties(${moduleName}_python PROPERTIES + OUTPUT_NAME ${moduleName}_python + CLEAN_DIRECT_OUTPUT 1) -#wrap_python("base" ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} ${base_src}) -wrap_python("pygtsam" ${PROJECT_SOURCE_DIR}/python/gtsam exportgtsam.cpp - ${geometry_src} ${linear_src} ${nonlinear_src} ${slam_src}) -#wrap_python("nonlinear" ${PROJECT_SOURCE_DIR}/python/gtsam ${nonlinear_src}) -#wrap_python("slam" ${PROJECT_SOURCE_DIR}/python/gtsam ${slam_src}) -#add_python_export_library(${PROJECT_NAME}_test ${PROJECT_SOURCE_DIR}/python/${PROJECT_NAME} -# ${AUTOGEN_TEST_FILES} -#) \ No newline at end of file +target_link_libraries(${moduleName}_python ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp + +# On OSX and Linux, the python library must end in the extension .so. Build this +# filename here. +get_property(PYLIB_OUTPUT_FILE TARGET ${moduleName}_python PROPERTY LOCATION) +set(PYLIB_OUTPUT_FILE $) +get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE) +set(PYLIB_SO_NAME lib${moduleName}_python.so) + +# Installs the library in the gtsam folder, which is used by setup.py to create the gtsam package +set(PYTHON_MODULE_DIRECTORY ${CMAKE_SOURCE_DIR}/python/gtsam) +# Cause the library to be output in the correct directory. +add_custom_command(TARGET ${moduleName}_python + POST_BUILD + COMMAND cp -v ${PYLIB_OUTPUT_FILE} ${PYTHON_MODULE_DIRECTORY}/${PYLIB_SO_NAME} + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} + COMMENT "Copying library files to python directory" ) diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 51e0ae1f3..3799ef584 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -45,7 +45,7 @@ typedef gtsam::BetweenFactor Pose2BetweenFactor; //-----------------------------------// -BOOST_PYTHON_MODULE(libgtsam){ +BOOST_PYTHON_MODULE(libgtsam_python){ using namespace boost::python; exportPoint2(); exportRot2(); diff --git a/python/handwritten/geometry/Point2.cpp b/python/handwritten/geometry/Point2.cpp index 0d1e7092b..9e1a4d6b8 100644 --- a/python/handwritten/geometry/Point2.cpp +++ b/python/handwritten/geometry/Point2.cpp @@ -15,9 +15,9 @@ void exportPoint2(){ .def("print", &Point2::print, print_overloads(args("s"))) .def("equals", &Point2::equals, equals_overloads(args("q","tol"))) .def("inverse", &Point2::inverse) - .def("compose", &Point2::compose, compose_overloads(args("q", "H1", "H2"))) + // .def("compose", &Point2::compose, compose_overloads(args("q", "H1", "H2"))) .def("between", &Point2::between) - .def("dim", &Point2::dim) + // .def("dim", &Point2::dim) .def("retract", &Point2::retract) .def("x", &Point2::x) .def("y", &Point2::y) diff --git a/python/handwritten/geometry/Pose2.cpp b/python/handwritten/geometry/Pose2.cpp index 577a8da2c..133a6f05f 100644 --- a/python/handwritten/geometry/Pose2.cpp +++ b/python/handwritten/geometry/Pose2.cpp @@ -17,15 +17,15 @@ BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, Pose2::range, 1, 3) void exportPose2(){ - double (Pose2::*range1)(const Pose2&, boost::optional, boost::optional) const - = &Pose2::range; - double (Pose2::*range2)(const Point2&, boost::optional, boost::optional) const - = &Pose2::range; + // double (Pose2::*range1)(const Pose2&, boost::optional, boost::optional) const + // = &Pose2::range; + // double (Pose2::*range2)(const Point2&, boost::optional, boost::optional) const + // = &Pose2::range; - Rot2 (Pose2::*bearing1)(const Pose2&, boost::optional, boost::optional) const - = &Pose2::bearing; - Rot2 (Pose2::*bearing2)(const Point2&, boost::optional, boost::optional) const - = &Pose2::bearing; + // Rot2 (Pose2::*bearing1)(const Pose2&, boost::optional, boost::optional) const + // = &Pose2::bearing; + // Rot2 (Pose2::*bearing2)(const Point2&, boost::optional, boost::optional) const + // = &Pose2::bearing; class_("Pose2", init<>()) .def(init()) @@ -34,11 +34,11 @@ void exportPose2(){ .def("print", &Pose2::print, print_overloads(args("s"))) .def("equals", &Pose2::equals, equals_overloads(args("pose","tol"))) - .def("inverse", &Pose2::inverse) - .def("compose", &Pose2::compose, compose_overloads(args("p2", "H1", "H2"))) - .def("between", &Pose2::between, between_overloads(args("p2", "H1", "H2"))) - .def("dim", &Pose2::dim) - .def("retract", &Pose2::retract) + // .def("inverse", &Pose2::inverse) + // .def("compose", &Pose2::compose, compose_overloads(args("p2", "H1", "H2"))) + // .def("between", &Pose2::between, between_overloads(args("p2", "H1", "H2"))) + // .def("dim", &Pose2::dim) + // .def("retract", &Pose2::retract) .def("transform_to", &Pose2::transform_to, transform_to_overloads(args("point", "H1", "H2"))) @@ -55,12 +55,12 @@ void exportPose2(){ .def("translation", &Pose2::translation, return_value_policy()) .def("rotation", &Pose2::rotation, return_value_policy()) - .def("bearing", bearing1, bearing_overloads()) - .def("bearing", bearing2, bearing_overloads()) + // .def("bearing", bearing1, bearing_overloads()) + // .def("bearing", bearing2, bearing_overloads()) // Function overload example - .def("range", range1, range_overloads()) - .def("range", range2, range_overloads()) + // .def("range", range1, range_overloads()) + // .def("range", range2, range_overloads()) .def("Expmap", &Pose2::Expmap) diff --git a/python/handwritten/geometry/Rot2.cpp b/python/handwritten/geometry/Rot2.cpp index 06a6a7072..e79fabd9d 100644 --- a/python/handwritten/geometry/Rot2.cpp +++ b/python/handwritten/geometry/Rot2.cpp @@ -28,11 +28,11 @@ void exportRot2(){ .def("print", &Rot2::print, print_overloads(args("s"))) .def("equals", &Rot2::equals, equals_overloads(args("q","tol"))) - .def("inverse", &Rot2::inverse) - .def("compose", &Rot2::compose, compose_overloads(args("q", "H1", "H2"))) - .def("between", &Rot2::between) - .def("dim", &Rot2::dim) - .def("retract", &Rot2::retract) + // .def("inverse", &Rot2::inverse) + // .def("compose", &Rot2::compose, compose_overloads(args("q", "H1", "H2"))) + // .def("between", &Rot2::between) + // .def("dim", &Rot2::dim) + // .def("retract", &Rot2::retract) .def("Expmap", &Rot2::Expmap) .staticmethod("Expmap") From d76ed71c99f5b9775cffe9030fb4624f16afbf18 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Thu, 19 Nov 2015 18:31:38 +0100 Subject: [PATCH 025/105] Move my developments to the handwritten structure of files that existed before There's a problem with numpy_eigen causing a segmentation fault. --- python/gtsam/__init__.py | 2 +- python/gtsam/geometry/.gitignore | 1 - python/gtsam/geometry/__init__.py | 1 - python/gtsam/noiseModel/.gitignore | 1 - python/gtsam/noiseModel/__init__.py | 1 - python/gtsam/nonlinear/.gitignore | 1 - python/gtsam/nonlinear/__init__.py | 1 - python/gtsam/registernumpyeigen/.gitignore | 1 - python/gtsam/registernumpyeigen/__init__.py | 1 - python/gtsam/slam/.gitignore | 1 - python/gtsam/slam/__init__.py | 1 - python/handwritten/exportgtsam.cpp | 66 +++++---- python/handwritten/geometry/Point2.cpp | 40 +++++- python/handwritten/geometry/Point3.cpp | 60 ++++++++ python/handwritten/geometry/Pose2.cpp | 17 +++ python/handwritten/geometry/Pose3.cpp | 74 ++++++++++ python/handwritten/geometry/Rot2.cpp | 63 +++++---- python/handwritten/geometry/Rot3.cpp | 91 ++++++++++++ python/handwritten/linear/NoiseModel.cpp | 131 +++++++++++++++++- python/handwritten/nonlinear/ISAM2.cpp | 44 ++++++ .../handwritten/nonlinear/NonlinearFactor.cpp | 45 ++++++ .../nonlinear/NonlinearFactorGraph.cpp | 29 +++- python/handwritten/nonlinear/Values.cpp | 98 ++++++++++++- python/handwritten/slam/BetweenFactor.cpp | 53 ++++++- python/handwritten/slam/PriorFactor.cpp | 51 ++++++- python/handwritten/utils/NumpyEigen.cpp | 52 +++++++ 26 files changed, 831 insertions(+), 95 deletions(-) delete mode 100644 python/gtsam/geometry/.gitignore delete mode 100644 python/gtsam/geometry/__init__.py delete mode 100644 python/gtsam/noiseModel/.gitignore delete mode 100644 python/gtsam/noiseModel/__init__.py delete mode 100644 python/gtsam/nonlinear/.gitignore delete mode 100644 python/gtsam/nonlinear/__init__.py delete mode 100644 python/gtsam/registernumpyeigen/.gitignore delete mode 100644 python/gtsam/registernumpyeigen/__init__.py delete mode 100644 python/gtsam/slam/.gitignore delete mode 100644 python/gtsam/slam/__init__.py create mode 100644 python/handwritten/geometry/Point3.cpp create mode 100644 python/handwritten/geometry/Pose3.cpp create mode 100644 python/handwritten/geometry/Rot3.cpp create mode 100644 python/handwritten/nonlinear/ISAM2.cpp create mode 100644 python/handwritten/nonlinear/NonlinearFactor.cpp create mode 100644 python/handwritten/utils/NumpyEigen.cpp diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 4b18783d3..f1b07905b 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1 +1 @@ -from libgtsam_python import * \ No newline at end of file +from libgtsam_python import * diff --git a/python/gtsam/geometry/.gitignore b/python/gtsam/geometry/.gitignore deleted file mode 100644 index 7e7c8fdb2..000000000 --- a/python/gtsam/geometry/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/libgeometry_python.so diff --git a/python/gtsam/geometry/__init__.py b/python/gtsam/geometry/__init__.py deleted file mode 100644 index 32a465828..000000000 --- a/python/gtsam/geometry/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from libgeometry_python import * \ No newline at end of file diff --git a/python/gtsam/noiseModel/.gitignore b/python/gtsam/noiseModel/.gitignore deleted file mode 100644 index e054d5cfe..000000000 --- a/python/gtsam/noiseModel/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/libnoiseModel_python.so diff --git a/python/gtsam/noiseModel/__init__.py b/python/gtsam/noiseModel/__init__.py deleted file mode 100644 index 492937407..000000000 --- a/python/gtsam/noiseModel/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from libnoiseModel_python import * \ No newline at end of file diff --git a/python/gtsam/nonlinear/.gitignore b/python/gtsam/nonlinear/.gitignore deleted file mode 100644 index d2353be92..000000000 --- a/python/gtsam/nonlinear/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/libnonlinear_python.so diff --git a/python/gtsam/nonlinear/__init__.py b/python/gtsam/nonlinear/__init__.py deleted file mode 100644 index 74a227d48..000000000 --- a/python/gtsam/nonlinear/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from libnonlinear_python import * \ No newline at end of file diff --git a/python/gtsam/registernumpyeigen/.gitignore b/python/gtsam/registernumpyeigen/.gitignore deleted file mode 100644 index 7ed4e4844..000000000 --- a/python/gtsam/registernumpyeigen/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/libregisternumpyeigen_python.so diff --git a/python/gtsam/registernumpyeigen/__init__.py b/python/gtsam/registernumpyeigen/__init__.py deleted file mode 100644 index ac6856e8c..000000000 --- a/python/gtsam/registernumpyeigen/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from libregisternumpyeigen_python import * \ No newline at end of file diff --git a/python/gtsam/slam/.gitignore b/python/gtsam/slam/.gitignore deleted file mode 100644 index 4fbe984da..000000000 --- a/python/gtsam/slam/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/libslam_python.so diff --git a/python/gtsam/slam/__init__.py b/python/gtsam/slam/__init__.py deleted file mode 100644 index 8c327e67f..000000000 --- a/python/gtsam/slam/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from libslam_python import * \ No newline at end of file diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 3799ef584..2424cd4da 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -1,63 +1,77 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports the python module + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include #include -#include -#include -#include -#include -#include +#include +#include using namespace boost::python; using namespace gtsam; using namespace std; -// Geometery +// Geometry void exportPoint2(); +void exportPoint3(); void exportRot2(); +void exportRot3(); void exportPose2(); +void exportPose3(); // Linear void exportNoiseModels(); // Nonlinear void exportValues(); +void exportNonlinearFactor(); void exportNonlinearFactorGraph(); void exportLevenbergMarquardtOptimizer(); +void exportISAM2(); // Slam -template< class FACTOR, class VALUE > -void exportPriorFactor(const std::string& name){ - class_< FACTOR >(name.c_str(), init<>()) - .def(init< Key, VALUE&, SharedNoiseModel >()) - ; -} +void exportPriorFactors(); +void exportBetweenFactors(); -template -void exportBetweenFactor(const std::string& name){ - class_(name.c_str(), init<>()) - .def(init()) - ; -} - -typedef gtsam::PriorFactor Point2PriorFactor; -typedef gtsam::PriorFactor Pose2PriorFactor; -typedef gtsam::BetweenFactor Pose2BetweenFactor; +// Utils (or Python wrapper specific functions) +void registerNumpyEigenConversions(); //-----------------------------------// BOOST_PYTHON_MODULE(libgtsam_python){ - using namespace boost::python; + + // Should be the first thing to be done + registerNumpyEigenConversions(); + exportPoint2(); + exportPoint3(); exportRot2(); + exportRot3(); exportPose2(); + exportPose3(); exportNoiseModels(); exportValues(); + exportNonlinearFactor(); exportNonlinearFactorGraph(); exportLevenbergMarquardtOptimizer(); + exportISAM2(); - exportPriorFactor< Point2PriorFactor, Point2 >("Point2PriorFactor"); - exportPriorFactor< Pose2PriorFactor, Pose2 >("Pose2PriorFactor"); - exportBetweenFactor< Pose2BetweenFactor, Pose2 >("Pose2BetweenFactor"); + exportPriorFactors(); + exportBetweenFactors(); } \ No newline at end of file diff --git a/python/handwritten/geometry/Point2.cpp b/python/handwritten/geometry/Point2.cpp index 9e1a4d6b8..77abca636 100644 --- a/python/handwritten/geometry/Point2.cpp +++ b/python/handwritten/geometry/Point2.cpp @@ -1,3 +1,20 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Point2 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include #include "gtsam/geometry/Point2.h" @@ -12,15 +29,26 @@ void exportPoint2(){ class_("Point2", init<>()) .def(init()) - .def("print", &Point2::print, print_overloads(args("s"))) + .def(init()) + .def("identity", &Point2::identity) + .def("dist", &Point2::dist) + .def("distance", &Point2::distance) .def("equals", &Point2::equals, equals_overloads(args("q","tol"))) - .def("inverse", &Point2::inverse) - // .def("compose", &Point2::compose, compose_overloads(args("q", "H1", "H2"))) - .def("between", &Point2::between) - // .def("dim", &Point2::dim) - .def("retract", &Point2::retract) + .def("norm", &Point2::norm) + .def("print", &Point2::print, print_overloads(args("s"))) + .def("unit", &Point2::unit) + .def("vector", &Point2::vector) .def("x", &Point2::x) .def("y", &Point2::y) + .def(self * other()) // __mult__ + .def(other() * self) // __mult__ + .def(self + self) + .def(-self) + .def(self - self) + .def(self / other()) + .def(self_ns::str(self)) + .def(repr(self)) + .def(self == self) ; } \ No newline at end of file diff --git a/python/handwritten/geometry/Point3.cpp b/python/handwritten/geometry/Point3.cpp new file mode 100644 index 000000000..fd703f3ce --- /dev/null +++ b/python/handwritten/geometry/Point3.cpp @@ -0,0 +1,60 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Point3 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include "gtsam/geometry/Point3.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Point3::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Point3::equals, 1, 2) + +void exportPoint3(){ + +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, equals_overloads(args("q","tol"))) + .def("norm", &Point3::norm) + .def("normalize", &Point3::normalize) + .def("print", &Point3::print, print_overloads(args("s"))) + .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) +; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/Pose2.cpp b/python/handwritten/geometry/Pose2.cpp index 133a6f05f..6640d47a9 100644 --- a/python/handwritten/geometry/Pose2.cpp +++ b/python/handwritten/geometry/Pose2.cpp @@ -1,3 +1,20 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Pose2 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include #include "gtsam/geometry/Pose2.h" diff --git a/python/handwritten/geometry/Pose3.cpp b/python/handwritten/geometry/Pose3.cpp new file mode 100644 index 000000000..a7e3ae2fd --- /dev/null +++ b/python/handwritten/geometry/Pose3.cpp @@ -0,0 +1,74 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Pose3 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include "gtsam/geometry/Pose3.h" + +#include "gtsam/geometry/Pose2.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Pose3::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Pose3::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_to_overloads, Pose3::transform_to, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_from_overloads, Pose3::transform_from, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(translation_overloads, Pose3::translation, 0, 1) +// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(bearing_overloads, Pose3::bearing, 1, 3) +// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, Pose3::range, 1, 3) +// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Pose3::compose, 1, 3) +// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Pose3::between, 1, 3) + +void exportPose3(){ + + Point3 (Pose3::*transform_to1)(const Point3&, OptionalJacobian< 3, 6 >, OptionalJacobian< 3, 3 > ) const + = &Pose3::transform_to; + Pose3 (Pose3::*transform_to2)(const Pose3&) const + = &Pose3::transform_to; + + class_("Pose3") + .def(init<>()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &Pose3::print, print_overloads(args("s"))) + .def("equals", &Pose3::equals, equals_overloads(args("pose","tol"))) + .def("identity", &Pose3::identity) + .staticmethod("identity") + .def("bearing", &Pose3::bearing) + .def("matrix", &Pose3::matrix) + .def("transform_from", &Pose3::transform_from, + transform_from_overloads(args("point", "H1", "H2"))) + .def("transform_to", transform_to1, + transform_to_overloads(args("point", "H1", "H2"))) + .def("transform_to", transform_to2) + .def("x", &Pose3::x) + .def("y", &Pose3::y) + .def("z", &Pose3::z) + .def("translation", &Pose3::translation, + translation_overloads()[return_value_policy()]) + .def("rotation", &Pose3::rotation, return_value_policy()) + .def(self * self) // __mult__ + .def(self * other()) // __mult__ + .def(self_ns::str(self)) // __str__ + .def(repr(self)) // __repr__ + ; +} \ No newline at end of file diff --git a/python/handwritten/geometry/Rot2.cpp b/python/handwritten/geometry/Rot2.cpp index e79fabd9d..d7bcf8cf1 100644 --- a/python/handwritten/geometry/Rot2.cpp +++ b/python/handwritten/geometry/Rot2.cpp @@ -1,3 +1,20 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Rot2 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include #include "gtsam/geometry/Rot2.h" @@ -13,35 +30,31 @@ void exportRot2(){ class_("Rot2", init<>()) .def(init()) - - .def("fromAngle", &Rot2::fromAngle) - .staticmethod("fromAngle") - - .def("fromDegrees", &Rot2::fromDegrees) - .staticmethod("fromDegrees") - - .def("fromCosSin", &Rot2::fromCosSin) - .staticmethod("fromCosSin") - - .def("atan2", &Rot2::atan2) - .staticmethod("atan2") - - .def("print", &Rot2::print, print_overloads(args("s"))) - .def("equals", &Rot2::equals, equals_overloads(args("q","tol"))) - // .def("inverse", &Rot2::inverse) - // .def("compose", &Rot2::compose, compose_overloads(args("q", "H1", "H2"))) - // .def("between", &Rot2::between) - // .def("dim", &Rot2::dim) - // .def("retract", &Rot2::retract) - .def("Expmap", &Rot2::Expmap) .staticmethod("Expmap") - - .def("theta", &Rot2::theta) - .def("degrees", &Rot2::degrees) + .def("Logmap", &Rot2::Logmap) + .staticmethod("Logmap") + .def("atan2", &Rot2::atan2) + .staticmethod("atan2") + .def("fromAngle", &Rot2::fromAngle) + .staticmethod("fromAngle") + .def("fromCosSin", &Rot2::fromCosSin) + .staticmethod("fromCosSin") + .def("fromDegrees", &Rot2::fromDegrees) + .staticmethod("fromDegrees") + .def("identity", &Rot2::identity) + .staticmethod("identity") + .def("relativeBearing", &Rot2::relativeBearing) + .staticmethod("relativeBearing") .def("c", &Rot2::c) + .def("degrees", &Rot2::degrees) + .def("equals", &Rot2::equals, equals_overloads(args("q","tol"))) + .def("matrix", &Rot2::matrix) + .def("print", &Rot2::print, print_overloads(args("s"))) + .def("rotate", &Rot2::rotate) .def("s", &Rot2::s) - + .def("theta", &Rot2::theta) + .def("unrotate", &Rot2::unrotate) .def(self * self) // __mult__ ; diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp new file mode 100644 index 000000000..8f1728214 --- /dev/null +++ b/python/handwritten/geometry/Rot3.cpp @@ -0,0 +1,91 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Rot3 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include "gtsam/geometry/Rot3.h" + +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 +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; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Rot3::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Rot3::equals, 1, 2) + +void exportRot3(){ + + 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, equals_overloads(args("q","tol"))) + .def("localCayley", &Rot3::localCayley) + .def("matrix", &Rot3::matrix) + .def("print", &Rot3::print, print_overloads(args("s"))) + .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)) // __str__ + .def(repr(self)) // __repr__ + ; + +} \ No newline at end of file diff --git a/python/handwritten/linear/NoiseModel.cpp b/python/handwritten/linear/NoiseModel.cpp index 89ee26e9a..2b492b7e5 100644 --- a/python/handwritten/linear/NoiseModel.cpp +++ b/python/handwritten/linear/NoiseModel.cpp @@ -1,13 +1,134 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @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 + +#include "gtsam/linear/NoiseModel.h" 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) + void exportNoiseModels(){ - // Diagonal Noise Model, no constructor - class_("DiagonalNoiseModel", no_init) - .def("Sigmas", &noiseModel::Diagonal::Sigmas) - .staticmethod("Sigmas") + + // Create a scope "noiseModel". See: http://isolation-nation.blogspot.fr/2008/09/packages-in-python-extension-modules.html + std::string noiseModel_name = extract(scope().attr("__name__") + ".noiseModel"); + object noiseModel_module(handle<>(borrowed(PyImport_AddModule(noiseModel_name.c_str())))); + scope().attr("noiseModel") = noiseModel_module; + scope noiseModel_scope = noiseModel_module; + + // Then export our classes in the noiseModel scope + 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/ISAM2.cpp b/python/handwritten/nonlinear/ISAM2.cpp new file mode 100644 index 000000000..d55da3752 --- /dev/null +++ b/python/handwritten/nonlinear/ISAM2.cpp @@ -0,0 +1,44 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports ISAM2 class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include "gtsam/nonlinear/ISAM2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(update_overloads, ISAM2::update, 0, 7) + +void exportISAM2(){ + +// 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, update_overloads()) + .def("calculate_estimate", calculateEstimate_0) +; + +} \ No newline at end of file diff --git a/python/handwritten/nonlinear/NonlinearFactor.cpp b/python/handwritten/nonlinear/NonlinearFactor.cpp new file mode 100644 index 000000000..e111f65f7 --- /dev/null +++ b/python/handwritten/nonlinear/NonlinearFactor.cpp @@ -0,0 +1,45 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports virtual class NonlinearFactor to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include "gtsam/nonlinear/NonlinearFactor.h" + +using namespace boost::python; +using namespace gtsam; + +// 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); + } +}; + +void exportNonlinearFactor(){ + + class_("NonlinearFactor") + ; + +} \ No newline at end of file diff --git a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp index 16aa4c6e4..a2262f9fd 100644 --- a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp +++ b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp @@ -1,6 +1,23 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports NonlinearFactorGraph class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include #include "gtsam/nonlinear/NonlinearFactorGraph.h" -#include +#include "gtsam/nonlinear/NonlinearFactor.h" using namespace boost::python; using namespace gtsam; @@ -8,11 +25,15 @@ using namespace gtsam; void exportNonlinearFactorGraph(){ - typedef boost::shared_ptr shared_factor; + typedef NonlinearFactorGraph::sharedFactor sharedFactor; - void (NonlinearFactorGraph::*push_back1)(const shared_factor& factor) = &NonlinearFactorGraph::push_back; + void (NonlinearFactorGraph::*push_back1)(const sharedFactor&) = &NonlinearFactorGraph::push_back; + void (NonlinearFactorGraph::*add1)(const sharedFactor&) = &NonlinearFactorGraph::add; class_("NonlinearFactorGraph", init<>()) - .def("push_back", push_back1) + .def("size",&NonlinearFactorGraph::size) + .def("push_back", push_back1) + .def("add", add1) ; + } \ No newline at end of file diff --git a/python/handwritten/nonlinear/Values.cpp b/python/handwritten/nonlinear/Values.cpp index c1451cef1..7d68e88c8 100644 --- a/python/handwritten/nonlinear/Values.cpp +++ b/python/handwritten/nonlinear/Values.cpp @@ -1,19 +1,107 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Values class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include -#include +#include "gtsam/nonlinear/Values.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" +#include "gtsam/geometry/Pose3.h" using namespace boost::python; using namespace gtsam; +/** 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); +// } + void exportValues(){ - const Value& (Values::*at1)(Key) const = &Values::at; + // NOTE: Apparently the class 'Value'' is deprecated, so the commented lines below + // will compile, but are useless in the python wrapper. We need to use specific + // 'at' and 'insert' methods for each type. + // const Value& (Values::*at1)(Key) const = &Values::at; + // void (Values::*insert1)(Key, const Value&) = &Values::insert; bool (Values::*exists1)(Key) const = &Values::exists; - void (Values::*insert1)(Key, const Value&) = &Values::insert; + void (Values::*insert_point3)(Key, const gtsam::Point3&) = &Values::insert; + void (Values::*insert_rot3) (Key, const gtsam::Rot3&) = &Values::insert; + void (Values::*insert_pose3) (Key, const gtsam::Pose3&) = &Values::insert; class_("Values", init<>()) .def(init()) - .def("at", at1, return_value_policy()) + .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) + // NOTE: Following commented lines add useless methods on Values + // .def("insert", insert1) + // .def("at", at1, return_value_policy()) + .def("insert", insert_point3) + .def("insert", insert_rot3) + .def("insert", insert_pose3) + // NOTE: The following commented lines are another way of specializing the return type. + // See long comment above. + // .def("at", &ValuesAt, return_internal_reference<>()) + // .def("at", &ValuesAt, return_internal_reference<>()) + // .def("at", &ValuesAt, return_internal_reference<>()) + .def("point3_at", &Values::at, return_value_policy()) + .def("rot3_at", &Values::at, return_value_policy()) + .def("pose3_at", &Values::at, return_value_policy()) .def("exists", exists1) - .def("insert", insert1, return_value_policy()) ; } \ No newline at end of file diff --git a/python/handwritten/slam/BetweenFactor.cpp b/python/handwritten/slam/BetweenFactor.cpp index 2732e4e7e..428f54e6f 100644 --- a/python/handwritten/slam/BetweenFactor.cpp +++ b/python/handwritten/slam/BetweenFactor.cpp @@ -1,14 +1,53 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps BetweenFactor for several values to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include -#include +#include "gtsam/slam/BetweenFactor.h" +#include "gtsam/geometry/Point2.h" +#include "gtsam/geometry/Rot2.h" +#include "gtsam/geometry/Pose2.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" +#include "gtsam/geometry/Pose3.h" using namespace boost::python; using namespace gtsam; using namespace std; -template -void exportBetweenFactor(const std::string& name){ - class_(name, init<>()) - .def(init()) - ; -} \ No newline at end of file +// template +// void exportBetweenFactor(const std::string& name){ +// class_(name, init<>()) +// .def(init()) +// ; +// } + +#define BETWEENFACTOR(VALUE) \ + class_< BetweenFactor, bases, boost::shared_ptr< BetweenFactor > >("BetweenFactor"#VALUE) \ + .def(init()) \ + .def("measured", &BetweenFactor::measured, return_internal_reference<>()) \ +; + +void exportBetweenFactors() +{ + BETWEENFACTOR(Point2) + BETWEENFACTOR(Rot2) + BETWEENFACTOR(Pose2) + BETWEENFACTOR(Point3) + BETWEENFACTOR(Rot3) + BETWEENFACTOR(Pose3) +} diff --git a/python/handwritten/slam/PriorFactor.cpp b/python/handwritten/slam/PriorFactor.cpp index 1984fe144..6004c9957 100644 --- a/python/handwritten/slam/PriorFactor.cpp +++ b/python/handwritten/slam/PriorFactor.cpp @@ -1,14 +1,53 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps PriorFactor for several values to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + #include -#include +#include "gtsam/slam/PriorFactor.h" +#include "gtsam/geometry/Point2.h" +#include "gtsam/geometry/Rot2.h" +#include "gtsam/geometry/Pose2.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" +#include "gtsam/geometry/Pose3.h" using namespace boost::python; using namespace gtsam; using namespace std; -template< class FACTOR, class VALUE > -void exportPriorFactor(const std::string& name){ - class_< FACTOR >(name.c_str(), init<>()) - .def(init< Key, VALUE&, SharedNoiseModel >()) - ; +// template< class FACTOR, class VALUE > +// void exportPriorFactor(const std::string& name){ +// class_< FACTOR >(name.c_str(), init<>()) +// .def(init< Key, VALUE&, SharedNoiseModel >()) +// ; +// } + +#define PRIORFACTOR(VALUE) \ + class_< PriorFactor, bases, boost::shared_ptr< PriorFactor > >("PriorFactor"#VALUE) \ + .def(init()) \ + .def("prior", &PriorFactor::prior, return_internal_reference<>()) \ +; + +void exportPriorFactors() +{ + PRIORFACTOR(Point2) + PRIORFACTOR(Rot2) + PRIORFACTOR(Pose2) + PRIORFACTOR(Point3) + PRIORFACTOR(Rot3) + PRIORFACTOR(Pose3) } \ No newline at end of file diff --git a/python/handwritten/utils/NumpyEigen.cpp b/python/handwritten/utils/NumpyEigen.cpp new file mode 100644 index 000000000..82d3b6d5a --- /dev/null +++ b/python/handwritten/utils/NumpyEigen.cpp @@ -0,0 +1,52 @@ + /* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief register conversion matrix between numpy and Eigen + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + + #include + +#include + +#include "gtsam/base/Matrix.h" +#include "gtsam/base/Vector.h" + +using namespace boost::python; +using namespace gtsam; + +void registerNumpyEigenConversions() +{ + 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(); + +} From c140a784fe95762433a45d4ea44af36cce49b512 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Fri, 20 Nov 2015 16:05:42 +0100 Subject: [PATCH 026/105] Add constness to matrices and vectors --- python/handwritten/geometry/Point2.cpp | 2 +- python/handwritten/geometry/Point3.cpp | 2 +- python/handwritten/geometry/Pose3.cpp | 10 +++++----- python/handwritten/geometry/Rot3.cpp | 4 ++-- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/python/handwritten/geometry/Point2.cpp b/python/handwritten/geometry/Point2.cpp index 77abca636..f94d8ef1e 100644 --- a/python/handwritten/geometry/Point2.cpp +++ b/python/handwritten/geometry/Point2.cpp @@ -29,7 +29,7 @@ void exportPoint2(){ class_("Point2", init<>()) .def(init()) - .def(init()) + .def(init()) .def("identity", &Point2::identity) .def("dist", &Point2::dist) .def("distance", &Point2::distance) diff --git a/python/handwritten/geometry/Point3.cpp b/python/handwritten/geometry/Point3.cpp index fd703f3ce..99adff5f2 100644 --- a/python/handwritten/geometry/Point3.cpp +++ b/python/handwritten/geometry/Point3.cpp @@ -29,7 +29,7 @@ void exportPoint3(){ class_("Point3") .def(init<>()) .def(init()) - .def(init()) + .def(init()) .def("identity", &Point3::identity) .staticmethod("identity") .def("add", &Point3::add) diff --git a/python/handwritten/geometry/Pose3.cpp b/python/handwritten/geometry/Pose3.cpp index a7e3ae2fd..2257bab46 100644 --- a/python/handwritten/geometry/Pose3.cpp +++ b/python/handwritten/geometry/Pose3.cpp @@ -44,11 +44,11 @@ void exportPose3(){ class_("Pose3") .def(init<>()) - .def(init()) - .def(init()) - .def(init()) - .def(init()) - .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) .def("print", &Pose3::print, print_overloads(args("s"))) .def("equals", &Pose3::equals, equals_overloads(args("pose","tol"))) .def("identity", &Pose3::identity) diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp index 8f1728214..8c82e5396 100644 --- a/python/handwritten/geometry/Rot3.cpp +++ b/python/handwritten/geometry/Rot3.cpp @@ -39,8 +39,8 @@ void exportRot3(){ .def(init<>()) .def(init()) .def(init()) - .def(init()) - .def(init()) + .def(init()) + .def(init()) .def("AxisAngle", AxisAngle_0) .def("AxisAngle", AxisAngle_1) .staticmethod("AxisAngle") From 05f6237f716547d7208ddbc2dba3eec1b50b8175 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Fri, 20 Nov 2015 21:40:40 +0100 Subject: [PATCH 027/105] Define NO_IMPORT_ARRAY in all cpp files before including NumpyEigenConverter.hpp This fixes the segmentation fault when converting numpy and Eigen. The reason is that NumpyEigenConverter.hpp includes numpy/arrayobject.h, and for the numpy's C-API to work in multiple files we need to define NO_IMPORT_ARRAY before including numpy/arrayobject.h in all the source files but the one that defines the module initialization (exportgtsam.cpp in out case), as explained here: http://docs.scipy.org/doc/numpy/reference/c-api.array.html#importing-the-api Note that PY_ARRAY_UNIQUE_SYMBOL, also needed to work multifile, is already defined on NumpyEigenConverter.hpp. --- python/handwritten/exportgtsam.cpp | 4 ++++ python/handwritten/geometry/Point2.cpp | 4 ++++ python/handwritten/geometry/Point3.cpp | 4 ++++ python/handwritten/geometry/Pose2.cpp | 4 ++++ python/handwritten/geometry/Pose3.cpp | 4 ++++ python/handwritten/geometry/Rot2.cpp | 4 ++++ python/handwritten/geometry/Rot3.cpp | 4 ++++ python/handwritten/linear/NoiseModel.cpp | 3 +++ python/handwritten/nonlinear/ISAM2.cpp | 4 ++++ .../handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp | 4 ++++ python/handwritten/nonlinear/NonlinearFactor.cpp | 4 ++++ python/handwritten/nonlinear/NonlinearFactorGraph.cpp | 4 ++++ python/handwritten/nonlinear/Values.cpp | 4 ++++ python/handwritten/slam/BearingFactor.cpp | 4 ++++ python/handwritten/slam/BetweenFactor.cpp | 4 ++++ python/handwritten/slam/PriorFactor.cpp | 4 ++++ python/handwritten/utils/NumpyEigen.cpp | 6 ++++-- 17 files changed, 67 insertions(+), 2 deletions(-) diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 2424cd4da..84585adff 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -18,6 +18,8 @@ #include #include +#include + #include #include @@ -55,6 +57,8 @@ void registerNumpyEigenConversions(); BOOST_PYTHON_MODULE(libgtsam_python){ // Should be the first thing to be done + import_array(); + registerNumpyEigenConversions(); exportPoint2(); diff --git a/python/handwritten/geometry/Point2.cpp b/python/handwritten/geometry/Point2.cpp index f94d8ef1e..7af3f8cf6 100644 --- a/python/handwritten/geometry/Point2.cpp +++ b/python/handwritten/geometry/Point2.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/geometry/Point2.h" using namespace boost::python; diff --git a/python/handwritten/geometry/Point3.cpp b/python/handwritten/geometry/Point3.cpp index 99adff5f2..664b4ffda 100644 --- a/python/handwritten/geometry/Point3.cpp +++ b/python/handwritten/geometry/Point3.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/geometry/Point3.h" using namespace boost::python; diff --git a/python/handwritten/geometry/Pose2.cpp b/python/handwritten/geometry/Pose2.cpp index 6640d47a9..4f402df7e 100644 --- a/python/handwritten/geometry/Pose2.cpp +++ b/python/handwritten/geometry/Pose2.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/geometry/Pose2.h" using namespace boost::python; diff --git a/python/handwritten/geometry/Pose3.cpp b/python/handwritten/geometry/Pose3.cpp index 2257bab46..11b09608d 100644 --- a/python/handwritten/geometry/Pose3.cpp +++ b/python/handwritten/geometry/Pose3.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/geometry/Pose3.h" #include "gtsam/geometry/Pose2.h" diff --git a/python/handwritten/geometry/Rot2.cpp b/python/handwritten/geometry/Rot2.cpp index d7bcf8cf1..59b4ce4e8 100644 --- a/python/handwritten/geometry/Rot2.cpp +++ b/python/handwritten/geometry/Rot2.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/geometry/Rot2.h" using namespace boost::python; diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp index 8c82e5396..ff2b61b63 100644 --- a/python/handwritten/geometry/Rot3.cpp +++ b/python/handwritten/geometry/Rot3.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/geometry/Rot3.h" using namespace boost::python; diff --git a/python/handwritten/linear/NoiseModel.cpp b/python/handwritten/linear/NoiseModel.cpp index 2b492b7e5..3453184bd 100644 --- a/python/handwritten/linear/NoiseModel.cpp +++ b/python/handwritten/linear/NoiseModel.cpp @@ -23,6 +23,9 @@ #include +#define NO_IMPORT_ARRAY +#include + #include "gtsam/linear/NoiseModel.h" using namespace boost::python; diff --git a/python/handwritten/nonlinear/ISAM2.cpp b/python/handwritten/nonlinear/ISAM2.cpp index d55da3752..9c042a011 100644 --- a/python/handwritten/nonlinear/ISAM2.cpp +++ b/python/handwritten/nonlinear/ISAM2.cpp @@ -15,6 +15,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/nonlinear/ISAM2.h" using namespace boost::python; diff --git a/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp b/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp index b7e38359f..44b11f00b 100644 --- a/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -1,4 +1,8 @@ #include + +#define NO_IMPORT_ARRAY +#include + #include using namespace boost::python; diff --git a/python/handwritten/nonlinear/NonlinearFactor.cpp b/python/handwritten/nonlinear/NonlinearFactor.cpp index e111f65f7..9a130d8e9 100644 --- a/python/handwritten/nonlinear/NonlinearFactor.cpp +++ b/python/handwritten/nonlinear/NonlinearFactor.cpp @@ -15,6 +15,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/nonlinear/NonlinearFactor.h" using namespace boost::python; diff --git a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp index a2262f9fd..830e16898 100644 --- a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp +++ b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/nonlinear/NonlinearFactorGraph.h" #include "gtsam/nonlinear/NonlinearFactor.h" diff --git a/python/handwritten/nonlinear/Values.cpp b/python/handwritten/nonlinear/Values.cpp index 7d68e88c8..021cf019f 100644 --- a/python/handwritten/nonlinear/Values.cpp +++ b/python/handwritten/nonlinear/Values.cpp @@ -15,6 +15,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/nonlinear/Values.h" #include "gtsam/geometry/Point3.h" #include "gtsam/geometry/Rot3.h" diff --git a/python/handwritten/slam/BearingFactor.cpp b/python/handwritten/slam/BearingFactor.cpp index b13d1f281..84c67d522 100644 --- a/python/handwritten/slam/BearingFactor.cpp +++ b/python/handwritten/slam/BearingFactor.cpp @@ -1,4 +1,8 @@ #include + +#define NO_IMPORT_ARRAY +#include + #include using namespace boost::python; diff --git a/python/handwritten/slam/BetweenFactor.cpp b/python/handwritten/slam/BetweenFactor.cpp index 428f54e6f..b6fc552a0 100644 --- a/python/handwritten/slam/BetweenFactor.cpp +++ b/python/handwritten/slam/BetweenFactor.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/slam/BetweenFactor.h" #include "gtsam/geometry/Point2.h" #include "gtsam/geometry/Rot2.h" diff --git a/python/handwritten/slam/PriorFactor.cpp b/python/handwritten/slam/PriorFactor.cpp index 6004c9957..dcb9de8ea 100644 --- a/python/handwritten/slam/PriorFactor.cpp +++ b/python/handwritten/slam/PriorFactor.cpp @@ -16,6 +16,10 @@ **/ #include + +#define NO_IMPORT_ARRAY +#include + #include "gtsam/slam/PriorFactor.h" #include "gtsam/geometry/Point2.h" #include "gtsam/geometry/Rot2.h" diff --git a/python/handwritten/utils/NumpyEigen.cpp b/python/handwritten/utils/NumpyEigen.cpp index 82d3b6d5a..d7cebe7ad 100644 --- a/python/handwritten/utils/NumpyEigen.cpp +++ b/python/handwritten/utils/NumpyEigen.cpp @@ -14,8 +14,9 @@ * @author Ellon Paiva Mendes (LAAS-CNRS) **/ - #include +#include +#define NO_IMPORT_ARRAY #include #include "gtsam/base/Matrix.h" @@ -26,7 +27,8 @@ using namespace gtsam; void registerNumpyEigenConversions() { - import_array(); + // NOTE: import array should be called only in the cpp defining the module + // import_array(); NumpyEigenConverter::register_converter(); NumpyEigenConverter::register_converter(); NumpyEigenConverter::register_converter(); From ade8ab4053859e99047d513ecdd30b4d0cbdc012 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Fri, 20 Nov 2015 21:51:53 +0100 Subject: [PATCH 028/105] Remove old files which content was was already moved to other src files --- python/handwritten/geometry_python.cpp | 155 ------------------ python/handwritten/noiseModel_python.cpp | 128 --------------- python/handwritten/nonlinear_python.cpp | 139 ---------------- .../handwritten/registernumpyeigen_python.cpp | 54 ------ python/handwritten/slam_python.cpp | 86 ---------- 5 files changed, 562 deletions(-) delete mode 100644 python/handwritten/geometry_python.cpp delete mode 100644 python/handwritten/noiseModel_python.cpp delete mode 100644 python/handwritten/nonlinear_python.cpp delete mode 100644 python/handwritten/registernumpyeigen_python.cpp delete mode 100644 python/handwritten/slam_python.cpp 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 From 0e134c09dbb59a1190355f2d8a8a2ff53da2a4c8 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 12:33:33 +0100 Subject: [PATCH 029/105] Wrap PinholeCameraCal3_S2 to python --- python/handwritten/exportgtsam.cpp | 2 + python/handwritten/geometry/PinholeCamera.cpp | 49 +++++++++++++++++++ 2 files changed, 51 insertions(+) create mode 100644 python/handwritten/geometry/PinholeCamera.cpp diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 84585adff..6afc1f85e 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -34,6 +34,7 @@ void exportRot2(); void exportRot3(); void exportPose2(); void exportPose3(); +void exportPinholeCamera(); // Linear void exportNoiseModels(); @@ -67,6 +68,7 @@ BOOST_PYTHON_MODULE(libgtsam_python){ exportRot3(); exportPose2(); exportPose3(); + exportPinholeCamera(); exportNoiseModels(); diff --git a/python/handwritten/geometry/PinholeCamera.cpp b/python/handwritten/geometry/PinholeCamera.cpp new file mode 100644 index 000000000..4123b520c --- /dev/null +++ b/python/handwritten/geometry/PinholeCamera.cpp @@ -0,0 +1,49 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps PinholeCamera classes to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/PinholeCamera.h" +#include "gtsam/geometry/Cal3_S2.h" + + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, PinholeCamera::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, PinholeCamera::equals, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Lookat_overloads, PinholeCamera::Lookat, 3, 4) + +void exportPinholeCamera(){ + +class_ >("PinholeCameraCal3_S2") + .def(init<>()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &PinholeCamera::print, print_overloads(args("s"))) + .def("equals", &PinholeCamera::equals, equals_overloads(args("q","tol"))) + .def("pose", &PinholeCamera::pose, return_value_policy()) + .def("calibration", &PinholeCamera::calibration, return_value_policy()) + .def("Lookat", &PinholeCamera::Lookat, Lookat_overloads()) + .staticmethod("Lookat") +; + +} \ No newline at end of file From 982d81e1c974ef784b84d278b394b84e12e25982 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 12:34:15 +0100 Subject: [PATCH 030/105] Add python version of SFMdata as gtsam.examples submodule The gtsam.examples submodule should be loaded explicitely: >>> import gtsam.examples --- python/gtsam/examples/SFMdata.py | 32 +++++++++++++++++++++++++++++++ python/gtsam/examples/__init__.py | 1 + 2 files changed, 33 insertions(+) create mode 100644 python/gtsam/examples/SFMdata.py create mode 100644 python/gtsam/examples/__init__.py diff --git a/python/gtsam/examples/SFMdata.py b/python/gtsam/examples/SFMdata.py new file mode 100644 index 000000000..21a438226 --- /dev/null +++ b/python/gtsam/examples/SFMdata.py @@ -0,0 +1,32 @@ + + # A structure-from-motion example with landmarks + # - The landmarks form a 10 meter cube + # - The robot rotates around the landmarks, always facing towards the cube + +import gtsam +import numpy as np + +def createPoints(): + # Create the set of ground-truth landmarks + points = [gtsam.Point3(10.0,10.0,10.0), + gtsam.Point3(-10.0,10.0,10.0), + gtsam.Point3(-10.0,-10.0,10.0), + gtsam.Point3(10.0,-10.0,10.0), + gtsam.Point3(10.0,10.0,-10.0), + gtsam.Point3(-10.0,10.0,-10.0), + gtsam.Point3(-10.0,-10.0,-10.0), + gtsam.Point3(10.0,-10.0,-10.0)] + return points + +def createPoses(): + # Create the set of ground-truth poses + radius = 30.0 + angles = np.linspace(0,2*np.pi,8,endpoint=False) + up = gtsam.Point3(0,0,1) + target = gtsam.Point3(0,0,0) + poses = [] + for theta in angles: + position = gtsam.Point3(radius*np.cos(theta), radius*np.sin(theta), 0.0) + camera = gtsam.PinholeCameraCal3_S2.Lookat(position, target, up) + poses.append(camera.pose()) + return poses diff --git a/python/gtsam/examples/__init__.py b/python/gtsam/examples/__init__.py new file mode 100644 index 000000000..41889bb40 --- /dev/null +++ b/python/gtsam/examples/__init__.py @@ -0,0 +1 @@ +from SFMdata import * From 818db173929f04a047121a394eab1f513378d5de Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 15:41:17 +0100 Subject: [PATCH 031/105] Wrap symbol to python --- python/handwritten/exportgtsam.cpp | 5 ++ python/handwritten/inference/Symbol.cpp | 66 +++++++++++++++++++++++++ 2 files changed, 71 insertions(+) create mode 100644 python/handwritten/inference/Symbol.cpp diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 6afc1f85e..a0ba634e2 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -36,6 +36,9 @@ void exportPose2(); void exportPose3(); void exportPinholeCamera(); +// Inference +void exportSymbol(); + // Linear void exportNoiseModels(); @@ -70,6 +73,8 @@ BOOST_PYTHON_MODULE(libgtsam_python){ exportPose3(); exportPinholeCamera(); + exportSymbol(); + exportNoiseModels(); exportValues(); diff --git a/python/handwritten/inference/Symbol.cpp b/python/handwritten/inference/Symbol.cpp new file mode 100644 index 000000000..ace26c67d --- /dev/null +++ b/python/handwritten/inference/Symbol.cpp @@ -0,0 +1,66 @@ + /* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Symbol class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/inference/Symbol.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Symbol::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Symbol::equals, 1, 2) + +// Helper function to allow building a symbol from a python string and a index. +static boost::shared_ptr makeSymbol(const std::string &str, size_t j) +{ + if(str.size() > 1) + throw std::runtime_error("string argument must have one character only"); + + return boost::make_shared(str.at(0),j); +} + +// Helper function to print the symbol as "char-and-index" in python +std::string selfToString(const Symbol & self) +{ + return (std::string)self; +} + +void exportSymbol(){ + +class_ >("Symbol") + .def(init<>()) + .def(init()) + .def("__init__", make_constructor(makeSymbol)) + .def(init()) + .def("print", &Symbol::print, print_overloads(args("s"))) + .def("equals", &Symbol::equals, equals_overloads(args("q","tol"))) + .def("key", &Symbol::key) + .def("chr", &Symbol::chr) + .def("index", &Symbol::index) + .def(self < self) + .def(self == self) + .def(self == other()) + .def(self != self) + .def(self != other()) + .def("__repr__", &selfToString) +; + +} \ No newline at end of file From 6196f953010b348d3ede15d76f8317075144adc7 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 16:07:07 +0100 Subject: [PATCH 032/105] Wrap Cal3_S2 to python --- python/handwritten/exportgtsam.cpp | 2 + python/handwritten/geometry/Cal3_S2.cpp | 62 +++++++++++++++++++++++++ 2 files changed, 64 insertions(+) create mode 100644 python/handwritten/geometry/Cal3_S2.cpp diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index a0ba634e2..6e85ea504 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -35,6 +35,7 @@ void exportRot3(); void exportPose2(); void exportPose3(); void exportPinholeCamera(); +void exportCal3_S2(); // Inference void exportSymbol(); @@ -72,6 +73,7 @@ BOOST_PYTHON_MODULE(libgtsam_python){ exportPose2(); exportPose3(); exportPinholeCamera(); + exportCal3_S2(); exportSymbol(); diff --git a/python/handwritten/geometry/Cal3_S2.cpp b/python/handwritten/geometry/Cal3_S2.cpp new file mode 100644 index 000000000..339cd6a3c --- /dev/null +++ b/python/handwritten/geometry/Cal3_S2.cpp @@ -0,0 +1,62 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Cal3_S2 class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Cal3_S2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Cal3_S2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Cal3_S2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(uncalibrate_overloads, Cal3_S2::uncalibrate, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(calibrate_overloads, Cal3_S2::calibrate, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Cal3_S2::between, 1, 3) + +// Function pointers to desambiguate Cal3_S2::calibrate calls +Point2 (Cal3_S2::*calibrate1)(const Point2 &, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp) const = &Cal3_S2::calibrate; +Vector3 (Cal3_S2::*calibrate2)(const Vector3 &) const = &Cal3_S2::calibrate; + +void exportCal3_S2(){ + +class_("Cal3_S2", init<>()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &Cal3_S2::print, print_overloads(args("s"))) + .def("equals", &Cal3_S2::equals, equals_overloads(args("q","tol"))) + .def("fx",&Cal3_S2::fx) + .def("fy",&Cal3_S2::fy) + .def("skew",&Cal3_S2::skew) + .def("px",&Cal3_S2::px) + .def("py",&Cal3_S2::py) + .def("principal_point",&Cal3_S2::principalPoint) + .def("vector",&Cal3_S2::vector) + .def("k",&Cal3_S2::K) + .def("matrix",&Cal3_S2::matrix) + .def("matrix_inverse",&Cal3_S2::matrix_inverse) + .def("uncalibrate",&Cal3_S2::uncalibrate, uncalibrate_overloads()) + .def("calibrate",calibrate1, calibrate_overloads()) + .def("calibrate",calibrate2) + .def("between",&Cal3_S2::between, between_overloads()) +; + +} \ No newline at end of file From c8782786873e7158011d1740ea92b86179403cf0 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 19:06:24 +0100 Subject: [PATCH 033/105] Wrap GenericProjectionFactor to python --- python/handwritten/exportgtsam.cpp | 2 + .../slam/GenericProjectionFactor.cpp | 54 +++++++++++++++++++ 2 files changed, 56 insertions(+) create mode 100644 python/handwritten/slam/GenericProjectionFactor.cpp diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 6e85ea504..4b7abdecd 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -53,6 +53,7 @@ void exportISAM2(); // Slam void exportPriorFactors(); void exportBetweenFactors(); +void exportGenericProjectionFactor(); // Utils (or Python wrapper specific functions) void registerNumpyEigenConversions(); @@ -87,4 +88,5 @@ BOOST_PYTHON_MODULE(libgtsam_python){ exportPriorFactors(); exportBetweenFactors(); + exportGenericProjectionFactor(); } \ No newline at end of file diff --git a/python/handwritten/slam/GenericProjectionFactor.cpp b/python/handwritten/slam/GenericProjectionFactor.cpp new file mode 100644 index 000000000..dd932ccd4 --- /dev/null +++ b/python/handwritten/slam/GenericProjectionFactor.cpp @@ -0,0 +1,54 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps GenericProjectionFactor for several values to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/slam/ProjectionFactor.h" +#include "gtsam/geometry/Pose3.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Cal3_S2.h" + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +typedef GenericProjectionFactor GenericProjectionFactorCal3_S2; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, GenericProjectionFactorCal3_S2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, GenericProjectionFactorCal3_S2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(evaluateError_overloads, GenericProjectionFactorCal3_S2::evaluateError, 2, 4) + +void exportGenericProjectionFactor() +{ + + class_ >("GenericProjectionFactorCal3_S2", init<>()) + .def(init &, optional >()) + .def(init &, bool, bool, optional >()) + .def("print", &GenericProjectionFactorCal3_S2::print, print_overloads(args("s"))) + .def("equals", &GenericProjectionFactorCal3_S2::equals, equals_overloads(args("q","tol"))) + .def("evaluate_error", &GenericProjectionFactorCal3_S2::evaluateError, evaluateError_overloads()) + .def("measured", &GenericProjectionFactorCal3_S2::measured, return_value_policy()) + // TODO(Ellon): Find the right return policy when returning a 'const shared_ptr<...> &' + // .def("calibration", &GenericProjectionFactorCal3_S2::calibration, return_value_policy()) + .def("verbose_cheirality", &GenericProjectionFactorCal3_S2::verboseCheirality) + .def("throw_cheirality", &GenericProjectionFactorCal3_S2::throwCheirality) + ; + +} From 49d02c798f1a3d507b41776a74d55b30c980c312 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 20:36:01 +0100 Subject: [PATCH 034/105] Wrap PinholeBaseK to python and declare it as parent of PinholeCamera --- python/handwritten/exportgtsam.cpp | 2 + python/handwritten/geometry/PinholeBaseK.cpp | 66 +++++++++++++++++++ python/handwritten/geometry/PinholeCamera.cpp | 24 +++---- 3 files changed, 81 insertions(+), 11 deletions(-) create mode 100644 python/handwritten/geometry/PinholeBaseK.cpp diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 4b7abdecd..0f4ee48b5 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -34,6 +34,7 @@ void exportRot2(); void exportRot3(); void exportPose2(); void exportPose3(); +void exportPinholeBaseK(); void exportPinholeCamera(); void exportCal3_S2(); @@ -73,6 +74,7 @@ BOOST_PYTHON_MODULE(libgtsam_python){ exportRot3(); exportPose2(); exportPose3(); + exportPinholeBaseK(); exportPinholeCamera(); exportCal3_S2(); diff --git a/python/handwritten/geometry/PinholeBaseK.cpp b/python/handwritten/geometry/PinholeBaseK.cpp new file mode 100644 index 000000000..da98783e2 --- /dev/null +++ b/python/handwritten/geometry/PinholeBaseK.cpp @@ -0,0 +1,66 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps PinholeCamera classes to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/PinholeCamera.h" +#include "gtsam/geometry/Cal3_S2.h" + + +using namespace boost::python; +using namespace gtsam; + +typedef PinholeBaseK PinholeBaseKCal3_S2; + +// Wrapper on PinholeBaseK because it has pure virtual method calibration() +struct PinholeBaseKCal3_S2Callback : PinholeBaseKCal3_S2, wrapper +{ + const Cal3_S2 & calibration () const { + return this->get_override("calibration")(); + } +}; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(project_overloads, PinholeBaseKCal3_S2::project, 2, 4) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, PinholeBaseKCal3_S2::range, 1, 3) + +// Function pointers to desambiguate project() calls +Point2 (PinholeBaseKCal3_S2::*project1) (const Point3 &pw) const = &PinholeBaseKCal3_S2::project; +Point2 (PinholeBaseKCal3_S2::*project2) (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; +Point2 (PinholeBaseKCal3_S2::*project3) (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 2 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; + +// function pointers to desambiguate range() calls +double (PinholeBaseKCal3_S2::*range1) (const Point3 &point, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 3 > Dpoint) const = &PinholeBaseKCal3_S2::range; +double (PinholeBaseKCal3_S2::*range2) (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 6 > Dpose) const = &PinholeBaseKCal3_S2::range; +double (PinholeBaseKCal3_S2::*range3) (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 6 > Dother) const = &PinholeBaseKCal3_S2::range; + +void exportPinholeBaseK(){ + + class_("PinholeBaseKCal3_S2", no_init) + .def("calibration", pure_virtual(&PinholeBaseKCal3_S2::calibration), return_value_policy()) + .def("project", project1) + .def("project", project2, project_overloads()) + .def("project", project3, project_overloads()) + .def("backproject", &PinholeBaseKCal3_S2::backproject) + .def("backproject_point_at_infinity", &PinholeBaseKCal3_S2::backprojectPointAtInfinity) + .def("range", range1, range_overloads()) + .def("range", range2, range_overloads()) + .def("range", range3, range_overloads()) + ; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/PinholeCamera.cpp b/python/handwritten/geometry/PinholeCamera.cpp index 4123b520c..21ffcdeb7 100644 --- a/python/handwritten/geometry/PinholeCamera.cpp +++ b/python/handwritten/geometry/PinholeCamera.cpp @@ -22,27 +22,29 @@ #include "gtsam/geometry/PinholeCamera.h" #include "gtsam/geometry/Cal3_S2.h" - using namespace boost::python; using namespace gtsam; -BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, PinholeCamera::print, 0, 1) -BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, PinholeCamera::equals, 1, 2) -BOOST_PYTHON_FUNCTION_OVERLOADS(Lookat_overloads, PinholeCamera::Lookat, 3, 4) +typedef PinholeBaseK PinholeBaseKCal3_S2; +typedef PinholeCamera PinholeCameraCal3_S2; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, PinholeCameraCal3_S2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, PinholeCameraCal3_S2::equals, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Lookat_overloads, PinholeCameraCal3_S2::Lookat, 3, 4) void exportPinholeCamera(){ -class_ >("PinholeCameraCal3_S2") - .def(init<>()) +class_ >("PinholeCameraCal3_S2", init<>()) .def(init()) .def(init()) .def(init()) .def(init()) - .def("print", &PinholeCamera::print, print_overloads(args("s"))) - .def("equals", &PinholeCamera::equals, equals_overloads(args("q","tol"))) - .def("pose", &PinholeCamera::pose, return_value_policy()) - .def("calibration", &PinholeCamera::calibration, return_value_policy()) - .def("Lookat", &PinholeCamera::Lookat, Lookat_overloads()) + .def("print", &PinholeCameraCal3_S2::print, print_overloads(args("s"))) + .def("equals", &PinholeCameraCal3_S2::equals, equals_overloads(args("q","tol"))) + .def("pose", &PinholeCameraCal3_S2::pose, return_value_policy()) + // We don't need to define calibration() here because it's already defined as virtual in the base class PinholeBaseKCal3_S2 + // .def("calibration", &PinholeCameraCal3_S2::calibration, return_value_policy()) + .def("Lookat", &PinholeCameraCal3_S2::Lookat, Lookat_overloads()) .staticmethod("Lookat") ; From 8ae3dda6a6c89758f90ae957aa9280554c174f32 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 20:56:51 +0100 Subject: [PATCH 035/105] Add helper functions to better handle gtsam.Symbol on python --- python/handwritten/inference/Symbol.cpp | 19 ++++++++++++++++++- 1 file changed, 18 insertions(+), 1 deletion(-) diff --git a/python/handwritten/inference/Symbol.cpp b/python/handwritten/inference/Symbol.cpp index ace26c67d..9fc5b74e7 100644 --- a/python/handwritten/inference/Symbol.cpp +++ b/python/handwritten/inference/Symbol.cpp @@ -20,6 +20,8 @@ #define NO_IMPORT_ARRAY #include +#include // for stringstream + #include "gtsam/inference/Symbol.h" using namespace boost::python; @@ -43,6 +45,20 @@ std::string selfToString(const Symbol & self) return (std::string)self; } +// Helper function to convert a Symbol to int using int() cast in python +size_t selfToKey(const Symbol & self) +{ + return self.key(); +} + +// Helper function to recover symbol's unsigned char as string +std::string chrFromSelf(const Symbol & self) +{ + std::stringstream ss; + ss << self.chr(); + return ss.str(); +} + void exportSymbol(){ class_ >("Symbol") @@ -53,7 +69,6 @@ class_ >("Symbol") .def("print", &Symbol::print, print_overloads(args("s"))) .def("equals", &Symbol::equals, equals_overloads(args("q","tol"))) .def("key", &Symbol::key) - .def("chr", &Symbol::chr) .def("index", &Symbol::index) .def(self < self) .def(self == self) @@ -61,6 +76,8 @@ class_ >("Symbol") .def(self != self) .def(self != other()) .def("__repr__", &selfToString) + .def("__int__", &selfToKey) + .def("chr", &chrFromSelf) ; } \ No newline at end of file From 7576dc359d4579a1ee7d1b8633246e46b91be22b Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 22:42:19 +0100 Subject: [PATCH 036/105] Wrap more methods of Pose3 to python --- python/handwritten/geometry/Pose3.cpp | 34 +++++++++++++++++++-------- 1 file changed, 24 insertions(+), 10 deletions(-) diff --git a/python/handwritten/geometry/Pose3.cpp b/python/handwritten/geometry/Pose3.cpp index 11b09608d..dfdfe8ad1 100644 --- a/python/handwritten/geometry/Pose3.cpp +++ b/python/handwritten/geometry/Pose3.cpp @@ -21,7 +21,6 @@ #include #include "gtsam/geometry/Pose3.h" - #include "gtsam/geometry/Pose2.h" #include "gtsam/geometry/Point3.h" #include "gtsam/geometry/Rot3.h" @@ -34,18 +33,26 @@ BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Pose3::equals, 1, 2) BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_to_overloads, Pose3::transform_to, 1, 3) BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_from_overloads, Pose3::transform_from, 1, 3) BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(translation_overloads, Pose3::translation, 0, 1) -// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(bearing_overloads, Pose3::bearing, 1, 3) -// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, Pose3::range, 1, 3) -// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Pose3::compose, 1, 3) -// BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Pose3::between, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Pose3::compose, 2, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Pose3::between, 2, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(bearing_overloads, Pose3::bearing, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, Pose3::range, 1, 3) void exportPose3(){ - Point3 (Pose3::*transform_to1)(const Point3&, OptionalJacobian< 3, 6 >, OptionalJacobian< 3, 3 > ) const - = &Pose3::transform_to; - Pose3 (Pose3::*transform_to2)(const Pose3&) const - = &Pose3::transform_to; - + // function pointers to desambiguate transform_to() calls + Point3 (Pose3::*transform_to1)(const Point3&, OptionalJacobian< 3, 6 >, OptionalJacobian< 3, 3 > ) const = &Pose3::transform_to; + Pose3 (Pose3::*transform_to2)(const Pose3&) const = &Pose3::transform_to; + // function pointers to desambiguate compose() calls + Pose3 (Pose3::*compose1)(const Pose3 &g) const = &Pose3::compose; + Pose3 (Pose3::*compose2)(const Pose3 &g, typename Pose3::ChartJacobian, typename Pose3::ChartJacobian) const = &Pose3::compose; + // function pointers to desambiguate between() calls + Pose3 (Pose3::*between1)(const Pose3 &g) const = &Pose3::between; + Pose3 (Pose3::*between2)(const Pose3 &g, typename Pose3::ChartJacobian, typename Pose3::ChartJacobian) const = &Pose3::between; + // function pointers to desambiguate range() calls + double (Pose3::*range1)(const Point3 &, OptionalJacobian<1,6>, OptionalJacobian<1,3>) const = &Pose3::range; + double (Pose3::*range2)(const Pose3 &, OptionalJacobian<1,6>, OptionalJacobian<1,6>) const = &Pose3::range; + class_("Pose3") .def(init<>()) .def(init()) @@ -74,5 +81,12 @@ void exportPose3(){ .def(self * other()) // __mult__ .def(self_ns::str(self)) // __str__ .def(repr(self)) // __repr__ + .def("compose", compose1) + .def("compose", compose2, compose_overloads()) + .def("between", between1) + .def("between", between2, between_overloads()) + .def("range", range1, range_overloads()) + .def("range", range2, range_overloads()) + .def("bearing", &Pose3::bearing, bearing_overloads()) ; } \ No newline at end of file From bc73a5132ab0545ebc2d38ba227df09b7106ded6 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 23:22:18 +0100 Subject: [PATCH 037/105] Wrap few more missing methods on ISAM2 and NonlinearFactorGraph --- python/handwritten/nonlinear/ISAM2.cpp | 1 + python/handwritten/nonlinear/NonlinearFactorGraph.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/python/handwritten/nonlinear/ISAM2.cpp b/python/handwritten/nonlinear/ISAM2.cpp index 9c042a011..31ff20400 100644 --- a/python/handwritten/nonlinear/ISAM2.cpp +++ b/python/handwritten/nonlinear/ISAM2.cpp @@ -40,6 +40,7 @@ class_("ISAM2Result") Values (ISAM2::*calculateEstimate_0)() const = &ISAM2::calculateEstimate; class_("ISAM2") + .def(init()) // TODO(Ellon): wrap all optional values of update .def("update",&ISAM2::update, update_overloads()) .def("calculate_estimate", calculateEstimate_0) diff --git a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp index 830e16898..4200a150e 100644 --- a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp +++ b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp @@ -38,6 +38,8 @@ void exportNonlinearFactorGraph(){ .def("size",&NonlinearFactorGraph::size) .def("push_back", push_back1) .def("add", add1) + .def("resize", &NonlinearFactorGraph::resize) + .def("empty", &NonlinearFactorGraph::empty) ; } \ No newline at end of file From cba608555791e714a0fd2759c78b0c84f7298578 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 23 Nov 2015 23:31:12 +0100 Subject: [PATCH 038/105] Add VisualISAM2Example. Still need to finish some details of the example --- python/gtsam/examples/VisualISAM2Example.py | 77 +++++++++++++++++++++ python/gtsam/examples/__init__.py | 1 + 2 files changed, 78 insertions(+) create mode 100644 python/gtsam/examples/VisualISAM2Example.py diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py new file mode 100644 index 000000000..221f22b41 --- /dev/null +++ b/python/gtsam/examples/VisualISAM2Example.py @@ -0,0 +1,77 @@ +import gtsam +from gtsam.examples.SFMdata import * + +def visual_ISAM2_example(): + # Define the camera calibration parameters + K = gtsam.Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = createPoints() # from SFMdata + + # Create the set of ground-truth poses + poses = createPoses() # from SFMdata + + # Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps to maintain proper linearization + # and efficient variable ordering, iSAM2 performs partial relinearization/reordering at each step. A parameter + # structure is available that allows the user to set various properties, such as the relinearization threshold + # and type of linear solver. For this example, we we set the relinearization threshold small so the iSAM2 result + # will approach the batch result. + parameters = gtsam.ISAM2Params() + # parameters.relinearizeThreshold = 0.01; # TODO + # parameters.relinearizeSkip = 1; # TODO + isam = gtsam.ISAM2(parameters) + + # Create a Factor Graph and Values to hold the new data + graph = gtsam.NonlinearFactorGraph() + initialEstimate = gtsam.Values() + + # Loop over the different poses, adding the observations to iSAM incrementally + for i, pose in enumerate(poses): + + # Add factors for each landmark observation + for j, point in enumerate(points): + camera = gtsam.PinholeCameraCal3_S2(pose, K) + measurement = camera.project(point) + graph.push_back(gtsam.GenericProjectionFactorCal3_S2(measurement, measurementNoise, int(gtsam.Symbol('x', i)), int(gtsam.Symbol('l', j)), K)) + + # Add an initial guess for the current pose + # Intentionally initialize the variables off from the ground truth + initialEstimate.insert(int(gtsam.Symbol('x', i)), pose.compose(gtsam.Pose3(gtsam.Rot3.Rodrigues(-0.1, 0.2, 0.25), gtsam.Point3(0.05, -0.10, 0.20)))) + + # If this is the first iteration, add a prior on the first pose to set the coordinate frame + # and a prior on the first landmark to set the scale + # Also, as iSAM solves incrementally, we must wait until each is observed at least twice before + # adding it to iSAM. + if( i == 0): + # Add a prior on pose x0 + poseNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.push_back(gtsam.PriorFactorPose3(int(gtsam.Symbol('x', 0)), poses[0], poseNoise)) + + # Add a prior on landmark l0 + pointNoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + graph.push_back(gtsam.PriorFactorPoint3(int(gtsam.Symbol('l', 0)), points[0], pointNoise)) # add directly to graph + + # Add initial guesses to all observed landmarks + # Intentionally initialize the variables off from the ground truth + for j, point in enumerate(points): + initialEstimate.insert(int(gtsam.Symbol('l', j)), point + gtsam.Point3(-0.25, 0.20, 0.15)); + else: + # Update iSAM with the new factors + isam.update(graph, initialEstimate) + # Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. + # If accuracy is desired at the expense of time, update(*) can be called additional times + # to perform multiple optimizer iterations every step. + isam.update() + currentEstimate = isam.calculate_estimate(); + # print "****************************************************" + # print "Frame", i, ":" + # currentEstimate.print("Current estimate: "); # TODO: Print to screen or plot using matplotlib + + # Clear the factor graph and values for the next iteration + graph.resize(0); + initialEstimate.clear(); + +# TODO: Add a __main__ section here \ No newline at end of file diff --git a/python/gtsam/examples/__init__.py b/python/gtsam/examples/__init__.py index 41889bb40..ab7c3bd81 100644 --- a/python/gtsam/examples/__init__.py +++ b/python/gtsam/examples/__init__.py @@ -1 +1,2 @@ from SFMdata import * +from VisualISAM2Example import * From 92bfcaa00488d36cd0d319b1a52e0b71f603919d Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 24 Nov 2015 11:30:35 +0100 Subject: [PATCH 039/105] Wrap some properties of ISAM2Params to python --- python/handwritten/nonlinear/ISAM2.cpp | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/python/handwritten/nonlinear/ISAM2.cpp b/python/handwritten/nonlinear/ISAM2.cpp index 31ff20400..7155c679d 100644 --- a/python/handwritten/nonlinear/ISAM2.cpp +++ b/python/handwritten/nonlinear/ISAM2.cpp @@ -30,6 +30,21 @@ void exportISAM2(){ // TODO(Ellon): Export all properties of ISAM2Params class_("ISAM2Params") + .add_property("relinearize_skip", &ISAM2Params::getRelinearizeSkip, &ISAM2Params::setRelinearizeSkip) + .add_property("enable_relinearization", &ISAM2Params::isEnableRelinearization, &ISAM2Params::setEnableRelinearization) + .add_property("evaluate_non_linear_error", &ISAM2Params::isEvaluateNonlinearError, &ISAM2Params::setEvaluateNonlinearError) + .add_property("factorization", &ISAM2Params::getFactorization, &ISAM2Params::setFactorization) + .add_property("cache_linearized_factors", &ISAM2Params::isCacheLinearizedFactors, &ISAM2Params::setCacheLinearizedFactors) + .add_property("enable_detailed_results", &ISAM2Params::isEnableDetailedResults, &ISAM2Params::setEnableDetailedResults) + .add_property("enable_partial_linearization_check", &ISAM2Params::isEnablePartialRelinearizationCheck, &ISAM2Params::setEnablePartialRelinearizationCheck) + // TODO(Ellon): Check if it works with FastMap; Implement properly if it doesn't. + .add_property("relinearization_threshold", &ISAM2Params::getRelinearizeThreshold, &ISAM2Params::setRelinearizeThreshold) + // TODO(Ellon): Wrap the following setters/getters: + // void setOptimizationParams (OptimizationParams optimizationParams) + // OptimizationParams getOptimizationParams () const + // void setKeyFormatter (KeyFormatter keyFormatter) + // KeyFormatter getKeyFormatter () const + // GaussianFactorGraph::Eliminate getEliminationFunction () const ; // TODO(Ellon): Export useful methods/properties of ISAM2Result From a6b48194fdd8eb3f7107f0f7390369438bf53574 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 24 Nov 2015 11:31:40 +0100 Subject: [PATCH 040/105] Print result of example to console --- python/gtsam/examples/VisualISAM2Example.py | 41 +++++++++++++-------- 1 file changed, 25 insertions(+), 16 deletions(-) diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py index 221f22b41..abc0bbde9 100644 --- a/python/gtsam/examples/VisualISAM2Example.py +++ b/python/gtsam/examples/VisualISAM2Example.py @@ -20,8 +20,8 @@ def visual_ISAM2_example(): # and type of linear solver. For this example, we we set the relinearization threshold small so the iSAM2 result # will approach the batch result. parameters = gtsam.ISAM2Params() - # parameters.relinearizeThreshold = 0.01; # TODO - # parameters.relinearizeSkip = 1; # TODO + parameters.relinearize_threshold = 0.01 + parameters.relinearize_skip = 1 isam = gtsam.ISAM2(parameters) # Create a Factor Graph and Values to hold the new data @@ -59,19 +59,28 @@ def visual_ISAM2_example(): for j, point in enumerate(points): initialEstimate.insert(int(gtsam.Symbol('l', j)), point + gtsam.Point3(-0.25, 0.20, 0.15)); else: - # Update iSAM with the new factors - isam.update(graph, initialEstimate) - # Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. - # If accuracy is desired at the expense of time, update(*) can be called additional times - # to perform multiple optimizer iterations every step. - isam.update() - currentEstimate = isam.calculate_estimate(); - # print "****************************************************" - # print "Frame", i, ":" - # currentEstimate.print("Current estimate: "); # TODO: Print to screen or plot using matplotlib + # Update iSAM with the new factors + isam.update(graph, initialEstimate) + # Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. + # If accuracy is desired at the expense of time, update(*) can be called additional times + # to perform multiple optimizer iterations every step. + isam.update() + currentEstimate = isam.calculate_estimate(); + print "****************************************************" + print "Frame", i, ":" + for j in range(i+1): + print gtsam.Symbol('x',j) + print currentEstimate.pose3_at(int(gtsam.Symbol('x',j))) - # Clear the factor graph and values for the next iteration - graph.resize(0); - initialEstimate.clear(); + for j in range(len(points)): + print gtsam.Symbol('l',j) + print currentEstimate.point3_at(int(gtsam.Symbol('l',j))) -# TODO: Add a __main__ section here \ No newline at end of file + # TODO: Print to screen or plot using matplotlib + + # Clear the factor graph and values for the next iteration + graph.resize(0); + initialEstimate.clear(); + +if __name__ == '__main__': + visual_ISAM2_example() From 46a197073162523848485981496f763abe981211 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 24 Nov 2015 13:28:01 +0100 Subject: [PATCH 041/105] Wrap KeyVector to python While here, do small cleanup on exportgtsam.cpp --- python/handwritten/base/FastVector.cpp | 37 +++++++++++++++++++++++++ python/handwritten/exportgtsam.cpp | 10 +++---- python/handwritten/nonlinear/Values.cpp | 1 + 3 files changed, 42 insertions(+), 6 deletions(-) create mode 100644 python/handwritten/base/FastVector.cpp diff --git a/python/handwritten/base/FastVector.cpp b/python/handwritten/base/FastVector.cpp new file mode 100644 index 000000000..1c3582813 --- /dev/null +++ b/python/handwritten/base/FastVector.cpp @@ -0,0 +1,37 @@ + /* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps FastVector instances to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/base/FastVector.h" +#include "gtsam/base/types.h" // for Key definition + +using namespace boost::python; +using namespace gtsam; + +void exportFastVectors(){ + + typedef FastVector KeyVector; + + class_("KeyVector") + .def(vector_indexing_suite()) + ; + +} \ No newline at end of file diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 0f4ee48b5..2802a779c 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -20,12 +20,8 @@ #include -#include -#include - -using namespace boost::python; -using namespace gtsam; -using namespace std; +// Base +void exportFastVectors(); // Geometry void exportPoint2(); @@ -68,6 +64,8 @@ BOOST_PYTHON_MODULE(libgtsam_python){ registerNumpyEigenConversions(); + exportFastVectors(); + exportPoint2(); exportPoint3(); exportRot2(); diff --git a/python/handwritten/nonlinear/Values.cpp b/python/handwritten/nonlinear/Values.cpp index 021cf019f..0302abbe2 100644 --- a/python/handwritten/nonlinear/Values.cpp +++ b/python/handwritten/nonlinear/Values.cpp @@ -107,5 +107,6 @@ void exportValues(){ .def("rot3_at", &Values::at, return_value_policy()) .def("pose3_at", &Values::at, return_value_policy()) .def("exists", exists1) + .def("keys", &Values::keys) ; } \ No newline at end of file From 4f37929d8001bb1c08ee36a3ae5bb365349c682f Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 24 Nov 2015 17:54:05 +0100 Subject: [PATCH 042/105] Add ploting to VisualISAM2Example.py --- python/gtsam/examples/VisualISAM2Example.py | 98 ++++++++++++++++++++- 1 file changed, 97 insertions(+), 1 deletion(-) diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py index abc0bbde9..bd797d271 100644 --- a/python/gtsam/examples/VisualISAM2Example.py +++ b/python/gtsam/examples/VisualISAM2Example.py @@ -1,5 +1,100 @@ import gtsam from gtsam.examples.SFMdata import * +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D +import time # for sleep() + +def plotPoint3(fignum, point, linespec): + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + ax.plot([point.x()],[point.y()],[point.z()], linespec) + + +def plot3DPoints(fignum, values, linespec, marginals=None): + # PLOT3DPOINTS Plots the Point3's in a values, with optional covariances + # Finds all the Point3 objects in the given Values object and plots them. + # If a Marginals object is given, this function will also plot marginal + # covariance ellipses for each point. + + keys = values.keys() + + # Plot points and covariance matrices + for key in keys: + try: + p = values.point3_at(key); + # if haveMarginals + # P = marginals.marginalCovariance(key); + # gtsam.plotPoint3(p, linespec, P); + # else + plotPoint3(fignum, p, linespec); + except RuntimeError: + continue + #I guess it's not a Point3 + + +def plotPose3(fignum, pose, axisLength=0.1): + # get figure object + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + + # get rotation and translation (center) + gRp = pose.rotation().matrix() # rotation from pose to global + C = pose.translation().vector() + + # draw the camera axes + xAxis = C+gRp[:,0]*axisLength + L = np.append(C[np.newaxis], xAxis[np.newaxis], axis=0) + ax.plot(L[:,0],L[:,1],L[:,2],'r-') + + yAxis = C+gRp[:,1]*axisLength + L = np.append(C[np.newaxis], yAxis[np.newaxis], axis=0) + ax.plot(L[:,0],L[:,1],L[:,2],'g-') + + zAxis = C+gRp[:,2]*axisLength + L = np.append(C[np.newaxis], zAxis[np.newaxis], axis=0) + ax.plot(L[:,0],L[:,1],L[:,2],'b-') + + # # plot the covariance + # if (nargin>2) && (~isempty(P)) + # pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame + # gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame + # gtsam.covarianceEllipse3D(C,gPp); + # end + + +def visual_ISAM2_plot(poses, points, result): + # VisualISAMPlot plots current state of ISAM2 object + # Author: Ellon Paiva + # Based on MATLAB version by: Duy Nguyen Ta and Frank Dellaert + + # Declare an id for the figure + fignum = 0; + + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + plt.cla() + + # Plot points + # Can't use data because current frame might not see all points + # marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()); # TODO - this is slow + # gtsam.plot3DPoints(result, [], marginals); + plot3DPoints(fignum, result, 'rx'); + + # Plot cameras + M = 0; + while result.exists(int(gtsam.Symbol('x',M))): + ii = int(gtsam.Symbol('x',M)); + pose_i = result.pose3_at(ii); + plotPose3(fignum, pose_i, 10); + + M = M + 1; + + # draw + ax.set_xlim3d(-40, 40) + ax.set_ylim3d(-40, 40) + ax.set_zlim3d(-40, 40) + plt.show(block=False) + plt.draw(); def visual_ISAM2_example(): # Define the camera calibration parameters @@ -76,7 +171,8 @@ def visual_ISAM2_example(): print gtsam.Symbol('l',j) print currentEstimate.point3_at(int(gtsam.Symbol('l',j))) - # TODO: Print to screen or plot using matplotlib + visual_ISAM2_plot(poses, points, currentEstimate); + time.sleep(1) # Clear the factor graph and values for the next iteration graph.resize(0); From 8fa1acc5535e29b81d2d00efecbf5b6e16d1ed2f Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 24 Nov 2015 18:06:44 +0100 Subject: [PATCH 043/105] Move plot functions to a submodule utils --- python/gtsam/__init__.py | 1 + python/gtsam/examples/VisualISAM2Example.py | 59 +-------------------- python/gtsam/utils/__init__.py | 1 + python/gtsam/utils/_plot.py | 59 +++++++++++++++++++++ 4 files changed, 62 insertions(+), 58 deletions(-) create mode 100644 python/gtsam/utils/__init__.py create mode 100644 python/gtsam/utils/_plot.py diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index f1b07905b..9ac4cc939 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1 +1,2 @@ from libgtsam_python import * +import utils diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py index bd797d271..06221a303 100644 --- a/python/gtsam/examples/VisualISAM2Example.py +++ b/python/gtsam/examples/VisualISAM2Example.py @@ -1,67 +1,10 @@ import gtsam from gtsam.examples.SFMdata import * +from gtsam.utils import * import matplotlib.pyplot as plt from mpl_toolkits.mplot3d import Axes3D import time # for sleep() -def plotPoint3(fignum, point, linespec): - fig = plt.figure(fignum) - ax = fig.gca(projection='3d') - ax.plot([point.x()],[point.y()],[point.z()], linespec) - - -def plot3DPoints(fignum, values, linespec, marginals=None): - # PLOT3DPOINTS Plots the Point3's in a values, with optional covariances - # Finds all the Point3 objects in the given Values object and plots them. - # If a Marginals object is given, this function will also plot marginal - # covariance ellipses for each point. - - keys = values.keys() - - # Plot points and covariance matrices - for key in keys: - try: - p = values.point3_at(key); - # if haveMarginals - # P = marginals.marginalCovariance(key); - # gtsam.plotPoint3(p, linespec, P); - # else - plotPoint3(fignum, p, linespec); - except RuntimeError: - continue - #I guess it's not a Point3 - - -def plotPose3(fignum, pose, axisLength=0.1): - # get figure object - fig = plt.figure(fignum) - ax = fig.gca(projection='3d') - - # get rotation and translation (center) - gRp = pose.rotation().matrix() # rotation from pose to global - C = pose.translation().vector() - - # draw the camera axes - xAxis = C+gRp[:,0]*axisLength - L = np.append(C[np.newaxis], xAxis[np.newaxis], axis=0) - ax.plot(L[:,0],L[:,1],L[:,2],'r-') - - yAxis = C+gRp[:,1]*axisLength - L = np.append(C[np.newaxis], yAxis[np.newaxis], axis=0) - ax.plot(L[:,0],L[:,1],L[:,2],'g-') - - zAxis = C+gRp[:,2]*axisLength - L = np.append(C[np.newaxis], zAxis[np.newaxis], axis=0) - ax.plot(L[:,0],L[:,1],L[:,2],'b-') - - # # plot the covariance - # if (nargin>2) && (~isempty(P)) - # pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame - # gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame - # gtsam.covarianceEllipse3D(C,gPp); - # end - - def visual_ISAM2_plot(poses, points, result): # VisualISAMPlot plots current state of ISAM2 object # Author: Ellon Paiva diff --git a/python/gtsam/utils/__init__.py b/python/gtsam/utils/__init__.py new file mode 100644 index 000000000..eedd7484e --- /dev/null +++ b/python/gtsam/utils/__init__.py @@ -0,0 +1 @@ +from _plot import * diff --git a/python/gtsam/utils/_plot.py b/python/gtsam/utils/_plot.py new file mode 100644 index 000000000..f1603bbf5 --- /dev/null +++ b/python/gtsam/utils/_plot.py @@ -0,0 +1,59 @@ +import numpy as _np +import matplotlib.pyplot as _plt +from mpl_toolkits.mplot3d import Axes3D as _Axes3D + +def plotPoint3(fignum, point, linespec): + fig = _plt.figure(fignum) + ax = fig.gca(projection='3d') + ax.plot([point.x()],[point.y()],[point.z()], linespec) + + +def plot3DPoints(fignum, values, linespec, marginals=None): + # PLOT3DPOINTS Plots the Point3's in a values, with optional covariances + # Finds all the Point3 objects in the given Values object and plots them. + # If a Marginals object is given, this function will also plot marginal + # covariance ellipses for each point. + + keys = values.keys() + + # Plot points and covariance matrices + for key in keys: + try: + p = values.point3_at(key); + # if haveMarginals + # P = marginals.marginalCovariance(key); + # gtsam.plotPoint3(p, linespec, P); + # else + plotPoint3(fignum, p, linespec); + except RuntimeError: + continue + #I guess it's not a Point3 + +def plotPose3(fignum, pose, axisLength=0.1): + # get figure object + fig = _plt.figure(fignum) + ax = fig.gca(projection='3d') + + # get rotation and translation (center) + gRp = pose.rotation().matrix() # rotation from pose to global + C = pose.translation().vector() + + # draw the camera axes + xAxis = C+gRp[:,0]*axisLength + L = _np.append(C[_np.newaxis], xAxis[_np.newaxis], axis=0) + ax.plot(L[:,0],L[:,1],L[:,2],'r-') + + yAxis = C+gRp[:,1]*axisLength + L = _np.append(C[_np.newaxis], yAxis[_np.newaxis], axis=0) + ax.plot(L[:,0],L[:,1],L[:,2],'g-') + + zAxis = C+gRp[:,2]*axisLength + L = _np.append(C[_np.newaxis], zAxis[_np.newaxis], axis=0) + ax.plot(L[:,0],L[:,1],L[:,2],'b-') + + # # plot the covariance + # if (nargin>2) && (~isempty(P)) + # pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame + # gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame + # gtsam.covarianceEllipse3D(C,gPp); + # end \ No newline at end of file From d3db7309bce0717df1c5ec400af8cb8ff91e9c62 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 25 Nov 2015 14:06:49 +0100 Subject: [PATCH 044/105] Make libgtsam_python a hidden module by adding '_' before lib name --- python/gtsam/.gitignore | 2 +- python/gtsam/__init__.py | 2 +- python/handwritten/CMakeLists.txt | 2 +- python/handwritten/exportgtsam.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/python/gtsam/.gitignore b/python/gtsam/.gitignore index 8f89b0f14..580cd8494 100644 --- a/python/gtsam/.gitignore +++ b/python/gtsam/.gitignore @@ -1 +1 @@ -/libgtsam_python.so +/_libgtsam_python.so diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 9ac4cc939..9a0a4536e 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,2 +1,2 @@ -from libgtsam_python import * +from _libgtsam_python import * import utils diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 753e33831..93b928d94 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -43,6 +43,6 @@ set(PYTHON_MODULE_DIRECTORY ${CMAKE_SOURCE_DIR}/python/gtsam) # Cause the library to be output in the correct directory. add_custom_command(TARGET ${moduleName}_python POST_BUILD - COMMAND cp -v ${PYLIB_OUTPUT_FILE} ${PYTHON_MODULE_DIRECTORY}/${PYLIB_SO_NAME} + COMMAND cp -v ${PYLIB_OUTPUT_FILE} ${PYTHON_MODULE_DIRECTORY}/_${PYLIB_SO_NAME} WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} COMMENT "Copying library files to python directory" ) diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index 2802a779c..e1dc646b1 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -57,7 +57,7 @@ void registerNumpyEigenConversions(); //-----------------------------------// -BOOST_PYTHON_MODULE(libgtsam_python){ +BOOST_PYTHON_MODULE(_libgtsam_python){ // Should be the first thing to be done import_array(); From 4f98ec889ccaef986150feb5678be29dbb5cf220 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 25 Nov 2015 14:36:44 +0100 Subject: [PATCH 045/105] Fix python instalation using distutils Conflicts: python/README.md --- python/.gitignore | 1 + python/README.md | 2 ++ python/setup.py | 14 ++++++++------ 3 files changed, 11 insertions(+), 6 deletions(-) create mode 100644 python/.gitignore diff --git a/python/.gitignore b/python/.gitignore new file mode 100644 index 000000000..d16386367 --- /dev/null +++ b/python/.gitignore @@ -0,0 +1 @@ +build/ \ No newline at end of file diff --git a/python/README.md b/python/README.md index 4d908e52c..c6e5ed37d 100644 --- a/python/README.md +++ b/python/README.md @@ -9,6 +9,8 @@ During the build of gtsam, when GTSAM_BUILD_PYTHON is enabled, the following ins * The user can use the setup.py script to build and install a python package, allowing easy importing into a python project. Examples: * python setup.py sdist ---- Builds a tarball of the python package which can then be distributed * python setup.py install ---- Installs the package into the python dist-packages folder. Can then be imported from any python file. + * python setup.py install --prefix="your/local/install/path"---- Installs the package into a local instalation folder. Can then be imported from any python file if _prefix_/lib/pythonX.Y/site-packages is present in your $PYTHONPATH + * To run the unit tests, you must first install the package on your path (TODO: Make this easier) diff --git a/python/setup.py b/python/setup.py index a6013da81..46bbfaddf 100755 --- a/python/setup.py +++ b/python/setup.py @@ -4,12 +4,14 @@ from distutils.core import setup -setup(name='GTSAM', - version='3.0', - description='Python Distribution Utilities', +setup(name='gtsam', + version='4.0.0', + description='GTSAM Python wrapper', + license = "BSD", author='Dellaert et. al', author_email='Andrew.Melim@gatech.edu', - url='http://www.python.org/sigs/distutils-sig/', - packages=['gtsam'], - package_data={'gtsam' : ['libgtsam_python.so']}, + maintainer_email='gtsam@lists.gatech.edu', + url='https://collab.cc.gatech.edu/borg/gtsam', + packages=['gtsam', 'gtsam.examples', 'gtsam.utils'], + package_data={'gtsam' : ['_libgtsam_python.so']}, ) From ea6ecdd9d561bc8b6b7b4834d5f999d2ac9541ce Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 25 Nov 2015 18:21:10 +0100 Subject: [PATCH 046/105] Move subdirlist macro to cmake/GtsamPythonWrap.cmake Conflicts: cmake/GtsamPythonWrap.cmake --- CMakeLists.txt | 3 ++- cmake/GtsamPythonWrap.cmake | 12 ++++++++++++ python/handwritten/CMakeLists.txt | 21 +++++---------------- 3 files changed, 19 insertions(+), 17 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2719a77ab..bbb998e80 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -347,12 +347,13 @@ endif() # Python wrap if (GTSAM_BUILD_PYTHON) + include(GtsamPythonWrap) + # NOTE: The automatic generation of python wrapper from the gtsampy.h interface is # not working yet, so we're using a handwritten wrapper files on python/handwritten. # Once the python wrapping from the interface file is working, you can _swap_ the # comments on the next lines - # include(GtsamPythonWrap) # wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "") add_subdirectory(python) diff --git a/cmake/GtsamPythonWrap.cmake b/cmake/GtsamPythonWrap.cmake index cfbe89c1f..c23ee783d 100644 --- a/cmake/GtsamPythonWrap.cmake +++ b/cmake/GtsamPythonWrap.cmake @@ -87,3 +87,15 @@ function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY) list(APPEND AMCF ${PYTHON_MODULE_DIRECTORY}/${PYLIB_SO_NAME}) set_directory_properties(PROPERTIES ADDITIONAL_MAKE_CLEAN_FILES "${AMCF}") endfunction(wrap_python) + +# Macro to get list of subdirectories +macro(SUBDIRLIST result curdir) + file(GLOB children RELATIVE ${curdir} ${curdir}/*) + set(dirlist "") + foreach(child ${children}) + if(IS_DIRECTORY ${curdir}/${child}) + list(APPEND dirlist ${child}) + endif() + endforeach() + set(${result} ${dirlist}) +endmacro() diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 93b928d94..1090ef9cf 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -1,24 +1,13 @@ -# Macro to get list of subdirectories -MACRO(SUBDIRLIST result curdir) - FILE(GLOB children RELATIVE ${curdir} ${curdir}/*) - SET(dirlist "") - FOREACH(child ${children}) - IF(IS_DIRECTORY ${curdir}/${child}) - LIST(APPEND dirlist ${child}) - ENDIF() - ENDFOREACH() - SET(${result} ${dirlist}) -ENDMACRO() # get subdirectories list -SUBDIRLIST(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}) +subdirlist(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}) # get the sources needed to compile gtsam python module -SET(gtsam_python_srcs "") -FOREACH(subdir ${SUBDIRS}) +set(gtsam_python_srcs "") +foreach(subdir ${SUBDIRS}) file(GLOB ${subdir}_src "${subdir}/*.cpp") - LIST(APPEND gtsam_python_srcs ${${subdir}_src}) -ENDFOREACH() + list(APPEND gtsam_python_srcs ${${subdir}_src}) +endforeach() # Create the library set(moduleName gtsam) From 5b116a4a67fbe930fdc01913537f1ed743e59a05 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Sat, 28 Nov 2015 00:34:48 +0100 Subject: [PATCH 047/105] Add option to chose target python version to create module --- cmake/GtsamPythonWrap.cmake | 13 +++++++------ python/CMakeLists.txt | 29 ++++++++++++++++++++++++----- python/handwritten/CMakeLists.txt | 2 +- 3 files changed, 32 insertions(+), 12 deletions(-) diff --git a/cmake/GtsamPythonWrap.cmake b/cmake/GtsamPythonWrap.cmake index c23ee783d..f7d468940 100644 --- a/cmake/GtsamPythonWrap.cmake +++ b/cmake/GtsamPythonWrap.cmake @@ -1,4 +1,5 @@ #Setup cache options +set(GTSAM_PYTHON_VERSION "2.7" CACHE STRING "Version of python used to build the wrapper") set(GTSAM_BUILD_PYTHON_FLAGS "" CACHE STRING "Extra flags for running Matlab PYTHON compilation") set(GTSAM_PYTHON_INSTALL_PATH "" CACHE PATH "Python toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/borg/python") if(NOT GTSAM_PYTHON_INSTALL_PATH) @@ -7,13 +8,13 @@ endif() #Author: Paul Furgale Modified by Andrew Melim function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY) - # Boost - find_package(Boost COMPONENTS python filesystem system REQUIRED) - include_directories(${Boost_INCLUDE_DIRS}) + # # Boost + # find_package(Boost COMPONENTS python filesystem system REQUIRED) + # include_directories(${Boost_INCLUDE_DIRS}) - # Find Python - FIND_PACKAGE(PythonLibs 2.7 REQUIRED) - INCLUDE_DIRECTORIES(${PYTHON_INCLUDE_DIRS}) + # # Find Python + # FIND_PACKAGE(PythonLibs 2.7 REQUIRED) + # INCLUDE_DIRECTORIES(${PYTHON_INCLUDE_DIRS}) IF(APPLE) # The apple framework headers don't include the numpy headers for some reason. diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 0fcb1fc28..4fe0d8cf9 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,12 +1,31 @@ -# Obtain Dependencies -# Boost Python -find_package(Boost COMPONENTS python REQUIRED) -include_directories(${Boost_INCLUDE_DIRS}) +# The code below allows to clear the PythonLibs cache if we change GTSAM_PYTHON_VERSION +# Inspired from the solution found here: http://blog.bethcodes.com/cmake-tips-tricks-drop-down-list +if((NOT DEFINED GTSAM_LAST_PYTHON_VERSION)) + set(GTSAM_LAST_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "Python version used in the last build") + mark_as_advanced(FORCE GTSAM_LAST_PYTHON_VERSION) +endif() +if((NOT (${GTSAM_PYTHON_VERSION} MATCHES ${GTSAM_LAST_PYTHON_VERSION}))) + unset(PYTHON_INCLUDE_DIR CACHE) + unset(PYTHON_INCLUDE_DIR2 CACHE) + unset(PYTHON_LIBRARY CACHE) + unset(PYTHON_LIBRARY_DEBUG CACHE) + set(GTSAM_LAST_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "Updating python version used in the last build" FORCE) +endif() + +# Be sure that python version can be found by FindPythonLibs.cmake +# See: http://stackoverflow.com/a/15660652/2220173 +set(Python_ADDITIONAL_VERSIONS ${GTSAM_PYTHON_VERSION}) # Find Python -find_package(PythonLibs 2.7 REQUIRED) +find_package(PythonLibs ${GTSAM_PYTHON_VERSION} REQUIRED) include_directories(${PYTHON_INCLUDE_DIRS}) +# Boost Python +string(REPLACE "." "" PYTHON_VERSION_NUMBER ${GTSAM_PYTHON_VERSION}) # Remove '.' from version +string(SUBSTRING ${PYTHON_VERSION_NUMBER} 0 2 PYTHON_VERSION_NUMBER) # Trim version number to 2 digits +find_package(Boost COMPONENTS python-py${PYTHON_VERSION_NUMBER} REQUIRED) +include_directories(${Boost_INCLUDE_DIRS}) + # Numpy_Eigen include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 1090ef9cf..893fbae71 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -18,7 +18,7 @@ set_target_properties(${moduleName}_python PROPERTIES OUTPUT_NAME ${moduleName}_python CLEAN_DIRECT_OUTPUT 1) -target_link_libraries(${moduleName}_python ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp +target_link_libraries(${moduleName}_python ${Boost_PYTHON-PY${PYTHON_VERSION_NUMBER}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp # On OSX and Linux, the python library must end in the extension .so. Build this # filename here. From dfa2b53eeb1f33663b1f6888d66aebf2b36bd99c Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Sat, 28 Nov 2015 00:35:39 +0100 Subject: [PATCH 048/105] import_array() --> import_array1() --- python/handwritten/exportgtsam.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp index e1dc646b1..da8382d71 100644 --- a/python/handwritten/exportgtsam.cpp +++ b/python/handwritten/exportgtsam.cpp @@ -59,8 +59,13 @@ void registerNumpyEigenConversions(); BOOST_PYTHON_MODULE(_libgtsam_python){ + // NOTE: We need to call import_array1() instead of import_array() to support both python 2 + // and 3. The reason is that BOOST_PYTHON_MODULE puts all its contents in a function + // returning void, and import_array() is a macro that when expanded for python 3, adds + // a 'return __null' statement to that function. For more info check files: + // boost/python/module_init.hpp and numpy/__multiarray_api.h (bottom of the file). // Should be the first thing to be done - import_array(); + import_array1(); registerNumpyEigenConversions(); From 72bcc4f08eefd59ee9949faabae9c34f2efe11d1 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Sat, 28 Nov 2015 00:36:29 +0100 Subject: [PATCH 049/105] Change VisualISAM2Example to work with python 2 and python 3 --- python/gtsam/examples/VisualISAM2Example.py | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py index 06221a303..a8be94719 100644 --- a/python/gtsam/examples/VisualISAM2Example.py +++ b/python/gtsam/examples/VisualISAM2Example.py @@ -1,3 +1,4 @@ +from __future__ import print_function import gtsam from gtsam.examples.SFMdata import * from gtsam.utils import * @@ -36,8 +37,9 @@ def visual_ISAM2_plot(poses, points, result): ax.set_xlim3d(-40, 40) ax.set_ylim3d(-40, 40) ax.set_zlim3d(-40, 40) - plt.show(block=False) - plt.draw(); + plt.ion() + plt.show() + plt.draw() def visual_ISAM2_example(): # Define the camera calibration parameters @@ -104,15 +106,15 @@ def visual_ISAM2_example(): # to perform multiple optimizer iterations every step. isam.update() currentEstimate = isam.calculate_estimate(); - print "****************************************************" - print "Frame", i, ":" + print( "****************************************************" ) + print( "Frame", i, ":" ) for j in range(i+1): - print gtsam.Symbol('x',j) - print currentEstimate.pose3_at(int(gtsam.Symbol('x',j))) + print( gtsam.Symbol('x',j) ) + print( currentEstimate.pose3_at(int(gtsam.Symbol('x',j))) ) for j in range(len(points)): - print gtsam.Symbol('l',j) - print currentEstimate.point3_at(int(gtsam.Symbol('l',j))) + print( gtsam.Symbol('l',j) ) + print( currentEstimate.point3_at(int(gtsam.Symbol('l',j))) ) visual_ISAM2_plot(poses, points, currentEstimate); time.sleep(1) From 09ec3060134a9cec1939c79e19c597a24a466742 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Sat, 28 Nov 2015 00:37:53 +0100 Subject: [PATCH 050/105] Update __ini__.py to be supported in python 2 and 3 --- python/gtsam/__init__.py | 4 ++-- python/gtsam/examples/__init__.py | 4 ++-- python/gtsam/utils/__init__.py | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 9a0a4536e..8e093879c 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,2 +1,2 @@ -from _libgtsam_python import * -import utils +from ._libgtsam_python import * +from . import utils \ No newline at end of file diff --git a/python/gtsam/examples/__init__.py b/python/gtsam/examples/__init__.py index ab7c3bd81..f9d032d54 100644 --- a/python/gtsam/examples/__init__.py +++ b/python/gtsam/examples/__init__.py @@ -1,2 +1,2 @@ -from SFMdata import * -from VisualISAM2Example import * +from . import SFMdata +from . import VisualISAM2Example diff --git a/python/gtsam/utils/__init__.py b/python/gtsam/utils/__init__.py index eedd7484e..0ef2dfcd3 100644 --- a/python/gtsam/utils/__init__.py +++ b/python/gtsam/utils/__init__.py @@ -1 +1 @@ -from _plot import * +from ._plot import * From ff298451d79520d9a69af61c67648cdbfa559e22 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 30 Nov 2015 15:46:36 +0100 Subject: [PATCH 051/105] Build Python module by default --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index bbb998e80..1c220d169 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,7 +64,7 @@ option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TB option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" ON) option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" ON) option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) -option(GTSAM_BUILD_PYTHON "Build Python wrapper statically (increases build time)" OFF) +option(GTSAM_BUILD_PYTHON "Build Python wrapper statically (increases build time)" ON) # Options relating to MATLAB wrapper # TODO: Check for matlab mex binary before handling building of binaries From 86c3cf7ff69db28354a42716faae3fb8f8ffb9eb Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Mon, 30 Nov 2015 15:47:16 +0100 Subject: [PATCH 052/105] Print cmake python options --- CMakeLists.txt | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1c220d169..a886f2702 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -476,6 +476,12 @@ print_config_flag(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full Ex message(STATUS "MATLAB toolbox flags ") print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") + +message(STATUS "Python module flags ") +print_config_flag(${GTSAM_BUILD_PYTHON} "Build python module ") +if(GTSAM_BUILD_PYTHON) + message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") +endif() message(STATUS "===============================================================") # Print warnings at the end From d51c6f3313174b7bd6f685fd7ca4c40d9c6f49f8 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 1 Dec 2015 11:47:28 +0100 Subject: [PATCH 053/105] Fix cmake to use default python and boost python versions --- cmake/GtsamPythonWrap.cmake | 2 +- python/CMakeLists.txt | 67 +++++++++++++++++++++++++------ python/handwritten/CMakeLists.txt | 2 +- 3 files changed, 56 insertions(+), 15 deletions(-) diff --git a/cmake/GtsamPythonWrap.cmake b/cmake/GtsamPythonWrap.cmake index f7d468940..714e37488 100644 --- a/cmake/GtsamPythonWrap.cmake +++ b/cmake/GtsamPythonWrap.cmake @@ -1,5 +1,5 @@ #Setup cache options -set(GTSAM_PYTHON_VERSION "2.7" CACHE STRING "Version of python used to build the wrapper") +set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "Target python version for GTSAM python module. Use 'Default' to chose the default version") set(GTSAM_BUILD_PYTHON_FLAGS "" CACHE STRING "Extra flags for running Matlab PYTHON compilation") set(GTSAM_PYTHON_INSTALL_PATH "" CACHE PATH "Python toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/borg/python") if(NOT GTSAM_PYTHON_INSTALL_PATH) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 4fe0d8cf9..28b916ab2 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,10 +1,15 @@ +# Guard to avoid breaking this code in ccmake if by accident GTSAM_PYTHON_VERSION is set to an empty string +if(GTSAM_PYTHON_VERSION STREQUAL "") + set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "Target python version for GTSAM python module. Use 'Default' to chose the default version" FORCE) +endif() + # The code below allows to clear the PythonLibs cache if we change GTSAM_PYTHON_VERSION # Inspired from the solution found here: http://blog.bethcodes.com/cmake-tips-tricks-drop-down-list -if((NOT DEFINED GTSAM_LAST_PYTHON_VERSION)) +if(NOT DEFINED GTSAM_LAST_PYTHON_VERSION) set(GTSAM_LAST_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "Python version used in the last build") mark_as_advanced(FORCE GTSAM_LAST_PYTHON_VERSION) endif() -if((NOT (${GTSAM_PYTHON_VERSION} MATCHES ${GTSAM_LAST_PYTHON_VERSION}))) +if(NOT (${GTSAM_PYTHON_VERSION} MATCHES ${GTSAM_LAST_PYTHON_VERSION})) unset(PYTHON_INCLUDE_DIR CACHE) unset(PYTHON_INCLUDE_DIR2 CACHE) unset(PYTHON_LIBRARY CACHE) @@ -12,21 +17,57 @@ if((NOT (${GTSAM_PYTHON_VERSION} MATCHES ${GTSAM_LAST_PYTHON_VERSION}))) set(GTSAM_LAST_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "Updating python version used in the last build" FORCE) endif() +# Compose strings used to specify the boost python version. They will be empty if we want to use the defaut +if(NOT GTSAM_PYTHON_VERSION STREQUAL "Default") + string(REPLACE "." "" BOOST_PYTHON_VERSION_STRING ${GTSAM_PYTHON_VERSION}) # Remove '.' from version + string(SUBSTRING ${BOOST_PYTHON_VERSION_STRING} 0 2 BOOST_PYTHON_VERSION_STRING) # Trim version number to 2 digits + set(BOOST_PYTHON_VERSION_STRING "-py${BOOST_PYTHON_VERSION_STRING}") # Add '-py' prefix + string(TOUPPER ${BOOST_PYTHON_VERSION_STRING} UPPER_BOOST_PYTHON_VERSION_STRING) # Get uppercase string +else() + set(BOOST_PYTHON_VERSION_STRING "") + set(UPPER_BOOST_PYTHON_VERSION_STRING "") +endif() + # Be sure that python version can be found by FindPythonLibs.cmake # See: http://stackoverflow.com/a/15660652/2220173 set(Python_ADDITIONAL_VERSIONS ${GTSAM_PYTHON_VERSION}) -# Find Python -find_package(PythonLibs ${GTSAM_PYTHON_VERSION} REQUIRED) -include_directories(${PYTHON_INCLUDE_DIRS}) +# Find Python +if(GTSAM_PYTHON_VERSION STREQUAL "Default") + # If no version is specified when looking for PythonLibs it searches the default version. + # See: https://cmake.org/cmake/help/v3.1/module/FindPythonInterp.html + find_package(PythonLibs) +else() + find_package(PythonLibs ${GTSAM_PYTHON_VERSION}) +endif() -# Boost Python -string(REPLACE "." "" PYTHON_VERSION_NUMBER ${GTSAM_PYTHON_VERSION}) # Remove '.' from version -string(SUBSTRING ${PYTHON_VERSION_NUMBER} 0 2 PYTHON_VERSION_NUMBER) # Trim version number to 2 digits -find_package(Boost COMPONENTS python-py${PYTHON_VERSION_NUMBER} REQUIRED) -include_directories(${Boost_INCLUDE_DIRS}) +# Find Boost Python +find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_STRING}) -# Numpy_Eigen -include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) +# Add handwritten directory if we found python and boost python +if(Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND AND PYTHONLIBS_FOUND) + include_directories(${PYTHON_INCLUDE_DIRS}) + include_directories(${Boost_INCLUDE_DIRS}) + include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) + add_subdirectory(handwritten) +# Disable python module if we didn't find required lybraries +else() + set(GTSAM_BUILD_PYTHON OFF CACHE BOOL "Build Python wrapper statically (increases build time)" FORCE) +endif() -add_subdirectory(handwritten) \ No newline at end of file +# Print warnings (useful for ccmake) +if(NOT PYTHONLIBS_FOUND) + if(GTSAM_PYTHON_VERSION STREQUAL "Default") + message(WARNING "Default PythonLibs was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") + else() + message(WARNING "PythonLibs version ${GTSAM_PYTHON_VERSION} was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") + endif() +endif() + +if(NOT Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND) + if(GTSAM_PYTHON_VERSION STREQUAL "Default") + message(WARNING "Default Boost python was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") + else() + message(WARNING "Boost Python for python ${GTSAM_PYTHON_VERSION} was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") + endif() +endif() \ No newline at end of file diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 893fbae71..ffd970217 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -18,7 +18,7 @@ set_target_properties(${moduleName}_python PROPERTIES OUTPUT_NAME ${moduleName}_python CLEAN_DIRECT_OUTPUT 1) -target_link_libraries(${moduleName}_python ${Boost_PYTHON-PY${PYTHON_VERSION_NUMBER}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp +target_link_libraries(${moduleName}_python ${Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp # On OSX and Linux, the python library must end in the extension .so. Build this # filename here. From 40a567c1eda547bbbfacf232221cc088d0308115 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 1 Dec 2015 12:52:31 +0100 Subject: [PATCH 054/105] Look for NumPy C-API if building the python module --- cmake/FindNumPy.cmake | 102 ++++++++++++++++++++++++++++++++++++++++++ python/CMakeLists.txt | 18 +++++--- 2 files changed, 114 insertions(+), 6 deletions(-) create mode 100644 cmake/FindNumPy.cmake diff --git a/cmake/FindNumPy.cmake b/cmake/FindNumPy.cmake new file mode 100644 index 000000000..eafed165e --- /dev/null +++ b/cmake/FindNumPy.cmake @@ -0,0 +1,102 @@ +# - Find the NumPy libraries +# This module finds if NumPy is installed, and sets the following variables +# indicating where it is. +# +# TODO: Update to provide the libraries and paths for linking npymath lib. +# +# NUMPY_FOUND - was NumPy found +# NUMPY_VERSION - the version of NumPy found as a string +# NUMPY_VERSION_MAJOR - the major version number of NumPy +# NUMPY_VERSION_MINOR - the minor version number of NumPy +# NUMPY_VERSION_PATCH - the patch version number of NumPy +# NUMPY_VERSION_DECIMAL - e.g. version 1.6.1 is 10601 +# NUMPY_INCLUDE_DIRS - path to the NumPy include files + +#============================================================================ +# Copyright 2012 Continuum Analytics, Inc. +# +# MIT License +# +# Permission is hereby granted, free of charge, to any person obtaining +# a copy of this software and associated documentation files +# (the "Software"), to deal in the Software without restriction, including +# without limitation the rights to use, copy, modify, merge, publish, +# distribute, sublicense, and/or sell copies of the Software, and to permit +# persons to whom the Software is furnished to do so, subject to +# the following conditions: +# +# The above copyright notice and this permission notice shall be included +# in all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS +# OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL +# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR +# OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, +# ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR +# OTHER DEALINGS IN THE SOFTWARE. +# +#============================================================================ + +# Finding NumPy involves calling the Python interpreter +if(NumPy_FIND_REQUIRED) + find_package(PythonInterp REQUIRED) +else() + find_package(PythonInterp) +endif() + +if(NOT PYTHONINTERP_FOUND) + set(NUMPY_FOUND FALSE) + return() +endif() + +execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" + "import numpy as n; print(n.__version__); print(n.get_include());" + RESULT_VARIABLE _NUMPY_SEARCH_SUCCESS + OUTPUT_VARIABLE _NUMPY_VALUES_OUTPUT + ERROR_VARIABLE _NUMPY_ERROR_VALUE + OUTPUT_STRIP_TRAILING_WHITESPACE) + +if(NOT _NUMPY_SEARCH_SUCCESS MATCHES 0) + if(NumPy_FIND_REQUIRED) + message(FATAL_ERROR + "NumPy import failure:\n${_NUMPY_ERROR_VALUE}") + endif() + set(NUMPY_FOUND FALSE) + return() +endif() + +# Convert the process output into a list +string(REGEX REPLACE ";" "\\\\;" _NUMPY_VALUES ${_NUMPY_VALUES_OUTPUT}) +string(REGEX REPLACE "\n" ";" _NUMPY_VALUES ${_NUMPY_VALUES}) +# Just in case there is unexpected output from the Python command. +list(GET _NUMPY_VALUES -2 NUMPY_VERSION) +list(GET _NUMPY_VALUES -1 NUMPY_INCLUDE_DIRS) + +string(REGEX MATCH "^[0-9]+\\.[0-9]+\\.[0-9]+" _VER_CHECK "${NUMPY_VERSION}") +if("${_VER_CHECK}" STREQUAL "") + # The output from Python was unexpected. Raise an error always + # here, because we found NumPy, but it appears to be corrupted somehow. + message(FATAL_ERROR + "Requested version and include path from NumPy, got instead:\n${_NUMPY_VALUES_OUTPUT}\n") + return() +endif() + +# Make sure all directory separators are '/' +string(REGEX REPLACE "\\\\" "/" NUMPY_INCLUDE_DIRS ${NUMPY_INCLUDE_DIRS}) + +# Get the major and minor version numbers +string(REGEX REPLACE "\\." ";" _NUMPY_VERSION_LIST ${NUMPY_VERSION}) +list(GET _NUMPY_VERSION_LIST 0 NUMPY_VERSION_MAJOR) +list(GET _NUMPY_VERSION_LIST 1 NUMPY_VERSION_MINOR) +list(GET _NUMPY_VERSION_LIST 2 NUMPY_VERSION_PATCH) +string(REGEX MATCH "[0-9]*" NUMPY_VERSION_PATCH ${NUMPY_VERSION_PATCH}) +math(EXPR NUMPY_VERSION_DECIMAL + "(${NUMPY_VERSION_MAJOR} * 10000) + (${NUMPY_VERSION_MINOR} * 100) + ${NUMPY_VERSION_PATCH}") + +find_package_message(NUMPY + "Found NumPy: version \"${NUMPY_VERSION}\" ${NUMPY_INCLUDE_DIRS}" + "${NUMPY_INCLUDE_DIRS}${NUMPY_VERSION}") + +set(NUMPY_FOUND TRUE) + diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 28b916ab2..0e1a5f0dd 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -28,14 +28,16 @@ else() set(UPPER_BOOST_PYTHON_VERSION_STRING "") endif() -# Be sure that python version can be found by FindPythonLibs.cmake +# Find NumPy C-API +find_package(NumPy) + +# Find Python +# First, be sure that python version can be found by FindPythonLibs.cmake # See: http://stackoverflow.com/a/15660652/2220173 set(Python_ADDITIONAL_VERSIONS ${GTSAM_PYTHON_VERSION}) - -# Find Python +# Then look for the the lib. If no version is specified when looking for PythonLibs it searches the default version. +# See: https://cmake.org/cmake/help/v3.1/module/FindPythonInterp.html if(GTSAM_PYTHON_VERSION STREQUAL "Default") - # If no version is specified when looking for PythonLibs it searches the default version. - # See: https://cmake.org/cmake/help/v3.1/module/FindPythonInterp.html find_package(PythonLibs) else() find_package(PythonLibs ${GTSAM_PYTHON_VERSION}) @@ -45,7 +47,7 @@ endif() find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_STRING}) # Add handwritten directory if we found python and boost python -if(Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND AND PYTHONLIBS_FOUND) +if(Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND AND PYTHONLIBS_FOUND AND NUMPY_FOUND) include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) @@ -70,4 +72,8 @@ if(NOT Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND) else() message(WARNING "Boost Python for python ${GTSAM_PYTHON_VERSION} was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") endif() +endif() + +if(NOT NUMPY_FOUND) + message(WARNING "NumPy C-API was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") endif() \ No newline at end of file From eb798f88fe4345b28c31fa3ed85493e36727a1d5 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 1 Dec 2015 13:28:29 +0100 Subject: [PATCH 055/105] Add NumPy C-API 1.8.2 to gtsam/3rdparty; Add option o use system or bundled one --- .../include/numpy/__multiarray_api.h | 1721 ++++++++++++ .../numpy_c_api/include/numpy/__ufunc_api.h | 328 +++ .../numpy/_neighborhood_iterator_imp.h | 90 + .../numpy_c_api/include/numpy/_numpyconfig.h | 32 + .../numpy_c_api/include/numpy/arrayobject.h | 11 + .../numpy_c_api/include/numpy/arrayscalars.h | 175 ++ .../numpy_c_api/include/numpy/halffloat.h | 69 + .../include/numpy/multiarray_api.txt | 2430 +++++++++++++++++ .../numpy_c_api/include/numpy/ndarrayobject.h | 237 ++ .../numpy_c_api/include/numpy/ndarraytypes.h | 1777 ++++++++++++ .../numpy_c_api/include/numpy/noprefix.h | 209 ++ .../include/numpy/npy_1_7_deprecated_api.h | 130 + .../numpy_c_api/include/numpy/npy_3kcompat.h | 502 ++++ .../numpy_c_api/include/numpy/npy_common.h | 1005 +++++++ .../numpy_c_api/include/numpy/npy_cpu.h | 114 + .../numpy_c_api/include/numpy/npy_endian.h | 48 + .../numpy_c_api/include/numpy/npy_interrupt.h | 117 + .../numpy_c_api/include/numpy/npy_math.h | 468 ++++ .../include/numpy/npy_no_deprecated_api.h | 19 + .../numpy_c_api/include/numpy/npy_os.h | 30 + .../numpy_c_api/include/numpy/numpyconfig.h | 34 + .../numpy_c_api/include/numpy/old_defines.h | 187 ++ .../numpy_c_api/include/numpy/oldnumeric.h | 23 + .../numpy_c_api/include/numpy/ufunc_api.txt | 321 +++ .../numpy_c_api/include/numpy/ufuncobject.h | 479 ++++ .../numpy_c_api/include/numpy/utils.h | 19 + python/CMakeLists.txt | 15 +- 27 files changed, 10584 insertions(+), 6 deletions(-) create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h create mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/utils.h diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h new file mode 100644 index 000000000..bfa87d8df --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h @@ -0,0 +1,1721 @@ + +#ifdef _MULTIARRAYMODULE + +typedef struct { + PyObject_HEAD + npy_bool obval; +} PyBoolScalarObject; + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION +extern NPY_NO_EXPORT PyTypeObject PyArrayMapIter_Type; +extern NPY_NO_EXPORT PyTypeObject PyArrayNeighborhoodIter_Type; +extern NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; +#else +NPY_NO_EXPORT PyTypeObject PyArrayMapIter_Type; +NPY_NO_EXPORT PyTypeObject PyArrayNeighborhoodIter_Type; +NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; +#endif + +NPY_NO_EXPORT unsigned int PyArray_GetNDArrayCVersion \ + (void); +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyBigArray_Type; +#else + NPY_NO_EXPORT PyTypeObject PyBigArray_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyArray_Type; +#else + NPY_NO_EXPORT PyTypeObject PyArray_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyArrayDescr_Type; +#else + NPY_NO_EXPORT PyTypeObject PyArrayDescr_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyArrayFlags_Type; +#else + NPY_NO_EXPORT PyTypeObject PyArrayFlags_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyArrayIter_Type; +#else + NPY_NO_EXPORT PyTypeObject PyArrayIter_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyArrayMultiIter_Type; +#else + NPY_NO_EXPORT PyTypeObject PyArrayMultiIter_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT int NPY_NUMUSERTYPES; +#else + NPY_NO_EXPORT int NPY_NUMUSERTYPES; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyBoolArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyBoolArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION +extern NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; +#else +NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyGenericArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyGenericArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyNumberArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyNumberArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyIntegerArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyIntegerArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PySignedIntegerArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PySignedIntegerArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyUnsignedIntegerArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyUnsignedIntegerArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyInexactArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyInexactArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyFloatingArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyFloatingArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyComplexFloatingArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyComplexFloatingArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyFlexibleArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyFlexibleArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyCharacterArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyCharacterArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyByteArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyByteArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyShortArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyShortArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyIntArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyIntArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyLongArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyLongArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyLongLongArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyLongLongArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyUByteArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyUByteArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyUShortArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyUShortArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyUIntArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyUIntArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyULongArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyULongArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyULongLongArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyULongLongArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyFloatArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyFloatArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyDoubleArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyDoubleArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyLongDoubleArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyLongDoubleArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyCFloatArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyCFloatArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyCDoubleArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyCDoubleArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyCLongDoubleArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyCLongDoubleArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyObjectArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyObjectArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyStringArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyStringArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyUnicodeArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyUnicodeArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyVoidArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyVoidArrType_Type; +#endif + +NPY_NO_EXPORT int PyArray_SetNumericOps \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_GetNumericOps \ + (void); +NPY_NO_EXPORT int PyArray_INCREF \ + (PyArrayObject *); +NPY_NO_EXPORT int PyArray_XDECREF \ + (PyArrayObject *); +NPY_NO_EXPORT void PyArray_SetStringFunction \ + (PyObject *, int); +NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromType \ + (int); +NPY_NO_EXPORT PyObject * PyArray_TypeObjectFromType \ + (int); +NPY_NO_EXPORT char * PyArray_Zero \ + (PyArrayObject *); +NPY_NO_EXPORT char * PyArray_One \ + (PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_CastToType \ + (PyArrayObject *, PyArray_Descr *, int); +NPY_NO_EXPORT int PyArray_CastTo \ + (PyArrayObject *, PyArrayObject *); +NPY_NO_EXPORT int PyArray_CastAnyTo \ + (PyArrayObject *, PyArrayObject *); +NPY_NO_EXPORT int PyArray_CanCastSafely \ + (int, int); +NPY_NO_EXPORT npy_bool PyArray_CanCastTo \ + (PyArray_Descr *, PyArray_Descr *); +NPY_NO_EXPORT int PyArray_ObjectType \ + (PyObject *, int); +NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromObject \ + (PyObject *, PyArray_Descr *); +NPY_NO_EXPORT PyArrayObject ** PyArray_ConvertToCommonType \ + (PyObject *, int *); +NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromScalar \ + (PyObject *); +NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromTypeObject \ + (PyObject *); +NPY_NO_EXPORT npy_intp PyArray_Size \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_Scalar \ + (void *, PyArray_Descr *, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_FromScalar \ + (PyObject *, PyArray_Descr *); +NPY_NO_EXPORT void PyArray_ScalarAsCtype \ + (PyObject *, void *); +NPY_NO_EXPORT int PyArray_CastScalarToCtype \ + (PyObject *, void *, PyArray_Descr *); +NPY_NO_EXPORT int PyArray_CastScalarDirect \ + (PyObject *, PyArray_Descr *, void *, int); +NPY_NO_EXPORT PyObject * PyArray_ScalarFromObject \ + (PyObject *); +NPY_NO_EXPORT PyArray_VectorUnaryFunc * PyArray_GetCastFunc \ + (PyArray_Descr *, int); +NPY_NO_EXPORT PyObject * PyArray_FromDims \ + (int, int *, int); +NPY_NO_EXPORT PyObject * PyArray_FromDimsAndDataAndDescr \ + (int, int *, PyArray_Descr *, char *); +NPY_NO_EXPORT PyObject * PyArray_FromAny \ + (PyObject *, PyArray_Descr *, int, int, int, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_EnsureArray \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_EnsureAnyArray \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_FromFile \ + (FILE *, PyArray_Descr *, npy_intp, char *); +NPY_NO_EXPORT PyObject * PyArray_FromString \ + (char *, npy_intp, PyArray_Descr *, npy_intp, char *); +NPY_NO_EXPORT PyObject * PyArray_FromBuffer \ + (PyObject *, PyArray_Descr *, npy_intp, npy_intp); +NPY_NO_EXPORT PyObject * PyArray_FromIter \ + (PyObject *, PyArray_Descr *, npy_intp); +NPY_NO_EXPORT PyObject * PyArray_Return \ + (PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_GetField \ + (PyArrayObject *, PyArray_Descr *, int); +NPY_NO_EXPORT int PyArray_SetField \ + (PyArrayObject *, PyArray_Descr *, int, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_Byteswap \ + (PyArrayObject *, npy_bool); +NPY_NO_EXPORT PyObject * PyArray_Resize \ + (PyArrayObject *, PyArray_Dims *, int, NPY_ORDER); +NPY_NO_EXPORT int PyArray_MoveInto \ + (PyArrayObject *, PyArrayObject *); +NPY_NO_EXPORT int PyArray_CopyInto \ + (PyArrayObject *, PyArrayObject *); +NPY_NO_EXPORT int PyArray_CopyAnyInto \ + (PyArrayObject *, PyArrayObject *); +NPY_NO_EXPORT int PyArray_CopyObject \ + (PyArrayObject *, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_NewCopy \ + (PyArrayObject *, NPY_ORDER); +NPY_NO_EXPORT PyObject * PyArray_ToList \ + (PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_ToString \ + (PyArrayObject *, NPY_ORDER); +NPY_NO_EXPORT int PyArray_ToFile \ + (PyArrayObject *, FILE *, char *, char *); +NPY_NO_EXPORT int PyArray_Dump \ + (PyObject *, PyObject *, int); +NPY_NO_EXPORT PyObject * PyArray_Dumps \ + (PyObject *, int); +NPY_NO_EXPORT int PyArray_ValidType \ + (int); +NPY_NO_EXPORT void PyArray_UpdateFlags \ + (PyArrayObject *, int); +NPY_NO_EXPORT PyObject * PyArray_New \ + (PyTypeObject *, int, npy_intp *, int, npy_intp *, void *, int, int, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_NewFromDescr \ + (PyTypeObject *, PyArray_Descr *, int, npy_intp *, npy_intp *, void *, int, PyObject *); +NPY_NO_EXPORT PyArray_Descr * PyArray_DescrNew \ + (PyArray_Descr *); +NPY_NO_EXPORT PyArray_Descr * PyArray_DescrNewFromType \ + (int); +NPY_NO_EXPORT double PyArray_GetPriority \ + (PyObject *, double); +NPY_NO_EXPORT PyObject * PyArray_IterNew \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_MultiIterNew \ + (int, ...); +NPY_NO_EXPORT int PyArray_PyIntAsInt \ + (PyObject *); +NPY_NO_EXPORT npy_intp PyArray_PyIntAsIntp \ + (PyObject *); +NPY_NO_EXPORT int PyArray_Broadcast \ + (PyArrayMultiIterObject *); +NPY_NO_EXPORT void PyArray_FillObjectArray \ + (PyArrayObject *, PyObject *); +NPY_NO_EXPORT int PyArray_FillWithScalar \ + (PyArrayObject *, PyObject *); +NPY_NO_EXPORT npy_bool PyArray_CheckStrides \ + (int, int, npy_intp, npy_intp, npy_intp *, npy_intp *); +NPY_NO_EXPORT PyArray_Descr * PyArray_DescrNewByteorder \ + (PyArray_Descr *, char); +NPY_NO_EXPORT PyObject * PyArray_IterAllButAxis \ + (PyObject *, int *); +NPY_NO_EXPORT PyObject * PyArray_CheckFromAny \ + (PyObject *, PyArray_Descr *, int, int, int, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_FromArray \ + (PyArrayObject *, PyArray_Descr *, int); +NPY_NO_EXPORT PyObject * PyArray_FromInterface \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_FromStructInterface \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_FromArrayAttr \ + (PyObject *, PyArray_Descr *, PyObject *); +NPY_NO_EXPORT NPY_SCALARKIND PyArray_ScalarKind \ + (int, PyArrayObject **); +NPY_NO_EXPORT int PyArray_CanCoerceScalar \ + (int, int, NPY_SCALARKIND); +NPY_NO_EXPORT PyObject * PyArray_NewFlagsObject \ + (PyObject *); +NPY_NO_EXPORT npy_bool PyArray_CanCastScalar \ + (PyTypeObject *, PyTypeObject *); +NPY_NO_EXPORT int PyArray_CompareUCS4 \ + (npy_ucs4 *, npy_ucs4 *, size_t); +NPY_NO_EXPORT int PyArray_RemoveSmallest \ + (PyArrayMultiIterObject *); +NPY_NO_EXPORT int PyArray_ElementStrides \ + (PyObject *); +NPY_NO_EXPORT void PyArray_Item_INCREF \ + (char *, PyArray_Descr *); +NPY_NO_EXPORT void PyArray_Item_XDECREF \ + (char *, PyArray_Descr *); +NPY_NO_EXPORT PyObject * PyArray_FieldNames \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_Transpose \ + (PyArrayObject *, PyArray_Dims *); +NPY_NO_EXPORT PyObject * PyArray_TakeFrom \ + (PyArrayObject *, PyObject *, int, PyArrayObject *, NPY_CLIPMODE); +NPY_NO_EXPORT PyObject * PyArray_PutTo \ + (PyArrayObject *, PyObject*, PyObject *, NPY_CLIPMODE); +NPY_NO_EXPORT PyObject * PyArray_PutMask \ + (PyArrayObject *, PyObject*, PyObject*); +NPY_NO_EXPORT PyObject * PyArray_Repeat \ + (PyArrayObject *, PyObject *, int); +NPY_NO_EXPORT PyObject * PyArray_Choose \ + (PyArrayObject *, PyObject *, PyArrayObject *, NPY_CLIPMODE); +NPY_NO_EXPORT int PyArray_Sort \ + (PyArrayObject *, int, NPY_SORTKIND); +NPY_NO_EXPORT PyObject * PyArray_ArgSort \ + (PyArrayObject *, int, NPY_SORTKIND); +NPY_NO_EXPORT PyObject * PyArray_SearchSorted \ + (PyArrayObject *, PyObject *, NPY_SEARCHSIDE, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_ArgMax \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_ArgMin \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Reshape \ + (PyArrayObject *, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_Newshape \ + (PyArrayObject *, PyArray_Dims *, NPY_ORDER); +NPY_NO_EXPORT PyObject * PyArray_Squeeze \ + (PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_View \ + (PyArrayObject *, PyArray_Descr *, PyTypeObject *); +NPY_NO_EXPORT PyObject * PyArray_SwapAxes \ + (PyArrayObject *, int, int); +NPY_NO_EXPORT PyObject * PyArray_Max \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Min \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Ptp \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Mean \ + (PyArrayObject *, int, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Trace \ + (PyArrayObject *, int, int, int, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Diagonal \ + (PyArrayObject *, int, int, int); +NPY_NO_EXPORT PyObject * PyArray_Clip \ + (PyArrayObject *, PyObject *, PyObject *, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Conjugate \ + (PyArrayObject *, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Nonzero \ + (PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Std \ + (PyArrayObject *, int, int, PyArrayObject *, int); +NPY_NO_EXPORT PyObject * PyArray_Sum \ + (PyArrayObject *, int, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_CumSum \ + (PyArrayObject *, int, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Prod \ + (PyArrayObject *, int, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_CumProd \ + (PyArrayObject *, int, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_All \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Any \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Compress \ + (PyArrayObject *, PyObject *, int, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_Flatten \ + (PyArrayObject *, NPY_ORDER); +NPY_NO_EXPORT PyObject * PyArray_Ravel \ + (PyArrayObject *, NPY_ORDER); +NPY_NO_EXPORT npy_intp PyArray_MultiplyList \ + (npy_intp *, int); +NPY_NO_EXPORT int PyArray_MultiplyIntList \ + (int *, int); +NPY_NO_EXPORT void * PyArray_GetPtr \ + (PyArrayObject *, npy_intp*); +NPY_NO_EXPORT int PyArray_CompareLists \ + (npy_intp *, npy_intp *, int); +NPY_NO_EXPORT int PyArray_AsCArray \ + (PyObject **, void *, npy_intp *, int, PyArray_Descr*); +NPY_NO_EXPORT int PyArray_As1D \ + (PyObject **, char **, int *, int); +NPY_NO_EXPORT int PyArray_As2D \ + (PyObject **, char ***, int *, int *, int); +NPY_NO_EXPORT int PyArray_Free \ + (PyObject *, void *); +NPY_NO_EXPORT int PyArray_Converter \ + (PyObject *, PyObject **); +NPY_NO_EXPORT int PyArray_IntpFromSequence \ + (PyObject *, npy_intp *, int); +NPY_NO_EXPORT PyObject * PyArray_Concatenate \ + (PyObject *, int); +NPY_NO_EXPORT PyObject * PyArray_InnerProduct \ + (PyObject *, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_MatrixProduct \ + (PyObject *, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_CopyAndTranspose \ + (PyObject *); +NPY_NO_EXPORT PyObject * PyArray_Correlate \ + (PyObject *, PyObject *, int); +NPY_NO_EXPORT int PyArray_TypestrConvert \ + (int, int); +NPY_NO_EXPORT int PyArray_DescrConverter \ + (PyObject *, PyArray_Descr **); +NPY_NO_EXPORT int PyArray_DescrConverter2 \ + (PyObject *, PyArray_Descr **); +NPY_NO_EXPORT int PyArray_IntpConverter \ + (PyObject *, PyArray_Dims *); +NPY_NO_EXPORT int PyArray_BufferConverter \ + (PyObject *, PyArray_Chunk *); +NPY_NO_EXPORT int PyArray_AxisConverter \ + (PyObject *, int *); +NPY_NO_EXPORT int PyArray_BoolConverter \ + (PyObject *, npy_bool *); +NPY_NO_EXPORT int PyArray_ByteorderConverter \ + (PyObject *, char *); +NPY_NO_EXPORT int PyArray_OrderConverter \ + (PyObject *, NPY_ORDER *); +NPY_NO_EXPORT unsigned char PyArray_EquivTypes \ + (PyArray_Descr *, PyArray_Descr *); +NPY_NO_EXPORT PyObject * PyArray_Zeros \ + (int, npy_intp *, PyArray_Descr *, int); +NPY_NO_EXPORT PyObject * PyArray_Empty \ + (int, npy_intp *, PyArray_Descr *, int); +NPY_NO_EXPORT PyObject * PyArray_Where \ + (PyObject *, PyObject *, PyObject *); +NPY_NO_EXPORT PyObject * PyArray_Arange \ + (double, double, double, int); +NPY_NO_EXPORT PyObject * PyArray_ArangeObj \ + (PyObject *, PyObject *, PyObject *, PyArray_Descr *); +NPY_NO_EXPORT int PyArray_SortkindConverter \ + (PyObject *, NPY_SORTKIND *); +NPY_NO_EXPORT PyObject * PyArray_LexSort \ + (PyObject *, int); +NPY_NO_EXPORT PyObject * PyArray_Round \ + (PyArrayObject *, int, PyArrayObject *); +NPY_NO_EXPORT unsigned char PyArray_EquivTypenums \ + (int, int); +NPY_NO_EXPORT int PyArray_RegisterDataType \ + (PyArray_Descr *); +NPY_NO_EXPORT int PyArray_RegisterCastFunc \ + (PyArray_Descr *, int, PyArray_VectorUnaryFunc *); +NPY_NO_EXPORT int PyArray_RegisterCanCast \ + (PyArray_Descr *, int, NPY_SCALARKIND); +NPY_NO_EXPORT void PyArray_InitArrFuncs \ + (PyArray_ArrFuncs *); +NPY_NO_EXPORT PyObject * PyArray_IntTupleFromIntp \ + (int, npy_intp *); +NPY_NO_EXPORT int PyArray_TypeNumFromName \ + (char *); +NPY_NO_EXPORT int PyArray_ClipmodeConverter \ + (PyObject *, NPY_CLIPMODE *); +NPY_NO_EXPORT int PyArray_OutputConverter \ + (PyObject *, PyArrayObject **); +NPY_NO_EXPORT PyObject * PyArray_BroadcastToShape \ + (PyObject *, npy_intp *, int); +NPY_NO_EXPORT void _PyArray_SigintHandler \ + (int); +NPY_NO_EXPORT void* _PyArray_GetSigintBuf \ + (void); +NPY_NO_EXPORT int PyArray_DescrAlignConverter \ + (PyObject *, PyArray_Descr **); +NPY_NO_EXPORT int PyArray_DescrAlignConverter2 \ + (PyObject *, PyArray_Descr **); +NPY_NO_EXPORT int PyArray_SearchsideConverter \ + (PyObject *, void *); +NPY_NO_EXPORT PyObject * PyArray_CheckAxis \ + (PyArrayObject *, int *, int); +NPY_NO_EXPORT npy_intp PyArray_OverflowMultiplyList \ + (npy_intp *, int); +NPY_NO_EXPORT int PyArray_CompareString \ + (char *, char *, size_t); +NPY_NO_EXPORT PyObject * PyArray_MultiIterFromObjects \ + (PyObject **, int, int, ...); +NPY_NO_EXPORT int PyArray_GetEndianness \ + (void); +NPY_NO_EXPORT unsigned int PyArray_GetNDArrayCFeatureVersion \ + (void); +NPY_NO_EXPORT PyObject * PyArray_Correlate2 \ + (PyObject *, PyObject *, int); +NPY_NO_EXPORT PyObject* PyArray_NeighborhoodIterNew \ + (PyArrayIterObject *, npy_intp *, int, PyArrayObject*); +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyTimeIntegerArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyTimeIntegerArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyDatetimeArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyDatetimeArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyTimedeltaArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyTimedeltaArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyHalfArrType_Type; +#else + NPY_NO_EXPORT PyTypeObject PyHalfArrType_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject NpyIter_Type; +#else + NPY_NO_EXPORT PyTypeObject NpyIter_Type; +#endif + +NPY_NO_EXPORT void PyArray_SetDatetimeParseFunction \ + (PyObject *); +NPY_NO_EXPORT void PyArray_DatetimeToDatetimeStruct \ + (npy_datetime, NPY_DATETIMEUNIT, npy_datetimestruct *); +NPY_NO_EXPORT void PyArray_TimedeltaToTimedeltaStruct \ + (npy_timedelta, NPY_DATETIMEUNIT, npy_timedeltastruct *); +NPY_NO_EXPORT npy_datetime PyArray_DatetimeStructToDatetime \ + (NPY_DATETIMEUNIT, npy_datetimestruct *); +NPY_NO_EXPORT npy_datetime PyArray_TimedeltaStructToTimedelta \ + (NPY_DATETIMEUNIT, npy_timedeltastruct *); +NPY_NO_EXPORT NpyIter * NpyIter_New \ + (PyArrayObject *, npy_uint32, NPY_ORDER, NPY_CASTING, PyArray_Descr*); +NPY_NO_EXPORT NpyIter * NpyIter_MultiNew \ + (int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **); +NPY_NO_EXPORT NpyIter * NpyIter_AdvancedNew \ + (int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **, int, int **, npy_intp *, npy_intp); +NPY_NO_EXPORT NpyIter * NpyIter_Copy \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_Deallocate \ + (NpyIter *); +NPY_NO_EXPORT npy_bool NpyIter_HasDelayedBufAlloc \ + (NpyIter *); +NPY_NO_EXPORT npy_bool NpyIter_HasExternalLoop \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_EnableExternalLoop \ + (NpyIter *); +NPY_NO_EXPORT npy_intp * NpyIter_GetInnerStrideArray \ + (NpyIter *); +NPY_NO_EXPORT npy_intp * NpyIter_GetInnerLoopSizePtr \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_Reset \ + (NpyIter *, char **); +NPY_NO_EXPORT int NpyIter_ResetBasePointers \ + (NpyIter *, char **, char **); +NPY_NO_EXPORT int NpyIter_ResetToIterIndexRange \ + (NpyIter *, npy_intp, npy_intp, char **); +NPY_NO_EXPORT int NpyIter_GetNDim \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_GetNOp \ + (NpyIter *); +NPY_NO_EXPORT NpyIter_IterNextFunc * NpyIter_GetIterNext \ + (NpyIter *, char **); +NPY_NO_EXPORT npy_intp NpyIter_GetIterSize \ + (NpyIter *); +NPY_NO_EXPORT void NpyIter_GetIterIndexRange \ + (NpyIter *, npy_intp *, npy_intp *); +NPY_NO_EXPORT npy_intp NpyIter_GetIterIndex \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_GotoIterIndex \ + (NpyIter *, npy_intp); +NPY_NO_EXPORT npy_bool NpyIter_HasMultiIndex \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_GetShape \ + (NpyIter *, npy_intp *); +NPY_NO_EXPORT NpyIter_GetMultiIndexFunc * NpyIter_GetGetMultiIndex \ + (NpyIter *, char **); +NPY_NO_EXPORT int NpyIter_GotoMultiIndex \ + (NpyIter *, npy_intp *); +NPY_NO_EXPORT int NpyIter_RemoveMultiIndex \ + (NpyIter *); +NPY_NO_EXPORT npy_bool NpyIter_HasIndex \ + (NpyIter *); +NPY_NO_EXPORT npy_bool NpyIter_IsBuffered \ + (NpyIter *); +NPY_NO_EXPORT npy_bool NpyIter_IsGrowInner \ + (NpyIter *); +NPY_NO_EXPORT npy_intp NpyIter_GetBufferSize \ + (NpyIter *); +NPY_NO_EXPORT npy_intp * NpyIter_GetIndexPtr \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_GotoIndex \ + (NpyIter *, npy_intp); +NPY_NO_EXPORT char ** NpyIter_GetDataPtrArray \ + (NpyIter *); +NPY_NO_EXPORT PyArray_Descr ** NpyIter_GetDescrArray \ + (NpyIter *); +NPY_NO_EXPORT PyArrayObject ** NpyIter_GetOperandArray \ + (NpyIter *); +NPY_NO_EXPORT PyArrayObject * NpyIter_GetIterView \ + (NpyIter *, npy_intp); +NPY_NO_EXPORT void NpyIter_GetReadFlags \ + (NpyIter *, char *); +NPY_NO_EXPORT void NpyIter_GetWriteFlags \ + (NpyIter *, char *); +NPY_NO_EXPORT void NpyIter_DebugPrint \ + (NpyIter *); +NPY_NO_EXPORT npy_bool NpyIter_IterationNeedsAPI \ + (NpyIter *); +NPY_NO_EXPORT void NpyIter_GetInnerFixedStrideArray \ + (NpyIter *, npy_intp *); +NPY_NO_EXPORT int NpyIter_RemoveAxis \ + (NpyIter *, int); +NPY_NO_EXPORT npy_intp * NpyIter_GetAxisStrideArray \ + (NpyIter *, int); +NPY_NO_EXPORT npy_bool NpyIter_RequiresBuffering \ + (NpyIter *); +NPY_NO_EXPORT char ** NpyIter_GetInitialDataPtrArray \ + (NpyIter *); +NPY_NO_EXPORT int NpyIter_CreateCompatibleStrides \ + (NpyIter *, npy_intp, npy_intp *); +NPY_NO_EXPORT int PyArray_CastingConverter \ + (PyObject *, NPY_CASTING *); +NPY_NO_EXPORT npy_intp PyArray_CountNonzero \ + (PyArrayObject *); +NPY_NO_EXPORT PyArray_Descr * PyArray_PromoteTypes \ + (PyArray_Descr *, PyArray_Descr *); +NPY_NO_EXPORT PyArray_Descr * PyArray_MinScalarType \ + (PyArrayObject *); +NPY_NO_EXPORT PyArray_Descr * PyArray_ResultType \ + (npy_intp, PyArrayObject **, npy_intp, PyArray_Descr **); +NPY_NO_EXPORT npy_bool PyArray_CanCastArrayTo \ + (PyArrayObject *, PyArray_Descr *, NPY_CASTING); +NPY_NO_EXPORT npy_bool PyArray_CanCastTypeTo \ + (PyArray_Descr *, PyArray_Descr *, NPY_CASTING); +NPY_NO_EXPORT PyArrayObject * PyArray_EinsteinSum \ + (char *, npy_intp, PyArrayObject **, PyArray_Descr *, NPY_ORDER, NPY_CASTING, PyArrayObject *); +NPY_NO_EXPORT PyObject * PyArray_NewLikeArray \ + (PyArrayObject *, NPY_ORDER, PyArray_Descr *, int); +NPY_NO_EXPORT int PyArray_GetArrayParamsFromObject \ + (PyObject *, PyArray_Descr *, npy_bool, PyArray_Descr **, int *, npy_intp *, PyArrayObject **, PyObject *); +NPY_NO_EXPORT int PyArray_ConvertClipmodeSequence \ + (PyObject *, NPY_CLIPMODE *, int); +NPY_NO_EXPORT PyObject * PyArray_MatrixProduct2 \ + (PyObject *, PyObject *, PyArrayObject*); +NPY_NO_EXPORT npy_bool NpyIter_IsFirstVisit \ + (NpyIter *, int); +NPY_NO_EXPORT int PyArray_SetBaseObject \ + (PyArrayObject *, PyObject *); +NPY_NO_EXPORT void PyArray_CreateSortedStridePerm \ + (int, npy_intp *, npy_stride_sort_item *); +NPY_NO_EXPORT void PyArray_RemoveAxesInPlace \ + (PyArrayObject *, npy_bool *); +NPY_NO_EXPORT void PyArray_DebugPrint \ + (PyArrayObject *); +NPY_NO_EXPORT int PyArray_FailUnlessWriteable \ + (PyArrayObject *, const char *); +NPY_NO_EXPORT int PyArray_SetUpdateIfCopyBase \ + (PyArrayObject *, PyArrayObject *); +NPY_NO_EXPORT void * PyDataMem_NEW \ + (size_t); +NPY_NO_EXPORT void PyDataMem_FREE \ + (void *); +NPY_NO_EXPORT void * PyDataMem_RENEW \ + (void *, size_t); +NPY_NO_EXPORT PyDataMem_EventHookFunc * PyDataMem_SetEventHook \ + (PyDataMem_EventHookFunc *, void *, void **); +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT NPY_CASTING NPY_DEFAULT_ASSIGN_CASTING; +#else + NPY_NO_EXPORT NPY_CASTING NPY_DEFAULT_ASSIGN_CASTING; +#endif + +NPY_NO_EXPORT void PyArray_MapIterSwapAxes \ + (PyArrayMapIterObject *, PyArrayObject **, int); +NPY_NO_EXPORT PyObject * PyArray_MapIterArray \ + (PyArrayObject *, PyObject *); +NPY_NO_EXPORT void PyArray_MapIterNext \ + (PyArrayMapIterObject *); +NPY_NO_EXPORT int PyArray_Partition \ + (PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND); +NPY_NO_EXPORT PyObject * PyArray_ArgPartition \ + (PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND); +NPY_NO_EXPORT int PyArray_SelectkindConverter \ + (PyObject *, NPY_SELECTKIND *); +NPY_NO_EXPORT void * PyDataMem_NEW_ZEROED \ + (size_t, size_t); + +#else + +#if defined(PY_ARRAY_UNIQUE_SYMBOL) +#define PyArray_API PY_ARRAY_UNIQUE_SYMBOL +#endif + +#if defined(NO_IMPORT) || defined(NO_IMPORT_ARRAY) +extern void **PyArray_API; +#else +#if defined(PY_ARRAY_UNIQUE_SYMBOL) +void **PyArray_API; +#else +static void **PyArray_API=NULL; +#endif +#endif + +#define PyArray_GetNDArrayCVersion \ + (*(unsigned int (*)(void)) \ + PyArray_API[0]) +#define PyBigArray_Type (*(PyTypeObject *)PyArray_API[1]) +#define PyArray_Type (*(PyTypeObject *)PyArray_API[2]) +#define PyArrayDescr_Type (*(PyTypeObject *)PyArray_API[3]) +#define PyArrayFlags_Type (*(PyTypeObject *)PyArray_API[4]) +#define PyArrayIter_Type (*(PyTypeObject *)PyArray_API[5]) +#define PyArrayMultiIter_Type (*(PyTypeObject *)PyArray_API[6]) +#define NPY_NUMUSERTYPES (*(int *)PyArray_API[7]) +#define PyBoolArrType_Type (*(PyTypeObject *)PyArray_API[8]) +#define _PyArrayScalar_BoolValues ((PyBoolScalarObject *)PyArray_API[9]) +#define PyGenericArrType_Type (*(PyTypeObject *)PyArray_API[10]) +#define PyNumberArrType_Type (*(PyTypeObject *)PyArray_API[11]) +#define PyIntegerArrType_Type (*(PyTypeObject *)PyArray_API[12]) +#define PySignedIntegerArrType_Type (*(PyTypeObject *)PyArray_API[13]) +#define PyUnsignedIntegerArrType_Type (*(PyTypeObject *)PyArray_API[14]) +#define PyInexactArrType_Type (*(PyTypeObject *)PyArray_API[15]) +#define PyFloatingArrType_Type (*(PyTypeObject *)PyArray_API[16]) +#define PyComplexFloatingArrType_Type (*(PyTypeObject *)PyArray_API[17]) +#define PyFlexibleArrType_Type (*(PyTypeObject *)PyArray_API[18]) +#define PyCharacterArrType_Type (*(PyTypeObject *)PyArray_API[19]) +#define PyByteArrType_Type (*(PyTypeObject *)PyArray_API[20]) +#define PyShortArrType_Type (*(PyTypeObject *)PyArray_API[21]) +#define PyIntArrType_Type (*(PyTypeObject *)PyArray_API[22]) +#define PyLongArrType_Type (*(PyTypeObject *)PyArray_API[23]) +#define PyLongLongArrType_Type (*(PyTypeObject *)PyArray_API[24]) +#define PyUByteArrType_Type (*(PyTypeObject *)PyArray_API[25]) +#define PyUShortArrType_Type (*(PyTypeObject *)PyArray_API[26]) +#define PyUIntArrType_Type (*(PyTypeObject *)PyArray_API[27]) +#define PyULongArrType_Type (*(PyTypeObject *)PyArray_API[28]) +#define PyULongLongArrType_Type (*(PyTypeObject *)PyArray_API[29]) +#define PyFloatArrType_Type (*(PyTypeObject *)PyArray_API[30]) +#define PyDoubleArrType_Type (*(PyTypeObject *)PyArray_API[31]) +#define PyLongDoubleArrType_Type (*(PyTypeObject *)PyArray_API[32]) +#define PyCFloatArrType_Type (*(PyTypeObject *)PyArray_API[33]) +#define PyCDoubleArrType_Type (*(PyTypeObject *)PyArray_API[34]) +#define PyCLongDoubleArrType_Type (*(PyTypeObject *)PyArray_API[35]) +#define PyObjectArrType_Type (*(PyTypeObject *)PyArray_API[36]) +#define PyStringArrType_Type (*(PyTypeObject *)PyArray_API[37]) +#define PyUnicodeArrType_Type (*(PyTypeObject *)PyArray_API[38]) +#define PyVoidArrType_Type (*(PyTypeObject *)PyArray_API[39]) +#define PyArray_SetNumericOps \ + (*(int (*)(PyObject *)) \ + PyArray_API[40]) +#define PyArray_GetNumericOps \ + (*(PyObject * (*)(void)) \ + PyArray_API[41]) +#define PyArray_INCREF \ + (*(int (*)(PyArrayObject *)) \ + PyArray_API[42]) +#define PyArray_XDECREF \ + (*(int (*)(PyArrayObject *)) \ + PyArray_API[43]) +#define PyArray_SetStringFunction \ + (*(void (*)(PyObject *, int)) \ + PyArray_API[44]) +#define PyArray_DescrFromType \ + (*(PyArray_Descr * (*)(int)) \ + PyArray_API[45]) +#define PyArray_TypeObjectFromType \ + (*(PyObject * (*)(int)) \ + PyArray_API[46]) +#define PyArray_Zero \ + (*(char * (*)(PyArrayObject *)) \ + PyArray_API[47]) +#define PyArray_One \ + (*(char * (*)(PyArrayObject *)) \ + PyArray_API[48]) +#define PyArray_CastToType \ + (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, int)) \ + PyArray_API[49]) +#define PyArray_CastTo \ + (*(int (*)(PyArrayObject *, PyArrayObject *)) \ + PyArray_API[50]) +#define PyArray_CastAnyTo \ + (*(int (*)(PyArrayObject *, PyArrayObject *)) \ + PyArray_API[51]) +#define PyArray_CanCastSafely \ + (*(int (*)(int, int)) \ + PyArray_API[52]) +#define PyArray_CanCastTo \ + (*(npy_bool (*)(PyArray_Descr *, PyArray_Descr *)) \ + PyArray_API[53]) +#define PyArray_ObjectType \ + (*(int (*)(PyObject *, int)) \ + PyArray_API[54]) +#define PyArray_DescrFromObject \ + (*(PyArray_Descr * (*)(PyObject *, PyArray_Descr *)) \ + PyArray_API[55]) +#define PyArray_ConvertToCommonType \ + (*(PyArrayObject ** (*)(PyObject *, int *)) \ + PyArray_API[56]) +#define PyArray_DescrFromScalar \ + (*(PyArray_Descr * (*)(PyObject *)) \ + PyArray_API[57]) +#define PyArray_DescrFromTypeObject \ + (*(PyArray_Descr * (*)(PyObject *)) \ + PyArray_API[58]) +#define PyArray_Size \ + (*(npy_intp (*)(PyObject *)) \ + PyArray_API[59]) +#define PyArray_Scalar \ + (*(PyObject * (*)(void *, PyArray_Descr *, PyObject *)) \ + PyArray_API[60]) +#define PyArray_FromScalar \ + (*(PyObject * (*)(PyObject *, PyArray_Descr *)) \ + PyArray_API[61]) +#define PyArray_ScalarAsCtype \ + (*(void (*)(PyObject *, void *)) \ + PyArray_API[62]) +#define PyArray_CastScalarToCtype \ + (*(int (*)(PyObject *, void *, PyArray_Descr *)) \ + PyArray_API[63]) +#define PyArray_CastScalarDirect \ + (*(int (*)(PyObject *, PyArray_Descr *, void *, int)) \ + PyArray_API[64]) +#define PyArray_ScalarFromObject \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[65]) +#define PyArray_GetCastFunc \ + (*(PyArray_VectorUnaryFunc * (*)(PyArray_Descr *, int)) \ + PyArray_API[66]) +#define PyArray_FromDims \ + (*(PyObject * (*)(int, int *, int)) \ + PyArray_API[67]) +#define PyArray_FromDimsAndDataAndDescr \ + (*(PyObject * (*)(int, int *, PyArray_Descr *, char *)) \ + PyArray_API[68]) +#define PyArray_FromAny \ + (*(PyObject * (*)(PyObject *, PyArray_Descr *, int, int, int, PyObject *)) \ + PyArray_API[69]) +#define PyArray_EnsureArray \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[70]) +#define PyArray_EnsureAnyArray \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[71]) +#define PyArray_FromFile \ + (*(PyObject * (*)(FILE *, PyArray_Descr *, npy_intp, char *)) \ + PyArray_API[72]) +#define PyArray_FromString \ + (*(PyObject * (*)(char *, npy_intp, PyArray_Descr *, npy_intp, char *)) \ + PyArray_API[73]) +#define PyArray_FromBuffer \ + (*(PyObject * (*)(PyObject *, PyArray_Descr *, npy_intp, npy_intp)) \ + PyArray_API[74]) +#define PyArray_FromIter \ + (*(PyObject * (*)(PyObject *, PyArray_Descr *, npy_intp)) \ + PyArray_API[75]) +#define PyArray_Return \ + (*(PyObject * (*)(PyArrayObject *)) \ + PyArray_API[76]) +#define PyArray_GetField \ + (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, int)) \ + PyArray_API[77]) +#define PyArray_SetField \ + (*(int (*)(PyArrayObject *, PyArray_Descr *, int, PyObject *)) \ + PyArray_API[78]) +#define PyArray_Byteswap \ + (*(PyObject * (*)(PyArrayObject *, npy_bool)) \ + PyArray_API[79]) +#define PyArray_Resize \ + (*(PyObject * (*)(PyArrayObject *, PyArray_Dims *, int, NPY_ORDER)) \ + PyArray_API[80]) +#define PyArray_MoveInto \ + (*(int (*)(PyArrayObject *, PyArrayObject *)) \ + PyArray_API[81]) +#define PyArray_CopyInto \ + (*(int (*)(PyArrayObject *, PyArrayObject *)) \ + PyArray_API[82]) +#define PyArray_CopyAnyInto \ + (*(int (*)(PyArrayObject *, PyArrayObject *)) \ + PyArray_API[83]) +#define PyArray_CopyObject \ + (*(int (*)(PyArrayObject *, PyObject *)) \ + PyArray_API[84]) +#define PyArray_NewCopy \ + (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ + PyArray_API[85]) +#define PyArray_ToList \ + (*(PyObject * (*)(PyArrayObject *)) \ + PyArray_API[86]) +#define PyArray_ToString \ + (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ + PyArray_API[87]) +#define PyArray_ToFile \ + (*(int (*)(PyArrayObject *, FILE *, char *, char *)) \ + PyArray_API[88]) +#define PyArray_Dump \ + (*(int (*)(PyObject *, PyObject *, int)) \ + PyArray_API[89]) +#define PyArray_Dumps \ + (*(PyObject * (*)(PyObject *, int)) \ + PyArray_API[90]) +#define PyArray_ValidType \ + (*(int (*)(int)) \ + PyArray_API[91]) +#define PyArray_UpdateFlags \ + (*(void (*)(PyArrayObject *, int)) \ + PyArray_API[92]) +#define PyArray_New \ + (*(PyObject * (*)(PyTypeObject *, int, npy_intp *, int, npy_intp *, void *, int, int, PyObject *)) \ + PyArray_API[93]) +#define PyArray_NewFromDescr \ + (*(PyObject * (*)(PyTypeObject *, PyArray_Descr *, int, npy_intp *, npy_intp *, void *, int, PyObject *)) \ + PyArray_API[94]) +#define PyArray_DescrNew \ + (*(PyArray_Descr * (*)(PyArray_Descr *)) \ + PyArray_API[95]) +#define PyArray_DescrNewFromType \ + (*(PyArray_Descr * (*)(int)) \ + PyArray_API[96]) +#define PyArray_GetPriority \ + (*(double (*)(PyObject *, double)) \ + PyArray_API[97]) +#define PyArray_IterNew \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[98]) +#define PyArray_MultiIterNew \ + (*(PyObject * (*)(int, ...)) \ + PyArray_API[99]) +#define PyArray_PyIntAsInt \ + (*(int (*)(PyObject *)) \ + PyArray_API[100]) +#define PyArray_PyIntAsIntp \ + (*(npy_intp (*)(PyObject *)) \ + PyArray_API[101]) +#define PyArray_Broadcast \ + (*(int (*)(PyArrayMultiIterObject *)) \ + PyArray_API[102]) +#define PyArray_FillObjectArray \ + (*(void (*)(PyArrayObject *, PyObject *)) \ + PyArray_API[103]) +#define PyArray_FillWithScalar \ + (*(int (*)(PyArrayObject *, PyObject *)) \ + PyArray_API[104]) +#define PyArray_CheckStrides \ + (*(npy_bool (*)(int, int, npy_intp, npy_intp, npy_intp *, npy_intp *)) \ + PyArray_API[105]) +#define PyArray_DescrNewByteorder \ + (*(PyArray_Descr * (*)(PyArray_Descr *, char)) \ + PyArray_API[106]) +#define PyArray_IterAllButAxis \ + (*(PyObject * (*)(PyObject *, int *)) \ + PyArray_API[107]) +#define PyArray_CheckFromAny \ + (*(PyObject * (*)(PyObject *, PyArray_Descr *, int, int, int, PyObject *)) \ + PyArray_API[108]) +#define PyArray_FromArray \ + (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, int)) \ + PyArray_API[109]) +#define PyArray_FromInterface \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[110]) +#define PyArray_FromStructInterface \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[111]) +#define PyArray_FromArrayAttr \ + (*(PyObject * (*)(PyObject *, PyArray_Descr *, PyObject *)) \ + PyArray_API[112]) +#define PyArray_ScalarKind \ + (*(NPY_SCALARKIND (*)(int, PyArrayObject **)) \ + PyArray_API[113]) +#define PyArray_CanCoerceScalar \ + (*(int (*)(int, int, NPY_SCALARKIND)) \ + PyArray_API[114]) +#define PyArray_NewFlagsObject \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[115]) +#define PyArray_CanCastScalar \ + (*(npy_bool (*)(PyTypeObject *, PyTypeObject *)) \ + PyArray_API[116]) +#define PyArray_CompareUCS4 \ + (*(int (*)(npy_ucs4 *, npy_ucs4 *, size_t)) \ + PyArray_API[117]) +#define PyArray_RemoveSmallest \ + (*(int (*)(PyArrayMultiIterObject *)) \ + PyArray_API[118]) +#define PyArray_ElementStrides \ + (*(int (*)(PyObject *)) \ + PyArray_API[119]) +#define PyArray_Item_INCREF \ + (*(void (*)(char *, PyArray_Descr *)) \ + PyArray_API[120]) +#define PyArray_Item_XDECREF \ + (*(void (*)(char *, PyArray_Descr *)) \ + PyArray_API[121]) +#define PyArray_FieldNames \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[122]) +#define PyArray_Transpose \ + (*(PyObject * (*)(PyArrayObject *, PyArray_Dims *)) \ + PyArray_API[123]) +#define PyArray_TakeFrom \ + (*(PyObject * (*)(PyArrayObject *, PyObject *, int, PyArrayObject *, NPY_CLIPMODE)) \ + PyArray_API[124]) +#define PyArray_PutTo \ + (*(PyObject * (*)(PyArrayObject *, PyObject*, PyObject *, NPY_CLIPMODE)) \ + PyArray_API[125]) +#define PyArray_PutMask \ + (*(PyObject * (*)(PyArrayObject *, PyObject*, PyObject*)) \ + PyArray_API[126]) +#define PyArray_Repeat \ + (*(PyObject * (*)(PyArrayObject *, PyObject *, int)) \ + PyArray_API[127]) +#define PyArray_Choose \ + (*(PyObject * (*)(PyArrayObject *, PyObject *, PyArrayObject *, NPY_CLIPMODE)) \ + PyArray_API[128]) +#define PyArray_Sort \ + (*(int (*)(PyArrayObject *, int, NPY_SORTKIND)) \ + PyArray_API[129]) +#define PyArray_ArgSort \ + (*(PyObject * (*)(PyArrayObject *, int, NPY_SORTKIND)) \ + PyArray_API[130]) +#define PyArray_SearchSorted \ + (*(PyObject * (*)(PyArrayObject *, PyObject *, NPY_SEARCHSIDE, PyObject *)) \ + PyArray_API[131]) +#define PyArray_ArgMax \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[132]) +#define PyArray_ArgMin \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[133]) +#define PyArray_Reshape \ + (*(PyObject * (*)(PyArrayObject *, PyObject *)) \ + PyArray_API[134]) +#define PyArray_Newshape \ + (*(PyObject * (*)(PyArrayObject *, PyArray_Dims *, NPY_ORDER)) \ + PyArray_API[135]) +#define PyArray_Squeeze \ + (*(PyObject * (*)(PyArrayObject *)) \ + PyArray_API[136]) +#define PyArray_View \ + (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, PyTypeObject *)) \ + PyArray_API[137]) +#define PyArray_SwapAxes \ + (*(PyObject * (*)(PyArrayObject *, int, int)) \ + PyArray_API[138]) +#define PyArray_Max \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[139]) +#define PyArray_Min \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[140]) +#define PyArray_Ptp \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[141]) +#define PyArray_Mean \ + (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ + PyArray_API[142]) +#define PyArray_Trace \ + (*(PyObject * (*)(PyArrayObject *, int, int, int, int, PyArrayObject *)) \ + PyArray_API[143]) +#define PyArray_Diagonal \ + (*(PyObject * (*)(PyArrayObject *, int, int, int)) \ + PyArray_API[144]) +#define PyArray_Clip \ + (*(PyObject * (*)(PyArrayObject *, PyObject *, PyObject *, PyArrayObject *)) \ + PyArray_API[145]) +#define PyArray_Conjugate \ + (*(PyObject * (*)(PyArrayObject *, PyArrayObject *)) \ + PyArray_API[146]) +#define PyArray_Nonzero \ + (*(PyObject * (*)(PyArrayObject *)) \ + PyArray_API[147]) +#define PyArray_Std \ + (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *, int)) \ + PyArray_API[148]) +#define PyArray_Sum \ + (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ + PyArray_API[149]) +#define PyArray_CumSum \ + (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ + PyArray_API[150]) +#define PyArray_Prod \ + (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ + PyArray_API[151]) +#define PyArray_CumProd \ + (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ + PyArray_API[152]) +#define PyArray_All \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[153]) +#define PyArray_Any \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[154]) +#define PyArray_Compress \ + (*(PyObject * (*)(PyArrayObject *, PyObject *, int, PyArrayObject *)) \ + PyArray_API[155]) +#define PyArray_Flatten \ + (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ + PyArray_API[156]) +#define PyArray_Ravel \ + (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ + PyArray_API[157]) +#define PyArray_MultiplyList \ + (*(npy_intp (*)(npy_intp *, int)) \ + PyArray_API[158]) +#define PyArray_MultiplyIntList \ + (*(int (*)(int *, int)) \ + PyArray_API[159]) +#define PyArray_GetPtr \ + (*(void * (*)(PyArrayObject *, npy_intp*)) \ + PyArray_API[160]) +#define PyArray_CompareLists \ + (*(int (*)(npy_intp *, npy_intp *, int)) \ + PyArray_API[161]) +#define PyArray_AsCArray \ + (*(int (*)(PyObject **, void *, npy_intp *, int, PyArray_Descr*)) \ + PyArray_API[162]) +#define PyArray_As1D \ + (*(int (*)(PyObject **, char **, int *, int)) \ + PyArray_API[163]) +#define PyArray_As2D \ + (*(int (*)(PyObject **, char ***, int *, int *, int)) \ + PyArray_API[164]) +#define PyArray_Free \ + (*(int (*)(PyObject *, void *)) \ + PyArray_API[165]) +#define PyArray_Converter \ + (*(int (*)(PyObject *, PyObject **)) \ + PyArray_API[166]) +#define PyArray_IntpFromSequence \ + (*(int (*)(PyObject *, npy_intp *, int)) \ + PyArray_API[167]) +#define PyArray_Concatenate \ + (*(PyObject * (*)(PyObject *, int)) \ + PyArray_API[168]) +#define PyArray_InnerProduct \ + (*(PyObject * (*)(PyObject *, PyObject *)) \ + PyArray_API[169]) +#define PyArray_MatrixProduct \ + (*(PyObject * (*)(PyObject *, PyObject *)) \ + PyArray_API[170]) +#define PyArray_CopyAndTranspose \ + (*(PyObject * (*)(PyObject *)) \ + PyArray_API[171]) +#define PyArray_Correlate \ + (*(PyObject * (*)(PyObject *, PyObject *, int)) \ + PyArray_API[172]) +#define PyArray_TypestrConvert \ + (*(int (*)(int, int)) \ + PyArray_API[173]) +#define PyArray_DescrConverter \ + (*(int (*)(PyObject *, PyArray_Descr **)) \ + PyArray_API[174]) +#define PyArray_DescrConverter2 \ + (*(int (*)(PyObject *, PyArray_Descr **)) \ + PyArray_API[175]) +#define PyArray_IntpConverter \ + (*(int (*)(PyObject *, PyArray_Dims *)) \ + PyArray_API[176]) +#define PyArray_BufferConverter \ + (*(int (*)(PyObject *, PyArray_Chunk *)) \ + PyArray_API[177]) +#define PyArray_AxisConverter \ + (*(int (*)(PyObject *, int *)) \ + PyArray_API[178]) +#define PyArray_BoolConverter \ + (*(int (*)(PyObject *, npy_bool *)) \ + PyArray_API[179]) +#define PyArray_ByteorderConverter \ + (*(int (*)(PyObject *, char *)) \ + PyArray_API[180]) +#define PyArray_OrderConverter \ + (*(int (*)(PyObject *, NPY_ORDER *)) \ + PyArray_API[181]) +#define PyArray_EquivTypes \ + (*(unsigned char (*)(PyArray_Descr *, PyArray_Descr *)) \ + PyArray_API[182]) +#define PyArray_Zeros \ + (*(PyObject * (*)(int, npy_intp *, PyArray_Descr *, int)) \ + PyArray_API[183]) +#define PyArray_Empty \ + (*(PyObject * (*)(int, npy_intp *, PyArray_Descr *, int)) \ + PyArray_API[184]) +#define PyArray_Where \ + (*(PyObject * (*)(PyObject *, PyObject *, PyObject *)) \ + PyArray_API[185]) +#define PyArray_Arange \ + (*(PyObject * (*)(double, double, double, int)) \ + PyArray_API[186]) +#define PyArray_ArangeObj \ + (*(PyObject * (*)(PyObject *, PyObject *, PyObject *, PyArray_Descr *)) \ + PyArray_API[187]) +#define PyArray_SortkindConverter \ + (*(int (*)(PyObject *, NPY_SORTKIND *)) \ + PyArray_API[188]) +#define PyArray_LexSort \ + (*(PyObject * (*)(PyObject *, int)) \ + PyArray_API[189]) +#define PyArray_Round \ + (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ + PyArray_API[190]) +#define PyArray_EquivTypenums \ + (*(unsigned char (*)(int, int)) \ + PyArray_API[191]) +#define PyArray_RegisterDataType \ + (*(int (*)(PyArray_Descr *)) \ + PyArray_API[192]) +#define PyArray_RegisterCastFunc \ + (*(int (*)(PyArray_Descr *, int, PyArray_VectorUnaryFunc *)) \ + PyArray_API[193]) +#define PyArray_RegisterCanCast \ + (*(int (*)(PyArray_Descr *, int, NPY_SCALARKIND)) \ + PyArray_API[194]) +#define PyArray_InitArrFuncs \ + (*(void (*)(PyArray_ArrFuncs *)) \ + PyArray_API[195]) +#define PyArray_IntTupleFromIntp \ + (*(PyObject * (*)(int, npy_intp *)) \ + PyArray_API[196]) +#define PyArray_TypeNumFromName \ + (*(int (*)(char *)) \ + PyArray_API[197]) +#define PyArray_ClipmodeConverter \ + (*(int (*)(PyObject *, NPY_CLIPMODE *)) \ + PyArray_API[198]) +#define PyArray_OutputConverter \ + (*(int (*)(PyObject *, PyArrayObject **)) \ + PyArray_API[199]) +#define PyArray_BroadcastToShape \ + (*(PyObject * (*)(PyObject *, npy_intp *, int)) \ + PyArray_API[200]) +#define _PyArray_SigintHandler \ + (*(void (*)(int)) \ + PyArray_API[201]) +#define _PyArray_GetSigintBuf \ + (*(void* (*)(void)) \ + PyArray_API[202]) +#define PyArray_DescrAlignConverter \ + (*(int (*)(PyObject *, PyArray_Descr **)) \ + PyArray_API[203]) +#define PyArray_DescrAlignConverter2 \ + (*(int (*)(PyObject *, PyArray_Descr **)) \ + PyArray_API[204]) +#define PyArray_SearchsideConverter \ + (*(int (*)(PyObject *, void *)) \ + PyArray_API[205]) +#define PyArray_CheckAxis \ + (*(PyObject * (*)(PyArrayObject *, int *, int)) \ + PyArray_API[206]) +#define PyArray_OverflowMultiplyList \ + (*(npy_intp (*)(npy_intp *, int)) \ + PyArray_API[207]) +#define PyArray_CompareString \ + (*(int (*)(char *, char *, size_t)) \ + PyArray_API[208]) +#define PyArray_MultiIterFromObjects \ + (*(PyObject * (*)(PyObject **, int, int, ...)) \ + PyArray_API[209]) +#define PyArray_GetEndianness \ + (*(int (*)(void)) \ + PyArray_API[210]) +#define PyArray_GetNDArrayCFeatureVersion \ + (*(unsigned int (*)(void)) \ + PyArray_API[211]) +#define PyArray_Correlate2 \ + (*(PyObject * (*)(PyObject *, PyObject *, int)) \ + PyArray_API[212]) +#define PyArray_NeighborhoodIterNew \ + (*(PyObject* (*)(PyArrayIterObject *, npy_intp *, int, PyArrayObject*)) \ + PyArray_API[213]) +#define PyTimeIntegerArrType_Type (*(PyTypeObject *)PyArray_API[214]) +#define PyDatetimeArrType_Type (*(PyTypeObject *)PyArray_API[215]) +#define PyTimedeltaArrType_Type (*(PyTypeObject *)PyArray_API[216]) +#define PyHalfArrType_Type (*(PyTypeObject *)PyArray_API[217]) +#define NpyIter_Type (*(PyTypeObject *)PyArray_API[218]) +#define PyArray_SetDatetimeParseFunction \ + (*(void (*)(PyObject *)) \ + PyArray_API[219]) +#define PyArray_DatetimeToDatetimeStruct \ + (*(void (*)(npy_datetime, NPY_DATETIMEUNIT, npy_datetimestruct *)) \ + PyArray_API[220]) +#define PyArray_TimedeltaToTimedeltaStruct \ + (*(void (*)(npy_timedelta, NPY_DATETIMEUNIT, npy_timedeltastruct *)) \ + PyArray_API[221]) +#define PyArray_DatetimeStructToDatetime \ + (*(npy_datetime (*)(NPY_DATETIMEUNIT, npy_datetimestruct *)) \ + PyArray_API[222]) +#define PyArray_TimedeltaStructToTimedelta \ + (*(npy_datetime (*)(NPY_DATETIMEUNIT, npy_timedeltastruct *)) \ + PyArray_API[223]) +#define NpyIter_New \ + (*(NpyIter * (*)(PyArrayObject *, npy_uint32, NPY_ORDER, NPY_CASTING, PyArray_Descr*)) \ + PyArray_API[224]) +#define NpyIter_MultiNew \ + (*(NpyIter * (*)(int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **)) \ + PyArray_API[225]) +#define NpyIter_AdvancedNew \ + (*(NpyIter * (*)(int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **, int, int **, npy_intp *, npy_intp)) \ + PyArray_API[226]) +#define NpyIter_Copy \ + (*(NpyIter * (*)(NpyIter *)) \ + PyArray_API[227]) +#define NpyIter_Deallocate \ + (*(int (*)(NpyIter *)) \ + PyArray_API[228]) +#define NpyIter_HasDelayedBufAlloc \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[229]) +#define NpyIter_HasExternalLoop \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[230]) +#define NpyIter_EnableExternalLoop \ + (*(int (*)(NpyIter *)) \ + PyArray_API[231]) +#define NpyIter_GetInnerStrideArray \ + (*(npy_intp * (*)(NpyIter *)) \ + PyArray_API[232]) +#define NpyIter_GetInnerLoopSizePtr \ + (*(npy_intp * (*)(NpyIter *)) \ + PyArray_API[233]) +#define NpyIter_Reset \ + (*(int (*)(NpyIter *, char **)) \ + PyArray_API[234]) +#define NpyIter_ResetBasePointers \ + (*(int (*)(NpyIter *, char **, char **)) \ + PyArray_API[235]) +#define NpyIter_ResetToIterIndexRange \ + (*(int (*)(NpyIter *, npy_intp, npy_intp, char **)) \ + PyArray_API[236]) +#define NpyIter_GetNDim \ + (*(int (*)(NpyIter *)) \ + PyArray_API[237]) +#define NpyIter_GetNOp \ + (*(int (*)(NpyIter *)) \ + PyArray_API[238]) +#define NpyIter_GetIterNext \ + (*(NpyIter_IterNextFunc * (*)(NpyIter *, char **)) \ + PyArray_API[239]) +#define NpyIter_GetIterSize \ + (*(npy_intp (*)(NpyIter *)) \ + PyArray_API[240]) +#define NpyIter_GetIterIndexRange \ + (*(void (*)(NpyIter *, npy_intp *, npy_intp *)) \ + PyArray_API[241]) +#define NpyIter_GetIterIndex \ + (*(npy_intp (*)(NpyIter *)) \ + PyArray_API[242]) +#define NpyIter_GotoIterIndex \ + (*(int (*)(NpyIter *, npy_intp)) \ + PyArray_API[243]) +#define NpyIter_HasMultiIndex \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[244]) +#define NpyIter_GetShape \ + (*(int (*)(NpyIter *, npy_intp *)) \ + PyArray_API[245]) +#define NpyIter_GetGetMultiIndex \ + (*(NpyIter_GetMultiIndexFunc * (*)(NpyIter *, char **)) \ + PyArray_API[246]) +#define NpyIter_GotoMultiIndex \ + (*(int (*)(NpyIter *, npy_intp *)) \ + PyArray_API[247]) +#define NpyIter_RemoveMultiIndex \ + (*(int (*)(NpyIter *)) \ + PyArray_API[248]) +#define NpyIter_HasIndex \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[249]) +#define NpyIter_IsBuffered \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[250]) +#define NpyIter_IsGrowInner \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[251]) +#define NpyIter_GetBufferSize \ + (*(npy_intp (*)(NpyIter *)) \ + PyArray_API[252]) +#define NpyIter_GetIndexPtr \ + (*(npy_intp * (*)(NpyIter *)) \ + PyArray_API[253]) +#define NpyIter_GotoIndex \ + (*(int (*)(NpyIter *, npy_intp)) \ + PyArray_API[254]) +#define NpyIter_GetDataPtrArray \ + (*(char ** (*)(NpyIter *)) \ + PyArray_API[255]) +#define NpyIter_GetDescrArray \ + (*(PyArray_Descr ** (*)(NpyIter *)) \ + PyArray_API[256]) +#define NpyIter_GetOperandArray \ + (*(PyArrayObject ** (*)(NpyIter *)) \ + PyArray_API[257]) +#define NpyIter_GetIterView \ + (*(PyArrayObject * (*)(NpyIter *, npy_intp)) \ + PyArray_API[258]) +#define NpyIter_GetReadFlags \ + (*(void (*)(NpyIter *, char *)) \ + PyArray_API[259]) +#define NpyIter_GetWriteFlags \ + (*(void (*)(NpyIter *, char *)) \ + PyArray_API[260]) +#define NpyIter_DebugPrint \ + (*(void (*)(NpyIter *)) \ + PyArray_API[261]) +#define NpyIter_IterationNeedsAPI \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[262]) +#define NpyIter_GetInnerFixedStrideArray \ + (*(void (*)(NpyIter *, npy_intp *)) \ + PyArray_API[263]) +#define NpyIter_RemoveAxis \ + (*(int (*)(NpyIter *, int)) \ + PyArray_API[264]) +#define NpyIter_GetAxisStrideArray \ + (*(npy_intp * (*)(NpyIter *, int)) \ + PyArray_API[265]) +#define NpyIter_RequiresBuffering \ + (*(npy_bool (*)(NpyIter *)) \ + PyArray_API[266]) +#define NpyIter_GetInitialDataPtrArray \ + (*(char ** (*)(NpyIter *)) \ + PyArray_API[267]) +#define NpyIter_CreateCompatibleStrides \ + (*(int (*)(NpyIter *, npy_intp, npy_intp *)) \ + PyArray_API[268]) +#define PyArray_CastingConverter \ + (*(int (*)(PyObject *, NPY_CASTING *)) \ + PyArray_API[269]) +#define PyArray_CountNonzero \ + (*(npy_intp (*)(PyArrayObject *)) \ + PyArray_API[270]) +#define PyArray_PromoteTypes \ + (*(PyArray_Descr * (*)(PyArray_Descr *, PyArray_Descr *)) \ + PyArray_API[271]) +#define PyArray_MinScalarType \ + (*(PyArray_Descr * (*)(PyArrayObject *)) \ + PyArray_API[272]) +#define PyArray_ResultType \ + (*(PyArray_Descr * (*)(npy_intp, PyArrayObject **, npy_intp, PyArray_Descr **)) \ + PyArray_API[273]) +#define PyArray_CanCastArrayTo \ + (*(npy_bool (*)(PyArrayObject *, PyArray_Descr *, NPY_CASTING)) \ + PyArray_API[274]) +#define PyArray_CanCastTypeTo \ + (*(npy_bool (*)(PyArray_Descr *, PyArray_Descr *, NPY_CASTING)) \ + PyArray_API[275]) +#define PyArray_EinsteinSum \ + (*(PyArrayObject * (*)(char *, npy_intp, PyArrayObject **, PyArray_Descr *, NPY_ORDER, NPY_CASTING, PyArrayObject *)) \ + PyArray_API[276]) +#define PyArray_NewLikeArray \ + (*(PyObject * (*)(PyArrayObject *, NPY_ORDER, PyArray_Descr *, int)) \ + PyArray_API[277]) +#define PyArray_GetArrayParamsFromObject \ + (*(int (*)(PyObject *, PyArray_Descr *, npy_bool, PyArray_Descr **, int *, npy_intp *, PyArrayObject **, PyObject *)) \ + PyArray_API[278]) +#define PyArray_ConvertClipmodeSequence \ + (*(int (*)(PyObject *, NPY_CLIPMODE *, int)) \ + PyArray_API[279]) +#define PyArray_MatrixProduct2 \ + (*(PyObject * (*)(PyObject *, PyObject *, PyArrayObject*)) \ + PyArray_API[280]) +#define NpyIter_IsFirstVisit \ + (*(npy_bool (*)(NpyIter *, int)) \ + PyArray_API[281]) +#define PyArray_SetBaseObject \ + (*(int (*)(PyArrayObject *, PyObject *)) \ + PyArray_API[282]) +#define PyArray_CreateSortedStridePerm \ + (*(void (*)(int, npy_intp *, npy_stride_sort_item *)) \ + PyArray_API[283]) +#define PyArray_RemoveAxesInPlace \ + (*(void (*)(PyArrayObject *, npy_bool *)) \ + PyArray_API[284]) +#define PyArray_DebugPrint \ + (*(void (*)(PyArrayObject *)) \ + PyArray_API[285]) +#define PyArray_FailUnlessWriteable \ + (*(int (*)(PyArrayObject *, const char *)) \ + PyArray_API[286]) +#define PyArray_SetUpdateIfCopyBase \ + (*(int (*)(PyArrayObject *, PyArrayObject *)) \ + PyArray_API[287]) +#define PyDataMem_NEW \ + (*(void * (*)(size_t)) \ + PyArray_API[288]) +#define PyDataMem_FREE \ + (*(void (*)(void *)) \ + PyArray_API[289]) +#define PyDataMem_RENEW \ + (*(void * (*)(void *, size_t)) \ + PyArray_API[290]) +#define PyDataMem_SetEventHook \ + (*(PyDataMem_EventHookFunc * (*)(PyDataMem_EventHookFunc *, void *, void **)) \ + PyArray_API[291]) +#define NPY_DEFAULT_ASSIGN_CASTING (*(NPY_CASTING *)PyArray_API[292]) +#define PyArray_MapIterSwapAxes \ + (*(void (*)(PyArrayMapIterObject *, PyArrayObject **, int)) \ + PyArray_API[293]) +#define PyArray_MapIterArray \ + (*(PyObject * (*)(PyArrayObject *, PyObject *)) \ + PyArray_API[294]) +#define PyArray_MapIterNext \ + (*(void (*)(PyArrayMapIterObject *)) \ + PyArray_API[295]) +#define PyArray_Partition \ + (*(int (*)(PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND)) \ + PyArray_API[296]) +#define PyArray_ArgPartition \ + (*(PyObject * (*)(PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND)) \ + PyArray_API[297]) +#define PyArray_SelectkindConverter \ + (*(int (*)(PyObject *, NPY_SELECTKIND *)) \ + PyArray_API[298]) +#define PyDataMem_NEW_ZEROED \ + (*(void * (*)(size_t, size_t)) \ + PyArray_API[299]) + +#if !defined(NO_IMPORT_ARRAY) && !defined(NO_IMPORT) +static int +_import_array(void) +{ + int st; + PyObject *numpy = PyImport_ImportModule("numpy.core.multiarray"); + PyObject *c_api = NULL; + + if (numpy == NULL) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); + return -1; + } + c_api = PyObject_GetAttrString(numpy, "_ARRAY_API"); + Py_DECREF(numpy); + if (c_api == NULL) { + PyErr_SetString(PyExc_AttributeError, "_ARRAY_API not found"); + return -1; + } + +#if PY_VERSION_HEX >= 0x03000000 + if (!PyCapsule_CheckExact(c_api)) { + PyErr_SetString(PyExc_RuntimeError, "_ARRAY_API is not PyCapsule object"); + Py_DECREF(c_api); + return -1; + } + PyArray_API = (void **)PyCapsule_GetPointer(c_api, NULL); +#else + if (!PyCObject_Check(c_api)) { + PyErr_SetString(PyExc_RuntimeError, "_ARRAY_API is not PyCObject object"); + Py_DECREF(c_api); + return -1; + } + PyArray_API = (void **)PyCObject_AsVoidPtr(c_api); +#endif + Py_DECREF(c_api); + if (PyArray_API == NULL) { + PyErr_SetString(PyExc_RuntimeError, "_ARRAY_API is NULL pointer"); + return -1; + } + + /* Perform runtime check of C API version */ + if (NPY_VERSION != PyArray_GetNDArrayCVersion()) { + PyErr_Format(PyExc_RuntimeError, "module compiled against "\ + "ABI version %x but this version of numpy is %x", \ + (int) NPY_VERSION, (int) PyArray_GetNDArrayCVersion()); + return -1; + } + if (NPY_FEATURE_VERSION > PyArray_GetNDArrayCFeatureVersion()) { + PyErr_Format(PyExc_RuntimeError, "module compiled against "\ + "API version %x but this version of numpy is %x", \ + (int) NPY_FEATURE_VERSION, (int) PyArray_GetNDArrayCFeatureVersion()); + return -1; + } + + /* + * Perform runtime check of endianness and check it matches the one set by + * the headers (npy_endian.h) as a safeguard + */ + st = PyArray_GetEndianness(); + if (st == NPY_CPU_UNKNOWN_ENDIAN) { + PyErr_Format(PyExc_RuntimeError, "FATAL: module compiled as unknown endian"); + return -1; + } +#if NPY_BYTE_ORDER == NPY_BIG_ENDIAN + if (st != NPY_CPU_BIG) { + PyErr_Format(PyExc_RuntimeError, "FATAL: module compiled as "\ + "big endian, but detected different endianness at runtime"); + return -1; + } +#elif NPY_BYTE_ORDER == NPY_LITTLE_ENDIAN + if (st != NPY_CPU_LITTLE) { + PyErr_Format(PyExc_RuntimeError, "FATAL: module compiled as "\ + "little endian, but detected different endianness at runtime"); + return -1; + } +#endif + + return 0; +} + +#if PY_VERSION_HEX >= 0x03000000 +#define NUMPY_IMPORT_ARRAY_RETVAL NULL +#else +#define NUMPY_IMPORT_ARRAY_RETVAL +#endif + +#define import_array() {if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); return NUMPY_IMPORT_ARRAY_RETVAL; } } + +#define import_array1(ret) {if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); return ret; } } + +#define import_array2(msg, ret) {if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, msg); return ret; } } + +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h new file mode 100644 index 000000000..358523193 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h @@ -0,0 +1,328 @@ + +#ifdef _UMATHMODULE + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION +extern NPY_NO_EXPORT PyTypeObject PyUFunc_Type; +#else +NPY_NO_EXPORT PyTypeObject PyUFunc_Type; +#endif + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + extern NPY_NO_EXPORT PyTypeObject PyUFunc_Type; +#else + NPY_NO_EXPORT PyTypeObject PyUFunc_Type; +#endif + +NPY_NO_EXPORT PyObject * PyUFunc_FromFuncAndData \ + (PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int); +NPY_NO_EXPORT int PyUFunc_RegisterLoopForType \ + (PyUFuncObject *, int, PyUFuncGenericFunction, int *, void *); +NPY_NO_EXPORT int PyUFunc_GenericFunction \ + (PyUFuncObject *, PyObject *, PyObject *, PyArrayObject **); +NPY_NO_EXPORT void PyUFunc_f_f_As_d_d \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_d_d \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_f_f \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_g_g \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_F_F_As_D_D \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_F_F \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_D_D \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_G_G \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_O_O \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_ff_f_As_dd_d \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_ff_f \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_dd_d \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_gg_g \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_FF_F_As_DD_D \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_DD_D \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_FF_F \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_GG_G \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_OO_O \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_O_O_method \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_OO_O_method \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_On_Om \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT int PyUFunc_GetPyValues \ + (char *, int *, int *, PyObject **); +NPY_NO_EXPORT int PyUFunc_checkfperr \ + (int, PyObject *, int *); +NPY_NO_EXPORT void PyUFunc_clearfperr \ + (void); +NPY_NO_EXPORT int PyUFunc_getfperr \ + (void); +NPY_NO_EXPORT int PyUFunc_handlefperr \ + (int, PyObject *, int, int *); +NPY_NO_EXPORT int PyUFunc_ReplaceLoopBySignature \ + (PyUFuncObject *, PyUFuncGenericFunction, int *, PyUFuncGenericFunction *); +NPY_NO_EXPORT PyObject * PyUFunc_FromFuncAndDataAndSignature \ + (PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int, const char *); +NPY_NO_EXPORT int PyUFunc_SetUsesArraysAsData \ + (void **, size_t); +NPY_NO_EXPORT void PyUFunc_e_e \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_e_e_As_f_f \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_e_e_As_d_d \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_ee_e \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_ee_e_As_ff_f \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT void PyUFunc_ee_e_As_dd_d \ + (char **, npy_intp *, npy_intp *, void *); +NPY_NO_EXPORT int PyUFunc_DefaultTypeResolver \ + (PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyObject *, PyArray_Descr **); +NPY_NO_EXPORT int PyUFunc_ValidateCasting \ + (PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyArray_Descr **); +NPY_NO_EXPORT int PyUFunc_RegisterLoopForDescr \ + (PyUFuncObject *, PyArray_Descr *, PyUFuncGenericFunction, PyArray_Descr **, void *); + +#else + +#if defined(PY_UFUNC_UNIQUE_SYMBOL) +#define PyUFunc_API PY_UFUNC_UNIQUE_SYMBOL +#endif + +#if defined(NO_IMPORT) || defined(NO_IMPORT_UFUNC) +extern void **PyUFunc_API; +#else +#if defined(PY_UFUNC_UNIQUE_SYMBOL) +void **PyUFunc_API; +#else +static void **PyUFunc_API=NULL; +#endif +#endif + +#define PyUFunc_Type (*(PyTypeObject *)PyUFunc_API[0]) +#define PyUFunc_FromFuncAndData \ + (*(PyObject * (*)(PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int)) \ + PyUFunc_API[1]) +#define PyUFunc_RegisterLoopForType \ + (*(int (*)(PyUFuncObject *, int, PyUFuncGenericFunction, int *, void *)) \ + PyUFunc_API[2]) +#define PyUFunc_GenericFunction \ + (*(int (*)(PyUFuncObject *, PyObject *, PyObject *, PyArrayObject **)) \ + PyUFunc_API[3]) +#define PyUFunc_f_f_As_d_d \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[4]) +#define PyUFunc_d_d \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[5]) +#define PyUFunc_f_f \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[6]) +#define PyUFunc_g_g \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[7]) +#define PyUFunc_F_F_As_D_D \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[8]) +#define PyUFunc_F_F \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[9]) +#define PyUFunc_D_D \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[10]) +#define PyUFunc_G_G \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[11]) +#define PyUFunc_O_O \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[12]) +#define PyUFunc_ff_f_As_dd_d \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[13]) +#define PyUFunc_ff_f \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[14]) +#define PyUFunc_dd_d \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[15]) +#define PyUFunc_gg_g \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[16]) +#define PyUFunc_FF_F_As_DD_D \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[17]) +#define PyUFunc_DD_D \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[18]) +#define PyUFunc_FF_F \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[19]) +#define PyUFunc_GG_G \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[20]) +#define PyUFunc_OO_O \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[21]) +#define PyUFunc_O_O_method \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[22]) +#define PyUFunc_OO_O_method \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[23]) +#define PyUFunc_On_Om \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[24]) +#define PyUFunc_GetPyValues \ + (*(int (*)(char *, int *, int *, PyObject **)) \ + PyUFunc_API[25]) +#define PyUFunc_checkfperr \ + (*(int (*)(int, PyObject *, int *)) \ + PyUFunc_API[26]) +#define PyUFunc_clearfperr \ + (*(void (*)(void)) \ + PyUFunc_API[27]) +#define PyUFunc_getfperr \ + (*(int (*)(void)) \ + PyUFunc_API[28]) +#define PyUFunc_handlefperr \ + (*(int (*)(int, PyObject *, int, int *)) \ + PyUFunc_API[29]) +#define PyUFunc_ReplaceLoopBySignature \ + (*(int (*)(PyUFuncObject *, PyUFuncGenericFunction, int *, PyUFuncGenericFunction *)) \ + PyUFunc_API[30]) +#define PyUFunc_FromFuncAndDataAndSignature \ + (*(PyObject * (*)(PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int, const char *)) \ + PyUFunc_API[31]) +#define PyUFunc_SetUsesArraysAsData \ + (*(int (*)(void **, size_t)) \ + PyUFunc_API[32]) +#define PyUFunc_e_e \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[33]) +#define PyUFunc_e_e_As_f_f \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[34]) +#define PyUFunc_e_e_As_d_d \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[35]) +#define PyUFunc_ee_e \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[36]) +#define PyUFunc_ee_e_As_ff_f \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[37]) +#define PyUFunc_ee_e_As_dd_d \ + (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ + PyUFunc_API[38]) +#define PyUFunc_DefaultTypeResolver \ + (*(int (*)(PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyObject *, PyArray_Descr **)) \ + PyUFunc_API[39]) +#define PyUFunc_ValidateCasting \ + (*(int (*)(PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyArray_Descr **)) \ + PyUFunc_API[40]) +#define PyUFunc_RegisterLoopForDescr \ + (*(int (*)(PyUFuncObject *, PyArray_Descr *, PyUFuncGenericFunction, PyArray_Descr **, void *)) \ + PyUFunc_API[41]) + +static int +_import_umath(void) +{ + PyObject *numpy = PyImport_ImportModule("numpy.core.umath"); + PyObject *c_api = NULL; + + if (numpy == NULL) { + PyErr_SetString(PyExc_ImportError, "numpy.core.umath failed to import"); + return -1; + } + c_api = PyObject_GetAttrString(numpy, "_UFUNC_API"); + Py_DECREF(numpy); + if (c_api == NULL) { + PyErr_SetString(PyExc_AttributeError, "_UFUNC_API not found"); + return -1; + } + +#if PY_VERSION_HEX >= 0x03000000 + if (!PyCapsule_CheckExact(c_api)) { + PyErr_SetString(PyExc_RuntimeError, "_UFUNC_API is not PyCapsule object"); + Py_DECREF(c_api); + return -1; + } + PyUFunc_API = (void **)PyCapsule_GetPointer(c_api, NULL); +#else + if (!PyCObject_Check(c_api)) { + PyErr_SetString(PyExc_RuntimeError, "_UFUNC_API is not PyCObject object"); + Py_DECREF(c_api); + return -1; + } + PyUFunc_API = (void **)PyCObject_AsVoidPtr(c_api); +#endif + Py_DECREF(c_api); + if (PyUFunc_API == NULL) { + PyErr_SetString(PyExc_RuntimeError, "_UFUNC_API is NULL pointer"); + return -1; + } + return 0; +} + +#if PY_VERSION_HEX >= 0x03000000 +#define NUMPY_IMPORT_UMATH_RETVAL NULL +#else +#define NUMPY_IMPORT_UMATH_RETVAL +#endif + +#define import_umath() \ + do {\ + UFUNC_NOFPE\ + if (_import_umath() < 0) {\ + PyErr_Print();\ + PyErr_SetString(PyExc_ImportError,\ + "numpy.core.umath failed to import");\ + return NUMPY_IMPORT_UMATH_RETVAL;\ + }\ + } while(0) + +#define import_umath1(ret) \ + do {\ + UFUNC_NOFPE\ + if (_import_umath() < 0) {\ + PyErr_Print();\ + PyErr_SetString(PyExc_ImportError,\ + "numpy.core.umath failed to import");\ + return ret;\ + }\ + } while(0) + +#define import_umath2(ret, msg) \ + do {\ + UFUNC_NOFPE\ + if (_import_umath() < 0) {\ + PyErr_Print();\ + PyErr_SetString(PyExc_ImportError, msg);\ + return ret;\ + }\ + } while(0) + +#define import_ufunc() \ + do {\ + UFUNC_NOFPE\ + if (_import_umath() < 0) {\ + PyErr_Print();\ + PyErr_SetString(PyExc_ImportError,\ + "numpy.core.umath failed to import");\ + }\ + } while(0) + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h b/gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h new file mode 100644 index 000000000..e8860cbc7 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h @@ -0,0 +1,90 @@ +#ifndef _NPY_INCLUDE_NEIGHBORHOOD_IMP +#error You should not include this header directly +#endif +/* + * Private API (here for inline) + */ +static NPY_INLINE int +_PyArrayNeighborhoodIter_IncrCoord(PyArrayNeighborhoodIterObject* iter); + +/* + * Update to next item of the iterator + * + * Note: this simply increment the coordinates vector, last dimension + * incremented first , i.e, for dimension 3 + * ... + * -1, -1, -1 + * -1, -1, 0 + * -1, -1, 1 + * .... + * -1, 0, -1 + * -1, 0, 0 + * .... + * 0, -1, -1 + * 0, -1, 0 + * .... + */ +#define _UPDATE_COORD_ITER(c) \ + wb = iter->coordinates[c] < iter->bounds[c][1]; \ + if (wb) { \ + iter->coordinates[c] += 1; \ + return 0; \ + } \ + else { \ + iter->coordinates[c] = iter->bounds[c][0]; \ + } + +static NPY_INLINE int +_PyArrayNeighborhoodIter_IncrCoord(PyArrayNeighborhoodIterObject* iter) +{ + npy_intp i, wb; + + for (i = iter->nd - 1; i >= 0; --i) { + _UPDATE_COORD_ITER(i) + } + + return 0; +} + +/* + * Version optimized for 2d arrays, manual loop unrolling + */ +static NPY_INLINE int +_PyArrayNeighborhoodIter_IncrCoord2D(PyArrayNeighborhoodIterObject* iter) +{ + npy_intp wb; + + _UPDATE_COORD_ITER(1) + _UPDATE_COORD_ITER(0) + + return 0; +} +#undef _UPDATE_COORD_ITER + +/* + * Advance to the next neighbour + */ +static NPY_INLINE int +PyArrayNeighborhoodIter_Next(PyArrayNeighborhoodIterObject* iter) +{ + _PyArrayNeighborhoodIter_IncrCoord (iter); + iter->dataptr = iter->translate((PyArrayIterObject*)iter, iter->coordinates); + + return 0; +} + +/* + * Reset functions + */ +static NPY_INLINE int +PyArrayNeighborhoodIter_Reset(PyArrayNeighborhoodIterObject* iter) +{ + npy_intp i; + + for (i = 0; i < iter->nd; ++i) { + iter->coordinates[i] = iter->bounds[i][0]; + } + iter->dataptr = iter->translate((PyArrayIterObject*)iter, iter->coordinates); + + return 0; +} diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h b/gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h new file mode 100644 index 000000000..79ccc2904 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h @@ -0,0 +1,32 @@ +#define NPY_HAVE_ENDIAN_H 1 +#define NPY_SIZEOF_SHORT SIZEOF_SHORT +#define NPY_SIZEOF_INT SIZEOF_INT +#define NPY_SIZEOF_LONG SIZEOF_LONG +#define NPY_SIZEOF_FLOAT 4 +#define NPY_SIZEOF_COMPLEX_FLOAT 8 +#define NPY_SIZEOF_DOUBLE 8 +#define NPY_SIZEOF_COMPLEX_DOUBLE 16 +#define NPY_SIZEOF_LONGDOUBLE 16 +#define NPY_SIZEOF_COMPLEX_LONGDOUBLE 32 +#define NPY_SIZEOF_PY_INTPTR_T 8 +#define NPY_SIZEOF_OFF_T 8 +#define NPY_SIZEOF_PY_LONG_LONG 8 +#define NPY_SIZEOF_LONGLONG 8 +#define NPY_NO_SMP 0 +#define NPY_HAVE_DECL_ISNAN +#define NPY_HAVE_DECL_ISINF +#define NPY_HAVE_DECL_ISFINITE +#define NPY_HAVE_DECL_SIGNBIT +#define NPY_USE_C99_COMPLEX 1 +#define NPY_HAVE_COMPLEX_DOUBLE 1 +#define NPY_HAVE_COMPLEX_FLOAT 1 +#define NPY_HAVE_COMPLEX_LONG_DOUBLE 1 +#define NPY_ENABLE_SEPARATE_COMPILATION 1 +#define NPY_USE_C99_FORMATS 1 +#define NPY_VISIBILITY_HIDDEN __attribute__((visibility("hidden"))) +#define NPY_ABI_VERSION 0x01000009 +#define NPY_API_VERSION 0x00000009 + +#ifndef __STDC_FORMAT_MACROS +#define __STDC_FORMAT_MACROS 1 +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h b/gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h new file mode 100644 index 000000000..4f46d6b1a --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h @@ -0,0 +1,11 @@ +#ifndef Py_ARRAYOBJECT_H +#define Py_ARRAYOBJECT_H + +#include "ndarrayobject.h" +#include "npy_interrupt.h" + +#ifdef NPY_NO_PREFIX +#include "noprefix.h" +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h b/gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h new file mode 100644 index 000000000..64450e713 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h @@ -0,0 +1,175 @@ +#ifndef _NPY_ARRAYSCALARS_H_ +#define _NPY_ARRAYSCALARS_H_ + +#ifndef _MULTIARRAYMODULE +typedef struct { + PyObject_HEAD + npy_bool obval; +} PyBoolScalarObject; +#endif + + +typedef struct { + PyObject_HEAD + signed char obval; +} PyByteScalarObject; + + +typedef struct { + PyObject_HEAD + short obval; +} PyShortScalarObject; + + +typedef struct { + PyObject_HEAD + int obval; +} PyIntScalarObject; + + +typedef struct { + PyObject_HEAD + long obval; +} PyLongScalarObject; + + +typedef struct { + PyObject_HEAD + npy_longlong obval; +} PyLongLongScalarObject; + + +typedef struct { + PyObject_HEAD + unsigned char obval; +} PyUByteScalarObject; + + +typedef struct { + PyObject_HEAD + unsigned short obval; +} PyUShortScalarObject; + + +typedef struct { + PyObject_HEAD + unsigned int obval; +} PyUIntScalarObject; + + +typedef struct { + PyObject_HEAD + unsigned long obval; +} PyULongScalarObject; + + +typedef struct { + PyObject_HEAD + npy_ulonglong obval; +} PyULongLongScalarObject; + + +typedef struct { + PyObject_HEAD + npy_half obval; +} PyHalfScalarObject; + + +typedef struct { + PyObject_HEAD + float obval; +} PyFloatScalarObject; + + +typedef struct { + PyObject_HEAD + double obval; +} PyDoubleScalarObject; + + +typedef struct { + PyObject_HEAD + npy_longdouble obval; +} PyLongDoubleScalarObject; + + +typedef struct { + PyObject_HEAD + npy_cfloat obval; +} PyCFloatScalarObject; + + +typedef struct { + PyObject_HEAD + npy_cdouble obval; +} PyCDoubleScalarObject; + + +typedef struct { + PyObject_HEAD + npy_clongdouble obval; +} PyCLongDoubleScalarObject; + + +typedef struct { + PyObject_HEAD + PyObject * obval; +} PyObjectScalarObject; + +typedef struct { + PyObject_HEAD + npy_datetime obval; + PyArray_DatetimeMetaData obmeta; +} PyDatetimeScalarObject; + +typedef struct { + PyObject_HEAD + npy_timedelta obval; + PyArray_DatetimeMetaData obmeta; +} PyTimedeltaScalarObject; + + +typedef struct { + PyObject_HEAD + char obval; +} PyScalarObject; + +#define PyStringScalarObject PyStringObject +#define PyUnicodeScalarObject PyUnicodeObject + +typedef struct { + PyObject_VAR_HEAD + char *obval; + PyArray_Descr *descr; + int flags; + PyObject *base; +} PyVoidScalarObject; + +/* Macros + PyScalarObject + PyArrType_Type + are defined in ndarrayobject.h +*/ + +#define PyArrayScalar_False ((PyObject *)(&(_PyArrayScalar_BoolValues[0]))) +#define PyArrayScalar_True ((PyObject *)(&(_PyArrayScalar_BoolValues[1]))) +#define PyArrayScalar_FromLong(i) \ + ((PyObject *)(&(_PyArrayScalar_BoolValues[((i)!=0)]))) +#define PyArrayScalar_RETURN_BOOL_FROM_LONG(i) \ + return Py_INCREF(PyArrayScalar_FromLong(i)), \ + PyArrayScalar_FromLong(i) +#define PyArrayScalar_RETURN_FALSE \ + return Py_INCREF(PyArrayScalar_False), \ + PyArrayScalar_False +#define PyArrayScalar_RETURN_TRUE \ + return Py_INCREF(PyArrayScalar_True), \ + PyArrayScalar_True + +#define PyArrayScalar_New(cls) \ + Py##cls##ArrType_Type.tp_alloc(&Py##cls##ArrType_Type, 0) +#define PyArrayScalar_VAL(obj, cls) \ + ((Py##cls##ScalarObject *)obj)->obval +#define PyArrayScalar_ASSIGN(obj, cls, val) \ + PyArrayScalar_VAL(obj, cls) = val + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h b/gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h new file mode 100644 index 000000000..944f0ea34 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h @@ -0,0 +1,69 @@ +#ifndef __NPY_HALFFLOAT_H__ +#define __NPY_HALFFLOAT_H__ + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Half-precision routines + */ + +/* Conversions */ +float npy_half_to_float(npy_half h); +double npy_half_to_double(npy_half h); +npy_half npy_float_to_half(float f); +npy_half npy_double_to_half(double d); +/* Comparisons */ +int npy_half_eq(npy_half h1, npy_half h2); +int npy_half_ne(npy_half h1, npy_half h2); +int npy_half_le(npy_half h1, npy_half h2); +int npy_half_lt(npy_half h1, npy_half h2); +int npy_half_ge(npy_half h1, npy_half h2); +int npy_half_gt(npy_half h1, npy_half h2); +/* faster *_nonan variants for when you know h1 and h2 are not NaN */ +int npy_half_eq_nonan(npy_half h1, npy_half h2); +int npy_half_lt_nonan(npy_half h1, npy_half h2); +int npy_half_le_nonan(npy_half h1, npy_half h2); +/* Miscellaneous functions */ +int npy_half_iszero(npy_half h); +int npy_half_isnan(npy_half h); +int npy_half_isinf(npy_half h); +int npy_half_isfinite(npy_half h); +int npy_half_signbit(npy_half h); +npy_half npy_half_copysign(npy_half x, npy_half y); +npy_half npy_half_spacing(npy_half h); +npy_half npy_half_nextafter(npy_half x, npy_half y); + +/* + * Half-precision constants + */ + +#define NPY_HALF_ZERO (0x0000u) +#define NPY_HALF_PZERO (0x0000u) +#define NPY_HALF_NZERO (0x8000u) +#define NPY_HALF_ONE (0x3c00u) +#define NPY_HALF_NEGONE (0xbc00u) +#define NPY_HALF_PINF (0x7c00u) +#define NPY_HALF_NINF (0xfc00u) +#define NPY_HALF_NAN (0x7e00u) + +#define NPY_MAX_HALF (0x7bffu) + +/* + * Bit-level conversions + */ + +npy_uint16 npy_floatbits_to_halfbits(npy_uint32 f); +npy_uint16 npy_doublebits_to_halfbits(npy_uint64 d); +npy_uint32 npy_halfbits_to_floatbits(npy_uint16 h); +npy_uint64 npy_halfbits_to_doublebits(npy_uint16 h); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt b/gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt new file mode 100644 index 000000000..33bc88ca9 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt @@ -0,0 +1,2430 @@ + +=========== +Numpy C-API +=========== +:: + + unsigned int + PyArray_GetNDArrayCVersion(void ) + + +Included at the very first so not auto-grabbed and thus not labeled. + +:: + + int + PyArray_SetNumericOps(PyObject *dict) + +Set internal structure with number functions that all arrays will use + +:: + + PyObject * + PyArray_GetNumericOps(void ) + +Get dictionary showing number functions that all arrays will use + +:: + + int + PyArray_INCREF(PyArrayObject *mp) + +For object arrays, increment all internal references. + +:: + + int + PyArray_XDECREF(PyArrayObject *mp) + +Decrement all internal references for object arrays. +(or arrays with object fields) + +:: + + void + PyArray_SetStringFunction(PyObject *op, int repr) + +Set the array print function to be a Python function. + +:: + + PyArray_Descr * + PyArray_DescrFromType(int type) + +Get the PyArray_Descr structure for a type. + +:: + + PyObject * + PyArray_TypeObjectFromType(int type) + +Get a typeobject from a type-number -- can return NULL. + +New reference + +:: + + char * + PyArray_Zero(PyArrayObject *arr) + +Get pointer to zero of correct type for array. + +:: + + char * + PyArray_One(PyArrayObject *arr) + +Get pointer to one of correct type for array + +:: + + PyObject * + PyArray_CastToType(PyArrayObject *arr, PyArray_Descr *dtype, int + is_f_order) + +For backward compatibility + +Cast an array using typecode structure. +steals reference to at --- cannot be NULL + +This function always makes a copy of arr, even if the dtype +doesn't change. + +:: + + int + PyArray_CastTo(PyArrayObject *out, PyArrayObject *mp) + +Cast to an already created array. + +:: + + int + PyArray_CastAnyTo(PyArrayObject *out, PyArrayObject *mp) + +Cast to an already created array. Arrays don't have to be "broadcastable" +Only requirement is they have the same number of elements. + +:: + + int + PyArray_CanCastSafely(int fromtype, int totype) + +Check the type coercion rules. + +:: + + npy_bool + PyArray_CanCastTo(PyArray_Descr *from, PyArray_Descr *to) + +leaves reference count alone --- cannot be NULL + +PyArray_CanCastTypeTo is equivalent to this, but adds a 'casting' +parameter. + +:: + + int + PyArray_ObjectType(PyObject *op, int minimum_type) + +Return the typecode of the array a Python object would be converted to + +Returns the type number the result should have, or NPY_NOTYPE on error. + +:: + + PyArray_Descr * + PyArray_DescrFromObject(PyObject *op, PyArray_Descr *mintype) + +new reference -- accepts NULL for mintype + +:: + + PyArrayObject ** + PyArray_ConvertToCommonType(PyObject *op, int *retn) + + +:: + + PyArray_Descr * + PyArray_DescrFromScalar(PyObject *sc) + +Return descr object from array scalar. + +New reference + +:: + + PyArray_Descr * + PyArray_DescrFromTypeObject(PyObject *type) + + +:: + + npy_intp + PyArray_Size(PyObject *op) + +Compute the size of an array (in number of items) + +:: + + PyObject * + PyArray_Scalar(void *data, PyArray_Descr *descr, PyObject *base) + +Get scalar-equivalent to a region of memory described by a descriptor. + +:: + + PyObject * + PyArray_FromScalar(PyObject *scalar, PyArray_Descr *outcode) + +Get 0-dim array from scalar + +0-dim array from array-scalar object +always contains a copy of the data +unless outcode is NULL, it is of void type and the referrer does +not own it either. + +steals reference to outcode + +:: + + void + PyArray_ScalarAsCtype(PyObject *scalar, void *ctypeptr) + +Convert to c-type + +no error checking is performed -- ctypeptr must be same type as scalar +in case of flexible type, the data is not copied +into ctypeptr which is expected to be a pointer to pointer + +:: + + int + PyArray_CastScalarToCtype(PyObject *scalar, void + *ctypeptr, PyArray_Descr *outcode) + +Cast Scalar to c-type + +The output buffer must be large-enough to receive the value +Even for flexible types which is different from ScalarAsCtype +where only a reference for flexible types is returned + +This may not work right on narrow builds for NumPy unicode scalars. + +:: + + int + PyArray_CastScalarDirect(PyObject *scalar, PyArray_Descr + *indescr, void *ctypeptr, int outtype) + +Cast Scalar to c-type + +:: + + PyObject * + PyArray_ScalarFromObject(PyObject *object) + +Get an Array Scalar From a Python Object + +Returns NULL if unsuccessful but error is only set if another error occurred. +Currently only Numeric-like object supported. + +:: + + PyArray_VectorUnaryFunc * + PyArray_GetCastFunc(PyArray_Descr *descr, int type_num) + +Get a cast function to cast from the input descriptor to the +output type_number (must be a registered data-type). +Returns NULL if un-successful. + +:: + + PyObject * + PyArray_FromDims(int nd, int *d, int type) + +Construct an empty array from dimensions and typenum + +:: + + PyObject * + PyArray_FromDimsAndDataAndDescr(int nd, int *d, PyArray_Descr + *descr, char *data) + +Like FromDimsAndData but uses the Descr structure instead of typecode +as input. + +:: + + PyObject * + PyArray_FromAny(PyObject *op, PyArray_Descr *newtype, int + min_depth, int max_depth, int flags, PyObject + *context) + +Does not check for NPY_ARRAY_ENSURECOPY and NPY_ARRAY_NOTSWAPPED in flags +Steals a reference to newtype --- which can be NULL + +:: + + PyObject * + PyArray_EnsureArray(PyObject *op) + +This is a quick wrapper around PyArray_FromAny(op, NULL, 0, 0, ENSUREARRAY) +that special cases Arrays and PyArray_Scalars up front +It *steals a reference* to the object +It also guarantees that the result is PyArray_Type +Because it decrefs op if any conversion needs to take place +so it can be used like PyArray_EnsureArray(some_function(...)) + +:: + + PyObject * + PyArray_EnsureAnyArray(PyObject *op) + + +:: + + PyObject * + PyArray_FromFile(FILE *fp, PyArray_Descr *dtype, npy_intp num, char + *sep) + + +Given a ``FILE *`` pointer ``fp``, and a ``PyArray_Descr``, return an +array corresponding to the data encoded in that file. + +If the dtype is NULL, the default array type is used (double). +If non-null, the reference is stolen. + +The number of elements to read is given as ``num``; if it is < 0, then +then as many as possible are read. + +If ``sep`` is NULL or empty, then binary data is assumed, else +text data, with ``sep`` as the separator between elements. Whitespace in +the separator matches any length of whitespace in the text, and a match +for whitespace around the separator is added. + +For memory-mapped files, use the buffer interface. No more data than +necessary is read by this routine. + +:: + + PyObject * + PyArray_FromString(char *data, npy_intp slen, PyArray_Descr + *dtype, npy_intp num, char *sep) + + +Given a pointer to a string ``data``, a string length ``slen``, and +a ``PyArray_Descr``, return an array corresponding to the data +encoded in that string. + +If the dtype is NULL, the default array type is used (double). +If non-null, the reference is stolen. + +If ``slen`` is < 0, then the end of string is used for text data. +It is an error for ``slen`` to be < 0 for binary data (since embedded NULLs +would be the norm). + +The number of elements to read is given as ``num``; if it is < 0, then +then as many as possible are read. + +If ``sep`` is NULL or empty, then binary data is assumed, else +text data, with ``sep`` as the separator between elements. Whitespace in +the separator matches any length of whitespace in the text, and a match +for whitespace around the separator is added. + +:: + + PyObject * + PyArray_FromBuffer(PyObject *buf, PyArray_Descr *type, npy_intp + count, npy_intp offset) + + +:: + + PyObject * + PyArray_FromIter(PyObject *obj, PyArray_Descr *dtype, npy_intp count) + + +steals a reference to dtype (which cannot be NULL) + +:: + + PyObject * + PyArray_Return(PyArrayObject *mp) + + +Return either an array or the appropriate Python object if the array +is 0d and matches a Python type. + +:: + + PyObject * + PyArray_GetField(PyArrayObject *self, PyArray_Descr *typed, int + offset) + +Get a subset of bytes from each element of the array + +:: + + int + PyArray_SetField(PyArrayObject *self, PyArray_Descr *dtype, int + offset, PyObject *val) + +Set a subset of bytes from each element of the array + +:: + + PyObject * + PyArray_Byteswap(PyArrayObject *self, npy_bool inplace) + + +:: + + PyObject * + PyArray_Resize(PyArrayObject *self, PyArray_Dims *newshape, int + refcheck, NPY_ORDER order) + +Resize (reallocate data). Only works if nothing else is referencing this +array and it is contiguous. If refcheck is 0, then the reference count is +not checked and assumed to be 1. You still must own this data and have no +weak-references and no base object. + +:: + + int + PyArray_MoveInto(PyArrayObject *dst, PyArrayObject *src) + +Move the memory of one array into another, allowing for overlapping data. + +Returns 0 on success, negative on failure. + +:: + + int + PyArray_CopyInto(PyArrayObject *dst, PyArrayObject *src) + +Copy an Array into another array. +Broadcast to the destination shape if necessary. + +Returns 0 on success, -1 on failure. + +:: + + int + PyArray_CopyAnyInto(PyArrayObject *dst, PyArrayObject *src) + +Copy an Array into another array -- memory must not overlap +Does not require src and dest to have "broadcastable" shapes +(only the same number of elements). + +TODO: For NumPy 2.0, this could accept an order parameter which +only allows NPY_CORDER and NPY_FORDER. Could also rename +this to CopyAsFlat to make the name more intuitive. + +Returns 0 on success, -1 on error. + +:: + + int + PyArray_CopyObject(PyArrayObject *dest, PyObject *src_object) + + +:: + + PyObject * + PyArray_NewCopy(PyArrayObject *obj, NPY_ORDER order) + +Copy an array. + +:: + + PyObject * + PyArray_ToList(PyArrayObject *self) + +To List + +:: + + PyObject * + PyArray_ToString(PyArrayObject *self, NPY_ORDER order) + + +:: + + int + PyArray_ToFile(PyArrayObject *self, FILE *fp, char *sep, char *format) + +To File + +:: + + int + PyArray_Dump(PyObject *self, PyObject *file, int protocol) + + +:: + + PyObject * + PyArray_Dumps(PyObject *self, int protocol) + + +:: + + int + PyArray_ValidType(int type) + +Is the typenum valid? + +:: + + void + PyArray_UpdateFlags(PyArrayObject *ret, int flagmask) + +Update Several Flags at once. + +:: + + PyObject * + PyArray_New(PyTypeObject *subtype, int nd, npy_intp *dims, int + type_num, npy_intp *strides, void *data, int itemsize, int + flags, PyObject *obj) + +Generic new array creation routine. + +:: + + PyObject * + PyArray_NewFromDescr(PyTypeObject *subtype, PyArray_Descr *descr, int + nd, npy_intp *dims, npy_intp *strides, void + *data, int flags, PyObject *obj) + +Generic new array creation routine. + +steals a reference to descr (even on failure) + +:: + + PyArray_Descr * + PyArray_DescrNew(PyArray_Descr *base) + +base cannot be NULL + +:: + + PyArray_Descr * + PyArray_DescrNewFromType(int type_num) + + +:: + + double + PyArray_GetPriority(PyObject *obj, double default_) + +Get Priority from object + +:: + + PyObject * + PyArray_IterNew(PyObject *obj) + +Get Iterator. + +:: + + PyObject * + PyArray_MultiIterNew(int n, ... ) + +Get MultiIterator, + +:: + + int + PyArray_PyIntAsInt(PyObject *o) + + +:: + + npy_intp + PyArray_PyIntAsIntp(PyObject *o) + + +:: + + int + PyArray_Broadcast(PyArrayMultiIterObject *mit) + + +:: + + void + PyArray_FillObjectArray(PyArrayObject *arr, PyObject *obj) + +Assumes contiguous + +:: + + int + PyArray_FillWithScalar(PyArrayObject *arr, PyObject *obj) + + +:: + + npy_bool + PyArray_CheckStrides(int elsize, int nd, npy_intp numbytes, npy_intp + offset, npy_intp *dims, npy_intp *newstrides) + + +:: + + PyArray_Descr * + PyArray_DescrNewByteorder(PyArray_Descr *self, char newendian) + + +returns a copy of the PyArray_Descr structure with the byteorder +altered: +no arguments: The byteorder is swapped (in all subfields as well) +single argument: The byteorder is forced to the given state +(in all subfields as well) + +Valid states: ('big', '>') or ('little' or '<') +('native', or '=') + +If a descr structure with | is encountered it's own +byte-order is not changed but any fields are: + + +Deep bytorder change of a data-type descriptor +Leaves reference count of self unchanged --- does not DECREF self *** + +:: + + PyObject * + PyArray_IterAllButAxis(PyObject *obj, int *inaxis) + +Get Iterator that iterates over all but one axis (don't use this with +PyArray_ITER_GOTO1D). The axis will be over-written if negative +with the axis having the smallest stride. + +:: + + PyObject * + PyArray_CheckFromAny(PyObject *op, PyArray_Descr *descr, int + min_depth, int max_depth, int requires, PyObject + *context) + +steals a reference to descr -- accepts NULL + +:: + + PyObject * + PyArray_FromArray(PyArrayObject *arr, PyArray_Descr *newtype, int + flags) + +steals reference to newtype --- acc. NULL + +:: + + PyObject * + PyArray_FromInterface(PyObject *origin) + + +:: + + PyObject * + PyArray_FromStructInterface(PyObject *input) + + +:: + + PyObject * + PyArray_FromArrayAttr(PyObject *op, PyArray_Descr *typecode, PyObject + *context) + + +:: + + NPY_SCALARKIND + PyArray_ScalarKind(int typenum, PyArrayObject **arr) + +ScalarKind + +Returns the scalar kind of a type number, with an +optional tweak based on the scalar value itself. +If no scalar is provided, it returns INTPOS_SCALAR +for both signed and unsigned integers, otherwise +it checks the sign of any signed integer to choose +INTNEG_SCALAR when appropriate. + +:: + + int + PyArray_CanCoerceScalar(int thistype, int neededtype, NPY_SCALARKIND + scalar) + + +Determines whether the data type 'thistype', with +scalar kind 'scalar', can be coerced into 'neededtype'. + +:: + + PyObject * + PyArray_NewFlagsObject(PyObject *obj) + + +Get New ArrayFlagsObject + +:: + + npy_bool + PyArray_CanCastScalar(PyTypeObject *from, PyTypeObject *to) + +See if array scalars can be cast. + +TODO: For NumPy 2.0, add a NPY_CASTING parameter. + +:: + + int + PyArray_CompareUCS4(npy_ucs4 *s1, npy_ucs4 *s2, size_t len) + + +:: + + int + PyArray_RemoveSmallest(PyArrayMultiIterObject *multi) + +Adjusts previously broadcasted iterators so that the axis with +the smallest sum of iterator strides is not iterated over. +Returns dimension which is smallest in the range [0,multi->nd). +A -1 is returned if multi->nd == 0. + +don't use with PyArray_ITER_GOTO1D because factors are not adjusted + +:: + + int + PyArray_ElementStrides(PyObject *obj) + + +:: + + void + PyArray_Item_INCREF(char *data, PyArray_Descr *descr) + + +:: + + void + PyArray_Item_XDECREF(char *data, PyArray_Descr *descr) + + +:: + + PyObject * + PyArray_FieldNames(PyObject *fields) + +Return the tuple of ordered field names from a dictionary. + +:: + + PyObject * + PyArray_Transpose(PyArrayObject *ap, PyArray_Dims *permute) + +Return Transpose. + +:: + + PyObject * + PyArray_TakeFrom(PyArrayObject *self0, PyObject *indices0, int + axis, PyArrayObject *out, NPY_CLIPMODE clipmode) + +Take + +:: + + PyObject * + PyArray_PutTo(PyArrayObject *self, PyObject*values0, PyObject + *indices0, NPY_CLIPMODE clipmode) + +Put values into an array + +:: + + PyObject * + PyArray_PutMask(PyArrayObject *self, PyObject*values0, PyObject*mask0) + +Put values into an array according to a mask. + +:: + + PyObject * + PyArray_Repeat(PyArrayObject *aop, PyObject *op, int axis) + +Repeat the array. + +:: + + PyObject * + PyArray_Choose(PyArrayObject *ip, PyObject *op, PyArrayObject + *out, NPY_CLIPMODE clipmode) + + +:: + + int + PyArray_Sort(PyArrayObject *op, int axis, NPY_SORTKIND which) + +Sort an array in-place + +:: + + PyObject * + PyArray_ArgSort(PyArrayObject *op, int axis, NPY_SORTKIND which) + +ArgSort an array + +:: + + PyObject * + PyArray_SearchSorted(PyArrayObject *op1, PyObject *op2, NPY_SEARCHSIDE + side, PyObject *perm) + + +Search the sorted array op1 for the location of the items in op2. The +result is an array of indexes, one for each element in op2, such that if +the item were to be inserted in op1 just before that index the array +would still be in sorted order. + +Parameters +---------- +op1 : PyArrayObject * +Array to be searched, must be 1-D. +op2 : PyObject * +Array of items whose insertion indexes in op1 are wanted +side : {NPY_SEARCHLEFT, NPY_SEARCHRIGHT} +If NPY_SEARCHLEFT, return first valid insertion indexes +If NPY_SEARCHRIGHT, return last valid insertion indexes +perm : PyObject * +Permutation array that sorts op1 (optional) + +Returns +------- +ret : PyObject * +New reference to npy_intp array containing indexes where items in op2 +could be validly inserted into op1. NULL on error. + +Notes +----- +Binary search is used to find the indexes. + +:: + + PyObject * + PyArray_ArgMax(PyArrayObject *op, int axis, PyArrayObject *out) + +ArgMax + +:: + + PyObject * + PyArray_ArgMin(PyArrayObject *op, int axis, PyArrayObject *out) + +ArgMin + +:: + + PyObject * + PyArray_Reshape(PyArrayObject *self, PyObject *shape) + +Reshape + +:: + + PyObject * + PyArray_Newshape(PyArrayObject *self, PyArray_Dims *newdims, NPY_ORDER + order) + +New shape for an array + +:: + + PyObject * + PyArray_Squeeze(PyArrayObject *self) + + +return a new view of the array object with all of its unit-length +dimensions squeezed out if needed, otherwise +return the same array. + +:: + + PyObject * + PyArray_View(PyArrayObject *self, PyArray_Descr *type, PyTypeObject + *pytype) + +View +steals a reference to type -- accepts NULL + +:: + + PyObject * + PyArray_SwapAxes(PyArrayObject *ap, int a1, int a2) + +SwapAxes + +:: + + PyObject * + PyArray_Max(PyArrayObject *ap, int axis, PyArrayObject *out) + +Max + +:: + + PyObject * + PyArray_Min(PyArrayObject *ap, int axis, PyArrayObject *out) + +Min + +:: + + PyObject * + PyArray_Ptp(PyArrayObject *ap, int axis, PyArrayObject *out) + +Ptp + +:: + + PyObject * + PyArray_Mean(PyArrayObject *self, int axis, int rtype, PyArrayObject + *out) + +Mean + +:: + + PyObject * + PyArray_Trace(PyArrayObject *self, int offset, int axis1, int + axis2, int rtype, PyArrayObject *out) + +Trace + +:: + + PyObject * + PyArray_Diagonal(PyArrayObject *self, int offset, int axis1, int + axis2) + +Diagonal + +In NumPy versions prior to 1.7, this function always returned a copy of +the diagonal array. In 1.7, the code has been updated to compute a view +onto 'self', but it still copies this array before returning, as well as +setting the internal WARN_ON_WRITE flag. In a future version, it will +simply return a view onto self. + +:: + + PyObject * + PyArray_Clip(PyArrayObject *self, PyObject *min, PyObject + *max, PyArrayObject *out) + +Clip + +:: + + PyObject * + PyArray_Conjugate(PyArrayObject *self, PyArrayObject *out) + +Conjugate + +:: + + PyObject * + PyArray_Nonzero(PyArrayObject *self) + +Nonzero + +TODO: In NumPy 2.0, should make the iteration order a parameter. + +:: + + PyObject * + PyArray_Std(PyArrayObject *self, int axis, int rtype, PyArrayObject + *out, int variance) + +Set variance to 1 to by-pass square-root calculation and return variance +Std + +:: + + PyObject * + PyArray_Sum(PyArrayObject *self, int axis, int rtype, PyArrayObject + *out) + +Sum + +:: + + PyObject * + PyArray_CumSum(PyArrayObject *self, int axis, int rtype, PyArrayObject + *out) + +CumSum + +:: + + PyObject * + PyArray_Prod(PyArrayObject *self, int axis, int rtype, PyArrayObject + *out) + +Prod + +:: + + PyObject * + PyArray_CumProd(PyArrayObject *self, int axis, int + rtype, PyArrayObject *out) + +CumProd + +:: + + PyObject * + PyArray_All(PyArrayObject *self, int axis, PyArrayObject *out) + +All + +:: + + PyObject * + PyArray_Any(PyArrayObject *self, int axis, PyArrayObject *out) + +Any + +:: + + PyObject * + PyArray_Compress(PyArrayObject *self, PyObject *condition, int + axis, PyArrayObject *out) + +Compress + +:: + + PyObject * + PyArray_Flatten(PyArrayObject *a, NPY_ORDER order) + +Flatten + +:: + + PyObject * + PyArray_Ravel(PyArrayObject *arr, NPY_ORDER order) + +Ravel +Returns a contiguous array + +:: + + npy_intp + PyArray_MultiplyList(npy_intp *l1, int n) + +Multiply a List + +:: + + int + PyArray_MultiplyIntList(int *l1, int n) + +Multiply a List of ints + +:: + + void * + PyArray_GetPtr(PyArrayObject *obj, npy_intp*ind) + +Produce a pointer into array + +:: + + int + PyArray_CompareLists(npy_intp *l1, npy_intp *l2, int n) + +Compare Lists + +:: + + int + PyArray_AsCArray(PyObject **op, void *ptr, npy_intp *dims, int + nd, PyArray_Descr*typedescr) + +Simulate a C-array +steals a reference to typedescr -- can be NULL + +:: + + int + PyArray_As1D(PyObject **op, char **ptr, int *d1, int typecode) + +Convert to a 1D C-array + +:: + + int + PyArray_As2D(PyObject **op, char ***ptr, int *d1, int *d2, int + typecode) + +Convert to a 2D C-array + +:: + + int + PyArray_Free(PyObject *op, void *ptr) + +Free pointers created if As2D is called + +:: + + int + PyArray_Converter(PyObject *object, PyObject **address) + + +Useful to pass as converter function for O& processing in PyArgs_ParseTuple. + +This conversion function can be used with the "O&" argument for +PyArg_ParseTuple. It will immediately return an object of array type +or will convert to a NPY_ARRAY_CARRAY any other object. + +If you use PyArray_Converter, you must DECREF the array when finished +as you get a new reference to it. + +:: + + int + PyArray_IntpFromSequence(PyObject *seq, npy_intp *vals, int maxvals) + +PyArray_IntpFromSequence +Returns the number of integers converted or -1 if an error occurred. +vals must be large enough to hold maxvals + +:: + + PyObject * + PyArray_Concatenate(PyObject *op, int axis) + +Concatenate + +Concatenate an arbitrary Python sequence into an array. +op is a python object supporting the sequence interface. +Its elements will be concatenated together to form a single +multidimensional array. If axis is NPY_MAXDIMS or bigger, then +each sequence object will be flattened before concatenation + +:: + + PyObject * + PyArray_InnerProduct(PyObject *op1, PyObject *op2) + +Numeric.innerproduct(a,v) + +:: + + PyObject * + PyArray_MatrixProduct(PyObject *op1, PyObject *op2) + +Numeric.matrixproduct(a,v) +just like inner product but does the swapaxes stuff on the fly + +:: + + PyObject * + PyArray_CopyAndTranspose(PyObject *op) + +Copy and Transpose + +Could deprecate this function, as there isn't a speed benefit over +calling Transpose and then Copy. + +:: + + PyObject * + PyArray_Correlate(PyObject *op1, PyObject *op2, int mode) + +Numeric.correlate(a1,a2,mode) + +:: + + int + PyArray_TypestrConvert(int itemsize, int gentype) + +Typestr converter + +:: + + int + PyArray_DescrConverter(PyObject *obj, PyArray_Descr **at) + +Get typenum from an object -- None goes to NPY_DEFAULT_TYPE +This function takes a Python object representing a type and converts it +to a the correct PyArray_Descr * structure to describe the type. + +Many objects can be used to represent a data-type which in NumPy is +quite a flexible concept. + +This is the central code that converts Python objects to +Type-descriptor objects that are used throughout numpy. + +Returns a new reference in *at, but the returned should not be +modified as it may be one of the canonical immutable objects or +a reference to the input obj. + +:: + + int + PyArray_DescrConverter2(PyObject *obj, PyArray_Descr **at) + +Get typenum from an object -- None goes to NULL + +:: + + int + PyArray_IntpConverter(PyObject *obj, PyArray_Dims *seq) + +Get intp chunk from sequence + +This function takes a Python sequence object and allocates and +fills in an intp array with the converted values. + +Remember to free the pointer seq.ptr when done using +PyDimMem_FREE(seq.ptr)** + +:: + + int + PyArray_BufferConverter(PyObject *obj, PyArray_Chunk *buf) + +Get buffer chunk from object + +this function takes a Python object which exposes the (single-segment) +buffer interface and returns a pointer to the data segment + +You should increment the reference count by one of buf->base +if you will hang on to a reference + +You only get a borrowed reference to the object. Do not free the +memory... + +:: + + int + PyArray_AxisConverter(PyObject *obj, int *axis) + +Get axis from an object (possibly None) -- a converter function, + +See also PyArray_ConvertMultiAxis, which also handles a tuple of axes. + +:: + + int + PyArray_BoolConverter(PyObject *object, npy_bool *val) + +Convert an object to true / false + +:: + + int + PyArray_ByteorderConverter(PyObject *obj, char *endian) + +Convert object to endian + +:: + + int + PyArray_OrderConverter(PyObject *object, NPY_ORDER *val) + +Convert an object to FORTRAN / C / ANY / KEEP + +:: + + unsigned char + PyArray_EquivTypes(PyArray_Descr *type1, PyArray_Descr *type2) + + +This function returns true if the two typecodes are +equivalent (same basic kind and same itemsize). + +:: + + PyObject * + PyArray_Zeros(int nd, npy_intp *dims, PyArray_Descr *type, int + is_f_order) + +Zeros + +steal a reference +accepts NULL type + +:: + + PyObject * + PyArray_Empty(int nd, npy_intp *dims, PyArray_Descr *type, int + is_f_order) + +Empty + +accepts NULL type +steals referenct to type + +:: + + PyObject * + PyArray_Where(PyObject *condition, PyObject *x, PyObject *y) + +Where + +:: + + PyObject * + PyArray_Arange(double start, double stop, double step, int type_num) + +Arange, + +:: + + PyObject * + PyArray_ArangeObj(PyObject *start, PyObject *stop, PyObject + *step, PyArray_Descr *dtype) + + +ArangeObj, + +this doesn't change the references + +:: + + int + PyArray_SortkindConverter(PyObject *obj, NPY_SORTKIND *sortkind) + +Convert object to sort kind + +:: + + PyObject * + PyArray_LexSort(PyObject *sort_keys, int axis) + +LexSort an array providing indices that will sort a collection of arrays +lexicographically. The first key is sorted on first, followed by the second key +-- requires that arg"merge"sort is available for each sort_key + +Returns an index array that shows the indexes for the lexicographic sort along +the given axis. + +:: + + PyObject * + PyArray_Round(PyArrayObject *a, int decimals, PyArrayObject *out) + +Round + +:: + + unsigned char + PyArray_EquivTypenums(int typenum1, int typenum2) + + +:: + + int + PyArray_RegisterDataType(PyArray_Descr *descr) + +Register Data type +Does not change the reference count of descr + +:: + + int + PyArray_RegisterCastFunc(PyArray_Descr *descr, int + totype, PyArray_VectorUnaryFunc *castfunc) + +Register Casting Function +Replaces any function currently stored. + +:: + + int + PyArray_RegisterCanCast(PyArray_Descr *descr, int + totype, NPY_SCALARKIND scalar) + +Register a type number indicating that a descriptor can be cast +to it safely + +:: + + void + PyArray_InitArrFuncs(PyArray_ArrFuncs *f) + +Initialize arrfuncs to NULL + +:: + + PyObject * + PyArray_IntTupleFromIntp(int len, npy_intp *vals) + +PyArray_IntTupleFromIntp + +:: + + int + PyArray_TypeNumFromName(char *str) + + +:: + + int + PyArray_ClipmodeConverter(PyObject *object, NPY_CLIPMODE *val) + +Convert an object to NPY_RAISE / NPY_CLIP / NPY_WRAP + +:: + + int + PyArray_OutputConverter(PyObject *object, PyArrayObject **address) + +Useful to pass as converter function for O& processing in +PyArgs_ParseTuple for output arrays + +:: + + PyObject * + PyArray_BroadcastToShape(PyObject *obj, npy_intp *dims, int nd) + +Get Iterator broadcast to a particular shape + +:: + + void + _PyArray_SigintHandler(int signum) + + +:: + + void* + _PyArray_GetSigintBuf(void ) + + +:: + + int + PyArray_DescrAlignConverter(PyObject *obj, PyArray_Descr **at) + + +Get type-descriptor from an object forcing alignment if possible +None goes to DEFAULT type. + +any object with the .fields attribute and/or .itemsize attribute (if the +.fields attribute does not give the total size -- i.e. a partial record +naming). If itemsize is given it must be >= size computed from fields + +The .fields attribute must return a convertible dictionary if present. +Result inherits from NPY_VOID. + +:: + + int + PyArray_DescrAlignConverter2(PyObject *obj, PyArray_Descr **at) + + +Get type-descriptor from an object forcing alignment if possible +None goes to NULL. + +:: + + int + PyArray_SearchsideConverter(PyObject *obj, void *addr) + +Convert object to searchsorted side + +:: + + PyObject * + PyArray_CheckAxis(PyArrayObject *arr, int *axis, int flags) + +PyArray_CheckAxis + +check that axis is valid +convert 0-d arrays to 1-d arrays + +:: + + npy_intp + PyArray_OverflowMultiplyList(npy_intp *l1, int n) + +Multiply a List of Non-negative numbers with over-flow detection. + +:: + + int + PyArray_CompareString(char *s1, char *s2, size_t len) + + +:: + + PyObject * + PyArray_MultiIterFromObjects(PyObject **mps, int n, int nadd, ... ) + +Get MultiIterator from array of Python objects and any additional + +PyObject **mps -- array of PyObjects +int n - number of PyObjects in the array +int nadd - number of additional arrays to include in the iterator. + +Returns a multi-iterator object. + +:: + + int + PyArray_GetEndianness(void ) + + +:: + + unsigned int + PyArray_GetNDArrayCFeatureVersion(void ) + +Returns the built-in (at compilation time) C API version + +:: + + PyObject * + PyArray_Correlate2(PyObject *op1, PyObject *op2, int mode) + +correlate(a1,a2,mode) + +This function computes the usual correlation (correlate(a1, a2) != +correlate(a2, a1), and conjugate the second argument for complex inputs + +:: + + PyObject* + PyArray_NeighborhoodIterNew(PyArrayIterObject *x, npy_intp + *bounds, int mode, PyArrayObject*fill) + +A Neighborhood Iterator object. + +:: + + void + PyArray_SetDatetimeParseFunction(PyObject *op) + +This function is scheduled to be removed + +TO BE REMOVED - NOT USED INTERNALLY. + +:: + + void + PyArray_DatetimeToDatetimeStruct(npy_datetime val, NPY_DATETIMEUNIT + fr, npy_datetimestruct *result) + +Fill the datetime struct from the value and resolution unit. + +TO BE REMOVED - NOT USED INTERNALLY. + +:: + + void + PyArray_TimedeltaToTimedeltaStruct(npy_timedelta val, NPY_DATETIMEUNIT + fr, npy_timedeltastruct *result) + +Fill the timedelta struct from the timedelta value and resolution unit. + +TO BE REMOVED - NOT USED INTERNALLY. + +:: + + npy_datetime + PyArray_DatetimeStructToDatetime(NPY_DATETIMEUNIT + fr, npy_datetimestruct *d) + +Create a datetime value from a filled datetime struct and resolution unit. + +TO BE REMOVED - NOT USED INTERNALLY. + +:: + + npy_datetime + PyArray_TimedeltaStructToTimedelta(NPY_DATETIMEUNIT + fr, npy_timedeltastruct *d) + +Create a timdelta value from a filled timedelta struct and resolution unit. + +TO BE REMOVED - NOT USED INTERNALLY. + +:: + + NpyIter * + NpyIter_New(PyArrayObject *op, npy_uint32 flags, NPY_ORDER + order, NPY_CASTING casting, PyArray_Descr*dtype) + +Allocate a new iterator for one array object. + +:: + + NpyIter * + NpyIter_MultiNew(int nop, PyArrayObject **op_in, npy_uint32 + flags, NPY_ORDER order, NPY_CASTING + casting, npy_uint32 *op_flags, PyArray_Descr + **op_request_dtypes) + +Allocate a new iterator for more than one array object, using +standard NumPy broadcasting rules and the default buffer size. + +:: + + NpyIter * + NpyIter_AdvancedNew(int nop, PyArrayObject **op_in, npy_uint32 + flags, NPY_ORDER order, NPY_CASTING + casting, npy_uint32 *op_flags, PyArray_Descr + **op_request_dtypes, int oa_ndim, int + **op_axes, npy_intp *itershape, npy_intp + buffersize) + +Allocate a new iterator for multiple array objects, and advanced +options for controlling the broadcasting, shape, and buffer size. + +:: + + NpyIter * + NpyIter_Copy(NpyIter *iter) + +Makes a copy of the iterator + +:: + + int + NpyIter_Deallocate(NpyIter *iter) + +Deallocate an iterator + +:: + + npy_bool + NpyIter_HasDelayedBufAlloc(NpyIter *iter) + +Whether the buffer allocation is being delayed + +:: + + npy_bool + NpyIter_HasExternalLoop(NpyIter *iter) + +Whether the iterator handles the inner loop + +:: + + int + NpyIter_EnableExternalLoop(NpyIter *iter) + +Removes the inner loop handling (so HasExternalLoop returns true) + +:: + + npy_intp * + NpyIter_GetInnerStrideArray(NpyIter *iter) + +Get the array of strides for the inner loop (when HasExternalLoop is true) + +This function may be safely called without holding the Python GIL. + +:: + + npy_intp * + NpyIter_GetInnerLoopSizePtr(NpyIter *iter) + +Get a pointer to the size of the inner loop (when HasExternalLoop is true) + +This function may be safely called without holding the Python GIL. + +:: + + int + NpyIter_Reset(NpyIter *iter, char **errmsg) + +Resets the iterator to its initial state + +If errmsg is non-NULL, it should point to a variable which will +receive the error message, and no Python exception will be set. +This is so that the function can be called from code not holding +the GIL. + +:: + + int + NpyIter_ResetBasePointers(NpyIter *iter, char **baseptrs, char + **errmsg) + +Resets the iterator to its initial state, with new base data pointers. +This function requires great caution. + +If errmsg is non-NULL, it should point to a variable which will +receive the error message, and no Python exception will be set. +This is so that the function can be called from code not holding +the GIL. + +:: + + int + NpyIter_ResetToIterIndexRange(NpyIter *iter, npy_intp istart, npy_intp + iend, char **errmsg) + +Resets the iterator to a new iterator index range + +If errmsg is non-NULL, it should point to a variable which will +receive the error message, and no Python exception will be set. +This is so that the function can be called from code not holding +the GIL. + +:: + + int + NpyIter_GetNDim(NpyIter *iter) + +Gets the number of dimensions being iterated + +:: + + int + NpyIter_GetNOp(NpyIter *iter) + +Gets the number of operands being iterated + +:: + + NpyIter_IterNextFunc * + NpyIter_GetIterNext(NpyIter *iter, char **errmsg) + +Compute the specialized iteration function for an iterator + +If errmsg is non-NULL, it should point to a variable which will +receive the error message, and no Python exception will be set. +This is so that the function can be called from code not holding +the GIL. + +:: + + npy_intp + NpyIter_GetIterSize(NpyIter *iter) + +Gets the number of elements being iterated + +:: + + void + NpyIter_GetIterIndexRange(NpyIter *iter, npy_intp *istart, npy_intp + *iend) + +Gets the range of iteration indices being iterated + +:: + + npy_intp + NpyIter_GetIterIndex(NpyIter *iter) + +Gets the current iteration index + +:: + + int + NpyIter_GotoIterIndex(NpyIter *iter, npy_intp iterindex) + +Sets the iterator position to the specified iterindex, +which matches the iteration order of the iterator. + +Returns NPY_SUCCEED on success, NPY_FAIL on failure. + +:: + + npy_bool + NpyIter_HasMultiIndex(NpyIter *iter) + +Whether the iterator is tracking a multi-index + +:: + + int + NpyIter_GetShape(NpyIter *iter, npy_intp *outshape) + +Gets the broadcast shape if a multi-index is being tracked by the iterator, +otherwise gets the shape of the iteration as Fortran-order +(fastest-changing index first). + +The reason Fortran-order is returned when a multi-index +is not enabled is that this is providing a direct view into how +the iterator traverses the n-dimensional space. The iterator organizes +its memory from fastest index to slowest index, and when +a multi-index is enabled, it uses a permutation to recover the original +order. + +Returns NPY_SUCCEED or NPY_FAIL. + +:: + + NpyIter_GetMultiIndexFunc * + NpyIter_GetGetMultiIndex(NpyIter *iter, char **errmsg) + +Compute a specialized get_multi_index function for the iterator + +If errmsg is non-NULL, it should point to a variable which will +receive the error message, and no Python exception will be set. +This is so that the function can be called from code not holding +the GIL. + +:: + + int + NpyIter_GotoMultiIndex(NpyIter *iter, npy_intp *multi_index) + +Sets the iterator to the specified multi-index, which must have the +correct number of entries for 'ndim'. It is only valid +when NPY_ITER_MULTI_INDEX was passed to the constructor. This operation +fails if the multi-index is out of bounds. + +Returns NPY_SUCCEED on success, NPY_FAIL on failure. + +:: + + int + NpyIter_RemoveMultiIndex(NpyIter *iter) + +Removes multi-index support from an iterator. + +Returns NPY_SUCCEED or NPY_FAIL. + +:: + + npy_bool + NpyIter_HasIndex(NpyIter *iter) + +Whether the iterator is tracking an index + +:: + + npy_bool + NpyIter_IsBuffered(NpyIter *iter) + +Whether the iterator is buffered + +:: + + npy_bool + NpyIter_IsGrowInner(NpyIter *iter) + +Whether the inner loop can grow if buffering is unneeded + +:: + + npy_intp + NpyIter_GetBufferSize(NpyIter *iter) + +Gets the size of the buffer, or 0 if buffering is not enabled + +:: + + npy_intp * + NpyIter_GetIndexPtr(NpyIter *iter) + +Get a pointer to the index, if it is being tracked + +:: + + int + NpyIter_GotoIndex(NpyIter *iter, npy_intp flat_index) + +If the iterator is tracking an index, sets the iterator +to the specified index. + +Returns NPY_SUCCEED on success, NPY_FAIL on failure. + +:: + + char ** + NpyIter_GetDataPtrArray(NpyIter *iter) + +Get the array of data pointers (1 per object being iterated) + +This function may be safely called without holding the Python GIL. + +:: + + PyArray_Descr ** + NpyIter_GetDescrArray(NpyIter *iter) + +Get the array of data type pointers (1 per object being iterated) + +:: + + PyArrayObject ** + NpyIter_GetOperandArray(NpyIter *iter) + +Get the array of objects being iterated + +:: + + PyArrayObject * + NpyIter_GetIterView(NpyIter *iter, npy_intp i) + +Returns a view to the i-th object with the iterator's internal axes + +:: + + void + NpyIter_GetReadFlags(NpyIter *iter, char *outreadflags) + +Gets an array of read flags (1 per object being iterated) + +:: + + void + NpyIter_GetWriteFlags(NpyIter *iter, char *outwriteflags) + +Gets an array of write flags (1 per object being iterated) + +:: + + void + NpyIter_DebugPrint(NpyIter *iter) + +For debugging + +:: + + npy_bool + NpyIter_IterationNeedsAPI(NpyIter *iter) + +Whether the iteration loop, and in particular the iternext() +function, needs API access. If this is true, the GIL must +be retained while iterating. + +:: + + void + NpyIter_GetInnerFixedStrideArray(NpyIter *iter, npy_intp *out_strides) + +Get an array of strides which are fixed. Any strides which may +change during iteration receive the value NPY_MAX_INTP. Once +the iterator is ready to iterate, call this to get the strides +which will always be fixed in the inner loop, then choose optimized +inner loop functions which take advantage of those fixed strides. + +This function may be safely called without holding the Python GIL. + +:: + + int + NpyIter_RemoveAxis(NpyIter *iter, int axis) + +Removes an axis from iteration. This requires that NPY_ITER_MULTI_INDEX +was set for iterator creation, and does not work if buffering is +enabled. This function also resets the iterator to its initial state. + +Returns NPY_SUCCEED or NPY_FAIL. + +:: + + npy_intp * + NpyIter_GetAxisStrideArray(NpyIter *iter, int axis) + +Gets the array of strides for the specified axis. +If the iterator is tracking a multi-index, gets the strides +for the axis specified, otherwise gets the strides for +the iteration axis as Fortran order (fastest-changing axis first). + +Returns NULL if an error occurs. + +:: + + npy_bool + NpyIter_RequiresBuffering(NpyIter *iter) + +Whether the iteration could be done with no buffering. + +:: + + char ** + NpyIter_GetInitialDataPtrArray(NpyIter *iter) + +Get the array of data pointers (1 per object being iterated), +directly into the arrays (never pointing to a buffer), for starting +unbuffered iteration. This always returns the addresses for the +iterator position as reset to iterator index 0. + +These pointers are different from the pointers accepted by +NpyIter_ResetBasePointers, because the direction along some +axes may have been reversed, requiring base offsets. + +This function may be safely called without holding the Python GIL. + +:: + + int + NpyIter_CreateCompatibleStrides(NpyIter *iter, npy_intp + itemsize, npy_intp *outstrides) + +Builds a set of strides which are the same as the strides of an +output array created using the NPY_ITER_ALLOCATE flag, where NULL +was passed for op_axes. This is for data packed contiguously, +but not necessarily in C or Fortran order. This should be used +together with NpyIter_GetShape and NpyIter_GetNDim. + +A use case for this function is to match the shape and layout of +the iterator and tack on one or more dimensions. For example, +in order to generate a vector per input value for a numerical gradient, +you pass in ndim*itemsize for itemsize, then add another dimension to +the end with size ndim and stride itemsize. To do the Hessian matrix, +you do the same thing but add two dimensions, or take advantage of +the symmetry and pack it into 1 dimension with a particular encoding. + +This function may only be called if the iterator is tracking a multi-index +and if NPY_ITER_DONT_NEGATE_STRIDES was used to prevent an axis from +being iterated in reverse order. + +If an array is created with this method, simply adding 'itemsize' +for each iteration will traverse the new array matching the +iterator. + +Returns NPY_SUCCEED or NPY_FAIL. + +:: + + int + PyArray_CastingConverter(PyObject *obj, NPY_CASTING *casting) + +Convert any Python object, *obj*, to an NPY_CASTING enum. + +:: + + npy_intp + PyArray_CountNonzero(PyArrayObject *self) + +Counts the number of non-zero elements in the array. + +Returns -1 on error. + +:: + + PyArray_Descr * + PyArray_PromoteTypes(PyArray_Descr *type1, PyArray_Descr *type2) + +Produces the smallest size and lowest kind type to which both +input types can be cast. + +:: + + PyArray_Descr * + PyArray_MinScalarType(PyArrayObject *arr) + +If arr is a scalar (has 0 dimensions) with a built-in number data type, +finds the smallest type size/kind which can still represent its data. +Otherwise, returns the array's data type. + + +:: + + PyArray_Descr * + PyArray_ResultType(npy_intp narrs, PyArrayObject **arr, npy_intp + ndtypes, PyArray_Descr **dtypes) + +Produces the result type of a bunch of inputs, using the UFunc +type promotion rules. Use this function when you have a set of +input arrays, and need to determine an output array dtype. + +If all the inputs are scalars (have 0 dimensions) or the maximum "kind" +of the scalars is greater than the maximum "kind" of the arrays, does +a regular type promotion. + +Otherwise, does a type promotion on the MinScalarType +of all the inputs. Data types passed directly are treated as array +types. + + +:: + + npy_bool + PyArray_CanCastArrayTo(PyArrayObject *arr, PyArray_Descr + *to, NPY_CASTING casting) + +Returns 1 if the array object may be cast to the given data type using +the casting rule, 0 otherwise. This differs from PyArray_CanCastTo in +that it handles scalar arrays (0 dimensions) specially, by checking +their value. + +:: + + npy_bool + PyArray_CanCastTypeTo(PyArray_Descr *from, PyArray_Descr + *to, NPY_CASTING casting) + +Returns true if data of type 'from' may be cast to data of type +'to' according to the rule 'casting'. + +:: + + PyArrayObject * + PyArray_EinsteinSum(char *subscripts, npy_intp nop, PyArrayObject + **op_in, PyArray_Descr *dtype, NPY_ORDER + order, NPY_CASTING casting, PyArrayObject *out) + +This function provides summation of array elements according to +the Einstein summation convention. For example: +- trace(a) -> einsum("ii", a) +- transpose(a) -> einsum("ji", a) +- multiply(a,b) -> einsum(",", a, b) +- inner(a,b) -> einsum("i,i", a, b) +- outer(a,b) -> einsum("i,j", a, b) +- matvec(a,b) -> einsum("ij,j", a, b) +- matmat(a,b) -> einsum("ij,jk", a, b) + +subscripts: The string of subscripts for einstein summation. +nop: The number of operands +op_in: The array of operands +dtype: Either NULL, or the data type to force the calculation as. +order: The order for the calculation/the output axes. +casting: What kind of casts should be permitted. +out: Either NULL, or an array into which the output should be placed. + +By default, the labels get placed in alphabetical order +at the end of the output. So, if c = einsum("i,j", a, b) +then c[i,j] == a[i]*b[j], but if c = einsum("j,i", a, b) +then c[i,j] = a[j]*b[i]. + +Alternatively, you can control the output order or prevent +an axis from being summed/force an axis to be summed by providing +indices for the output. This allows us to turn 'trace' into +'diag', for example. +- diag(a) -> einsum("ii->i", a) +- sum(a, axis=0) -> einsum("i...->", a) + +Subscripts at the beginning and end may be specified by +putting an ellipsis "..." in the middle. For example, +the function einsum("i...i", a) takes the diagonal of +the first and last dimensions of the operand, and +einsum("ij...,jk...->ik...") takes the matrix product using +the first two indices of each operand instead of the last two. + +When there is only one operand, no axes being summed, and +no output parameter, this function returns a view +into the operand instead of making a copy. + +:: + + PyObject * + PyArray_NewLikeArray(PyArrayObject *prototype, NPY_ORDER + order, PyArray_Descr *dtype, int subok) + +Creates a new array with the same shape as the provided one, +with possible memory layout order and data type changes. + +prototype - The array the new one should be like. +order - NPY_CORDER - C-contiguous result. +NPY_FORTRANORDER - Fortran-contiguous result. +NPY_ANYORDER - Fortran if prototype is Fortran, C otherwise. +NPY_KEEPORDER - Keeps the axis ordering of prototype. +dtype - If not NULL, overrides the data type of the result. +subok - If 1, use the prototype's array subtype, otherwise +always create a base-class array. + +NOTE: If dtype is not NULL, steals the dtype reference. + +:: + + int + PyArray_GetArrayParamsFromObject(PyObject *op, PyArray_Descr + *requested_dtype, npy_bool + writeable, PyArray_Descr + **out_dtype, int *out_ndim, npy_intp + *out_dims, PyArrayObject + **out_arr, PyObject *context) + +Retrieves the array parameters for viewing/converting an arbitrary +PyObject* to a NumPy array. This allows the "innate type and shape" +of Python list-of-lists to be discovered without +actually converting to an array. + +In some cases, such as structured arrays and the __array__ interface, +a data type needs to be used to make sense of the object. When +this is needed, provide a Descr for 'requested_dtype', otherwise +provide NULL. This reference is not stolen. Also, if the requested +dtype doesn't modify the interpretation of the input, out_dtype will +still get the "innate" dtype of the object, not the dtype passed +in 'requested_dtype'. + +If writing to the value in 'op' is desired, set the boolean +'writeable' to 1. This raises an error when 'op' is a scalar, list +of lists, or other non-writeable 'op'. + +Result: When success (0 return value) is returned, either out_arr +is filled with a non-NULL PyArrayObject and +the rest of the parameters are untouched, or out_arr is +filled with NULL, and the rest of the parameters are +filled. + +Typical usage: + +PyArrayObject *arr = NULL; +PyArray_Descr *dtype = NULL; +int ndim = 0; +npy_intp dims[NPY_MAXDIMS]; + +if (PyArray_GetArrayParamsFromObject(op, NULL, 1, &dtype, +&ndim, &dims, &arr, NULL) < 0) { +return NULL; +} +if (arr == NULL) { +... validate/change dtype, validate flags, ndim, etc ... +// Could make custom strides here too +arr = PyArray_NewFromDescr(&PyArray_Type, dtype, ndim, +dims, NULL, +is_f_order ? NPY_ARRAY_F_CONTIGUOUS : 0, +NULL); +if (arr == NULL) { +return NULL; +} +if (PyArray_CopyObject(arr, op) < 0) { +Py_DECREF(arr); +return NULL; +} +} +else { +... in this case the other parameters weren't filled, just +validate and possibly copy arr itself ... +} +... use arr ... + +:: + + int + PyArray_ConvertClipmodeSequence(PyObject *object, NPY_CLIPMODE + *modes, int n) + +Convert an object to an array of n NPY_CLIPMODE values. +This is intended to be used in functions where a different mode +could be applied to each axis, like in ravel_multi_index. + +:: + + PyObject * + PyArray_MatrixProduct2(PyObject *op1, PyObject + *op2, PyArrayObject*out) + +Numeric.matrixproduct(a,v,out) +just like inner product but does the swapaxes stuff on the fly + +:: + + npy_bool + NpyIter_IsFirstVisit(NpyIter *iter, int iop) + +Checks to see whether this is the first time the elements +of the specified reduction operand which the iterator points at are +being seen for the first time. The function returns +a reasonable answer for reduction operands and when buffering is +disabled. The answer may be incorrect for buffered non-reduction +operands. + +This function is intended to be used in EXTERNAL_LOOP mode only, +and will produce some wrong answers when that mode is not enabled. + +If this function returns true, the caller should also +check the inner loop stride of the operand, because if +that stride is 0, then only the first element of the innermost +external loop is being visited for the first time. + +WARNING: For performance reasons, 'iop' is not bounds-checked, +it is not confirmed that 'iop' is actually a reduction +operand, and it is not confirmed that EXTERNAL_LOOP +mode is enabled. These checks are the responsibility of +the caller, and should be done outside of any inner loops. + +:: + + int + PyArray_SetBaseObject(PyArrayObject *arr, PyObject *obj) + +Sets the 'base' attribute of the array. This steals a reference +to 'obj'. + +Returns 0 on success, -1 on failure. + +:: + + void + PyArray_CreateSortedStridePerm(int ndim, npy_intp + *strides, npy_stride_sort_item + *out_strideperm) + + +This function populates the first ndim elements +of strideperm with sorted descending by their absolute values. +For example, the stride array (4, -2, 12) becomes +[(2, 12), (0, 4), (1, -2)]. + +:: + + void + PyArray_RemoveAxesInPlace(PyArrayObject *arr, npy_bool *flags) + + +Removes the axes flagged as True from the array, +modifying it in place. If an axis flagged for removal +has a shape entry bigger than one, this effectively selects +index zero for that axis. + +WARNING: If an axis flagged for removal has a shape equal to zero, +the array will point to invalid memory. The caller must +validate this! +If an axis flagged for removal has a shape larger then one, +the aligned flag (and in the future the contiguous flags), +may need explicite update. +(check also NPY_RELAXED_STRIDES_CHECKING) + +For example, this can be used to remove the reduction axes +from a reduction result once its computation is complete. + +:: + + void + PyArray_DebugPrint(PyArrayObject *obj) + +Prints the raw data of the ndarray in a form useful for debugging +low-level C issues. + +:: + + int + PyArray_FailUnlessWriteable(PyArrayObject *obj, const char *name) + + +This function does nothing if obj is writeable, and raises an exception +(and returns -1) if obj is not writeable. It may also do other +house-keeping, such as issuing warnings on arrays which are transitioning +to become views. Always call this function at some point before writing to +an array. + +'name' is a name for the array, used to give better error +messages. Something like "assignment destination", "output array", or even +just "array". + +:: + + int + PyArray_SetUpdateIfCopyBase(PyArrayObject *arr, PyArrayObject *base) + + +Precondition: 'arr' is a copy of 'base' (though possibly with different +strides, ordering, etc.). This function sets the UPDATEIFCOPY flag and the +->base pointer on 'arr', so that when 'arr' is destructed, it will copy any +changes back to 'base'. + +Steals a reference to 'base'. + +Returns 0 on success, -1 on failure. + +:: + + void * + PyDataMem_NEW(size_t size) + +Allocates memory for array data. + +:: + + void + PyDataMem_FREE(void *ptr) + +Free memory for array data. + +:: + + void * + PyDataMem_RENEW(void *ptr, size_t size) + +Reallocate/resize memory for array data. + +:: + + PyDataMem_EventHookFunc * + PyDataMem_SetEventHook(PyDataMem_EventHookFunc *newhook, void + *user_data, void **old_data) + +Sets the allocation event hook for numpy array data. +Takes a PyDataMem_EventHookFunc *, which has the signature: +void hook(void *old, void *new, size_t size, void *user_data). +Also takes a void *user_data, and void **old_data. + +Returns a pointer to the previous hook or NULL. If old_data is +non-NULL, the previous user_data pointer will be copied to it. + +If not NULL, hook will be called at the end of each PyDataMem_NEW/FREE/RENEW: +result = PyDataMem_NEW(size) -> (*hook)(NULL, result, size, user_data) +PyDataMem_FREE(ptr) -> (*hook)(ptr, NULL, 0, user_data) +result = PyDataMem_RENEW(ptr, size) -> (*hook)(ptr, result, size, user_data) + +When the hook is called, the GIL will be held by the calling +thread. The hook should be written to be reentrant, if it performs +operations that might cause new allocation events (such as the +creation/descruction numpy objects, or creating/destroying Python +objects which might cause a gc) + +:: + + void + PyArray_MapIterSwapAxes(PyArrayMapIterObject *mit, PyArrayObject + **ret, int getmap) + + +:: + + PyObject * + PyArray_MapIterArray(PyArrayObject *a, PyObject *index) + + +:: + + void + PyArray_MapIterNext(PyArrayMapIterObject *mit) + +This function needs to update the state of the map iterator +and point mit->dataptr to the memory-location of the next object + +:: + + int + PyArray_Partition(PyArrayObject *op, PyArrayObject *ktharray, int + axis, NPY_SELECTKIND which) + +Partition an array in-place + +:: + + PyObject * + PyArray_ArgPartition(PyArrayObject *op, PyArrayObject *ktharray, int + axis, NPY_SELECTKIND which) + +ArgPartition an array + +:: + + int + PyArray_SelectkindConverter(PyObject *obj, NPY_SELECTKIND *selectkind) + +Convert object to select kind + +:: + + void * + PyDataMem_NEW_ZEROED(size_t size, size_t elsize) + +Allocates zeroed memory for array data. + diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h b/gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h new file mode 100644 index 000000000..b8c7c3a2d --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h @@ -0,0 +1,237 @@ +/* + * DON'T INCLUDE THIS DIRECTLY. + */ + +#ifndef NPY_NDARRAYOBJECT_H +#define NPY_NDARRAYOBJECT_H +#ifdef __cplusplus +#define CONFUSE_EMACS { +#define CONFUSE_EMACS2 } +extern "C" CONFUSE_EMACS +#undef CONFUSE_EMACS +#undef CONFUSE_EMACS2 +/* ... otherwise a semi-smart identer (like emacs) tries to indent + everything when you're typing */ +#endif + +#include "ndarraytypes.h" + +/* Includes the "function" C-API -- these are all stored in a + list of pointers --- one for each file + The two lists are concatenated into one in multiarray. + + They are available as import_array() +*/ + +#include "__multiarray_api.h" + + +/* C-API that requries previous API to be defined */ + +#define PyArray_DescrCheck(op) (((PyObject*)(op))->ob_type==&PyArrayDescr_Type) + +#define PyArray_Check(op) PyObject_TypeCheck(op, &PyArray_Type) +#define PyArray_CheckExact(op) (((PyObject*)(op))->ob_type == &PyArray_Type) + +#define PyArray_HasArrayInterfaceType(op, type, context, out) \ + ((((out)=PyArray_FromStructInterface(op)) != Py_NotImplemented) || \ + (((out)=PyArray_FromInterface(op)) != Py_NotImplemented) || \ + (((out)=PyArray_FromArrayAttr(op, type, context)) != \ + Py_NotImplemented)) + +#define PyArray_HasArrayInterface(op, out) \ + PyArray_HasArrayInterfaceType(op, NULL, NULL, out) + +#define PyArray_IsZeroDim(op) (PyArray_Check(op) && \ + (PyArray_NDIM((PyArrayObject *)op) == 0)) + +#define PyArray_IsScalar(obj, cls) \ + (PyObject_TypeCheck(obj, &Py##cls##ArrType_Type)) + +#define PyArray_CheckScalar(m) (PyArray_IsScalar(m, Generic) || \ + PyArray_IsZeroDim(m)) + +#define PyArray_IsPythonNumber(obj) \ + (PyInt_Check(obj) || PyFloat_Check(obj) || PyComplex_Check(obj) || \ + PyLong_Check(obj) || PyBool_Check(obj)) + +#define PyArray_IsPythonScalar(obj) \ + (PyArray_IsPythonNumber(obj) || PyString_Check(obj) || \ + PyUnicode_Check(obj)) + +#define PyArray_IsAnyScalar(obj) \ + (PyArray_IsScalar(obj, Generic) || PyArray_IsPythonScalar(obj)) + +#define PyArray_CheckAnyScalar(obj) (PyArray_IsPythonScalar(obj) || \ + PyArray_CheckScalar(obj)) + +#define PyArray_IsIntegerScalar(obj) (PyInt_Check(obj) \ + || PyLong_Check(obj) \ + || PyArray_IsScalar((obj), Integer)) + + +#define PyArray_GETCONTIGUOUS(m) (PyArray_ISCONTIGUOUS(m) ? \ + Py_INCREF(m), (m) : \ + (PyArrayObject *)(PyArray_Copy(m))) + +#define PyArray_SAMESHAPE(a1,a2) ((PyArray_NDIM(a1) == PyArray_NDIM(a2)) && \ + PyArray_CompareLists(PyArray_DIMS(a1), \ + PyArray_DIMS(a2), \ + PyArray_NDIM(a1))) + +#define PyArray_SIZE(m) PyArray_MultiplyList(PyArray_DIMS(m), PyArray_NDIM(m)) +#define PyArray_NBYTES(m) (PyArray_ITEMSIZE(m) * PyArray_SIZE(m)) +#define PyArray_FROM_O(m) PyArray_FromAny(m, NULL, 0, 0, 0, NULL) + +#define PyArray_FROM_OF(m,flags) PyArray_CheckFromAny(m, NULL, 0, 0, flags, \ + NULL) + +#define PyArray_FROM_OT(m,type) PyArray_FromAny(m, \ + PyArray_DescrFromType(type), 0, 0, 0, NULL); + +#define PyArray_FROM_OTF(m, type, flags) \ + PyArray_FromAny(m, PyArray_DescrFromType(type), 0, 0, \ + (((flags) & NPY_ARRAY_ENSURECOPY) ? \ + ((flags) | NPY_ARRAY_DEFAULT) : (flags)), NULL) + +#define PyArray_FROMANY(m, type, min, max, flags) \ + PyArray_FromAny(m, PyArray_DescrFromType(type), min, max, \ + (((flags) & NPY_ARRAY_ENSURECOPY) ? \ + (flags) | NPY_ARRAY_DEFAULT : (flags)), NULL) + +#define PyArray_ZEROS(m, dims, type, is_f_order) \ + PyArray_Zeros(m, dims, PyArray_DescrFromType(type), is_f_order) + +#define PyArray_EMPTY(m, dims, type, is_f_order) \ + PyArray_Empty(m, dims, PyArray_DescrFromType(type), is_f_order) + +#define PyArray_FILLWBYTE(obj, val) memset(PyArray_DATA(obj), val, \ + PyArray_NBYTES(obj)) + +#define PyArray_REFCOUNT(obj) (((PyObject *)(obj))->ob_refcnt) +#define NPY_REFCOUNT PyArray_REFCOUNT +#define NPY_MAX_ELSIZE (2 * NPY_SIZEOF_LONGDOUBLE) + +#define PyArray_ContiguousFromAny(op, type, min_depth, max_depth) \ + PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ + max_depth, NPY_ARRAY_DEFAULT, NULL) + +#define PyArray_EquivArrTypes(a1, a2) \ + PyArray_EquivTypes(PyArray_DESCR(a1), PyArray_DESCR(a2)) + +#define PyArray_EquivByteorders(b1, b2) \ + (((b1) == (b2)) || (PyArray_ISNBO(b1) == PyArray_ISNBO(b2))) + +#define PyArray_SimpleNew(nd, dims, typenum) \ + PyArray_New(&PyArray_Type, nd, dims, typenum, NULL, NULL, 0, 0, NULL) + +#define PyArray_SimpleNewFromData(nd, dims, typenum, data) \ + PyArray_New(&PyArray_Type, nd, dims, typenum, NULL, \ + data, 0, NPY_ARRAY_CARRAY, NULL) + +#define PyArray_SimpleNewFromDescr(nd, dims, descr) \ + PyArray_NewFromDescr(&PyArray_Type, descr, nd, dims, \ + NULL, NULL, 0, NULL) + +#define PyArray_ToScalar(data, arr) \ + PyArray_Scalar(data, PyArray_DESCR(arr), (PyObject *)arr) + + +/* These might be faster without the dereferencing of obj + going on inside -- of course an optimizing compiler should + inline the constants inside a for loop making it a moot point +*/ + +#define PyArray_GETPTR1(obj, i) ((void *)(PyArray_BYTES(obj) + \ + (i)*PyArray_STRIDES(obj)[0])) + +#define PyArray_GETPTR2(obj, i, j) ((void *)(PyArray_BYTES(obj) + \ + (i)*PyArray_STRIDES(obj)[0] + \ + (j)*PyArray_STRIDES(obj)[1])) + +#define PyArray_GETPTR3(obj, i, j, k) ((void *)(PyArray_BYTES(obj) + \ + (i)*PyArray_STRIDES(obj)[0] + \ + (j)*PyArray_STRIDES(obj)[1] + \ + (k)*PyArray_STRIDES(obj)[2])) + +#define PyArray_GETPTR4(obj, i, j, k, l) ((void *)(PyArray_BYTES(obj) + \ + (i)*PyArray_STRIDES(obj)[0] + \ + (j)*PyArray_STRIDES(obj)[1] + \ + (k)*PyArray_STRIDES(obj)[2] + \ + (l)*PyArray_STRIDES(obj)[3])) + +static NPY_INLINE void +PyArray_XDECREF_ERR(PyArrayObject *arr) +{ + if (arr != NULL) { + if (PyArray_FLAGS(arr) & NPY_ARRAY_UPDATEIFCOPY) { + PyArrayObject *base = (PyArrayObject *)PyArray_BASE(arr); + PyArray_ENABLEFLAGS(base, NPY_ARRAY_WRITEABLE); + PyArray_CLEARFLAGS(arr, NPY_ARRAY_UPDATEIFCOPY); + } + Py_DECREF(arr); + } +} + +#define PyArray_DESCR_REPLACE(descr) do { \ + PyArray_Descr *_new_; \ + _new_ = PyArray_DescrNew(descr); \ + Py_XDECREF(descr); \ + descr = _new_; \ + } while(0) + +/* Copy should always return contiguous array */ +#define PyArray_Copy(obj) PyArray_NewCopy(obj, NPY_CORDER) + +#define PyArray_FromObject(op, type, min_depth, max_depth) \ + PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ + max_depth, NPY_ARRAY_BEHAVED | \ + NPY_ARRAY_ENSUREARRAY, NULL) + +#define PyArray_ContiguousFromObject(op, type, min_depth, max_depth) \ + PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ + max_depth, NPY_ARRAY_DEFAULT | \ + NPY_ARRAY_ENSUREARRAY, NULL) + +#define PyArray_CopyFromObject(op, type, min_depth, max_depth) \ + PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ + max_depth, NPY_ARRAY_ENSURECOPY | \ + NPY_ARRAY_DEFAULT | \ + NPY_ARRAY_ENSUREARRAY, NULL) + +#define PyArray_Cast(mp, type_num) \ + PyArray_CastToType(mp, PyArray_DescrFromType(type_num), 0) + +#define PyArray_Take(ap, items, axis) \ + PyArray_TakeFrom(ap, items, axis, NULL, NPY_RAISE) + +#define PyArray_Put(ap, items, values) \ + PyArray_PutTo(ap, items, values, NPY_RAISE) + +/* Compatibility with old Numeric stuff -- don't use in new code */ + +#define PyArray_FromDimsAndData(nd, d, type, data) \ + PyArray_FromDimsAndDataAndDescr(nd, d, PyArray_DescrFromType(type), \ + data) + + +/* + Check to see if this key in the dictionary is the "title" + entry of the tuple (i.e. a duplicate dictionary entry in the fields + dict. +*/ + +#define NPY_TITLE_KEY(key, value) ((PyTuple_GET_SIZE((value))==3) && \ + (PyTuple_GET_ITEM((value), 2) == (key))) + + +#define DEPRECATE(msg) PyErr_WarnEx(PyExc_DeprecationWarning,msg,1) +#define DEPRECATE_FUTUREWARNING(msg) PyErr_WarnEx(PyExc_FutureWarning,msg,1) + + +#ifdef __cplusplus +} +#endif + + +#endif /* NPY_NDARRAYOBJECT_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h b/gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h new file mode 100644 index 000000000..373a4df53 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h @@ -0,0 +1,1777 @@ +#ifndef NDARRAYTYPES_H +#define NDARRAYTYPES_H + +#include "npy_common.h" +#include "npy_endian.h" +#include "npy_cpu.h" +#include "utils.h" + +#ifdef NPY_ENABLE_SEPARATE_COMPILATION + #define NPY_NO_EXPORT NPY_VISIBILITY_HIDDEN +#else + #define NPY_NO_EXPORT static +#endif + +/* Only use thread if configured in config and python supports it */ +#if defined WITH_THREAD && !NPY_NO_SMP + #define NPY_ALLOW_THREADS 1 +#else + #define NPY_ALLOW_THREADS 0 +#endif + + + +/* + * There are several places in the code where an array of dimensions + * is allocated statically. This is the size of that static + * allocation. + * + * The array creation itself could have arbitrary dimensions but all + * the places where static allocation is used would need to be changed + * to dynamic (including inside of several structures) + */ + +#define NPY_MAXDIMS 32 +#define NPY_MAXARGS 32 + +/* Used for Converter Functions "O&" code in ParseTuple */ +#define NPY_FAIL 0 +#define NPY_SUCCEED 1 + +/* + * Binary compatibility version number. This number is increased + * whenever the C-API is changed such that binary compatibility is + * broken, i.e. whenever a recompile of extension modules is needed. + */ +#define NPY_VERSION NPY_ABI_VERSION + +/* + * Minor API version. This number is increased whenever a change is + * made to the C-API -- whether it breaks binary compatibility or not. + * Some changes, such as adding a function pointer to the end of the + * function table, can be made without breaking binary compatibility. + * In this case, only the NPY_FEATURE_VERSION (*not* NPY_VERSION) + * would be increased. Whenever binary compatibility is broken, both + * NPY_VERSION and NPY_FEATURE_VERSION should be increased. + */ +#define NPY_FEATURE_VERSION NPY_API_VERSION + +enum NPY_TYPES { NPY_BOOL=0, + NPY_BYTE, NPY_UBYTE, + NPY_SHORT, NPY_USHORT, + NPY_INT, NPY_UINT, + NPY_LONG, NPY_ULONG, + NPY_LONGLONG, NPY_ULONGLONG, + NPY_FLOAT, NPY_DOUBLE, NPY_LONGDOUBLE, + NPY_CFLOAT, NPY_CDOUBLE, NPY_CLONGDOUBLE, + NPY_OBJECT=17, + NPY_STRING, NPY_UNICODE, + NPY_VOID, + /* + * New 1.6 types appended, may be integrated + * into the above in 2.0. + */ + NPY_DATETIME, NPY_TIMEDELTA, NPY_HALF, + + NPY_NTYPES, + NPY_NOTYPE, + NPY_CHAR, /* special flag */ + NPY_USERDEF=256, /* leave room for characters */ + + /* The number of types not including the new 1.6 types */ + NPY_NTYPES_ABI_COMPATIBLE=21 +}; + +/* basetype array priority */ +#define NPY_PRIORITY 0.0 + +/* default subtype priority */ +#define NPY_SUBTYPE_PRIORITY 1.0 + +/* default scalar priority */ +#define NPY_SCALAR_PRIORITY -1000000.0 + +/* How many floating point types are there (excluding half) */ +#define NPY_NUM_FLOATTYPE 3 + +/* + * These characters correspond to the array type and the struct + * module + */ + +enum NPY_TYPECHAR { + NPY_BOOLLTR = '?', + NPY_BYTELTR = 'b', + NPY_UBYTELTR = 'B', + NPY_SHORTLTR = 'h', + NPY_USHORTLTR = 'H', + NPY_INTLTR = 'i', + NPY_UINTLTR = 'I', + NPY_LONGLTR = 'l', + NPY_ULONGLTR = 'L', + NPY_LONGLONGLTR = 'q', + NPY_ULONGLONGLTR = 'Q', + NPY_HALFLTR = 'e', + NPY_FLOATLTR = 'f', + NPY_DOUBLELTR = 'd', + NPY_LONGDOUBLELTR = 'g', + NPY_CFLOATLTR = 'F', + NPY_CDOUBLELTR = 'D', + NPY_CLONGDOUBLELTR = 'G', + NPY_OBJECTLTR = 'O', + NPY_STRINGLTR = 'S', + NPY_STRINGLTR2 = 'a', + NPY_UNICODELTR = 'U', + NPY_VOIDLTR = 'V', + NPY_DATETIMELTR = 'M', + NPY_TIMEDELTALTR = 'm', + NPY_CHARLTR = 'c', + + /* + * No Descriptor, just a define -- this let's + * Python users specify an array of integers + * large enough to hold a pointer on the + * platform + */ + NPY_INTPLTR = 'p', + NPY_UINTPLTR = 'P', + + /* + * These are for dtype 'kinds', not dtype 'typecodes' + * as the above are for. + */ + NPY_GENBOOLLTR ='b', + NPY_SIGNEDLTR = 'i', + NPY_UNSIGNEDLTR = 'u', + NPY_FLOATINGLTR = 'f', + NPY_COMPLEXLTR = 'c' +}; + +typedef enum { + NPY_QUICKSORT=0, + NPY_HEAPSORT=1, + NPY_MERGESORT=2 +} NPY_SORTKIND; +#define NPY_NSORTS (NPY_MERGESORT + 1) + + +typedef enum { + NPY_INTROSELECT=0, +} NPY_SELECTKIND; +#define NPY_NSELECTS (NPY_INTROSELECT + 1) + + +typedef enum { + NPY_SEARCHLEFT=0, + NPY_SEARCHRIGHT=1 +} NPY_SEARCHSIDE; +#define NPY_NSEARCHSIDES (NPY_SEARCHRIGHT + 1) + + +typedef enum { + NPY_NOSCALAR=-1, + NPY_BOOL_SCALAR, + NPY_INTPOS_SCALAR, + NPY_INTNEG_SCALAR, + NPY_FLOAT_SCALAR, + NPY_COMPLEX_SCALAR, + NPY_OBJECT_SCALAR +} NPY_SCALARKIND; +#define NPY_NSCALARKINDS (NPY_OBJECT_SCALAR + 1) + +/* For specifying array memory layout or iteration order */ +typedef enum { + /* Fortran order if inputs are all Fortran, C otherwise */ + NPY_ANYORDER=-1, + /* C order */ + NPY_CORDER=0, + /* Fortran order */ + NPY_FORTRANORDER=1, + /* An order as close to the inputs as possible */ + NPY_KEEPORDER=2 +} NPY_ORDER; + +/* For specifying allowed casting in operations which support it */ +typedef enum { + /* Only allow identical types */ + NPY_NO_CASTING=0, + /* Allow identical and byte swapped types */ + NPY_EQUIV_CASTING=1, + /* Only allow safe casts */ + NPY_SAFE_CASTING=2, + /* Allow safe casts or casts within the same kind */ + NPY_SAME_KIND_CASTING=3, + /* Allow any casts */ + NPY_UNSAFE_CASTING=4, + + /* + * Temporary internal definition only, will be removed in upcoming + * release, see below + * */ + NPY_INTERNAL_UNSAFE_CASTING_BUT_WARN_UNLESS_SAME_KIND = 100, +} NPY_CASTING; + +typedef enum { + NPY_CLIP=0, + NPY_WRAP=1, + NPY_RAISE=2 +} NPY_CLIPMODE; + +/* The special not-a-time (NaT) value */ +#define NPY_DATETIME_NAT NPY_MIN_INT64 + +/* + * Upper bound on the length of a DATETIME ISO 8601 string + * YEAR: 21 (64-bit year) + * MONTH: 3 + * DAY: 3 + * HOURS: 3 + * MINUTES: 3 + * SECONDS: 3 + * ATTOSECONDS: 1 + 3*6 + * TIMEZONE: 5 + * NULL TERMINATOR: 1 + */ +#define NPY_DATETIME_MAX_ISO8601_STRLEN (21+3*5+1+3*6+6+1) + +typedef enum { + NPY_FR_Y = 0, /* Years */ + NPY_FR_M = 1, /* Months */ + NPY_FR_W = 2, /* Weeks */ + /* Gap where 1.6 NPY_FR_B (value 3) was */ + NPY_FR_D = 4, /* Days */ + NPY_FR_h = 5, /* hours */ + NPY_FR_m = 6, /* minutes */ + NPY_FR_s = 7, /* seconds */ + NPY_FR_ms = 8, /* milliseconds */ + NPY_FR_us = 9, /* microseconds */ + NPY_FR_ns = 10,/* nanoseconds */ + NPY_FR_ps = 11,/* picoseconds */ + NPY_FR_fs = 12,/* femtoseconds */ + NPY_FR_as = 13,/* attoseconds */ + NPY_FR_GENERIC = 14 /* Generic, unbound units, can convert to anything */ +} NPY_DATETIMEUNIT; + +/* + * NOTE: With the NPY_FR_B gap for 1.6 ABI compatibility, NPY_DATETIME_NUMUNITS + * is technically one more than the actual number of units. + */ +#define NPY_DATETIME_NUMUNITS (NPY_FR_GENERIC + 1) +#define NPY_DATETIME_DEFAULTUNIT NPY_FR_GENERIC + +/* + * Business day conventions for mapping invalid business + * days to valid business days. + */ +typedef enum { + /* Go forward in time to the following business day. */ + NPY_BUSDAY_FORWARD, + NPY_BUSDAY_FOLLOWING = NPY_BUSDAY_FORWARD, + /* Go backward in time to the preceding business day. */ + NPY_BUSDAY_BACKWARD, + NPY_BUSDAY_PRECEDING = NPY_BUSDAY_BACKWARD, + /* + * Go forward in time to the following business day, unless it + * crosses a month boundary, in which case go backward + */ + NPY_BUSDAY_MODIFIEDFOLLOWING, + /* + * Go backward in time to the preceding business day, unless it + * crosses a month boundary, in which case go forward. + */ + NPY_BUSDAY_MODIFIEDPRECEDING, + /* Produce a NaT for non-business days. */ + NPY_BUSDAY_NAT, + /* Raise an exception for non-business days. */ + NPY_BUSDAY_RAISE +} NPY_BUSDAY_ROLL; + +/************************************************************ + * NumPy Auxiliary Data for inner loops, sort functions, etc. + ************************************************************/ + +/* + * When creating an auxiliary data struct, this should always appear + * as the first member, like this: + * + * typedef struct { + * NpyAuxData base; + * double constant; + * } constant_multiplier_aux_data; + */ +typedef struct NpyAuxData_tag NpyAuxData; + +/* Function pointers for freeing or cloning auxiliary data */ +typedef void (NpyAuxData_FreeFunc) (NpyAuxData *); +typedef NpyAuxData *(NpyAuxData_CloneFunc) (NpyAuxData *); + +struct NpyAuxData_tag { + NpyAuxData_FreeFunc *free; + NpyAuxData_CloneFunc *clone; + /* To allow for a bit of expansion without breaking the ABI */ + void *reserved[2]; +}; + +/* Macros to use for freeing and cloning auxiliary data */ +#define NPY_AUXDATA_FREE(auxdata) \ + do { \ + if ((auxdata) != NULL) { \ + (auxdata)->free(auxdata); \ + } \ + } while(0) +#define NPY_AUXDATA_CLONE(auxdata) \ + ((auxdata)->clone(auxdata)) + +#define NPY_ERR(str) fprintf(stderr, #str); fflush(stderr); +#define NPY_ERR2(str) fprintf(stderr, str); fflush(stderr); + +#define NPY_STRINGIFY(x) #x +#define NPY_TOSTRING(x) NPY_STRINGIFY(x) + + /* + * Macros to define how array, and dimension/strides data is + * allocated. + */ + + /* Data buffer - PyDataMem_NEW/FREE/RENEW are in multiarraymodule.c */ + +#define NPY_USE_PYMEM 1 + +#if NPY_USE_PYMEM == 1 +#define PyArray_malloc PyMem_Malloc +#define PyArray_free PyMem_Free +#define PyArray_realloc PyMem_Realloc +#else +#define PyArray_malloc malloc +#define PyArray_free free +#define PyArray_realloc realloc +#endif + +/* Dimensions and strides */ +#define PyDimMem_NEW(size) \ + ((npy_intp *)PyArray_malloc(size*sizeof(npy_intp))) + +#define PyDimMem_FREE(ptr) PyArray_free(ptr) + +#define PyDimMem_RENEW(ptr,size) \ + ((npy_intp *)PyArray_realloc(ptr,size*sizeof(npy_intp))) + +/* forward declaration */ +struct _PyArray_Descr; + +/* These must deal with unaligned and swapped data if necessary */ +typedef PyObject * (PyArray_GetItemFunc) (void *, void *); +typedef int (PyArray_SetItemFunc)(PyObject *, void *, void *); + +typedef void (PyArray_CopySwapNFunc)(void *, npy_intp, void *, npy_intp, + npy_intp, int, void *); + +typedef void (PyArray_CopySwapFunc)(void *, void *, int, void *); +typedef npy_bool (PyArray_NonzeroFunc)(void *, void *); + + +/* + * These assume aligned and notswapped data -- a buffer will be used + * before or contiguous data will be obtained + */ + +typedef int (PyArray_CompareFunc)(const void *, const void *, void *); +typedef int (PyArray_ArgFunc)(void*, npy_intp, npy_intp*, void *); + +typedef void (PyArray_DotFunc)(void *, npy_intp, void *, npy_intp, void *, + npy_intp, void *); + +typedef void (PyArray_VectorUnaryFunc)(void *, void *, npy_intp, void *, + void *); + +/* + * XXX the ignore argument should be removed next time the API version + * is bumped. It used to be the separator. + */ +typedef int (PyArray_ScanFunc)(FILE *fp, void *dptr, + char *ignore, struct _PyArray_Descr *); +typedef int (PyArray_FromStrFunc)(char *s, void *dptr, char **endptr, + struct _PyArray_Descr *); + +typedef int (PyArray_FillFunc)(void *, npy_intp, void *); + +typedef int (PyArray_SortFunc)(void *, npy_intp, void *); +typedef int (PyArray_ArgSortFunc)(void *, npy_intp *, npy_intp, void *); +typedef int (PyArray_PartitionFunc)(void *, npy_intp, npy_intp, + npy_intp *, npy_intp *, + void *); +typedef int (PyArray_ArgPartitionFunc)(void *, npy_intp *, npy_intp, npy_intp, + npy_intp *, npy_intp *, + void *); + +typedef int (PyArray_FillWithScalarFunc)(void *, npy_intp, void *, void *); + +typedef int (PyArray_ScalarKindFunc)(void *); + +typedef void (PyArray_FastClipFunc)(void *in, npy_intp n_in, void *min, + void *max, void *out); +typedef void (PyArray_FastPutmaskFunc)(void *in, void *mask, npy_intp n_in, + void *values, npy_intp nv); +typedef int (PyArray_FastTakeFunc)(void *dest, void *src, npy_intp *indarray, + npy_intp nindarray, npy_intp n_outer, + npy_intp m_middle, npy_intp nelem, + NPY_CLIPMODE clipmode); + +typedef struct { + npy_intp *ptr; + int len; +} PyArray_Dims; + +typedef struct { + /* + * Functions to cast to most other standard types + * Can have some NULL entries. The types + * DATETIME, TIMEDELTA, and HALF go into the castdict + * even though they are built-in. + */ + PyArray_VectorUnaryFunc *cast[NPY_NTYPES_ABI_COMPATIBLE]; + + /* The next four functions *cannot* be NULL */ + + /* + * Functions to get and set items with standard Python types + * -- not array scalars + */ + PyArray_GetItemFunc *getitem; + PyArray_SetItemFunc *setitem; + + /* + * Copy and/or swap data. Memory areas may not overlap + * Use memmove first if they might + */ + PyArray_CopySwapNFunc *copyswapn; + PyArray_CopySwapFunc *copyswap; + + /* + * Function to compare items + * Can be NULL + */ + PyArray_CompareFunc *compare; + + /* + * Function to select largest + * Can be NULL + */ + PyArray_ArgFunc *argmax; + + /* + * Function to compute dot product + * Can be NULL + */ + PyArray_DotFunc *dotfunc; + + /* + * Function to scan an ASCII file and + * place a single value plus possible separator + * Can be NULL + */ + PyArray_ScanFunc *scanfunc; + + /* + * Function to read a single value from a string + * and adjust the pointer; Can be NULL + */ + PyArray_FromStrFunc *fromstr; + + /* + * Function to determine if data is zero or not + * If NULL a default version is + * used at Registration time. + */ + PyArray_NonzeroFunc *nonzero; + + /* + * Used for arange. + * Can be NULL. + */ + PyArray_FillFunc *fill; + + /* + * Function to fill arrays with scalar values + * Can be NULL + */ + PyArray_FillWithScalarFunc *fillwithscalar; + + /* + * Sorting functions + * Can be NULL + */ + PyArray_SortFunc *sort[NPY_NSORTS]; + PyArray_ArgSortFunc *argsort[NPY_NSORTS]; + + /* + * Dictionary of additional casting functions + * PyArray_VectorUnaryFuncs + * which can be populated to support casting + * to other registered types. Can be NULL + */ + PyObject *castdict; + + /* + * Functions useful for generalizing + * the casting rules. + * Can be NULL; + */ + PyArray_ScalarKindFunc *scalarkind; + int **cancastscalarkindto; + int *cancastto; + + PyArray_FastClipFunc *fastclip; + PyArray_FastPutmaskFunc *fastputmask; + PyArray_FastTakeFunc *fasttake; + + /* + * Function to select smallest + * Can be NULL + */ + PyArray_ArgFunc *argmin; + +} PyArray_ArrFuncs; + +/* The item must be reference counted when it is inserted or extracted. */ +#define NPY_ITEM_REFCOUNT 0x01 +/* Same as needing REFCOUNT */ +#define NPY_ITEM_HASOBJECT 0x01 +/* Convert to list for pickling */ +#define NPY_LIST_PICKLE 0x02 +/* The item is a POINTER */ +#define NPY_ITEM_IS_POINTER 0x04 +/* memory needs to be initialized for this data-type */ +#define NPY_NEEDS_INIT 0x08 +/* operations need Python C-API so don't give-up thread. */ +#define NPY_NEEDS_PYAPI 0x10 +/* Use f.getitem when extracting elements of this data-type */ +#define NPY_USE_GETITEM 0x20 +/* Use f.setitem when setting creating 0-d array from this data-type.*/ +#define NPY_USE_SETITEM 0x40 +/* A sticky flag specifically for structured arrays */ +#define NPY_ALIGNED_STRUCT 0x80 + +/* + *These are inherited for global data-type if any data-types in the + * field have them + */ +#define NPY_FROM_FIELDS (NPY_NEEDS_INIT | NPY_LIST_PICKLE | \ + NPY_ITEM_REFCOUNT | NPY_NEEDS_PYAPI) + +#define NPY_OBJECT_DTYPE_FLAGS (NPY_LIST_PICKLE | NPY_USE_GETITEM | \ + NPY_ITEM_IS_POINTER | NPY_ITEM_REFCOUNT | \ + NPY_NEEDS_INIT | NPY_NEEDS_PYAPI) + +#define PyDataType_FLAGCHK(dtype, flag) \ + (((dtype)->flags & (flag)) == (flag)) + +#define PyDataType_REFCHK(dtype) \ + PyDataType_FLAGCHK(dtype, NPY_ITEM_REFCOUNT) + +typedef struct _PyArray_Descr { + PyObject_HEAD + /* + * the type object representing an + * instance of this type -- should not + * be two type_numbers with the same type + * object. + */ + PyTypeObject *typeobj; + /* kind for this type */ + char kind; + /* unique-character representing this type */ + char type; + /* + * '>' (big), '<' (little), '|' + * (not-applicable), or '=' (native). + */ + char byteorder; + /* flags describing data type */ + char flags; + /* number representing this type */ + int type_num; + /* element size (itemsize) for this type */ + int elsize; + /* alignment needed for this type */ + int alignment; + /* + * Non-NULL if this type is + * is an array (C-contiguous) + * of some other type + */ + struct _arr_descr *subarray; + /* + * The fields dictionary for this type + * For statically defined descr this + * is always Py_None + */ + PyObject *fields; + /* + * An ordered tuple of field names or NULL + * if no fields are defined + */ + PyObject *names; + /* + * a table of functions specific for each + * basic data descriptor + */ + PyArray_ArrFuncs *f; + /* Metadata about this dtype */ + PyObject *metadata; + /* + * Metadata specific to the C implementation + * of the particular dtype. This was added + * for NumPy 1.7.0. + */ + NpyAuxData *c_metadata; +} PyArray_Descr; + +typedef struct _arr_descr { + PyArray_Descr *base; + PyObject *shape; /* a tuple */ +} PyArray_ArrayDescr; + +/* + * The main array object structure. + * + * It has been recommended to use the inline functions defined below + * (PyArray_DATA and friends) to access fields here for a number of + * releases. Direct access to the members themselves is deprecated. + * To ensure that your code does not use deprecated access, + * #define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION + * (or NPY_1_8_API_VERSION or higher as required). + */ +/* This struct will be moved to a private header in a future release */ +typedef struct tagPyArrayObject_fields { + PyObject_HEAD + /* Pointer to the raw data buffer */ + char *data; + /* The number of dimensions, also called 'ndim' */ + int nd; + /* The size in each dimension, also called 'shape' */ + npy_intp *dimensions; + /* + * Number of bytes to jump to get to the + * next element in each dimension + */ + npy_intp *strides; + /* + * This object is decref'd upon + * deletion of array. Except in the + * case of UPDATEIFCOPY which has + * special handling. + * + * For views it points to the original + * array, collapsed so no chains of + * views occur. + * + * For creation from buffer object it + * points to an object that shold be + * decref'd on deletion + * + * For UPDATEIFCOPY flag this is an + * array to-be-updated upon deletion + * of this one + */ + PyObject *base; + /* Pointer to type structure */ + PyArray_Descr *descr; + /* Flags describing array -- see below */ + int flags; + /* For weak references */ + PyObject *weakreflist; +} PyArrayObject_fields; + +/* + * To hide the implementation details, we only expose + * the Python struct HEAD. + */ +#if !defined(NPY_NO_DEPRECATED_API) || \ + (NPY_NO_DEPRECATED_API < NPY_1_7_API_VERSION) +/* + * Can't put this in npy_deprecated_api.h like the others. + * PyArrayObject field access is deprecated as of NumPy 1.7. + */ +typedef PyArrayObject_fields PyArrayObject; +#else +typedef struct tagPyArrayObject { + PyObject_HEAD +} PyArrayObject; +#endif + +#define NPY_SIZEOF_PYARRAYOBJECT (sizeof(PyArrayObject_fields)) + +/* Array Flags Object */ +typedef struct PyArrayFlagsObject { + PyObject_HEAD + PyObject *arr; + int flags; +} PyArrayFlagsObject; + +/* Mirrors buffer object to ptr */ + +typedef struct { + PyObject_HEAD + PyObject *base; + void *ptr; + npy_intp len; + int flags; +} PyArray_Chunk; + +typedef struct { + NPY_DATETIMEUNIT base; + int num; +} PyArray_DatetimeMetaData; + +typedef struct { + NpyAuxData base; + PyArray_DatetimeMetaData meta; +} PyArray_DatetimeDTypeMetaData; + +/* + * This structure contains an exploded view of a date-time value. + * NaT is represented by year == NPY_DATETIME_NAT. + */ +typedef struct { + npy_int64 year; + npy_int32 month, day, hour, min, sec, us, ps, as; +} npy_datetimestruct; + +/* This is not used internally. */ +typedef struct { + npy_int64 day; + npy_int32 sec, us, ps, as; +} npy_timedeltastruct; + +typedef int (PyArray_FinalizeFunc)(PyArrayObject *, PyObject *); + +/* + * Means c-style contiguous (last index varies the fastest). The data + * elements right after each other. + * + * This flag may be requested in constructor functions. + * This flag may be tested for in PyArray_FLAGS(arr). + */ +#define NPY_ARRAY_C_CONTIGUOUS 0x0001 + +/* + * Set if array is a contiguous Fortran array: the first index varies + * the fastest in memory (strides array is reverse of C-contiguous + * array) + * + * This flag may be requested in constructor functions. + * This flag may be tested for in PyArray_FLAGS(arr). + */ +#define NPY_ARRAY_F_CONTIGUOUS 0x0002 + +/* + * Note: all 0-d arrays are C_CONTIGUOUS and F_CONTIGUOUS. If a + * 1-d array is C_CONTIGUOUS it is also F_CONTIGUOUS. Arrays with + * more then one dimension can be C_CONTIGUOUS and F_CONTIGUOUS + * at the same time if they have either zero or one element. + * If NPY_RELAXED_STRIDES_CHECKING is set, a higher dimensional + * array is always C_CONTIGUOUS and F_CONTIGUOUS if it has zero elements + * and the array is contiguous if ndarray.squeeze() is contiguous. + * I.e. dimensions for which `ndarray.shape[dimension] == 1` are + * ignored. + */ + +/* + * If set, the array owns the data: it will be free'd when the array + * is deleted. + * + * This flag may be tested for in PyArray_FLAGS(arr). + */ +#define NPY_ARRAY_OWNDATA 0x0004 + +/* + * An array never has the next four set; they're only used as parameter + * flags to the the various FromAny functions + * + * This flag may be requested in constructor functions. + */ + +/* Cause a cast to occur regardless of whether or not it is safe. */ +#define NPY_ARRAY_FORCECAST 0x0010 + +/* + * Always copy the array. Returned arrays are always CONTIGUOUS, + * ALIGNED, and WRITEABLE. + * + * This flag may be requested in constructor functions. + */ +#define NPY_ARRAY_ENSURECOPY 0x0020 + +/* + * Make sure the returned array is a base-class ndarray + * + * This flag may be requested in constructor functions. + */ +#define NPY_ARRAY_ENSUREARRAY 0x0040 + +/* + * Make sure that the strides are in units of the element size Needed + * for some operations with record-arrays. + * + * This flag may be requested in constructor functions. + */ +#define NPY_ARRAY_ELEMENTSTRIDES 0x0080 + +/* + * Array data is aligned on the appropiate memory address for the type + * stored according to how the compiler would align things (e.g., an + * array of integers (4 bytes each) starts on a memory address that's + * a multiple of 4) + * + * This flag may be requested in constructor functions. + * This flag may be tested for in PyArray_FLAGS(arr). + */ +#define NPY_ARRAY_ALIGNED 0x0100 + +/* + * Array data has the native endianness + * + * This flag may be requested in constructor functions. + */ +#define NPY_ARRAY_NOTSWAPPED 0x0200 + +/* + * Array data is writeable + * + * This flag may be requested in constructor functions. + * This flag may be tested for in PyArray_FLAGS(arr). + */ +#define NPY_ARRAY_WRITEABLE 0x0400 + +/* + * If this flag is set, then base contains a pointer to an array of + * the same size that should be updated with the current contents of + * this array when this array is deallocated + * + * This flag may be requested in constructor functions. + * This flag may be tested for in PyArray_FLAGS(arr). + */ +#define NPY_ARRAY_UPDATEIFCOPY 0x1000 + +/* + * NOTE: there are also internal flags defined in multiarray/arrayobject.h, + * which start at bit 31 and work down. + */ + +#define NPY_ARRAY_BEHAVED (NPY_ARRAY_ALIGNED | \ + NPY_ARRAY_WRITEABLE) +#define NPY_ARRAY_BEHAVED_NS (NPY_ARRAY_ALIGNED | \ + NPY_ARRAY_WRITEABLE | \ + NPY_ARRAY_NOTSWAPPED) +#define NPY_ARRAY_CARRAY (NPY_ARRAY_C_CONTIGUOUS | \ + NPY_ARRAY_BEHAVED) +#define NPY_ARRAY_CARRAY_RO (NPY_ARRAY_C_CONTIGUOUS | \ + NPY_ARRAY_ALIGNED) +#define NPY_ARRAY_FARRAY (NPY_ARRAY_F_CONTIGUOUS | \ + NPY_ARRAY_BEHAVED) +#define NPY_ARRAY_FARRAY_RO (NPY_ARRAY_F_CONTIGUOUS | \ + NPY_ARRAY_ALIGNED) +#define NPY_ARRAY_DEFAULT (NPY_ARRAY_CARRAY) +#define NPY_ARRAY_IN_ARRAY (NPY_ARRAY_CARRAY_RO) +#define NPY_ARRAY_OUT_ARRAY (NPY_ARRAY_CARRAY) +#define NPY_ARRAY_INOUT_ARRAY (NPY_ARRAY_CARRAY | \ + NPY_ARRAY_UPDATEIFCOPY) +#define NPY_ARRAY_IN_FARRAY (NPY_ARRAY_FARRAY_RO) +#define NPY_ARRAY_OUT_FARRAY (NPY_ARRAY_FARRAY) +#define NPY_ARRAY_INOUT_FARRAY (NPY_ARRAY_FARRAY | \ + NPY_ARRAY_UPDATEIFCOPY) + +#define NPY_ARRAY_UPDATE_ALL (NPY_ARRAY_C_CONTIGUOUS | \ + NPY_ARRAY_F_CONTIGUOUS | \ + NPY_ARRAY_ALIGNED) + +/* This flag is for the array interface, not PyArrayObject */ +#define NPY_ARR_HAS_DESCR 0x0800 + + + + +/* + * Size of internal buffers used for alignment Make BUFSIZE a multiple + * of sizeof(npy_cdouble) -- usually 16 so that ufunc buffers are aligned + */ +#define NPY_MIN_BUFSIZE ((int)sizeof(npy_cdouble)) +#define NPY_MAX_BUFSIZE (((int)sizeof(npy_cdouble))*1000000) +#define NPY_BUFSIZE 8192 +/* buffer stress test size: */ +/*#define NPY_BUFSIZE 17*/ + +#define PyArray_MAX(a,b) (((a)>(b))?(a):(b)) +#define PyArray_MIN(a,b) (((a)<(b))?(a):(b)) +#define PyArray_CLT(p,q) ((((p).real==(q).real) ? ((p).imag < (q).imag) : \ + ((p).real < (q).real))) +#define PyArray_CGT(p,q) ((((p).real==(q).real) ? ((p).imag > (q).imag) : \ + ((p).real > (q).real))) +#define PyArray_CLE(p,q) ((((p).real==(q).real) ? ((p).imag <= (q).imag) : \ + ((p).real <= (q).real))) +#define PyArray_CGE(p,q) ((((p).real==(q).real) ? ((p).imag >= (q).imag) : \ + ((p).real >= (q).real))) +#define PyArray_CEQ(p,q) (((p).real==(q).real) && ((p).imag == (q).imag)) +#define PyArray_CNE(p,q) (((p).real!=(q).real) || ((p).imag != (q).imag)) + +/* + * C API: consists of Macros and functions. The MACROS are defined + * here. + */ + + +#define PyArray_ISCONTIGUOUS(m) PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS) +#define PyArray_ISWRITEABLE(m) PyArray_CHKFLAGS(m, NPY_ARRAY_WRITEABLE) +#define PyArray_ISALIGNED(m) PyArray_CHKFLAGS(m, NPY_ARRAY_ALIGNED) + +#define PyArray_IS_C_CONTIGUOUS(m) PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS) +#define PyArray_IS_F_CONTIGUOUS(m) PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS) + +#if NPY_ALLOW_THREADS +#define NPY_BEGIN_ALLOW_THREADS Py_BEGIN_ALLOW_THREADS +#define NPY_END_ALLOW_THREADS Py_END_ALLOW_THREADS +#define NPY_BEGIN_THREADS_DEF PyThreadState *_save=NULL; +#define NPY_BEGIN_THREADS do {_save = PyEval_SaveThread();} while (0); +#define NPY_END_THREADS do {if (_save) PyEval_RestoreThread(_save);} while (0); +#define NPY_BEGIN_THREADS_THRESHOLDED(loop_size) do { if (loop_size > 500) \ + { _save = PyEval_SaveThread();} } while (0); + +#define NPY_BEGIN_THREADS_DESCR(dtype) \ + do {if (!(PyDataType_FLAGCHK(dtype, NPY_NEEDS_PYAPI))) \ + NPY_BEGIN_THREADS;} while (0); + +#define NPY_END_THREADS_DESCR(dtype) \ + do {if (!(PyDataType_FLAGCHK(dtype, NPY_NEEDS_PYAPI))) \ + NPY_END_THREADS; } while (0); + +#define NPY_ALLOW_C_API_DEF PyGILState_STATE __save__; +#define NPY_ALLOW_C_API do {__save__ = PyGILState_Ensure();} while (0); +#define NPY_DISABLE_C_API do {PyGILState_Release(__save__);} while (0); +#else +#define NPY_BEGIN_ALLOW_THREADS +#define NPY_END_ALLOW_THREADS +#define NPY_BEGIN_THREADS_DEF +#define NPY_BEGIN_THREADS +#define NPY_END_THREADS +#define NPY_BEGIN_THREADS_THRESHOLDED(loop_size) +#define NPY_BEGIN_THREADS_DESCR(dtype) +#define NPY_END_THREADS_DESCR(dtype) +#define NPY_ALLOW_C_API_DEF +#define NPY_ALLOW_C_API +#define NPY_DISABLE_C_API +#endif + +/********************************** + * The nditer object, added in 1.6 + **********************************/ + +/* The actual structure of the iterator is an internal detail */ +typedef struct NpyIter_InternalOnly NpyIter; + +/* Iterator function pointers that may be specialized */ +typedef int (NpyIter_IterNextFunc)(NpyIter *iter); +typedef void (NpyIter_GetMultiIndexFunc)(NpyIter *iter, + npy_intp *outcoords); + +/*** Global flags that may be passed to the iterator constructors ***/ + +/* Track an index representing C order */ +#define NPY_ITER_C_INDEX 0x00000001 +/* Track an index representing Fortran order */ +#define NPY_ITER_F_INDEX 0x00000002 +/* Track a multi-index */ +#define NPY_ITER_MULTI_INDEX 0x00000004 +/* User code external to the iterator does the 1-dimensional innermost loop */ +#define NPY_ITER_EXTERNAL_LOOP 0x00000008 +/* Convert all the operands to a common data type */ +#define NPY_ITER_COMMON_DTYPE 0x00000010 +/* Operands may hold references, requiring API access during iteration */ +#define NPY_ITER_REFS_OK 0x00000020 +/* Zero-sized operands should be permitted, iteration checks IterSize for 0 */ +#define NPY_ITER_ZEROSIZE_OK 0x00000040 +/* Permits reductions (size-0 stride with dimension size > 1) */ +#define NPY_ITER_REDUCE_OK 0x00000080 +/* Enables sub-range iteration */ +#define NPY_ITER_RANGED 0x00000100 +/* Enables buffering */ +#define NPY_ITER_BUFFERED 0x00000200 +/* When buffering is enabled, grows the inner loop if possible */ +#define NPY_ITER_GROWINNER 0x00000400 +/* Delay allocation of buffers until first Reset* call */ +#define NPY_ITER_DELAY_BUFALLOC 0x00000800 +/* When NPY_KEEPORDER is specified, disable reversing negative-stride axes */ +#define NPY_ITER_DONT_NEGATE_STRIDES 0x00001000 + +/*** Per-operand flags that may be passed to the iterator constructors ***/ + +/* The operand will be read from and written to */ +#define NPY_ITER_READWRITE 0x00010000 +/* The operand will only be read from */ +#define NPY_ITER_READONLY 0x00020000 +/* The operand will only be written to */ +#define NPY_ITER_WRITEONLY 0x00040000 +/* The operand's data must be in native byte order */ +#define NPY_ITER_NBO 0x00080000 +/* The operand's data must be aligned */ +#define NPY_ITER_ALIGNED 0x00100000 +/* The operand's data must be contiguous (within the inner loop) */ +#define NPY_ITER_CONTIG 0x00200000 +/* The operand may be copied to satisfy requirements */ +#define NPY_ITER_COPY 0x00400000 +/* The operand may be copied with UPDATEIFCOPY to satisfy requirements */ +#define NPY_ITER_UPDATEIFCOPY 0x00800000 +/* Allocate the operand if it is NULL */ +#define NPY_ITER_ALLOCATE 0x01000000 +/* If an operand is allocated, don't use any subtype */ +#define NPY_ITER_NO_SUBTYPE 0x02000000 +/* This is a virtual array slot, operand is NULL but temporary data is there */ +#define NPY_ITER_VIRTUAL 0x04000000 +/* Require that the dimension match the iterator dimensions exactly */ +#define NPY_ITER_NO_BROADCAST 0x08000000 +/* A mask is being used on this array, affects buffer -> array copy */ +#define NPY_ITER_WRITEMASKED 0x10000000 +/* This array is the mask for all WRITEMASKED operands */ +#define NPY_ITER_ARRAYMASK 0x20000000 + +#define NPY_ITER_GLOBAL_FLAGS 0x0000ffff +#define NPY_ITER_PER_OP_FLAGS 0xffff0000 + + +/***************************** + * Basic iterator object + *****************************/ + +/* FWD declaration */ +typedef struct PyArrayIterObject_tag PyArrayIterObject; + +/* + * type of the function which translates a set of coordinates to a + * pointer to the data + */ +typedef char* (*npy_iter_get_dataptr_t)(PyArrayIterObject* iter, npy_intp*); + +struct PyArrayIterObject_tag { + PyObject_HEAD + int nd_m1; /* number of dimensions - 1 */ + npy_intp index, size; + npy_intp coordinates[NPY_MAXDIMS];/* N-dimensional loop */ + npy_intp dims_m1[NPY_MAXDIMS]; /* ao->dimensions - 1 */ + npy_intp strides[NPY_MAXDIMS]; /* ao->strides or fake */ + npy_intp backstrides[NPY_MAXDIMS];/* how far to jump back */ + npy_intp factors[NPY_MAXDIMS]; /* shape factors */ + PyArrayObject *ao; + char *dataptr; /* pointer to current item*/ + npy_bool contiguous; + + npy_intp bounds[NPY_MAXDIMS][2]; + npy_intp limits[NPY_MAXDIMS][2]; + npy_intp limits_sizes[NPY_MAXDIMS]; + npy_iter_get_dataptr_t translate; +} ; + + +/* Iterator API */ +#define PyArrayIter_Check(op) PyObject_TypeCheck(op, &PyArrayIter_Type) + +#define _PyAIT(it) ((PyArrayIterObject *)(it)) +#define PyArray_ITER_RESET(it) do { \ + _PyAIT(it)->index = 0; \ + _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao); \ + memset(_PyAIT(it)->coordinates, 0, \ + (_PyAIT(it)->nd_m1+1)*sizeof(npy_intp)); \ +} while (0) + +#define _PyArray_ITER_NEXT1(it) do { \ + (it)->dataptr += _PyAIT(it)->strides[0]; \ + (it)->coordinates[0]++; \ +} while (0) + +#define _PyArray_ITER_NEXT2(it) do { \ + if ((it)->coordinates[1] < (it)->dims_m1[1]) { \ + (it)->coordinates[1]++; \ + (it)->dataptr += (it)->strides[1]; \ + } \ + else { \ + (it)->coordinates[1] = 0; \ + (it)->coordinates[0]++; \ + (it)->dataptr += (it)->strides[0] - \ + (it)->backstrides[1]; \ + } \ +} while (0) + +#define _PyArray_ITER_NEXT3(it) do { \ + if ((it)->coordinates[2] < (it)->dims_m1[2]) { \ + (it)->coordinates[2]++; \ + (it)->dataptr += (it)->strides[2]; \ + } \ + else { \ + (it)->coordinates[2] = 0; \ + (it)->dataptr -= (it)->backstrides[2]; \ + if ((it)->coordinates[1] < (it)->dims_m1[1]) { \ + (it)->coordinates[1]++; \ + (it)->dataptr += (it)->strides[1]; \ + } \ + else { \ + (it)->coordinates[1] = 0; \ + (it)->coordinates[0]++; \ + (it)->dataptr += (it)->strides[0] \ + (it)->backstrides[1]; \ + } \ + } \ +} while (0) + +#define PyArray_ITER_NEXT(it) do { \ + _PyAIT(it)->index++; \ + if (_PyAIT(it)->nd_m1 == 0) { \ + _PyArray_ITER_NEXT1(_PyAIT(it)); \ + } \ + else if (_PyAIT(it)->contiguous) \ + _PyAIT(it)->dataptr += PyArray_DESCR(_PyAIT(it)->ao)->elsize; \ + else if (_PyAIT(it)->nd_m1 == 1) { \ + _PyArray_ITER_NEXT2(_PyAIT(it)); \ + } \ + else { \ + int __npy_i; \ + for (__npy_i=_PyAIT(it)->nd_m1; __npy_i >= 0; __npy_i--) { \ + if (_PyAIT(it)->coordinates[__npy_i] < \ + _PyAIT(it)->dims_m1[__npy_i]) { \ + _PyAIT(it)->coordinates[__npy_i]++; \ + _PyAIT(it)->dataptr += \ + _PyAIT(it)->strides[__npy_i]; \ + break; \ + } \ + else { \ + _PyAIT(it)->coordinates[__npy_i] = 0; \ + _PyAIT(it)->dataptr -= \ + _PyAIT(it)->backstrides[__npy_i]; \ + } \ + } \ + } \ +} while (0) + +#define PyArray_ITER_GOTO(it, destination) do { \ + int __npy_i; \ + _PyAIT(it)->index = 0; \ + _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao); \ + for (__npy_i = _PyAIT(it)->nd_m1; __npy_i>=0; __npy_i--) { \ + if (destination[__npy_i] < 0) { \ + destination[__npy_i] += \ + _PyAIT(it)->dims_m1[__npy_i]+1; \ + } \ + _PyAIT(it)->dataptr += destination[__npy_i] * \ + _PyAIT(it)->strides[__npy_i]; \ + _PyAIT(it)->coordinates[__npy_i] = \ + destination[__npy_i]; \ + _PyAIT(it)->index += destination[__npy_i] * \ + ( __npy_i==_PyAIT(it)->nd_m1 ? 1 : \ + _PyAIT(it)->dims_m1[__npy_i+1]+1) ; \ + } \ +} while (0) + +#define PyArray_ITER_GOTO1D(it, ind) do { \ + int __npy_i; \ + npy_intp __npy_ind = (npy_intp) (ind); \ + if (__npy_ind < 0) __npy_ind += _PyAIT(it)->size; \ + _PyAIT(it)->index = __npy_ind; \ + if (_PyAIT(it)->nd_m1 == 0) { \ + _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao) + \ + __npy_ind * _PyAIT(it)->strides[0]; \ + } \ + else if (_PyAIT(it)->contiguous) \ + _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao) + \ + __npy_ind * PyArray_DESCR(_PyAIT(it)->ao)->elsize; \ + else { \ + _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao); \ + for (__npy_i = 0; __npy_i<=_PyAIT(it)->nd_m1; \ + __npy_i++) { \ + _PyAIT(it)->dataptr += \ + (__npy_ind / _PyAIT(it)->factors[__npy_i]) \ + * _PyAIT(it)->strides[__npy_i]; \ + __npy_ind %= _PyAIT(it)->factors[__npy_i]; \ + } \ + } \ +} while (0) + +#define PyArray_ITER_DATA(it) ((void *)(_PyAIT(it)->dataptr)) + +#define PyArray_ITER_NOTDONE(it) (_PyAIT(it)->index < _PyAIT(it)->size) + + +/* + * Any object passed to PyArray_Broadcast must be binary compatible + * with this structure. + */ + +typedef struct { + PyObject_HEAD + int numiter; /* number of iters */ + npy_intp size; /* broadcasted size */ + npy_intp index; /* current index */ + int nd; /* number of dims */ + npy_intp dimensions[NPY_MAXDIMS]; /* dimensions */ + PyArrayIterObject *iters[NPY_MAXARGS]; /* iterators */ +} PyArrayMultiIterObject; + +#define _PyMIT(m) ((PyArrayMultiIterObject *)(m)) +#define PyArray_MultiIter_RESET(multi) do { \ + int __npy_mi; \ + _PyMIT(multi)->index = 0; \ + for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ + PyArray_ITER_RESET(_PyMIT(multi)->iters[__npy_mi]); \ + } \ +} while (0) + +#define PyArray_MultiIter_NEXT(multi) do { \ + int __npy_mi; \ + _PyMIT(multi)->index++; \ + for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ + PyArray_ITER_NEXT(_PyMIT(multi)->iters[__npy_mi]); \ + } \ +} while (0) + +#define PyArray_MultiIter_GOTO(multi, dest) do { \ + int __npy_mi; \ + for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ + PyArray_ITER_GOTO(_PyMIT(multi)->iters[__npy_mi], dest); \ + } \ + _PyMIT(multi)->index = _PyMIT(multi)->iters[0]->index; \ +} while (0) + +#define PyArray_MultiIter_GOTO1D(multi, ind) do { \ + int __npy_mi; \ + for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ + PyArray_ITER_GOTO1D(_PyMIT(multi)->iters[__npy_mi], ind); \ + } \ + _PyMIT(multi)->index = _PyMIT(multi)->iters[0]->index; \ +} while (0) + +#define PyArray_MultiIter_DATA(multi, i) \ + ((void *)(_PyMIT(multi)->iters[i]->dataptr)) + +#define PyArray_MultiIter_NEXTi(multi, i) \ + PyArray_ITER_NEXT(_PyMIT(multi)->iters[i]) + +#define PyArray_MultiIter_NOTDONE(multi) \ + (_PyMIT(multi)->index < _PyMIT(multi)->size) + +/* Store the information needed for fancy-indexing over an array */ + +typedef struct { + PyObject_HEAD + /* + * Multi-iterator portion --- needs to be present in this + * order to work with PyArray_Broadcast + */ + + int numiter; /* number of index-array + iterators */ + npy_intp size; /* size of broadcasted + result */ + npy_intp index; /* current index */ + int nd; /* number of dims */ + npy_intp dimensions[NPY_MAXDIMS]; /* dimensions */ + PyArrayIterObject *iters[NPY_MAXDIMS]; /* index object + iterators */ + PyArrayIterObject *ait; /* flat Iterator for + underlying array */ + + /* flat iterator for subspace (when numiter < nd) */ + PyArrayIterObject *subspace; + + /* + * if subspace iteration, then this is the array of axes in + * the underlying array represented by the index objects + */ + int iteraxes[NPY_MAXDIMS]; + /* + * if subspace iteration, the these are the coordinates to the + * start of the subspace. + */ + npy_intp bscoord[NPY_MAXDIMS]; + + PyObject *indexobj; /* creating obj */ + /* + * consec is first used to indicate wether fancy indices are + * consecutive and then denotes at which axis they are inserted + */ + int consec; + char *dataptr; + +} PyArrayMapIterObject; + +enum { + NPY_NEIGHBORHOOD_ITER_ZERO_PADDING, + NPY_NEIGHBORHOOD_ITER_ONE_PADDING, + NPY_NEIGHBORHOOD_ITER_CONSTANT_PADDING, + NPY_NEIGHBORHOOD_ITER_CIRCULAR_PADDING, + NPY_NEIGHBORHOOD_ITER_MIRROR_PADDING +}; + +typedef struct { + PyObject_HEAD + + /* + * PyArrayIterObject part: keep this in this exact order + */ + int nd_m1; /* number of dimensions - 1 */ + npy_intp index, size; + npy_intp coordinates[NPY_MAXDIMS];/* N-dimensional loop */ + npy_intp dims_m1[NPY_MAXDIMS]; /* ao->dimensions - 1 */ + npy_intp strides[NPY_MAXDIMS]; /* ao->strides or fake */ + npy_intp backstrides[NPY_MAXDIMS];/* how far to jump back */ + npy_intp factors[NPY_MAXDIMS]; /* shape factors */ + PyArrayObject *ao; + char *dataptr; /* pointer to current item*/ + npy_bool contiguous; + + npy_intp bounds[NPY_MAXDIMS][2]; + npy_intp limits[NPY_MAXDIMS][2]; + npy_intp limits_sizes[NPY_MAXDIMS]; + npy_iter_get_dataptr_t translate; + + /* + * New members + */ + npy_intp nd; + + /* Dimensions is the dimension of the array */ + npy_intp dimensions[NPY_MAXDIMS]; + + /* + * Neighborhood points coordinates are computed relatively to the + * point pointed by _internal_iter + */ + PyArrayIterObject* _internal_iter; + /* + * To keep a reference to the representation of the constant value + * for constant padding + */ + char* constant; + + int mode; +} PyArrayNeighborhoodIterObject; + +/* + * Neighborhood iterator API + */ + +/* General: those work for any mode */ +static NPY_INLINE int +PyArrayNeighborhoodIter_Reset(PyArrayNeighborhoodIterObject* iter); +static NPY_INLINE int +PyArrayNeighborhoodIter_Next(PyArrayNeighborhoodIterObject* iter); +#if 0 +static NPY_INLINE int +PyArrayNeighborhoodIter_Next2D(PyArrayNeighborhoodIterObject* iter); +#endif + +/* + * Include inline implementations - functions defined there are not + * considered public API + */ +#define _NPY_INCLUDE_NEIGHBORHOOD_IMP +#include "_neighborhood_iterator_imp.h" +#undef _NPY_INCLUDE_NEIGHBORHOOD_IMP + +/* The default array type */ +#define NPY_DEFAULT_TYPE NPY_DOUBLE + +/* + * All sorts of useful ways to look into a PyArrayObject. It is recommended + * to use PyArrayObject * objects instead of always casting from PyObject *, + * for improved type checking. + * + * In many cases here the macro versions of the accessors are deprecated, + * but can't be immediately changed to inline functions because the + * preexisting macros accept PyObject * and do automatic casts. Inline + * functions accepting PyArrayObject * provides for some compile-time + * checking of correctness when working with these objects in C. + */ + +#define PyArray_ISONESEGMENT(m) (PyArray_NDIM(m) == 0 || \ + PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS) || \ + PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS)) + +#define PyArray_ISFORTRAN(m) (PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS) && \ + (!PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS))) + +#define PyArray_FORTRAN_IF(m) ((PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS) ? \ + NPY_ARRAY_F_CONTIGUOUS : 0)) + +#if (defined(NPY_NO_DEPRECATED_API) && (NPY_1_7_API_VERSION <= NPY_NO_DEPRECATED_API)) +/* + * Changing access macros into functions, to allow for future hiding + * of the internal memory layout. This later hiding will allow the 2.x series + * to change the internal representation of arrays without affecting + * ABI compatibility. + */ + +static NPY_INLINE int +PyArray_NDIM(const PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->nd; +} + +static NPY_INLINE void * +PyArray_DATA(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->data; +} + +static NPY_INLINE char * +PyArray_BYTES(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->data; +} + +static NPY_INLINE npy_intp * +PyArray_DIMS(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->dimensions; +} + +static NPY_INLINE npy_intp * +PyArray_STRIDES(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->strides; +} + +static NPY_INLINE npy_intp +PyArray_DIM(const PyArrayObject *arr, int idim) +{ + return ((PyArrayObject_fields *)arr)->dimensions[idim]; +} + +static NPY_INLINE npy_intp +PyArray_STRIDE(const PyArrayObject *arr, int istride) +{ + return ((PyArrayObject_fields *)arr)->strides[istride]; +} + +static NPY_INLINE PyObject * +PyArray_BASE(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->base; +} + +static NPY_INLINE PyArray_Descr * +PyArray_DESCR(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->descr; +} + +static NPY_INLINE int +PyArray_FLAGS(const PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->flags; +} + +static NPY_INLINE npy_intp +PyArray_ITEMSIZE(const PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->descr->elsize; +} + +static NPY_INLINE int +PyArray_TYPE(const PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->descr->type_num; +} + +static NPY_INLINE int +PyArray_CHKFLAGS(const PyArrayObject *arr, int flags) +{ + return (PyArray_FLAGS(arr) & flags) == flags; +} + +static NPY_INLINE PyObject * +PyArray_GETITEM(const PyArrayObject *arr, const char *itemptr) +{ + return ((PyArrayObject_fields *)arr)->descr->f->getitem( + (void *)itemptr, (PyArrayObject *)arr); +} + +static NPY_INLINE int +PyArray_SETITEM(PyArrayObject *arr, char *itemptr, PyObject *v) +{ + return ((PyArrayObject_fields *)arr)->descr->f->setitem( + v, itemptr, arr); +} + +#else + +/* These macros are deprecated as of NumPy 1.7. */ +#define PyArray_NDIM(obj) (((PyArrayObject_fields *)(obj))->nd) +#define PyArray_BYTES(obj) (((PyArrayObject_fields *)(obj))->data) +#define PyArray_DATA(obj) ((void *)((PyArrayObject_fields *)(obj))->data) +#define PyArray_DIMS(obj) (((PyArrayObject_fields *)(obj))->dimensions) +#define PyArray_STRIDES(obj) (((PyArrayObject_fields *)(obj))->strides) +#define PyArray_DIM(obj,n) (PyArray_DIMS(obj)[n]) +#define PyArray_STRIDE(obj,n) (PyArray_STRIDES(obj)[n]) +#define PyArray_BASE(obj) (((PyArrayObject_fields *)(obj))->base) +#define PyArray_DESCR(obj) (((PyArrayObject_fields *)(obj))->descr) +#define PyArray_FLAGS(obj) (((PyArrayObject_fields *)(obj))->flags) +#define PyArray_CHKFLAGS(m, FLAGS) \ + ((((PyArrayObject_fields *)(m))->flags & (FLAGS)) == (FLAGS)) +#define PyArray_ITEMSIZE(obj) \ + (((PyArrayObject_fields *)(obj))->descr->elsize) +#define PyArray_TYPE(obj) \ + (((PyArrayObject_fields *)(obj))->descr->type_num) +#define PyArray_GETITEM(obj,itemptr) \ + PyArray_DESCR(obj)->f->getitem((char *)(itemptr), \ + (PyArrayObject *)(obj)) + +#define PyArray_SETITEM(obj,itemptr,v) \ + PyArray_DESCR(obj)->f->setitem((PyObject *)(v), \ + (char *)(itemptr), \ + (PyArrayObject *)(obj)) +#endif + +static NPY_INLINE PyArray_Descr * +PyArray_DTYPE(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->descr; +} + +static NPY_INLINE npy_intp * +PyArray_SHAPE(PyArrayObject *arr) +{ + return ((PyArrayObject_fields *)arr)->dimensions; +} + +/* + * Enables the specified array flags. Does no checking, + * assumes you know what you're doing. + */ +static NPY_INLINE void +PyArray_ENABLEFLAGS(PyArrayObject *arr, int flags) +{ + ((PyArrayObject_fields *)arr)->flags |= flags; +} + +/* + * Clears the specified array flags. Does no checking, + * assumes you know what you're doing. + */ +static NPY_INLINE void +PyArray_CLEARFLAGS(PyArrayObject *arr, int flags) +{ + ((PyArrayObject_fields *)arr)->flags &= ~flags; +} + +#define PyTypeNum_ISBOOL(type) ((type) == NPY_BOOL) + +#define PyTypeNum_ISUNSIGNED(type) (((type) == NPY_UBYTE) || \ + ((type) == NPY_USHORT) || \ + ((type) == NPY_UINT) || \ + ((type) == NPY_ULONG) || \ + ((type) == NPY_ULONGLONG)) + +#define PyTypeNum_ISSIGNED(type) (((type) == NPY_BYTE) || \ + ((type) == NPY_SHORT) || \ + ((type) == NPY_INT) || \ + ((type) == NPY_LONG) || \ + ((type) == NPY_LONGLONG)) + +#define PyTypeNum_ISINTEGER(type) (((type) >= NPY_BYTE) && \ + ((type) <= NPY_ULONGLONG)) + +#define PyTypeNum_ISFLOAT(type) ((((type) >= NPY_FLOAT) && \ + ((type) <= NPY_LONGDOUBLE)) || \ + ((type) == NPY_HALF)) + +#define PyTypeNum_ISNUMBER(type) (((type) <= NPY_CLONGDOUBLE) || \ + ((type) == NPY_HALF)) + +#define PyTypeNum_ISSTRING(type) (((type) == NPY_STRING) || \ + ((type) == NPY_UNICODE)) + +#define PyTypeNum_ISCOMPLEX(type) (((type) >= NPY_CFLOAT) && \ + ((type) <= NPY_CLONGDOUBLE)) + +#define PyTypeNum_ISPYTHON(type) (((type) == NPY_LONG) || \ + ((type) == NPY_DOUBLE) || \ + ((type) == NPY_CDOUBLE) || \ + ((type) == NPY_BOOL) || \ + ((type) == NPY_OBJECT )) + +#define PyTypeNum_ISFLEXIBLE(type) (((type) >=NPY_STRING) && \ + ((type) <=NPY_VOID)) + +#define PyTypeNum_ISDATETIME(type) (((type) >=NPY_DATETIME) && \ + ((type) <=NPY_TIMEDELTA)) + +#define PyTypeNum_ISUSERDEF(type) (((type) >= NPY_USERDEF) && \ + ((type) < NPY_USERDEF+ \ + NPY_NUMUSERTYPES)) + +#define PyTypeNum_ISEXTENDED(type) (PyTypeNum_ISFLEXIBLE(type) || \ + PyTypeNum_ISUSERDEF(type)) + +#define PyTypeNum_ISOBJECT(type) ((type) == NPY_OBJECT) + + +#define PyDataType_ISBOOL(obj) PyTypeNum_ISBOOL(_PyADt(obj)) +#define PyDataType_ISUNSIGNED(obj) PyTypeNum_ISUNSIGNED(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISSIGNED(obj) PyTypeNum_ISSIGNED(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISINTEGER(obj) PyTypeNum_ISINTEGER(((PyArray_Descr*)(obj))->type_num ) +#define PyDataType_ISFLOAT(obj) PyTypeNum_ISFLOAT(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISNUMBER(obj) PyTypeNum_ISNUMBER(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISSTRING(obj) PyTypeNum_ISSTRING(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISCOMPLEX(obj) PyTypeNum_ISCOMPLEX(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISPYTHON(obj) PyTypeNum_ISPYTHON(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISFLEXIBLE(obj) PyTypeNum_ISFLEXIBLE(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISDATETIME(obj) PyTypeNum_ISDATETIME(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISUSERDEF(obj) PyTypeNum_ISUSERDEF(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISEXTENDED(obj) PyTypeNum_ISEXTENDED(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_ISOBJECT(obj) PyTypeNum_ISOBJECT(((PyArray_Descr*)(obj))->type_num) +#define PyDataType_HASFIELDS(obj) (((PyArray_Descr *)(obj))->names != NULL) +#define PyDataType_HASSUBARRAY(dtype) ((dtype)->subarray != NULL) + +#define PyArray_ISBOOL(obj) PyTypeNum_ISBOOL(PyArray_TYPE(obj)) +#define PyArray_ISUNSIGNED(obj) PyTypeNum_ISUNSIGNED(PyArray_TYPE(obj)) +#define PyArray_ISSIGNED(obj) PyTypeNum_ISSIGNED(PyArray_TYPE(obj)) +#define PyArray_ISINTEGER(obj) PyTypeNum_ISINTEGER(PyArray_TYPE(obj)) +#define PyArray_ISFLOAT(obj) PyTypeNum_ISFLOAT(PyArray_TYPE(obj)) +#define PyArray_ISNUMBER(obj) PyTypeNum_ISNUMBER(PyArray_TYPE(obj)) +#define PyArray_ISSTRING(obj) PyTypeNum_ISSTRING(PyArray_TYPE(obj)) +#define PyArray_ISCOMPLEX(obj) PyTypeNum_ISCOMPLEX(PyArray_TYPE(obj)) +#define PyArray_ISPYTHON(obj) PyTypeNum_ISPYTHON(PyArray_TYPE(obj)) +#define PyArray_ISFLEXIBLE(obj) PyTypeNum_ISFLEXIBLE(PyArray_TYPE(obj)) +#define PyArray_ISDATETIME(obj) PyTypeNum_ISDATETIME(PyArray_TYPE(obj)) +#define PyArray_ISUSERDEF(obj) PyTypeNum_ISUSERDEF(PyArray_TYPE(obj)) +#define PyArray_ISEXTENDED(obj) PyTypeNum_ISEXTENDED(PyArray_TYPE(obj)) +#define PyArray_ISOBJECT(obj) PyTypeNum_ISOBJECT(PyArray_TYPE(obj)) +#define PyArray_HASFIELDS(obj) PyDataType_HASFIELDS(PyArray_DESCR(obj)) + + /* + * FIXME: This should check for a flag on the data-type that + * states whether or not it is variable length. Because the + * ISFLEXIBLE check is hard-coded to the built-in data-types. + */ +#define PyArray_ISVARIABLE(obj) PyTypeNum_ISFLEXIBLE(PyArray_TYPE(obj)) + +#define PyArray_SAFEALIGNEDCOPY(obj) (PyArray_ISALIGNED(obj) && !PyArray_ISVARIABLE(obj)) + + +#define NPY_LITTLE '<' +#define NPY_BIG '>' +#define NPY_NATIVE '=' +#define NPY_SWAP 's' +#define NPY_IGNORE '|' + +#if NPY_BYTE_ORDER == NPY_BIG_ENDIAN +#define NPY_NATBYTE NPY_BIG +#define NPY_OPPBYTE NPY_LITTLE +#else +#define NPY_NATBYTE NPY_LITTLE +#define NPY_OPPBYTE NPY_BIG +#endif + +#define PyArray_ISNBO(arg) ((arg) != NPY_OPPBYTE) +#define PyArray_IsNativeByteOrder PyArray_ISNBO +#define PyArray_ISNOTSWAPPED(m) PyArray_ISNBO(PyArray_DESCR(m)->byteorder) +#define PyArray_ISBYTESWAPPED(m) (!PyArray_ISNOTSWAPPED(m)) + +#define PyArray_FLAGSWAP(m, flags) (PyArray_CHKFLAGS(m, flags) && \ + PyArray_ISNOTSWAPPED(m)) + +#define PyArray_ISCARRAY(m) PyArray_FLAGSWAP(m, NPY_ARRAY_CARRAY) +#define PyArray_ISCARRAY_RO(m) PyArray_FLAGSWAP(m, NPY_ARRAY_CARRAY_RO) +#define PyArray_ISFARRAY(m) PyArray_FLAGSWAP(m, NPY_ARRAY_FARRAY) +#define PyArray_ISFARRAY_RO(m) PyArray_FLAGSWAP(m, NPY_ARRAY_FARRAY_RO) +#define PyArray_ISBEHAVED(m) PyArray_FLAGSWAP(m, NPY_ARRAY_BEHAVED) +#define PyArray_ISBEHAVED_RO(m) PyArray_FLAGSWAP(m, NPY_ARRAY_ALIGNED) + + +#define PyDataType_ISNOTSWAPPED(d) PyArray_ISNBO(((PyArray_Descr *)(d))->byteorder) +#define PyDataType_ISBYTESWAPPED(d) (!PyDataType_ISNOTSWAPPED(d)) + +/************************************************************ + * A struct used by PyArray_CreateSortedStridePerm, new in 1.7. + ************************************************************/ + +typedef struct { + npy_intp perm, stride; +} npy_stride_sort_item; + +/************************************************************ + * This is the form of the struct that's returned pointed by the + * PyCObject attribute of an array __array_struct__. See + * http://docs.scipy.org/doc/numpy/reference/arrays.interface.html for the full + * documentation. + ************************************************************/ +typedef struct { + int two; /* + * contains the integer 2 as a sanity + * check + */ + + int nd; /* number of dimensions */ + + char typekind; /* + * kind in array --- character code of + * typestr + */ + + int itemsize; /* size of each element */ + + int flags; /* + * how should be data interpreted. Valid + * flags are CONTIGUOUS (1), F_CONTIGUOUS (2), + * ALIGNED (0x100), NOTSWAPPED (0x200), and + * WRITEABLE (0x400). ARR_HAS_DESCR (0x800) + * states that arrdescr field is present in + * structure + */ + + npy_intp *shape; /* + * A length-nd array of shape + * information + */ + + npy_intp *strides; /* A length-nd array of stride information */ + + void *data; /* A pointer to the first element of the array */ + + PyObject *descr; /* + * A list of fields or NULL (ignored if flags + * does not have ARR_HAS_DESCR flag set) + */ +} PyArrayInterface; + +/* + * This is a function for hooking into the PyDataMem_NEW/FREE/RENEW functions. + * See the documentation for PyDataMem_SetEventHook. + */ +typedef void (PyDataMem_EventHookFunc)(void *inp, void *outp, size_t size, + void *user_data); + +/* + * Use the keyword NPY_DEPRECATED_INCLUDES to ensure that the header files + * npy_*_*_deprecated_api.h are only included from here and nowhere else. + */ +#ifdef NPY_DEPRECATED_INCLUDES +#error "Do not use the reserved keyword NPY_DEPRECATED_INCLUDES." +#endif +#define NPY_DEPRECATED_INCLUDES +#if !defined(NPY_NO_DEPRECATED_API) || \ + (NPY_NO_DEPRECATED_API < NPY_1_7_API_VERSION) +#include "npy_1_7_deprecated_api.h" +#endif +/* + * There is no file npy_1_8_deprecated_api.h since there are no additional + * deprecated API features in NumPy 1.8. + * + * Note to maintainers: insert code like the following in future NumPy + * versions. + * + * #if !defined(NPY_NO_DEPRECATED_API) || \ + * (NPY_NO_DEPRECATED_API < NPY_1_9_API_VERSION) + * #include "npy_1_9_deprecated_api.h" + * #endif + */ +#undef NPY_DEPRECATED_INCLUDES + +#endif /* NPY_ARRAYTYPES_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h b/gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h new file mode 100644 index 000000000..830617087 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h @@ -0,0 +1,209 @@ +#ifndef NPY_NOPREFIX_H +#define NPY_NOPREFIX_H + +/* + * You can directly include noprefix.h as a backward + * compatibility measure + */ +#ifndef NPY_NO_PREFIX +#include "ndarrayobject.h" +#include "npy_interrupt.h" +#endif + +#define SIGSETJMP NPY_SIGSETJMP +#define SIGLONGJMP NPY_SIGLONGJMP +#define SIGJMP_BUF NPY_SIGJMP_BUF + +#define MAX_DIMS NPY_MAXDIMS + +#define longlong npy_longlong +#define ulonglong npy_ulonglong +#define Bool npy_bool +#define longdouble npy_longdouble +#define byte npy_byte + +#ifndef _BSD_SOURCE +#define ushort npy_ushort +#define uint npy_uint +#define ulong npy_ulong +#endif + +#define ubyte npy_ubyte +#define ushort npy_ushort +#define uint npy_uint +#define ulong npy_ulong +#define cfloat npy_cfloat +#define cdouble npy_cdouble +#define clongdouble npy_clongdouble +#define Int8 npy_int8 +#define UInt8 npy_uint8 +#define Int16 npy_int16 +#define UInt16 npy_uint16 +#define Int32 npy_int32 +#define UInt32 npy_uint32 +#define Int64 npy_int64 +#define UInt64 npy_uint64 +#define Int128 npy_int128 +#define UInt128 npy_uint128 +#define Int256 npy_int256 +#define UInt256 npy_uint256 +#define Float16 npy_float16 +#define Complex32 npy_complex32 +#define Float32 npy_float32 +#define Complex64 npy_complex64 +#define Float64 npy_float64 +#define Complex128 npy_complex128 +#define Float80 npy_float80 +#define Complex160 npy_complex160 +#define Float96 npy_float96 +#define Complex192 npy_complex192 +#define Float128 npy_float128 +#define Complex256 npy_complex256 +#define intp npy_intp +#define uintp npy_uintp +#define datetime npy_datetime +#define timedelta npy_timedelta + +#define SIZEOF_LONGLONG NPY_SIZEOF_LONGLONG +#define SIZEOF_INTP NPY_SIZEOF_INTP +#define SIZEOF_UINTP NPY_SIZEOF_UINTP +#define SIZEOF_HALF NPY_SIZEOF_HALF +#define SIZEOF_LONGDOUBLE NPY_SIZEOF_LONGDOUBLE +#define SIZEOF_DATETIME NPY_SIZEOF_DATETIME +#define SIZEOF_TIMEDELTA NPY_SIZEOF_TIMEDELTA + +#define LONGLONG_FMT NPY_LONGLONG_FMT +#define ULONGLONG_FMT NPY_ULONGLONG_FMT +#define LONGLONG_SUFFIX NPY_LONGLONG_SUFFIX +#define ULONGLONG_SUFFIX NPY_ULONGLONG_SUFFIX + +#define MAX_INT8 127 +#define MIN_INT8 -128 +#define MAX_UINT8 255 +#define MAX_INT16 32767 +#define MIN_INT16 -32768 +#define MAX_UINT16 65535 +#define MAX_INT32 2147483647 +#define MIN_INT32 (-MAX_INT32 - 1) +#define MAX_UINT32 4294967295U +#define MAX_INT64 LONGLONG_SUFFIX(9223372036854775807) +#define MIN_INT64 (-MAX_INT64 - LONGLONG_SUFFIX(1)) +#define MAX_UINT64 ULONGLONG_SUFFIX(18446744073709551615) +#define MAX_INT128 LONGLONG_SUFFIX(85070591730234615865843651857942052864) +#define MIN_INT128 (-MAX_INT128 - LONGLONG_SUFFIX(1)) +#define MAX_UINT128 ULONGLONG_SUFFIX(170141183460469231731687303715884105728) +#define MAX_INT256 LONGLONG_SUFFIX(57896044618658097711785492504343953926634992332820282019728792003956564819967) +#define MIN_INT256 (-MAX_INT256 - LONGLONG_SUFFIX(1)) +#define MAX_UINT256 ULONGLONG_SUFFIX(115792089237316195423570985008687907853269984665640564039457584007913129639935) + +#define MAX_BYTE NPY_MAX_BYTE +#define MIN_BYTE NPY_MIN_BYTE +#define MAX_UBYTE NPY_MAX_UBYTE +#define MAX_SHORT NPY_MAX_SHORT +#define MIN_SHORT NPY_MIN_SHORT +#define MAX_USHORT NPY_MAX_USHORT +#define MAX_INT NPY_MAX_INT +#define MIN_INT NPY_MIN_INT +#define MAX_UINT NPY_MAX_UINT +#define MAX_LONG NPY_MAX_LONG +#define MIN_LONG NPY_MIN_LONG +#define MAX_ULONG NPY_MAX_ULONG +#define MAX_LONGLONG NPY_MAX_LONGLONG +#define MIN_LONGLONG NPY_MIN_LONGLONG +#define MAX_ULONGLONG NPY_MAX_ULONGLONG +#define MIN_DATETIME NPY_MIN_DATETIME +#define MAX_DATETIME NPY_MAX_DATETIME +#define MIN_TIMEDELTA NPY_MIN_TIMEDELTA +#define MAX_TIMEDELTA NPY_MAX_TIMEDELTA + +#define BITSOF_BOOL NPY_BITSOF_BOOL +#define BITSOF_CHAR NPY_BITSOF_CHAR +#define BITSOF_SHORT NPY_BITSOF_SHORT +#define BITSOF_INT NPY_BITSOF_INT +#define BITSOF_LONG NPY_BITSOF_LONG +#define BITSOF_LONGLONG NPY_BITSOF_LONGLONG +#define BITSOF_HALF NPY_BITSOF_HALF +#define BITSOF_FLOAT NPY_BITSOF_FLOAT +#define BITSOF_DOUBLE NPY_BITSOF_DOUBLE +#define BITSOF_LONGDOUBLE NPY_BITSOF_LONGDOUBLE +#define BITSOF_DATETIME NPY_BITSOF_DATETIME +#define BITSOF_TIMEDELTA NPY_BITSOF_TIMEDELTA + +#define _pya_malloc PyArray_malloc +#define _pya_free PyArray_free +#define _pya_realloc PyArray_realloc + +#define BEGIN_THREADS_DEF NPY_BEGIN_THREADS_DEF +#define BEGIN_THREADS NPY_BEGIN_THREADS +#define END_THREADS NPY_END_THREADS +#define ALLOW_C_API_DEF NPY_ALLOW_C_API_DEF +#define ALLOW_C_API NPY_ALLOW_C_API +#define DISABLE_C_API NPY_DISABLE_C_API + +#define PY_FAIL NPY_FAIL +#define PY_SUCCEED NPY_SUCCEED + +#ifndef TRUE +#define TRUE NPY_TRUE +#endif + +#ifndef FALSE +#define FALSE NPY_FALSE +#endif + +#define LONGDOUBLE_FMT NPY_LONGDOUBLE_FMT + +#define CONTIGUOUS NPY_CONTIGUOUS +#define C_CONTIGUOUS NPY_C_CONTIGUOUS +#define FORTRAN NPY_FORTRAN +#define F_CONTIGUOUS NPY_F_CONTIGUOUS +#define OWNDATA NPY_OWNDATA +#define FORCECAST NPY_FORCECAST +#define ENSURECOPY NPY_ENSURECOPY +#define ENSUREARRAY NPY_ENSUREARRAY +#define ELEMENTSTRIDES NPY_ELEMENTSTRIDES +#define ALIGNED NPY_ALIGNED +#define NOTSWAPPED NPY_NOTSWAPPED +#define WRITEABLE NPY_WRITEABLE +#define UPDATEIFCOPY NPY_UPDATEIFCOPY +#define ARR_HAS_DESCR NPY_ARR_HAS_DESCR +#define BEHAVED NPY_BEHAVED +#define BEHAVED_NS NPY_BEHAVED_NS +#define CARRAY NPY_CARRAY +#define CARRAY_RO NPY_CARRAY_RO +#define FARRAY NPY_FARRAY +#define FARRAY_RO NPY_FARRAY_RO +#define DEFAULT NPY_DEFAULT +#define IN_ARRAY NPY_IN_ARRAY +#define OUT_ARRAY NPY_OUT_ARRAY +#define INOUT_ARRAY NPY_INOUT_ARRAY +#define IN_FARRAY NPY_IN_FARRAY +#define OUT_FARRAY NPY_OUT_FARRAY +#define INOUT_FARRAY NPY_INOUT_FARRAY +#define UPDATE_ALL NPY_UPDATE_ALL + +#define OWN_DATA NPY_OWNDATA +#define BEHAVED_FLAGS NPY_BEHAVED +#define BEHAVED_FLAGS_NS NPY_BEHAVED_NS +#define CARRAY_FLAGS_RO NPY_CARRAY_RO +#define CARRAY_FLAGS NPY_CARRAY +#define FARRAY_FLAGS NPY_FARRAY +#define FARRAY_FLAGS_RO NPY_FARRAY_RO +#define DEFAULT_FLAGS NPY_DEFAULT +#define UPDATE_ALL_FLAGS NPY_UPDATE_ALL_FLAGS + +#ifndef MIN +#define MIN PyArray_MIN +#endif +#ifndef MAX +#define MAX PyArray_MAX +#endif +#define MAX_INTP NPY_MAX_INTP +#define MIN_INTP NPY_MIN_INTP +#define MAX_UINTP NPY_MAX_UINTP +#define INTP_FMT NPY_INTP_FMT + +#define REFCOUNT PyArray_REFCOUNT +#define MAX_ELSIZE NPY_MAX_ELSIZE + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h new file mode 100644 index 000000000..4c318bc47 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h @@ -0,0 +1,130 @@ +#ifndef _NPY_1_7_DEPRECATED_API_H +#define _NPY_1_7_DEPRECATED_API_H + +#ifndef NPY_DEPRECATED_INCLUDES +#error "Should never include npy_*_*_deprecated_api directly." +#endif + +#if defined(_WIN32) +#define _WARN___STR2__(x) #x +#define _WARN___STR1__(x) _WARN___STR2__(x) +#define _WARN___LOC__ __FILE__ "(" _WARN___STR1__(__LINE__) ") : Warning Msg: " +#pragma message(_WARN___LOC__"Using deprecated NumPy API, disable it by " \ + "#defining NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION") +#elif defined(__GNUC__) +#warning "Using deprecated NumPy API, disable it by " \ + "#defining NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION" +#endif +/* TODO: How to do this warning message for other compilers? */ + +/* + * This header exists to collect all dangerous/deprecated NumPy API + * as of NumPy 1.7. + * + * This is an attempt to remove bad API, the proliferation of macros, + * and namespace pollution currently produced by the NumPy headers. + */ + +/* These array flags are deprecated as of NumPy 1.7 */ +#define NPY_CONTIGUOUS NPY_ARRAY_C_CONTIGUOUS +#define NPY_FORTRAN NPY_ARRAY_F_CONTIGUOUS + +/* + * The consistent NPY_ARRAY_* names which don't pollute the NPY_* + * namespace were added in NumPy 1.7. + * + * These versions of the carray flags are deprecated, but + * probably should only be removed after two releases instead of one. + */ +#define NPY_C_CONTIGUOUS NPY_ARRAY_C_CONTIGUOUS +#define NPY_F_CONTIGUOUS NPY_ARRAY_F_CONTIGUOUS +#define NPY_OWNDATA NPY_ARRAY_OWNDATA +#define NPY_FORCECAST NPY_ARRAY_FORCECAST +#define NPY_ENSURECOPY NPY_ARRAY_ENSURECOPY +#define NPY_ENSUREARRAY NPY_ARRAY_ENSUREARRAY +#define NPY_ELEMENTSTRIDES NPY_ARRAY_ELEMENTSTRIDES +#define NPY_ALIGNED NPY_ARRAY_ALIGNED +#define NPY_NOTSWAPPED NPY_ARRAY_NOTSWAPPED +#define NPY_WRITEABLE NPY_ARRAY_WRITEABLE +#define NPY_UPDATEIFCOPY NPY_ARRAY_UPDATEIFCOPY +#define NPY_BEHAVED NPY_ARRAY_BEHAVED +#define NPY_BEHAVED_NS NPY_ARRAY_BEHAVED_NS +#define NPY_CARRAY NPY_ARRAY_CARRAY +#define NPY_CARRAY_RO NPY_ARRAY_CARRAY_RO +#define NPY_FARRAY NPY_ARRAY_FARRAY +#define NPY_FARRAY_RO NPY_ARRAY_FARRAY_RO +#define NPY_DEFAULT NPY_ARRAY_DEFAULT +#define NPY_IN_ARRAY NPY_ARRAY_IN_ARRAY +#define NPY_OUT_ARRAY NPY_ARRAY_OUT_ARRAY +#define NPY_INOUT_ARRAY NPY_ARRAY_INOUT_ARRAY +#define NPY_IN_FARRAY NPY_ARRAY_IN_FARRAY +#define NPY_OUT_FARRAY NPY_ARRAY_OUT_FARRAY +#define NPY_INOUT_FARRAY NPY_ARRAY_INOUT_FARRAY +#define NPY_UPDATE_ALL NPY_ARRAY_UPDATE_ALL + +/* This way of accessing the default type is deprecated as of NumPy 1.7 */ +#define PyArray_DEFAULT NPY_DEFAULT_TYPE + +/* These DATETIME bits aren't used internally */ +#if PY_VERSION_HEX >= 0x03000000 +#define PyDataType_GetDatetimeMetaData(descr) \ + ((descr->metadata == NULL) ? NULL : \ + ((PyArray_DatetimeMetaData *)(PyCapsule_GetPointer( \ + PyDict_GetItemString( \ + descr->metadata, NPY_METADATA_DTSTR), NULL)))) +#else +#define PyDataType_GetDatetimeMetaData(descr) \ + ((descr->metadata == NULL) ? NULL : \ + ((PyArray_DatetimeMetaData *)(PyCObject_AsVoidPtr( \ + PyDict_GetItemString(descr->metadata, NPY_METADATA_DTSTR))))) +#endif + +/* + * Deprecated as of NumPy 1.7, this kind of shortcut doesn't + * belong in the public API. + */ +#define NPY_AO PyArrayObject + +/* + * Deprecated as of NumPy 1.7, an all-lowercase macro doesn't + * belong in the public API. + */ +#define fortran fortran_ + +/* + * Deprecated as of NumPy 1.7, as it is a namespace-polluting + * macro. + */ +#define FORTRAN_IF PyArray_FORTRAN_IF + +/* Deprecated as of NumPy 1.7, datetime64 uses c_metadata instead */ +#define NPY_METADATA_DTSTR "__timeunit__" + +/* + * Deprecated as of NumPy 1.7. + * The reasoning: + * - These are for datetime, but there's no datetime "namespace". + * - They just turn NPY_STR_ into "", which is just + * making something simple be indirected. + */ +#define NPY_STR_Y "Y" +#define NPY_STR_M "M" +#define NPY_STR_W "W" +#define NPY_STR_D "D" +#define NPY_STR_h "h" +#define NPY_STR_m "m" +#define NPY_STR_s "s" +#define NPY_STR_ms "ms" +#define NPY_STR_us "us" +#define NPY_STR_ns "ns" +#define NPY_STR_ps "ps" +#define NPY_STR_fs "fs" +#define NPY_STR_as "as" + +/* + * The macros in old_defines.h are Deprecated as of NumPy 1.7 and will be + * removed in the next major release. + */ +#include "old_defines.h" + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h new file mode 100644 index 000000000..de2bf6a54 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h @@ -0,0 +1,502 @@ +/* + * This is a convenience header file providing compatibility utilities + * for supporting Python 2 and Python 3 in the same code base. + * + * If you want to use this for your own projects, it's recommended to make a + * copy of it. Although the stuff below is unlikely to change, we don't provide + * strong backwards compatibility guarantees at the moment. + */ + +#ifndef _NPY_3KCOMPAT_H_ +#define _NPY_3KCOMPAT_H_ + +#include +#include + +#if PY_VERSION_HEX >= 0x03000000 +#ifndef NPY_PY3K +#define NPY_PY3K 1 +#endif +#endif + +#include "numpy/npy_common.h" +#include "numpy/ndarrayobject.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * PyInt -> PyLong + */ + +#if defined(NPY_PY3K) +/* Return True only if the long fits in a C long */ +static NPY_INLINE int PyInt_Check(PyObject *op) { + int overflow = 0; + if (!PyLong_Check(op)) { + return 0; + } + PyLong_AsLongAndOverflow(op, &overflow); + return (overflow == 0); +} + +#define PyInt_FromLong PyLong_FromLong +#define PyInt_AsLong PyLong_AsLong +#define PyInt_AS_LONG PyLong_AsLong +#define PyInt_AsSsize_t PyLong_AsSsize_t + +/* NOTE: + * + * Since the PyLong type is very different from the fixed-range PyInt, + * we don't define PyInt_Type -> PyLong_Type. + */ +#endif /* NPY_PY3K */ + +/* + * PyString -> PyBytes + */ + +#if defined(NPY_PY3K) + +#define PyString_Type PyBytes_Type +#define PyString_Check PyBytes_Check +#define PyStringObject PyBytesObject +#define PyString_FromString PyBytes_FromString +#define PyString_FromStringAndSize PyBytes_FromStringAndSize +#define PyString_AS_STRING PyBytes_AS_STRING +#define PyString_AsStringAndSize PyBytes_AsStringAndSize +#define PyString_FromFormat PyBytes_FromFormat +#define PyString_Concat PyBytes_Concat +#define PyString_ConcatAndDel PyBytes_ConcatAndDel +#define PyString_AsString PyBytes_AsString +#define PyString_GET_SIZE PyBytes_GET_SIZE +#define PyString_Size PyBytes_Size + +#define PyUString_Type PyUnicode_Type +#define PyUString_Check PyUnicode_Check +#define PyUStringObject PyUnicodeObject +#define PyUString_FromString PyUnicode_FromString +#define PyUString_FromStringAndSize PyUnicode_FromStringAndSize +#define PyUString_FromFormat PyUnicode_FromFormat +#define PyUString_Concat PyUnicode_Concat2 +#define PyUString_ConcatAndDel PyUnicode_ConcatAndDel +#define PyUString_GET_SIZE PyUnicode_GET_SIZE +#define PyUString_Size PyUnicode_Size +#define PyUString_InternFromString PyUnicode_InternFromString +#define PyUString_Format PyUnicode_Format + +#else + +#define PyBytes_Type PyString_Type +#define PyBytes_Check PyString_Check +#define PyBytesObject PyStringObject +#define PyBytes_FromString PyString_FromString +#define PyBytes_FromStringAndSize PyString_FromStringAndSize +#define PyBytes_AS_STRING PyString_AS_STRING +#define PyBytes_AsStringAndSize PyString_AsStringAndSize +#define PyBytes_FromFormat PyString_FromFormat +#define PyBytes_Concat PyString_Concat +#define PyBytes_ConcatAndDel PyString_ConcatAndDel +#define PyBytes_AsString PyString_AsString +#define PyBytes_GET_SIZE PyString_GET_SIZE +#define PyBytes_Size PyString_Size + +#define PyUString_Type PyString_Type +#define PyUString_Check PyString_Check +#define PyUStringObject PyStringObject +#define PyUString_FromString PyString_FromString +#define PyUString_FromStringAndSize PyString_FromStringAndSize +#define PyUString_FromFormat PyString_FromFormat +#define PyUString_Concat PyString_Concat +#define PyUString_ConcatAndDel PyString_ConcatAndDel +#define PyUString_GET_SIZE PyString_GET_SIZE +#define PyUString_Size PyString_Size +#define PyUString_InternFromString PyString_InternFromString +#define PyUString_Format PyString_Format + +#endif /* NPY_PY3K */ + + +static NPY_INLINE void +PyUnicode_ConcatAndDel(PyObject **left, PyObject *right) +{ + PyObject *newobj; + newobj = PyUnicode_Concat(*left, right); + Py_DECREF(*left); + Py_DECREF(right); + *left = newobj; +} + +static NPY_INLINE void +PyUnicode_Concat2(PyObject **left, PyObject *right) +{ + PyObject *newobj; + newobj = PyUnicode_Concat(*left, right); + Py_DECREF(*left); + *left = newobj; +} + +/* + * PyFile_* compatibility + */ +#if defined(NPY_PY3K) +/* + * Get a FILE* handle to the file represented by the Python object + */ +static NPY_INLINE FILE* +npy_PyFile_Dup2(PyObject *file, char *mode, npy_off_t *orig_pos) +{ + int fd, fd2; + PyObject *ret, *os; + npy_off_t pos; + FILE *handle; + + /* Flush first to ensure things end up in the file in the correct order */ + ret = PyObject_CallMethod(file, "flush", ""); + if (ret == NULL) { + return NULL; + } + Py_DECREF(ret); + fd = PyObject_AsFileDescriptor(file); + if (fd == -1) { + return NULL; + } + + /* The handle needs to be dup'd because we have to call fclose + at the end */ + os = PyImport_ImportModule("os"); + if (os == NULL) { + return NULL; + } + ret = PyObject_CallMethod(os, "dup", "i", fd); + Py_DECREF(os); + if (ret == NULL) { + return NULL; + } + fd2 = PyNumber_AsSsize_t(ret, NULL); + Py_DECREF(ret); + + /* Convert to FILE* handle */ +#ifdef _WIN32 + handle = _fdopen(fd2, mode); +#else + handle = fdopen(fd2, mode); +#endif + if (handle == NULL) { + PyErr_SetString(PyExc_IOError, + "Getting a FILE* from a Python file object failed"); + } + + /* Record the original raw file handle position */ + *orig_pos = npy_ftell(handle); + if (*orig_pos == -1) { + PyErr_SetString(PyExc_IOError, "obtaining file position failed"); + fclose(handle); + return NULL; + } + + /* Seek raw handle to the Python-side position */ + ret = PyObject_CallMethod(file, "tell", ""); + if (ret == NULL) { + fclose(handle); + return NULL; + } + pos = PyLong_AsLongLong(ret); + Py_DECREF(ret); + if (PyErr_Occurred()) { + fclose(handle); + return NULL; + } + if (npy_fseek(handle, pos, SEEK_SET) == -1) { + PyErr_SetString(PyExc_IOError, "seeking file failed"); + fclose(handle); + return NULL; + } + return handle; +} + +/* + * Close the dup-ed file handle, and seek the Python one to the current position + */ +static NPY_INLINE int +npy_PyFile_DupClose2(PyObject *file, FILE* handle, npy_off_t orig_pos) +{ + int fd; + PyObject *ret; + npy_off_t position; + + position = npy_ftell(handle); + + /* Close the FILE* handle */ + fclose(handle); + + /* Restore original file handle position, in order to not confuse + Python-side data structures */ + fd = PyObject_AsFileDescriptor(file); + if (fd == -1) { + return -1; + } + if (npy_lseek(fd, orig_pos, SEEK_SET) == -1) { + PyErr_SetString(PyExc_IOError, "seeking file failed"); + return -1; + } + + if (position == -1) { + PyErr_SetString(PyExc_IOError, "obtaining file position failed"); + return -1; + } + + /* Seek Python-side handle to the FILE* handle position */ + ret = PyObject_CallMethod(file, "seek", NPY_OFF_T_PYFMT "i", position, 0); + if (ret == NULL) { + return -1; + } + Py_DECREF(ret); + return 0; +} + +static NPY_INLINE int +npy_PyFile_Check(PyObject *file) +{ + int fd; + fd = PyObject_AsFileDescriptor(file); + if (fd == -1) { + PyErr_Clear(); + return 0; + } + return 1; +} + +/* + * DEPRECATED DO NOT USE + * use npy_PyFile_Dup2 instead + * this function will mess ups python3 internal file object buffering + * Get a FILE* handle to the file represented by the Python object + */ +static NPY_INLINE FILE* +npy_PyFile_Dup(PyObject *file, char *mode) +{ + npy_off_t orig; + if (DEPRECATE("npy_PyFile_Dup is deprecated, use " + "npy_PyFile_Dup2") < 0) { + return NULL; + } + + return npy_PyFile_Dup2(file, mode, &orig); +} + +/* + * DEPRECATED DO NOT USE + * use npy_PyFile_DupClose2 instead + * this function will mess ups python3 internal file object buffering + * Close the dup-ed file handle, and seek the Python one to the current position + */ +static NPY_INLINE int +npy_PyFile_DupClose(PyObject *file, FILE* handle) +{ + PyObject *ret; + Py_ssize_t position; + position = npy_ftell(handle); + fclose(handle); + + ret = PyObject_CallMethod(file, "seek", NPY_SSIZE_T_PYFMT "i", position, 0); + if (ret == NULL) { + return -1; + } + Py_DECREF(ret); + return 0; +} + + +#else + +/* DEPRECATED DO NOT USE */ +#define npy_PyFile_Dup(file, mode) PyFile_AsFile(file) +#define npy_PyFile_DupClose(file, handle) (0) +/* use these */ +#define npy_PyFile_Dup2(file, mode, orig_pos_p) PyFile_AsFile(file) +#define npy_PyFile_DupClose2(file, handle, orig_pos) (0) +#define npy_PyFile_Check PyFile_Check + +#endif + +static NPY_INLINE PyObject* +npy_PyFile_OpenFile(PyObject *filename, const char *mode) +{ + PyObject *open; + open = PyDict_GetItemString(PyEval_GetBuiltins(), "open"); + if (open == NULL) { + return NULL; + } + return PyObject_CallFunction(open, "Os", filename, mode); +} + +static NPY_INLINE int +npy_PyFile_CloseFile(PyObject *file) +{ + PyObject *ret; + + ret = PyObject_CallMethod(file, "close", NULL); + if (ret == NULL) { + return -1; + } + Py_DECREF(ret); + return 0; +} + +/* + * PyObject_Cmp + */ +#if defined(NPY_PY3K) +static NPY_INLINE int +PyObject_Cmp(PyObject *i1, PyObject *i2, int *cmp) +{ + int v; + v = PyObject_RichCompareBool(i1, i2, Py_LT); + if (v == 0) { + *cmp = -1; + return 1; + } + else if (v == -1) { + return -1; + } + + v = PyObject_RichCompareBool(i1, i2, Py_GT); + if (v == 0) { + *cmp = 1; + return 1; + } + else if (v == -1) { + return -1; + } + + v = PyObject_RichCompareBool(i1, i2, Py_EQ); + if (v == 0) { + *cmp = 0; + return 1; + } + else { + *cmp = 0; + return -1; + } +} +#endif + +/* + * PyCObject functions adapted to PyCapsules. + * + * The main job here is to get rid of the improved error handling + * of PyCapsules. It's a shame... + */ +#if PY_VERSION_HEX >= 0x03000000 + +static NPY_INLINE PyObject * +NpyCapsule_FromVoidPtr(void *ptr, void (*dtor)(PyObject *)) +{ + PyObject *ret = PyCapsule_New(ptr, NULL, dtor); + if (ret == NULL) { + PyErr_Clear(); + } + return ret; +} + +static NPY_INLINE PyObject * +NpyCapsule_FromVoidPtrAndDesc(void *ptr, void* context, void (*dtor)(PyObject *)) +{ + PyObject *ret = NpyCapsule_FromVoidPtr(ptr, dtor); + if (ret != NULL && PyCapsule_SetContext(ret, context) != 0) { + PyErr_Clear(); + Py_DECREF(ret); + ret = NULL; + } + return ret; +} + +static NPY_INLINE void * +NpyCapsule_AsVoidPtr(PyObject *obj) +{ + void *ret = PyCapsule_GetPointer(obj, NULL); + if (ret == NULL) { + PyErr_Clear(); + } + return ret; +} + +static NPY_INLINE void * +NpyCapsule_GetDesc(PyObject *obj) +{ + return PyCapsule_GetContext(obj); +} + +static NPY_INLINE int +NpyCapsule_Check(PyObject *ptr) +{ + return PyCapsule_CheckExact(ptr); +} + +static NPY_INLINE void +simple_capsule_dtor(PyObject *cap) +{ + PyArray_free(PyCapsule_GetPointer(cap, NULL)); +} + +#else + +static NPY_INLINE PyObject * +NpyCapsule_FromVoidPtr(void *ptr, void (*dtor)(void *)) +{ + return PyCObject_FromVoidPtr(ptr, dtor); +} + +static NPY_INLINE PyObject * +NpyCapsule_FromVoidPtrAndDesc(void *ptr, void* context, + void (*dtor)(void *, void *)) +{ + return PyCObject_FromVoidPtrAndDesc(ptr, context, dtor); +} + +static NPY_INLINE void * +NpyCapsule_AsVoidPtr(PyObject *ptr) +{ + return PyCObject_AsVoidPtr(ptr); +} + +static NPY_INLINE void * +NpyCapsule_GetDesc(PyObject *obj) +{ + return PyCObject_GetDesc(obj); +} + +static NPY_INLINE int +NpyCapsule_Check(PyObject *ptr) +{ + return PyCObject_Check(ptr); +} + +static NPY_INLINE void +simple_capsule_dtor(void *ptr) +{ + PyArray_free(ptr); +} + +#endif + +/* + * Hash value compatibility. + * As of Python 3.2 hash values are of type Py_hash_t. + * Previous versions use C long. + */ +#if PY_VERSION_HEX < 0x03020000 +typedef long npy_hash_t; +#define NPY_SIZEOF_HASH_T NPY_SIZEOF_LONG +#else +typedef Py_hash_t npy_hash_t; +#define NPY_SIZEOF_HASH_T NPY_SIZEOF_INTP +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* _NPY_3KCOMPAT_H_ */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h new file mode 100644 index 000000000..c257f216d --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h @@ -0,0 +1,1005 @@ +#ifndef _NPY_COMMON_H_ +#define _NPY_COMMON_H_ + +/* numpconfig.h is auto-generated */ +#include "numpyconfig.h" +#ifdef HAVE_NPY_CONFIG_H +#include +#endif + +/* + * gcc does not unroll even with -O3 + * use with care, unrolling on modern cpus rarely speeds things up + */ +#ifdef HAVE_ATTRIBUTE_OPTIMIZE_UNROLL_LOOPS +#define NPY_GCC_UNROLL_LOOPS \ + __attribute__((optimize("unroll-loops"))) +#else +#define NPY_GCC_UNROLL_LOOPS +#endif + +#if defined HAVE_XMMINTRIN_H && defined HAVE__MM_LOAD_PS +#define NPY_HAVE_SSE_INTRINSICS +#endif + +#if defined HAVE_EMMINTRIN_H && defined HAVE__MM_LOAD_PD +#define NPY_HAVE_SSE2_INTRINSICS +#endif + +/* + * give a hint to the compiler which branch is more likely or unlikely + * to occur, e.g. rare error cases: + * + * if (NPY_UNLIKELY(failure == 0)) + * return NULL; + * + * the double !! is to cast the expression (e.g. NULL) to a boolean required by + * the intrinsic + */ +#ifdef HAVE___BUILTIN_EXPECT +#define NPY_LIKELY(x) __builtin_expect(!!(x), 1) +#define NPY_UNLIKELY(x) __builtin_expect(!!(x), 0) +#else +#define NPY_LIKELY(x) (x) +#define NPY_UNLIKELY(x) (x) +#endif + +#if defined(_MSC_VER) + #define NPY_INLINE __inline +#elif defined(__GNUC__) + #if defined(__STRICT_ANSI__) + #define NPY_INLINE __inline__ + #else + #define NPY_INLINE inline + #endif +#else + #define NPY_INLINE +#endif + +/* 64 bit file position support, also on win-amd64. Ticket #1660 */ +#if defined(_MSC_VER) && defined(_WIN64) && (_MSC_VER > 1400) || \ + defined(__MINGW32__) || defined(__MINGW64__) + #include + +/* mingw based on 3.4.5 has lseek but not ftell/fseek */ +#if defined(__MINGW32__) || defined(__MINGW64__) +extern int __cdecl _fseeki64(FILE *, long long, int); +extern long long __cdecl _ftelli64(FILE *); +#endif + + #define npy_fseek _fseeki64 + #define npy_ftell _ftelli64 + #define npy_lseek _lseeki64 + #define npy_off_t npy_int64 + + #if NPY_SIZEOF_INT == 8 + #define NPY_OFF_T_PYFMT "i" + #elif NPY_SIZEOF_LONG == 8 + #define NPY_OFF_T_PYFMT "l" + #elif NPY_SIZEOF_LONGLONG == 8 + #define NPY_OFF_T_PYFMT "L" + #else + #error Unsupported size for type off_t + #endif +#else +#ifdef HAVE_FSEEKO + #define npy_fseek fseeko +#else + #define npy_fseek fseek +#endif +#ifdef HAVE_FTELLO + #define npy_ftell ftello +#else + #define npy_ftell ftell +#endif + #define npy_lseek lseek + #define npy_off_t off_t + + #if NPY_SIZEOF_OFF_T == NPY_SIZEOF_SHORT + #define NPY_OFF_T_PYFMT "h" + #elif NPY_SIZEOF_OFF_T == NPY_SIZEOF_INT + #define NPY_OFF_T_PYFMT "i" + #elif NPY_SIZEOF_OFF_T == NPY_SIZEOF_LONG + #define NPY_OFF_T_PYFMT "l" + #elif NPY_SIZEOF_OFF_T == NPY_SIZEOF_LONGLONG + #define NPY_OFF_T_PYFMT "L" + #else + #error Unsupported size for type off_t + #endif +#endif + +/* enums for detected endianness */ +enum { + NPY_CPU_UNKNOWN_ENDIAN, + NPY_CPU_LITTLE, + NPY_CPU_BIG +}; + +/* + * This is to typedef npy_intp to the appropriate pointer size for this + * platform. Py_intptr_t, Py_uintptr_t are defined in pyport.h. + */ +typedef Py_intptr_t npy_intp; +typedef Py_uintptr_t npy_uintp; + +/* + * Define sizes that were not defined in numpyconfig.h. + */ +#define NPY_SIZEOF_CHAR 1 +#define NPY_SIZEOF_BYTE 1 +#define NPY_SIZEOF_DATETIME 8 +#define NPY_SIZEOF_TIMEDELTA 8 +#define NPY_SIZEOF_INTP NPY_SIZEOF_PY_INTPTR_T +#define NPY_SIZEOF_UINTP NPY_SIZEOF_PY_INTPTR_T +#define NPY_SIZEOF_HALF 2 +#define NPY_SIZEOF_CFLOAT NPY_SIZEOF_COMPLEX_FLOAT +#define NPY_SIZEOF_CDOUBLE NPY_SIZEOF_COMPLEX_DOUBLE +#define NPY_SIZEOF_CLONGDOUBLE NPY_SIZEOF_COMPLEX_LONGDOUBLE + +#ifdef constchar +#undef constchar +#endif + +#define NPY_SSIZE_T_PYFMT "n" +#define constchar char + +/* NPY_INTP_FMT Note: + * Unlike the other NPY_*_FMT macros which are used with + * PyOS_snprintf, NPY_INTP_FMT is used with PyErr_Format and + * PyString_Format. These functions use different formatting + * codes which are portably specified according to the Python + * documentation. See ticket #1795. + * + * On Windows x64, the LONGLONG formatter should be used, but + * in Python 2.6 the %lld formatter is not supported. In this + * case we work around the problem by using the %zd formatter. + */ +#if NPY_SIZEOF_PY_INTPTR_T == NPY_SIZEOF_INT + #define NPY_INTP NPY_INT + #define NPY_UINTP NPY_UINT + #define PyIntpArrType_Type PyIntArrType_Type + #define PyUIntpArrType_Type PyUIntArrType_Type + #define NPY_MAX_INTP NPY_MAX_INT + #define NPY_MIN_INTP NPY_MIN_INT + #define NPY_MAX_UINTP NPY_MAX_UINT + #define NPY_INTP_FMT "d" +#elif NPY_SIZEOF_PY_INTPTR_T == NPY_SIZEOF_LONG + #define NPY_INTP NPY_LONG + #define NPY_UINTP NPY_ULONG + #define PyIntpArrType_Type PyLongArrType_Type + #define PyUIntpArrType_Type PyULongArrType_Type + #define NPY_MAX_INTP NPY_MAX_LONG + #define NPY_MIN_INTP NPY_MIN_LONG + #define NPY_MAX_UINTP NPY_MAX_ULONG + #define NPY_INTP_FMT "ld" +#elif defined(PY_LONG_LONG) && (NPY_SIZEOF_PY_INTPTR_T == NPY_SIZEOF_LONGLONG) + #define NPY_INTP NPY_LONGLONG + #define NPY_UINTP NPY_ULONGLONG + #define PyIntpArrType_Type PyLongLongArrType_Type + #define PyUIntpArrType_Type PyULongLongArrType_Type + #define NPY_MAX_INTP NPY_MAX_LONGLONG + #define NPY_MIN_INTP NPY_MIN_LONGLONG + #define NPY_MAX_UINTP NPY_MAX_ULONGLONG + #if (PY_VERSION_HEX >= 0x02070000) + #define NPY_INTP_FMT "lld" + #else + #define NPY_INTP_FMT "zd" + #endif +#endif + +/* + * We can only use C99 formats for npy_int_p if it is the same as + * intp_t, hence the condition on HAVE_UNITPTR_T + */ +#if (NPY_USE_C99_FORMATS) == 1 \ + && (defined HAVE_UINTPTR_T) \ + && (defined HAVE_INTTYPES_H) + #include + #undef NPY_INTP_FMT + #define NPY_INTP_FMT PRIdPTR +#endif + + +/* + * Some platforms don't define bool, long long, or long double. + * Handle that here. + */ +#define NPY_BYTE_FMT "hhd" +#define NPY_UBYTE_FMT "hhu" +#define NPY_SHORT_FMT "hd" +#define NPY_USHORT_FMT "hu" +#define NPY_INT_FMT "d" +#define NPY_UINT_FMT "u" +#define NPY_LONG_FMT "ld" +#define NPY_ULONG_FMT "lu" +#define NPY_HALF_FMT "g" +#define NPY_FLOAT_FMT "g" +#define NPY_DOUBLE_FMT "g" + + +#ifdef PY_LONG_LONG +typedef PY_LONG_LONG npy_longlong; +typedef unsigned PY_LONG_LONG npy_ulonglong; +# ifdef _MSC_VER +# define NPY_LONGLONG_FMT "I64d" +# define NPY_ULONGLONG_FMT "I64u" +# elif defined(__APPLE__) || defined(__FreeBSD__) +/* "%Ld" only parses 4 bytes -- "L" is floating modifier on MacOS X/BSD */ +# define NPY_LONGLONG_FMT "lld" +# define NPY_ULONGLONG_FMT "llu" +/* + another possible variant -- *quad_t works on *BSD, but is deprecated: + #define LONGLONG_FMT "qd" + #define ULONGLONG_FMT "qu" +*/ +# else +# define NPY_LONGLONG_FMT "Ld" +# define NPY_ULONGLONG_FMT "Lu" +# endif +# ifdef _MSC_VER +# define NPY_LONGLONG_SUFFIX(x) (x##i64) +# define NPY_ULONGLONG_SUFFIX(x) (x##Ui64) +# else +# define NPY_LONGLONG_SUFFIX(x) (x##LL) +# define NPY_ULONGLONG_SUFFIX(x) (x##ULL) +# endif +#else +typedef long npy_longlong; +typedef unsigned long npy_ulonglong; +# define NPY_LONGLONG_SUFFIX(x) (x##L) +# define NPY_ULONGLONG_SUFFIX(x) (x##UL) +#endif + + +typedef unsigned char npy_bool; +#define NPY_FALSE 0 +#define NPY_TRUE 1 + + +#if NPY_SIZEOF_LONGDOUBLE == NPY_SIZEOF_DOUBLE + typedef double npy_longdouble; + #define NPY_LONGDOUBLE_FMT "g" +#else + typedef long double npy_longdouble; + #define NPY_LONGDOUBLE_FMT "Lg" +#endif + +#ifndef Py_USING_UNICODE +#error Must use Python with unicode enabled. +#endif + + +typedef signed char npy_byte; +typedef unsigned char npy_ubyte; +typedef unsigned short npy_ushort; +typedef unsigned int npy_uint; +typedef unsigned long npy_ulong; + +/* These are for completeness */ +typedef char npy_char; +typedef short npy_short; +typedef int npy_int; +typedef long npy_long; +typedef float npy_float; +typedef double npy_double; + +/* + * Disabling C99 complex usage: a lot of C code in numpy/scipy rely on being + * able to do .real/.imag. Will have to convert code first. + */ +#if 0 +#if defined(NPY_USE_C99_COMPLEX) && defined(NPY_HAVE_COMPLEX_DOUBLE) +typedef complex npy_cdouble; +#else +typedef struct { double real, imag; } npy_cdouble; +#endif + +#if defined(NPY_USE_C99_COMPLEX) && defined(NPY_HAVE_COMPLEX_FLOAT) +typedef complex float npy_cfloat; +#else +typedef struct { float real, imag; } npy_cfloat; +#endif + +#if defined(NPY_USE_C99_COMPLEX) && defined(NPY_HAVE_COMPLEX_LONG_DOUBLE) +typedef complex long double npy_clongdouble; +#else +typedef struct {npy_longdouble real, imag;} npy_clongdouble; +#endif +#endif +#if NPY_SIZEOF_COMPLEX_DOUBLE != 2 * NPY_SIZEOF_DOUBLE +#error npy_cdouble definition is not compatible with C99 complex definition ! \ + Please contact Numpy maintainers and give detailed information about your \ + compiler and platform +#endif +typedef struct { double real, imag; } npy_cdouble; + +#if NPY_SIZEOF_COMPLEX_FLOAT != 2 * NPY_SIZEOF_FLOAT +#error npy_cfloat definition is not compatible with C99 complex definition ! \ + Please contact Numpy maintainers and give detailed information about your \ + compiler and platform +#endif +typedef struct { float real, imag; } npy_cfloat; + +#if NPY_SIZEOF_COMPLEX_LONGDOUBLE != 2 * NPY_SIZEOF_LONGDOUBLE +#error npy_clongdouble definition is not compatible with C99 complex definition ! \ + Please contact Numpy maintainers and give detailed information about your \ + compiler and platform +#endif +typedef struct { npy_longdouble real, imag; } npy_clongdouble; + +/* + * numarray-style bit-width typedefs + */ +#define NPY_MAX_INT8 127 +#define NPY_MIN_INT8 -128 +#define NPY_MAX_UINT8 255 +#define NPY_MAX_INT16 32767 +#define NPY_MIN_INT16 -32768 +#define NPY_MAX_UINT16 65535 +#define NPY_MAX_INT32 2147483647 +#define NPY_MIN_INT32 (-NPY_MAX_INT32 - 1) +#define NPY_MAX_UINT32 4294967295U +#define NPY_MAX_INT64 NPY_LONGLONG_SUFFIX(9223372036854775807) +#define NPY_MIN_INT64 (-NPY_MAX_INT64 - NPY_LONGLONG_SUFFIX(1)) +#define NPY_MAX_UINT64 NPY_ULONGLONG_SUFFIX(18446744073709551615) +#define NPY_MAX_INT128 NPY_LONGLONG_SUFFIX(85070591730234615865843651857942052864) +#define NPY_MIN_INT128 (-NPY_MAX_INT128 - NPY_LONGLONG_SUFFIX(1)) +#define NPY_MAX_UINT128 NPY_ULONGLONG_SUFFIX(170141183460469231731687303715884105728) +#define NPY_MAX_INT256 NPY_LONGLONG_SUFFIX(57896044618658097711785492504343953926634992332820282019728792003956564819967) +#define NPY_MIN_INT256 (-NPY_MAX_INT256 - NPY_LONGLONG_SUFFIX(1)) +#define NPY_MAX_UINT256 NPY_ULONGLONG_SUFFIX(115792089237316195423570985008687907853269984665640564039457584007913129639935) +#define NPY_MIN_DATETIME NPY_MIN_INT64 +#define NPY_MAX_DATETIME NPY_MAX_INT64 +#define NPY_MIN_TIMEDELTA NPY_MIN_INT64 +#define NPY_MAX_TIMEDELTA NPY_MAX_INT64 + + /* Need to find the number of bits for each type and + make definitions accordingly. + + C states that sizeof(char) == 1 by definition + + So, just using the sizeof keyword won't help. + + It also looks like Python itself uses sizeof(char) quite a + bit, which by definition should be 1 all the time. + + Idea: Make Use of CHAR_BIT which should tell us how many + BITS per CHARACTER + */ + + /* Include platform definitions -- These are in the C89/90 standard */ +#include +#define NPY_MAX_BYTE SCHAR_MAX +#define NPY_MIN_BYTE SCHAR_MIN +#define NPY_MAX_UBYTE UCHAR_MAX +#define NPY_MAX_SHORT SHRT_MAX +#define NPY_MIN_SHORT SHRT_MIN +#define NPY_MAX_USHORT USHRT_MAX +#define NPY_MAX_INT INT_MAX +#ifndef INT_MIN +#define INT_MIN (-INT_MAX - 1) +#endif +#define NPY_MIN_INT INT_MIN +#define NPY_MAX_UINT UINT_MAX +#define NPY_MAX_LONG LONG_MAX +#define NPY_MIN_LONG LONG_MIN +#define NPY_MAX_ULONG ULONG_MAX + +#define NPY_BITSOF_BOOL (sizeof(npy_bool) * CHAR_BIT) +#define NPY_BITSOF_CHAR CHAR_BIT +#define NPY_BITSOF_BYTE (NPY_SIZEOF_BYTE * CHAR_BIT) +#define NPY_BITSOF_SHORT (NPY_SIZEOF_SHORT * CHAR_BIT) +#define NPY_BITSOF_INT (NPY_SIZEOF_INT * CHAR_BIT) +#define NPY_BITSOF_LONG (NPY_SIZEOF_LONG * CHAR_BIT) +#define NPY_BITSOF_LONGLONG (NPY_SIZEOF_LONGLONG * CHAR_BIT) +#define NPY_BITSOF_INTP (NPY_SIZEOF_INTP * CHAR_BIT) +#define NPY_BITSOF_HALF (NPY_SIZEOF_HALF * CHAR_BIT) +#define NPY_BITSOF_FLOAT (NPY_SIZEOF_FLOAT * CHAR_BIT) +#define NPY_BITSOF_DOUBLE (NPY_SIZEOF_DOUBLE * CHAR_BIT) +#define NPY_BITSOF_LONGDOUBLE (NPY_SIZEOF_LONGDOUBLE * CHAR_BIT) +#define NPY_BITSOF_CFLOAT (NPY_SIZEOF_CFLOAT * CHAR_BIT) +#define NPY_BITSOF_CDOUBLE (NPY_SIZEOF_CDOUBLE * CHAR_BIT) +#define NPY_BITSOF_CLONGDOUBLE (NPY_SIZEOF_CLONGDOUBLE * CHAR_BIT) +#define NPY_BITSOF_DATETIME (NPY_SIZEOF_DATETIME * CHAR_BIT) +#define NPY_BITSOF_TIMEDELTA (NPY_SIZEOF_TIMEDELTA * CHAR_BIT) + +#if NPY_BITSOF_LONG == 8 +#define NPY_INT8 NPY_LONG +#define NPY_UINT8 NPY_ULONG + typedef long npy_int8; + typedef unsigned long npy_uint8; +#define PyInt8ScalarObject PyLongScalarObject +#define PyInt8ArrType_Type PyLongArrType_Type +#define PyUInt8ScalarObject PyULongScalarObject +#define PyUInt8ArrType_Type PyULongArrType_Type +#define NPY_INT8_FMT NPY_LONG_FMT +#define NPY_UINT8_FMT NPY_ULONG_FMT +#elif NPY_BITSOF_LONG == 16 +#define NPY_INT16 NPY_LONG +#define NPY_UINT16 NPY_ULONG + typedef long npy_int16; + typedef unsigned long npy_uint16; +#define PyInt16ScalarObject PyLongScalarObject +#define PyInt16ArrType_Type PyLongArrType_Type +#define PyUInt16ScalarObject PyULongScalarObject +#define PyUInt16ArrType_Type PyULongArrType_Type +#define NPY_INT16_FMT NPY_LONG_FMT +#define NPY_UINT16_FMT NPY_ULONG_FMT +#elif NPY_BITSOF_LONG == 32 +#define NPY_INT32 NPY_LONG +#define NPY_UINT32 NPY_ULONG + typedef long npy_int32; + typedef unsigned long npy_uint32; + typedef unsigned long npy_ucs4; +#define PyInt32ScalarObject PyLongScalarObject +#define PyInt32ArrType_Type PyLongArrType_Type +#define PyUInt32ScalarObject PyULongScalarObject +#define PyUInt32ArrType_Type PyULongArrType_Type +#define NPY_INT32_FMT NPY_LONG_FMT +#define NPY_UINT32_FMT NPY_ULONG_FMT +#elif NPY_BITSOF_LONG == 64 +#define NPY_INT64 NPY_LONG +#define NPY_UINT64 NPY_ULONG + typedef long npy_int64; + typedef unsigned long npy_uint64; +#define PyInt64ScalarObject PyLongScalarObject +#define PyInt64ArrType_Type PyLongArrType_Type +#define PyUInt64ScalarObject PyULongScalarObject +#define PyUInt64ArrType_Type PyULongArrType_Type +#define NPY_INT64_FMT NPY_LONG_FMT +#define NPY_UINT64_FMT NPY_ULONG_FMT +#define MyPyLong_FromInt64 PyLong_FromLong +#define MyPyLong_AsInt64 PyLong_AsLong +#elif NPY_BITSOF_LONG == 128 +#define NPY_INT128 NPY_LONG +#define NPY_UINT128 NPY_ULONG + typedef long npy_int128; + typedef unsigned long npy_uint128; +#define PyInt128ScalarObject PyLongScalarObject +#define PyInt128ArrType_Type PyLongArrType_Type +#define PyUInt128ScalarObject PyULongScalarObject +#define PyUInt128ArrType_Type PyULongArrType_Type +#define NPY_INT128_FMT NPY_LONG_FMT +#define NPY_UINT128_FMT NPY_ULONG_FMT +#endif + +#if NPY_BITSOF_LONGLONG == 8 +# ifndef NPY_INT8 +# define NPY_INT8 NPY_LONGLONG +# define NPY_UINT8 NPY_ULONGLONG + typedef npy_longlong npy_int8; + typedef npy_ulonglong npy_uint8; +# define PyInt8ScalarObject PyLongLongScalarObject +# define PyInt8ArrType_Type PyLongLongArrType_Type +# define PyUInt8ScalarObject PyULongLongScalarObject +# define PyUInt8ArrType_Type PyULongLongArrType_Type +#define NPY_INT8_FMT NPY_LONGLONG_FMT +#define NPY_UINT8_FMT NPY_ULONGLONG_FMT +# endif +# define NPY_MAX_LONGLONG NPY_MAX_INT8 +# define NPY_MIN_LONGLONG NPY_MIN_INT8 +# define NPY_MAX_ULONGLONG NPY_MAX_UINT8 +#elif NPY_BITSOF_LONGLONG == 16 +# ifndef NPY_INT16 +# define NPY_INT16 NPY_LONGLONG +# define NPY_UINT16 NPY_ULONGLONG + typedef npy_longlong npy_int16; + typedef npy_ulonglong npy_uint16; +# define PyInt16ScalarObject PyLongLongScalarObject +# define PyInt16ArrType_Type PyLongLongArrType_Type +# define PyUInt16ScalarObject PyULongLongScalarObject +# define PyUInt16ArrType_Type PyULongLongArrType_Type +#define NPY_INT16_FMT NPY_LONGLONG_FMT +#define NPY_UINT16_FMT NPY_ULONGLONG_FMT +# endif +# define NPY_MAX_LONGLONG NPY_MAX_INT16 +# define NPY_MIN_LONGLONG NPY_MIN_INT16 +# define NPY_MAX_ULONGLONG NPY_MAX_UINT16 +#elif NPY_BITSOF_LONGLONG == 32 +# ifndef NPY_INT32 +# define NPY_INT32 NPY_LONGLONG +# define NPY_UINT32 NPY_ULONGLONG + typedef npy_longlong npy_int32; + typedef npy_ulonglong npy_uint32; + typedef npy_ulonglong npy_ucs4; +# define PyInt32ScalarObject PyLongLongScalarObject +# define PyInt32ArrType_Type PyLongLongArrType_Type +# define PyUInt32ScalarObject PyULongLongScalarObject +# define PyUInt32ArrType_Type PyULongLongArrType_Type +#define NPY_INT32_FMT NPY_LONGLONG_FMT +#define NPY_UINT32_FMT NPY_ULONGLONG_FMT +# endif +# define NPY_MAX_LONGLONG NPY_MAX_INT32 +# define NPY_MIN_LONGLONG NPY_MIN_INT32 +# define NPY_MAX_ULONGLONG NPY_MAX_UINT32 +#elif NPY_BITSOF_LONGLONG == 64 +# ifndef NPY_INT64 +# define NPY_INT64 NPY_LONGLONG +# define NPY_UINT64 NPY_ULONGLONG + typedef npy_longlong npy_int64; + typedef npy_ulonglong npy_uint64; +# define PyInt64ScalarObject PyLongLongScalarObject +# define PyInt64ArrType_Type PyLongLongArrType_Type +# define PyUInt64ScalarObject PyULongLongScalarObject +# define PyUInt64ArrType_Type PyULongLongArrType_Type +#define NPY_INT64_FMT NPY_LONGLONG_FMT +#define NPY_UINT64_FMT NPY_ULONGLONG_FMT +# define MyPyLong_FromInt64 PyLong_FromLongLong +# define MyPyLong_AsInt64 PyLong_AsLongLong +# endif +# define NPY_MAX_LONGLONG NPY_MAX_INT64 +# define NPY_MIN_LONGLONG NPY_MIN_INT64 +# define NPY_MAX_ULONGLONG NPY_MAX_UINT64 +#elif NPY_BITSOF_LONGLONG == 128 +# ifndef NPY_INT128 +# define NPY_INT128 NPY_LONGLONG +# define NPY_UINT128 NPY_ULONGLONG + typedef npy_longlong npy_int128; + typedef npy_ulonglong npy_uint128; +# define PyInt128ScalarObject PyLongLongScalarObject +# define PyInt128ArrType_Type PyLongLongArrType_Type +# define PyUInt128ScalarObject PyULongLongScalarObject +# define PyUInt128ArrType_Type PyULongLongArrType_Type +#define NPY_INT128_FMT NPY_LONGLONG_FMT +#define NPY_UINT128_FMT NPY_ULONGLONG_FMT +# endif +# define NPY_MAX_LONGLONG NPY_MAX_INT128 +# define NPY_MIN_LONGLONG NPY_MIN_INT128 +# define NPY_MAX_ULONGLONG NPY_MAX_UINT128 +#elif NPY_BITSOF_LONGLONG == 256 +# define NPY_INT256 NPY_LONGLONG +# define NPY_UINT256 NPY_ULONGLONG + typedef npy_longlong npy_int256; + typedef npy_ulonglong npy_uint256; +# define PyInt256ScalarObject PyLongLongScalarObject +# define PyInt256ArrType_Type PyLongLongArrType_Type +# define PyUInt256ScalarObject PyULongLongScalarObject +# define PyUInt256ArrType_Type PyULongLongArrType_Type +#define NPY_INT256_FMT NPY_LONGLONG_FMT +#define NPY_UINT256_FMT NPY_ULONGLONG_FMT +# define NPY_MAX_LONGLONG NPY_MAX_INT256 +# define NPY_MIN_LONGLONG NPY_MIN_INT256 +# define NPY_MAX_ULONGLONG NPY_MAX_UINT256 +#endif + +#if NPY_BITSOF_INT == 8 +#ifndef NPY_INT8 +#define NPY_INT8 NPY_INT +#define NPY_UINT8 NPY_UINT + typedef int npy_int8; + typedef unsigned int npy_uint8; +# define PyInt8ScalarObject PyIntScalarObject +# define PyInt8ArrType_Type PyIntArrType_Type +# define PyUInt8ScalarObject PyUIntScalarObject +# define PyUInt8ArrType_Type PyUIntArrType_Type +#define NPY_INT8_FMT NPY_INT_FMT +#define NPY_UINT8_FMT NPY_UINT_FMT +#endif +#elif NPY_BITSOF_INT == 16 +#ifndef NPY_INT16 +#define NPY_INT16 NPY_INT +#define NPY_UINT16 NPY_UINT + typedef int npy_int16; + typedef unsigned int npy_uint16; +# define PyInt16ScalarObject PyIntScalarObject +# define PyInt16ArrType_Type PyIntArrType_Type +# define PyUInt16ScalarObject PyIntUScalarObject +# define PyUInt16ArrType_Type PyIntUArrType_Type +#define NPY_INT16_FMT NPY_INT_FMT +#define NPY_UINT16_FMT NPY_UINT_FMT +#endif +#elif NPY_BITSOF_INT == 32 +#ifndef NPY_INT32 +#define NPY_INT32 NPY_INT +#define NPY_UINT32 NPY_UINT + typedef int npy_int32; + typedef unsigned int npy_uint32; + typedef unsigned int npy_ucs4; +# define PyInt32ScalarObject PyIntScalarObject +# define PyInt32ArrType_Type PyIntArrType_Type +# define PyUInt32ScalarObject PyUIntScalarObject +# define PyUInt32ArrType_Type PyUIntArrType_Type +#define NPY_INT32_FMT NPY_INT_FMT +#define NPY_UINT32_FMT NPY_UINT_FMT +#endif +#elif NPY_BITSOF_INT == 64 +#ifndef NPY_INT64 +#define NPY_INT64 NPY_INT +#define NPY_UINT64 NPY_UINT + typedef int npy_int64; + typedef unsigned int npy_uint64; +# define PyInt64ScalarObject PyIntScalarObject +# define PyInt64ArrType_Type PyIntArrType_Type +# define PyUInt64ScalarObject PyUIntScalarObject +# define PyUInt64ArrType_Type PyUIntArrType_Type +#define NPY_INT64_FMT NPY_INT_FMT +#define NPY_UINT64_FMT NPY_UINT_FMT +# define MyPyLong_FromInt64 PyLong_FromLong +# define MyPyLong_AsInt64 PyLong_AsLong +#endif +#elif NPY_BITSOF_INT == 128 +#ifndef NPY_INT128 +#define NPY_INT128 NPY_INT +#define NPY_UINT128 NPY_UINT + typedef int npy_int128; + typedef unsigned int npy_uint128; +# define PyInt128ScalarObject PyIntScalarObject +# define PyInt128ArrType_Type PyIntArrType_Type +# define PyUInt128ScalarObject PyUIntScalarObject +# define PyUInt128ArrType_Type PyUIntArrType_Type +#define NPY_INT128_FMT NPY_INT_FMT +#define NPY_UINT128_FMT NPY_UINT_FMT +#endif +#endif + +#if NPY_BITSOF_SHORT == 8 +#ifndef NPY_INT8 +#define NPY_INT8 NPY_SHORT +#define NPY_UINT8 NPY_USHORT + typedef short npy_int8; + typedef unsigned short npy_uint8; +# define PyInt8ScalarObject PyShortScalarObject +# define PyInt8ArrType_Type PyShortArrType_Type +# define PyUInt8ScalarObject PyUShortScalarObject +# define PyUInt8ArrType_Type PyUShortArrType_Type +#define NPY_INT8_FMT NPY_SHORT_FMT +#define NPY_UINT8_FMT NPY_USHORT_FMT +#endif +#elif NPY_BITSOF_SHORT == 16 +#ifndef NPY_INT16 +#define NPY_INT16 NPY_SHORT +#define NPY_UINT16 NPY_USHORT + typedef short npy_int16; + typedef unsigned short npy_uint16; +# define PyInt16ScalarObject PyShortScalarObject +# define PyInt16ArrType_Type PyShortArrType_Type +# define PyUInt16ScalarObject PyUShortScalarObject +# define PyUInt16ArrType_Type PyUShortArrType_Type +#define NPY_INT16_FMT NPY_SHORT_FMT +#define NPY_UINT16_FMT NPY_USHORT_FMT +#endif +#elif NPY_BITSOF_SHORT == 32 +#ifndef NPY_INT32 +#define NPY_INT32 NPY_SHORT +#define NPY_UINT32 NPY_USHORT + typedef short npy_int32; + typedef unsigned short npy_uint32; + typedef unsigned short npy_ucs4; +# define PyInt32ScalarObject PyShortScalarObject +# define PyInt32ArrType_Type PyShortArrType_Type +# define PyUInt32ScalarObject PyUShortScalarObject +# define PyUInt32ArrType_Type PyUShortArrType_Type +#define NPY_INT32_FMT NPY_SHORT_FMT +#define NPY_UINT32_FMT NPY_USHORT_FMT +#endif +#elif NPY_BITSOF_SHORT == 64 +#ifndef NPY_INT64 +#define NPY_INT64 NPY_SHORT +#define NPY_UINT64 NPY_USHORT + typedef short npy_int64; + typedef unsigned short npy_uint64; +# define PyInt64ScalarObject PyShortScalarObject +# define PyInt64ArrType_Type PyShortArrType_Type +# define PyUInt64ScalarObject PyUShortScalarObject +# define PyUInt64ArrType_Type PyUShortArrType_Type +#define NPY_INT64_FMT NPY_SHORT_FMT +#define NPY_UINT64_FMT NPY_USHORT_FMT +# define MyPyLong_FromInt64 PyLong_FromLong +# define MyPyLong_AsInt64 PyLong_AsLong +#endif +#elif NPY_BITSOF_SHORT == 128 +#ifndef NPY_INT128 +#define NPY_INT128 NPY_SHORT +#define NPY_UINT128 NPY_USHORT + typedef short npy_int128; + typedef unsigned short npy_uint128; +# define PyInt128ScalarObject PyShortScalarObject +# define PyInt128ArrType_Type PyShortArrType_Type +# define PyUInt128ScalarObject PyUShortScalarObject +# define PyUInt128ArrType_Type PyUShortArrType_Type +#define NPY_INT128_FMT NPY_SHORT_FMT +#define NPY_UINT128_FMT NPY_USHORT_FMT +#endif +#endif + + +#if NPY_BITSOF_CHAR == 8 +#ifndef NPY_INT8 +#define NPY_INT8 NPY_BYTE +#define NPY_UINT8 NPY_UBYTE + typedef signed char npy_int8; + typedef unsigned char npy_uint8; +# define PyInt8ScalarObject PyByteScalarObject +# define PyInt8ArrType_Type PyByteArrType_Type +# define PyUInt8ScalarObject PyUByteScalarObject +# define PyUInt8ArrType_Type PyUByteArrType_Type +#define NPY_INT8_FMT NPY_BYTE_FMT +#define NPY_UINT8_FMT NPY_UBYTE_FMT +#endif +#elif NPY_BITSOF_CHAR == 16 +#ifndef NPY_INT16 +#define NPY_INT16 NPY_BYTE +#define NPY_UINT16 NPY_UBYTE + typedef signed char npy_int16; + typedef unsigned char npy_uint16; +# define PyInt16ScalarObject PyByteScalarObject +# define PyInt16ArrType_Type PyByteArrType_Type +# define PyUInt16ScalarObject PyUByteScalarObject +# define PyUInt16ArrType_Type PyUByteArrType_Type +#define NPY_INT16_FMT NPY_BYTE_FMT +#define NPY_UINT16_FMT NPY_UBYTE_FMT +#endif +#elif NPY_BITSOF_CHAR == 32 +#ifndef NPY_INT32 +#define NPY_INT32 NPY_BYTE +#define NPY_UINT32 NPY_UBYTE + typedef signed char npy_int32; + typedef unsigned char npy_uint32; + typedef unsigned char npy_ucs4; +# define PyInt32ScalarObject PyByteScalarObject +# define PyInt32ArrType_Type PyByteArrType_Type +# define PyUInt32ScalarObject PyUByteScalarObject +# define PyUInt32ArrType_Type PyUByteArrType_Type +#define NPY_INT32_FMT NPY_BYTE_FMT +#define NPY_UINT32_FMT NPY_UBYTE_FMT +#endif +#elif NPY_BITSOF_CHAR == 64 +#ifndef NPY_INT64 +#define NPY_INT64 NPY_BYTE +#define NPY_UINT64 NPY_UBYTE + typedef signed char npy_int64; + typedef unsigned char npy_uint64; +# define PyInt64ScalarObject PyByteScalarObject +# define PyInt64ArrType_Type PyByteArrType_Type +# define PyUInt64ScalarObject PyUByteScalarObject +# define PyUInt64ArrType_Type PyUByteArrType_Type +#define NPY_INT64_FMT NPY_BYTE_FMT +#define NPY_UINT64_FMT NPY_UBYTE_FMT +# define MyPyLong_FromInt64 PyLong_FromLong +# define MyPyLong_AsInt64 PyLong_AsLong +#endif +#elif NPY_BITSOF_CHAR == 128 +#ifndef NPY_INT128 +#define NPY_INT128 NPY_BYTE +#define NPY_UINT128 NPY_UBYTE + typedef signed char npy_int128; + typedef unsigned char npy_uint128; +# define PyInt128ScalarObject PyByteScalarObject +# define PyInt128ArrType_Type PyByteArrType_Type +# define PyUInt128ScalarObject PyUByteScalarObject +# define PyUInt128ArrType_Type PyUByteArrType_Type +#define NPY_INT128_FMT NPY_BYTE_FMT +#define NPY_UINT128_FMT NPY_UBYTE_FMT +#endif +#endif + + + +#if NPY_BITSOF_DOUBLE == 32 +#ifndef NPY_FLOAT32 +#define NPY_FLOAT32 NPY_DOUBLE +#define NPY_COMPLEX64 NPY_CDOUBLE + typedef double npy_float32; + typedef npy_cdouble npy_complex64; +# define PyFloat32ScalarObject PyDoubleScalarObject +# define PyComplex64ScalarObject PyCDoubleScalarObject +# define PyFloat32ArrType_Type PyDoubleArrType_Type +# define PyComplex64ArrType_Type PyCDoubleArrType_Type +#define NPY_FLOAT32_FMT NPY_DOUBLE_FMT +#define NPY_COMPLEX64_FMT NPY_CDOUBLE_FMT +#endif +#elif NPY_BITSOF_DOUBLE == 64 +#ifndef NPY_FLOAT64 +#define NPY_FLOAT64 NPY_DOUBLE +#define NPY_COMPLEX128 NPY_CDOUBLE + typedef double npy_float64; + typedef npy_cdouble npy_complex128; +# define PyFloat64ScalarObject PyDoubleScalarObject +# define PyComplex128ScalarObject PyCDoubleScalarObject +# define PyFloat64ArrType_Type PyDoubleArrType_Type +# define PyComplex128ArrType_Type PyCDoubleArrType_Type +#define NPY_FLOAT64_FMT NPY_DOUBLE_FMT +#define NPY_COMPLEX128_FMT NPY_CDOUBLE_FMT +#endif +#elif NPY_BITSOF_DOUBLE == 80 +#ifndef NPY_FLOAT80 +#define NPY_FLOAT80 NPY_DOUBLE +#define NPY_COMPLEX160 NPY_CDOUBLE + typedef double npy_float80; + typedef npy_cdouble npy_complex160; +# define PyFloat80ScalarObject PyDoubleScalarObject +# define PyComplex160ScalarObject PyCDoubleScalarObject +# define PyFloat80ArrType_Type PyDoubleArrType_Type +# define PyComplex160ArrType_Type PyCDoubleArrType_Type +#define NPY_FLOAT80_FMT NPY_DOUBLE_FMT +#define NPY_COMPLEX160_FMT NPY_CDOUBLE_FMT +#endif +#elif NPY_BITSOF_DOUBLE == 96 +#ifndef NPY_FLOAT96 +#define NPY_FLOAT96 NPY_DOUBLE +#define NPY_COMPLEX192 NPY_CDOUBLE + typedef double npy_float96; + typedef npy_cdouble npy_complex192; +# define PyFloat96ScalarObject PyDoubleScalarObject +# define PyComplex192ScalarObject PyCDoubleScalarObject +# define PyFloat96ArrType_Type PyDoubleArrType_Type +# define PyComplex192ArrType_Type PyCDoubleArrType_Type +#define NPY_FLOAT96_FMT NPY_DOUBLE_FMT +#define NPY_COMPLEX192_FMT NPY_CDOUBLE_FMT +#endif +#elif NPY_BITSOF_DOUBLE == 128 +#ifndef NPY_FLOAT128 +#define NPY_FLOAT128 NPY_DOUBLE +#define NPY_COMPLEX256 NPY_CDOUBLE + typedef double npy_float128; + typedef npy_cdouble npy_complex256; +# define PyFloat128ScalarObject PyDoubleScalarObject +# define PyComplex256ScalarObject PyCDoubleScalarObject +# define PyFloat128ArrType_Type PyDoubleArrType_Type +# define PyComplex256ArrType_Type PyCDoubleArrType_Type +#define NPY_FLOAT128_FMT NPY_DOUBLE_FMT +#define NPY_COMPLEX256_FMT NPY_CDOUBLE_FMT +#endif +#endif + + + +#if NPY_BITSOF_FLOAT == 32 +#ifndef NPY_FLOAT32 +#define NPY_FLOAT32 NPY_FLOAT +#define NPY_COMPLEX64 NPY_CFLOAT + typedef float npy_float32; + typedef npy_cfloat npy_complex64; +# define PyFloat32ScalarObject PyFloatScalarObject +# define PyComplex64ScalarObject PyCFloatScalarObject +# define PyFloat32ArrType_Type PyFloatArrType_Type +# define PyComplex64ArrType_Type PyCFloatArrType_Type +#define NPY_FLOAT32_FMT NPY_FLOAT_FMT +#define NPY_COMPLEX64_FMT NPY_CFLOAT_FMT +#endif +#elif NPY_BITSOF_FLOAT == 64 +#ifndef NPY_FLOAT64 +#define NPY_FLOAT64 NPY_FLOAT +#define NPY_COMPLEX128 NPY_CFLOAT + typedef float npy_float64; + typedef npy_cfloat npy_complex128; +# define PyFloat64ScalarObject PyFloatScalarObject +# define PyComplex128ScalarObject PyCFloatScalarObject +# define PyFloat64ArrType_Type PyFloatArrType_Type +# define PyComplex128ArrType_Type PyCFloatArrType_Type +#define NPY_FLOAT64_FMT NPY_FLOAT_FMT +#define NPY_COMPLEX128_FMT NPY_CFLOAT_FMT +#endif +#elif NPY_BITSOF_FLOAT == 80 +#ifndef NPY_FLOAT80 +#define NPY_FLOAT80 NPY_FLOAT +#define NPY_COMPLEX160 NPY_CFLOAT + typedef float npy_float80; + typedef npy_cfloat npy_complex160; +# define PyFloat80ScalarObject PyFloatScalarObject +# define PyComplex160ScalarObject PyCFloatScalarObject +# define PyFloat80ArrType_Type PyFloatArrType_Type +# define PyComplex160ArrType_Type PyCFloatArrType_Type +#define NPY_FLOAT80_FMT NPY_FLOAT_FMT +#define NPY_COMPLEX160_FMT NPY_CFLOAT_FMT +#endif +#elif NPY_BITSOF_FLOAT == 96 +#ifndef NPY_FLOAT96 +#define NPY_FLOAT96 NPY_FLOAT +#define NPY_COMPLEX192 NPY_CFLOAT + typedef float npy_float96; + typedef npy_cfloat npy_complex192; +# define PyFloat96ScalarObject PyFloatScalarObject +# define PyComplex192ScalarObject PyCFloatScalarObject +# define PyFloat96ArrType_Type PyFloatArrType_Type +# define PyComplex192ArrType_Type PyCFloatArrType_Type +#define NPY_FLOAT96_FMT NPY_FLOAT_FMT +#define NPY_COMPLEX192_FMT NPY_CFLOAT_FMT +#endif +#elif NPY_BITSOF_FLOAT == 128 +#ifndef NPY_FLOAT128 +#define NPY_FLOAT128 NPY_FLOAT +#define NPY_COMPLEX256 NPY_CFLOAT + typedef float npy_float128; + typedef npy_cfloat npy_complex256; +# define PyFloat128ScalarObject PyFloatScalarObject +# define PyComplex256ScalarObject PyCFloatScalarObject +# define PyFloat128ArrType_Type PyFloatArrType_Type +# define PyComplex256ArrType_Type PyCFloatArrType_Type +#define NPY_FLOAT128_FMT NPY_FLOAT_FMT +#define NPY_COMPLEX256_FMT NPY_CFLOAT_FMT +#endif +#endif + +/* half/float16 isn't a floating-point type in C */ +#define NPY_FLOAT16 NPY_HALF +typedef npy_uint16 npy_half; +typedef npy_half npy_float16; + +#if NPY_BITSOF_LONGDOUBLE == 32 +#ifndef NPY_FLOAT32 +#define NPY_FLOAT32 NPY_LONGDOUBLE +#define NPY_COMPLEX64 NPY_CLONGDOUBLE + typedef npy_longdouble npy_float32; + typedef npy_clongdouble npy_complex64; +# define PyFloat32ScalarObject PyLongDoubleScalarObject +# define PyComplex64ScalarObject PyCLongDoubleScalarObject +# define PyFloat32ArrType_Type PyLongDoubleArrType_Type +# define PyComplex64ArrType_Type PyCLongDoubleArrType_Type +#define NPY_FLOAT32_FMT NPY_LONGDOUBLE_FMT +#define NPY_COMPLEX64_FMT NPY_CLONGDOUBLE_FMT +#endif +#elif NPY_BITSOF_LONGDOUBLE == 64 +#ifndef NPY_FLOAT64 +#define NPY_FLOAT64 NPY_LONGDOUBLE +#define NPY_COMPLEX128 NPY_CLONGDOUBLE + typedef npy_longdouble npy_float64; + typedef npy_clongdouble npy_complex128; +# define PyFloat64ScalarObject PyLongDoubleScalarObject +# define PyComplex128ScalarObject PyCLongDoubleScalarObject +# define PyFloat64ArrType_Type PyLongDoubleArrType_Type +# define PyComplex128ArrType_Type PyCLongDoubleArrType_Type +#define NPY_FLOAT64_FMT NPY_LONGDOUBLE_FMT +#define NPY_COMPLEX128_FMT NPY_CLONGDOUBLE_FMT +#endif +#elif NPY_BITSOF_LONGDOUBLE == 80 +#ifndef NPY_FLOAT80 +#define NPY_FLOAT80 NPY_LONGDOUBLE +#define NPY_COMPLEX160 NPY_CLONGDOUBLE + typedef npy_longdouble npy_float80; + typedef npy_clongdouble npy_complex160; +# define PyFloat80ScalarObject PyLongDoubleScalarObject +# define PyComplex160ScalarObject PyCLongDoubleScalarObject +# define PyFloat80ArrType_Type PyLongDoubleArrType_Type +# define PyComplex160ArrType_Type PyCLongDoubleArrType_Type +#define NPY_FLOAT80_FMT NPY_LONGDOUBLE_FMT +#define NPY_COMPLEX160_FMT NPY_CLONGDOUBLE_FMT +#endif +#elif NPY_BITSOF_LONGDOUBLE == 96 +#ifndef NPY_FLOAT96 +#define NPY_FLOAT96 NPY_LONGDOUBLE +#define NPY_COMPLEX192 NPY_CLONGDOUBLE + typedef npy_longdouble npy_float96; + typedef npy_clongdouble npy_complex192; +# define PyFloat96ScalarObject PyLongDoubleScalarObject +# define PyComplex192ScalarObject PyCLongDoubleScalarObject +# define PyFloat96ArrType_Type PyLongDoubleArrType_Type +# define PyComplex192ArrType_Type PyCLongDoubleArrType_Type +#define NPY_FLOAT96_FMT NPY_LONGDOUBLE_FMT +#define NPY_COMPLEX192_FMT NPY_CLONGDOUBLE_FMT +#endif +#elif NPY_BITSOF_LONGDOUBLE == 128 +#ifndef NPY_FLOAT128 +#define NPY_FLOAT128 NPY_LONGDOUBLE +#define NPY_COMPLEX256 NPY_CLONGDOUBLE + typedef npy_longdouble npy_float128; + typedef npy_clongdouble npy_complex256; +# define PyFloat128ScalarObject PyLongDoubleScalarObject +# define PyComplex256ScalarObject PyCLongDoubleScalarObject +# define PyFloat128ArrType_Type PyLongDoubleArrType_Type +# define PyComplex256ArrType_Type PyCLongDoubleArrType_Type +#define NPY_FLOAT128_FMT NPY_LONGDOUBLE_FMT +#define NPY_COMPLEX256_FMT NPY_CLONGDOUBLE_FMT +#endif +#elif NPY_BITSOF_LONGDOUBLE == 256 +#define NPY_FLOAT256 NPY_LONGDOUBLE +#define NPY_COMPLEX512 NPY_CLONGDOUBLE + typedef npy_longdouble npy_float256; + typedef npy_clongdouble npy_complex512; +# define PyFloat256ScalarObject PyLongDoubleScalarObject +# define PyComplex512ScalarObject PyCLongDoubleScalarObject +# define PyFloat256ArrType_Type PyLongDoubleArrType_Type +# define PyComplex512ArrType_Type PyCLongDoubleArrType_Type +#define NPY_FLOAT256_FMT NPY_LONGDOUBLE_FMT +#define NPY_COMPLEX512_FMT NPY_CLONGDOUBLE_FMT +#endif + +/* datetime typedefs */ +typedef npy_int64 npy_timedelta; +typedef npy_int64 npy_datetime; +#define NPY_DATETIME_FMT NPY_INT64_FMT +#define NPY_TIMEDELTA_FMT NPY_INT64_FMT + +/* End of typedefs for numarray style bit-width names */ + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h new file mode 100644 index 000000000..7958dc208 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h @@ -0,0 +1,114 @@ +/* + * This set (target) cpu specific macros: + * - Possible values: + * NPY_CPU_X86 + * NPY_CPU_AMD64 + * NPY_CPU_PPC + * NPY_CPU_PPC64 + * NPY_CPU_PPC64LE + * NPY_CPU_SPARC + * NPY_CPU_S390 + * NPY_CPU_IA64 + * NPY_CPU_HPPA + * NPY_CPU_ALPHA + * NPY_CPU_ARMEL + * NPY_CPU_ARMEB + * NPY_CPU_SH_LE + * NPY_CPU_SH_BE + */ +#ifndef _NPY_CPUARCH_H_ +#define _NPY_CPUARCH_H_ + +#include "numpyconfig.h" + +#if defined( __i386__ ) || defined(i386) || defined(_M_IX86) + /* + * __i386__ is defined by gcc and Intel compiler on Linux, + * _M_IX86 by VS compiler, + * i386 by Sun compilers on opensolaris at least + */ + #define NPY_CPU_X86 +#elif defined(__x86_64__) || defined(__amd64__) || defined(__x86_64) || defined(_M_AMD64) + /* + * both __x86_64__ and __amd64__ are defined by gcc + * __x86_64 defined by sun compiler on opensolaris at least + * _M_AMD64 defined by MS compiler + */ + #define NPY_CPU_AMD64 +#elif defined(__ppc__) || defined(__powerpc__) || defined(_ARCH_PPC) + /* + * __ppc__ is defined by gcc, I remember having seen __powerpc__ once, + * but can't find it ATM + * _ARCH_PPC is used by at least gcc on AIX + */ + #define NPY_CPU_PPC +#elif defined(__ppc64le__) + #define NPY_CPU_PPC64LE +#elif defined(__ppc64__) + #define NPY_CPU_PPC64 +#elif defined(__sparc__) || defined(__sparc) + /* __sparc__ is defined by gcc and Forte (e.g. Sun) compilers */ + #define NPY_CPU_SPARC +#elif defined(__s390__) + #define NPY_CPU_S390 +#elif defined(__ia64) + #define NPY_CPU_IA64 +#elif defined(__hppa) + #define NPY_CPU_HPPA +#elif defined(__alpha__) + #define NPY_CPU_ALPHA +#elif defined(__arm__) && defined(__ARMEL__) + #define NPY_CPU_ARMEL +#elif defined(__arm__) && defined(__ARMEB__) + #define NPY_CPU_ARMEB +#elif defined(__sh__) && defined(__LITTLE_ENDIAN__) + #define NPY_CPU_SH_LE +#elif defined(__sh__) && defined(__BIG_ENDIAN__) + #define NPY_CPU_SH_BE +#elif defined(__MIPSEL__) + #define NPY_CPU_MIPSEL +#elif defined(__MIPSEB__) + #define NPY_CPU_MIPSEB +#elif defined(__aarch64__) + #define NPY_CPU_AARCH64 +#elif defined(__mc68000__) + #define NPY_CPU_M68K +#else + #error Unknown CPU, please report this to numpy maintainers with \ + information about your platform (OS, CPU and compiler) +#endif + +/* + This "white-lists" the architectures that we know don't require + pointer alignment. We white-list, since the memcpy version will + work everywhere, whereas assignment will only work where pointer + dereferencing doesn't require alignment. + + TODO: There may be more architectures we can white list. +*/ +#if defined(NPY_CPU_X86) || defined(NPY_CPU_AMD64) + #define NPY_COPY_PYOBJECT_PTR(dst, src) (*((PyObject **)(dst)) = *((PyObject **)(src))) +#else + #if NPY_SIZEOF_PY_INTPTR_T == 4 + #define NPY_COPY_PYOBJECT_PTR(dst, src) \ + ((char*)(dst))[0] = ((char*)(src))[0]; \ + ((char*)(dst))[1] = ((char*)(src))[1]; \ + ((char*)(dst))[2] = ((char*)(src))[2]; \ + ((char*)(dst))[3] = ((char*)(src))[3]; + #elif NPY_SIZEOF_PY_INTPTR_T == 8 + #define NPY_COPY_PYOBJECT_PTR(dst, src) \ + ((char*)(dst))[0] = ((char*)(src))[0]; \ + ((char*)(dst))[1] = ((char*)(src))[1]; \ + ((char*)(dst))[2] = ((char*)(src))[2]; \ + ((char*)(dst))[3] = ((char*)(src))[3]; \ + ((char*)(dst))[4] = ((char*)(src))[4]; \ + ((char*)(dst))[5] = ((char*)(src))[5]; \ + ((char*)(dst))[6] = ((char*)(src))[6]; \ + ((char*)(dst))[7] = ((char*)(src))[7]; + #else + #error Unknown architecture, please report this to numpy maintainers with \ + information about your platform (OS, CPU and compiler) + #endif +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h new file mode 100644 index 000000000..44d4326b1 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h @@ -0,0 +1,48 @@ +#ifndef _NPY_ENDIAN_H_ +#define _NPY_ENDIAN_H_ + +/* + * NPY_BYTE_ORDER is set to the same value as BYTE_ORDER set by glibc in + * endian.h + */ + +#ifdef NPY_HAVE_ENDIAN_H + /* Use endian.h if available */ + #include + + #define NPY_BYTE_ORDER __BYTE_ORDER + #define NPY_LITTLE_ENDIAN __LITTLE_ENDIAN + #define NPY_BIG_ENDIAN __BIG_ENDIAN +#else + /* Set endianness info using target CPU */ + #include "npy_cpu.h" + + #define NPY_LITTLE_ENDIAN 1234 + #define NPY_BIG_ENDIAN 4321 + + #if defined(NPY_CPU_X86) \ + || defined(NPY_CPU_AMD64) \ + || defined(NPY_CPU_IA64) \ + || defined(NPY_CPU_ALPHA) \ + || defined(NPY_CPU_ARMEL) \ + || defined(NPY_CPU_AARCH64) \ + || defined(NPY_CPU_SH_LE) \ + || defined(NPY_CPU_MIPSEL) \ + || defined(NPY_CPU_PPC64LE) + #define NPY_BYTE_ORDER NPY_LITTLE_ENDIAN + #elif defined(NPY_CPU_PPC) \ + || defined(NPY_CPU_SPARC) \ + || defined(NPY_CPU_S390) \ + || defined(NPY_CPU_HPPA) \ + || defined(NPY_CPU_PPC64) \ + || defined(NPY_CPU_ARMEB) \ + || defined(NPY_CPU_SH_BE) \ + || defined(NPY_CPU_MIPSEB) \ + || defined(NPY_CPU_M68K) + #define NPY_BYTE_ORDER NPY_BIG_ENDIAN + #else + #error Unknown CPU: can not set endianness + #endif +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h new file mode 100644 index 000000000..f71fd689e --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h @@ -0,0 +1,117 @@ + +/* Signal handling: + +This header file defines macros that allow your code to handle +interrupts received during processing. Interrupts that +could reasonably be handled: + +SIGINT, SIGABRT, SIGALRM, SIGSEGV + +****Warning*************** + +Do not allow code that creates temporary memory or increases reference +counts of Python objects to be interrupted unless you handle it +differently. + +************************** + +The mechanism for handling interrupts is conceptually simple: + + - replace the signal handler with our own home-grown version + and store the old one. + - run the code to be interrupted -- if an interrupt occurs + the handler should basically just cause a return to the + calling function for finish work. + - restore the old signal handler + +Of course, every code that allows interrupts must account for +returning via the interrupt and handle clean-up correctly. But, +even still, the simple paradigm is complicated by at least three +factors. + + 1) platform portability (i.e. Microsoft says not to use longjmp + to return from signal handling. They have a __try and __except + extension to C instead but what about mingw?). + + 2) how to handle threads: apparently whether signals are delivered to + every thread of the process or the "invoking" thread is platform + dependent. --- we don't handle threads for now. + + 3) do we need to worry about re-entrance. For now, assume the + code will not call-back into itself. + +Ideas: + + 1) Start by implementing an approach that works on platforms that + can use setjmp and longjmp functionality and does nothing + on other platforms. + + 2) Ignore threads --- i.e. do not mix interrupt handling and threads + + 3) Add a default signal_handler function to the C-API but have the rest + use macros. + + +Simple Interface: + + +In your C-extension: around a block of code you want to be interruptable +with a SIGINT + +NPY_SIGINT_ON +[code] +NPY_SIGINT_OFF + +In order for this to work correctly, the +[code] block must not allocate any memory or alter the reference count of any +Python objects. In other words [code] must be interruptible so that continuation +after NPY_SIGINT_OFF will only be "missing some computations" + +Interrupt handling does not work well with threads. + +*/ + +/* Add signal handling macros + Make the global variable and signal handler part of the C-API +*/ + +#ifndef NPY_INTERRUPT_H +#define NPY_INTERRUPT_H + +#ifndef NPY_NO_SIGNAL + +#include +#include + +#ifndef sigsetjmp + +#define NPY_SIGSETJMP(arg1, arg2) setjmp(arg1) +#define NPY_SIGLONGJMP(arg1, arg2) longjmp(arg1, arg2) +#define NPY_SIGJMP_BUF jmp_buf + +#else + +#define NPY_SIGSETJMP(arg1, arg2) sigsetjmp(arg1, arg2) +#define NPY_SIGLONGJMP(arg1, arg2) siglongjmp(arg1, arg2) +#define NPY_SIGJMP_BUF sigjmp_buf + +#endif + +# define NPY_SIGINT_ON { \ + PyOS_sighandler_t _npy_sig_save; \ + _npy_sig_save = PyOS_setsig(SIGINT, _PyArray_SigintHandler); \ + if (NPY_SIGSETJMP(*((NPY_SIGJMP_BUF *)_PyArray_GetSigintBuf()), \ + 1) == 0) { \ + +# define NPY_SIGINT_OFF } \ + PyOS_setsig(SIGINT, _npy_sig_save); \ + } + +#else /* NPY_NO_SIGNAL */ + +#define NPY_SIGINT_ON +#define NPY_SIGINT_OFF + +#endif /* HAVE_SIGSETJMP */ + +#endif /* NPY_INTERRUPT_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h new file mode 100644 index 000000000..094286181 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h @@ -0,0 +1,468 @@ +#ifndef __NPY_MATH_C99_H_ +#define __NPY_MATH_C99_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#ifdef __SUNPRO_CC +#include +#endif +#ifdef HAVE_NPY_CONFIG_H +#include +#endif +#include + + +/* + * NAN and INFINITY like macros (same behavior as glibc for NAN, same as C99 + * for INFINITY) + * + * XXX: I should test whether INFINITY and NAN are available on the platform + */ +NPY_INLINE static float __npy_inff(void) +{ + const union { npy_uint32 __i; float __f;} __bint = {0x7f800000UL}; + return __bint.__f; +} + +NPY_INLINE static float __npy_nanf(void) +{ + const union { npy_uint32 __i; float __f;} __bint = {0x7fc00000UL}; + return __bint.__f; +} + +NPY_INLINE static float __npy_pzerof(void) +{ + const union { npy_uint32 __i; float __f;} __bint = {0x00000000UL}; + return __bint.__f; +} + +NPY_INLINE static float __npy_nzerof(void) +{ + const union { npy_uint32 __i; float __f;} __bint = {0x80000000UL}; + return __bint.__f; +} + +#define NPY_INFINITYF __npy_inff() +#define NPY_NANF __npy_nanf() +#define NPY_PZEROF __npy_pzerof() +#define NPY_NZEROF __npy_nzerof() + +#define NPY_INFINITY ((npy_double)NPY_INFINITYF) +#define NPY_NAN ((npy_double)NPY_NANF) +#define NPY_PZERO ((npy_double)NPY_PZEROF) +#define NPY_NZERO ((npy_double)NPY_NZEROF) + +#define NPY_INFINITYL ((npy_longdouble)NPY_INFINITYF) +#define NPY_NANL ((npy_longdouble)NPY_NANF) +#define NPY_PZEROL ((npy_longdouble)NPY_PZEROF) +#define NPY_NZEROL ((npy_longdouble)NPY_NZEROF) + +/* + * Useful constants + */ +#define NPY_E 2.718281828459045235360287471352662498 /* e */ +#define NPY_LOG2E 1.442695040888963407359924681001892137 /* log_2 e */ +#define NPY_LOG10E 0.434294481903251827651128918916605082 /* log_10 e */ +#define NPY_LOGE2 0.693147180559945309417232121458176568 /* log_e 2 */ +#define NPY_LOGE10 2.302585092994045684017991454684364208 /* log_e 10 */ +#define NPY_PI 3.141592653589793238462643383279502884 /* pi */ +#define NPY_PI_2 1.570796326794896619231321691639751442 /* pi/2 */ +#define NPY_PI_4 0.785398163397448309615660845819875721 /* pi/4 */ +#define NPY_1_PI 0.318309886183790671537767526745028724 /* 1/pi */ +#define NPY_2_PI 0.636619772367581343075535053490057448 /* 2/pi */ +#define NPY_EULER 0.577215664901532860606512090082402431 /* Euler constant */ +#define NPY_SQRT2 1.414213562373095048801688724209698079 /* sqrt(2) */ +#define NPY_SQRT1_2 0.707106781186547524400844362104849039 /* 1/sqrt(2) */ + +#define NPY_Ef 2.718281828459045235360287471352662498F /* e */ +#define NPY_LOG2Ef 1.442695040888963407359924681001892137F /* log_2 e */ +#define NPY_LOG10Ef 0.434294481903251827651128918916605082F /* log_10 e */ +#define NPY_LOGE2f 0.693147180559945309417232121458176568F /* log_e 2 */ +#define NPY_LOGE10f 2.302585092994045684017991454684364208F /* log_e 10 */ +#define NPY_PIf 3.141592653589793238462643383279502884F /* pi */ +#define NPY_PI_2f 1.570796326794896619231321691639751442F /* pi/2 */ +#define NPY_PI_4f 0.785398163397448309615660845819875721F /* pi/4 */ +#define NPY_1_PIf 0.318309886183790671537767526745028724F /* 1/pi */ +#define NPY_2_PIf 0.636619772367581343075535053490057448F /* 2/pi */ +#define NPY_EULERf 0.577215664901532860606512090082402431F /* Euler constan*/ +#define NPY_SQRT2f 1.414213562373095048801688724209698079F /* sqrt(2) */ +#define NPY_SQRT1_2f 0.707106781186547524400844362104849039F /* 1/sqrt(2) */ + +#define NPY_El 2.718281828459045235360287471352662498L /* e */ +#define NPY_LOG2El 1.442695040888963407359924681001892137L /* log_2 e */ +#define NPY_LOG10El 0.434294481903251827651128918916605082L /* log_10 e */ +#define NPY_LOGE2l 0.693147180559945309417232121458176568L /* log_e 2 */ +#define NPY_LOGE10l 2.302585092994045684017991454684364208L /* log_e 10 */ +#define NPY_PIl 3.141592653589793238462643383279502884L /* pi */ +#define NPY_PI_2l 1.570796326794896619231321691639751442L /* pi/2 */ +#define NPY_PI_4l 0.785398163397448309615660845819875721L /* pi/4 */ +#define NPY_1_PIl 0.318309886183790671537767526745028724L /* 1/pi */ +#define NPY_2_PIl 0.636619772367581343075535053490057448L /* 2/pi */ +#define NPY_EULERl 0.577215664901532860606512090082402431L /* Euler constan*/ +#define NPY_SQRT2l 1.414213562373095048801688724209698079L /* sqrt(2) */ +#define NPY_SQRT1_2l 0.707106781186547524400844362104849039L /* 1/sqrt(2) */ + +/* + * C99 double math funcs + */ +double npy_sin(double x); +double npy_cos(double x); +double npy_tan(double x); +double npy_sinh(double x); +double npy_cosh(double x); +double npy_tanh(double x); + +double npy_asin(double x); +double npy_acos(double x); +double npy_atan(double x); +double npy_aexp(double x); +double npy_alog(double x); +double npy_asqrt(double x); +double npy_afabs(double x); + +double npy_log(double x); +double npy_log10(double x); +double npy_exp(double x); +double npy_sqrt(double x); + +double npy_fabs(double x); +double npy_ceil(double x); +double npy_fmod(double x, double y); +double npy_floor(double x); + +double npy_expm1(double x); +double npy_log1p(double x); +double npy_hypot(double x, double y); +double npy_acosh(double x); +double npy_asinh(double xx); +double npy_atanh(double x); +double npy_rint(double x); +double npy_trunc(double x); +double npy_exp2(double x); +double npy_log2(double x); + +double npy_atan2(double x, double y); +double npy_pow(double x, double y); +double npy_modf(double x, double* y); + +double npy_copysign(double x, double y); +double npy_nextafter(double x, double y); +double npy_spacing(double x); + +/* + * IEEE 754 fpu handling. Those are guaranteed to be macros + */ + +/* use builtins to avoid function calls in tight loops + * only available if npy_config.h is available (= numpys own build) */ +#if HAVE___BUILTIN_ISNAN + #define npy_isnan(x) __builtin_isnan(x) +#else + #ifndef NPY_HAVE_DECL_ISNAN + #define npy_isnan(x) ((x) != (x)) + #else + #ifdef _MSC_VER + #define npy_isnan(x) _isnan((x)) + #else + #define npy_isnan(x) isnan(x) + #endif + #endif +#endif + + +/* only available if npy_config.h is available (= numpys own build) */ +#if HAVE___BUILTIN_ISFINITE + #define npy_isfinite(x) __builtin_isfinite(x) +#else + #ifndef NPY_HAVE_DECL_ISFINITE + #ifdef _MSC_VER + #define npy_isfinite(x) _finite((x)) + #else + #define npy_isfinite(x) !npy_isnan((x) + (-x)) + #endif + #else + #define npy_isfinite(x) isfinite((x)) + #endif +#endif + +/* only available if npy_config.h is available (= numpys own build) */ +#if HAVE___BUILTIN_ISINF + #define npy_isinf(x) __builtin_isinf(x) +#else + #ifndef NPY_HAVE_DECL_ISINF + #define npy_isinf(x) (!npy_isfinite(x) && !npy_isnan(x)) + #else + #ifdef _MSC_VER + #define npy_isinf(x) (!_finite((x)) && !_isnan((x))) + #else + #define npy_isinf(x) isinf((x)) + #endif + #endif +#endif + +#ifndef NPY_HAVE_DECL_SIGNBIT + int _npy_signbit_f(float x); + int _npy_signbit_d(double x); + int _npy_signbit_ld(long double x); + #define npy_signbit(x) \ + (sizeof (x) == sizeof (long double) ? _npy_signbit_ld (x) \ + : sizeof (x) == sizeof (double) ? _npy_signbit_d (x) \ + : _npy_signbit_f (x)) +#else + #define npy_signbit(x) signbit((x)) +#endif + +/* + * float C99 math functions + */ + +float npy_sinf(float x); +float npy_cosf(float x); +float npy_tanf(float x); +float npy_sinhf(float x); +float npy_coshf(float x); +float npy_tanhf(float x); +float npy_fabsf(float x); +float npy_floorf(float x); +float npy_ceilf(float x); +float npy_rintf(float x); +float npy_truncf(float x); +float npy_sqrtf(float x); +float npy_log10f(float x); +float npy_logf(float x); +float npy_expf(float x); +float npy_expm1f(float x); +float npy_asinf(float x); +float npy_acosf(float x); +float npy_atanf(float x); +float npy_asinhf(float x); +float npy_acoshf(float x); +float npy_atanhf(float x); +float npy_log1pf(float x); +float npy_exp2f(float x); +float npy_log2f(float x); + +float npy_atan2f(float x, float y); +float npy_hypotf(float x, float y); +float npy_powf(float x, float y); +float npy_fmodf(float x, float y); + +float npy_modff(float x, float* y); + +float npy_copysignf(float x, float y); +float npy_nextafterf(float x, float y); +float npy_spacingf(float x); + +/* + * float C99 math functions + */ + +npy_longdouble npy_sinl(npy_longdouble x); +npy_longdouble npy_cosl(npy_longdouble x); +npy_longdouble npy_tanl(npy_longdouble x); +npy_longdouble npy_sinhl(npy_longdouble x); +npy_longdouble npy_coshl(npy_longdouble x); +npy_longdouble npy_tanhl(npy_longdouble x); +npy_longdouble npy_fabsl(npy_longdouble x); +npy_longdouble npy_floorl(npy_longdouble x); +npy_longdouble npy_ceill(npy_longdouble x); +npy_longdouble npy_rintl(npy_longdouble x); +npy_longdouble npy_truncl(npy_longdouble x); +npy_longdouble npy_sqrtl(npy_longdouble x); +npy_longdouble npy_log10l(npy_longdouble x); +npy_longdouble npy_logl(npy_longdouble x); +npy_longdouble npy_expl(npy_longdouble x); +npy_longdouble npy_expm1l(npy_longdouble x); +npy_longdouble npy_asinl(npy_longdouble x); +npy_longdouble npy_acosl(npy_longdouble x); +npy_longdouble npy_atanl(npy_longdouble x); +npy_longdouble npy_asinhl(npy_longdouble x); +npy_longdouble npy_acoshl(npy_longdouble x); +npy_longdouble npy_atanhl(npy_longdouble x); +npy_longdouble npy_log1pl(npy_longdouble x); +npy_longdouble npy_exp2l(npy_longdouble x); +npy_longdouble npy_log2l(npy_longdouble x); + +npy_longdouble npy_atan2l(npy_longdouble x, npy_longdouble y); +npy_longdouble npy_hypotl(npy_longdouble x, npy_longdouble y); +npy_longdouble npy_powl(npy_longdouble x, npy_longdouble y); +npy_longdouble npy_fmodl(npy_longdouble x, npy_longdouble y); + +npy_longdouble npy_modfl(npy_longdouble x, npy_longdouble* y); + +npy_longdouble npy_copysignl(npy_longdouble x, npy_longdouble y); +npy_longdouble npy_nextafterl(npy_longdouble x, npy_longdouble y); +npy_longdouble npy_spacingl(npy_longdouble x); + +/* + * Non standard functions + */ +double npy_deg2rad(double x); +double npy_rad2deg(double x); +double npy_logaddexp(double x, double y); +double npy_logaddexp2(double x, double y); + +float npy_deg2radf(float x); +float npy_rad2degf(float x); +float npy_logaddexpf(float x, float y); +float npy_logaddexp2f(float x, float y); + +npy_longdouble npy_deg2radl(npy_longdouble x); +npy_longdouble npy_rad2degl(npy_longdouble x); +npy_longdouble npy_logaddexpl(npy_longdouble x, npy_longdouble y); +npy_longdouble npy_logaddexp2l(npy_longdouble x, npy_longdouble y); + +#define npy_degrees npy_rad2deg +#define npy_degreesf npy_rad2degf +#define npy_degreesl npy_rad2degl + +#define npy_radians npy_deg2rad +#define npy_radiansf npy_deg2radf +#define npy_radiansl npy_deg2radl + +/* + * Complex declarations + */ + +/* + * C99 specifies that complex numbers have the same representation as + * an array of two elements, where the first element is the real part + * and the second element is the imaginary part. + */ +#define __NPY_CPACK_IMP(x, y, type, ctype) \ + union { \ + ctype z; \ + type a[2]; \ + } z1;; \ + \ + z1.a[0] = (x); \ + z1.a[1] = (y); \ + \ + return z1.z; + +static NPY_INLINE npy_cdouble npy_cpack(double x, double y) +{ + __NPY_CPACK_IMP(x, y, double, npy_cdouble); +} + +static NPY_INLINE npy_cfloat npy_cpackf(float x, float y) +{ + __NPY_CPACK_IMP(x, y, float, npy_cfloat); +} + +static NPY_INLINE npy_clongdouble npy_cpackl(npy_longdouble x, npy_longdouble y) +{ + __NPY_CPACK_IMP(x, y, npy_longdouble, npy_clongdouble); +} +#undef __NPY_CPACK_IMP + +/* + * Same remark as above, but in the other direction: extract first/second + * member of complex number, assuming a C99-compatible representation + * + * Those are defineds as static inline, and such as a reasonable compiler would + * most likely compile this to one or two instructions (on CISC at least) + */ +#define __NPY_CEXTRACT_IMP(z, index, type, ctype) \ + union { \ + ctype z; \ + type a[2]; \ + } __z_repr; \ + __z_repr.z = z; \ + \ + return __z_repr.a[index]; + +static NPY_INLINE double npy_creal(npy_cdouble z) +{ + __NPY_CEXTRACT_IMP(z, 0, double, npy_cdouble); +} + +static NPY_INLINE double npy_cimag(npy_cdouble z) +{ + __NPY_CEXTRACT_IMP(z, 1, double, npy_cdouble); +} + +static NPY_INLINE float npy_crealf(npy_cfloat z) +{ + __NPY_CEXTRACT_IMP(z, 0, float, npy_cfloat); +} + +static NPY_INLINE float npy_cimagf(npy_cfloat z) +{ + __NPY_CEXTRACT_IMP(z, 1, float, npy_cfloat); +} + +static NPY_INLINE npy_longdouble npy_creall(npy_clongdouble z) +{ + __NPY_CEXTRACT_IMP(z, 0, npy_longdouble, npy_clongdouble); +} + +static NPY_INLINE npy_longdouble npy_cimagl(npy_clongdouble z) +{ + __NPY_CEXTRACT_IMP(z, 1, npy_longdouble, npy_clongdouble); +} +#undef __NPY_CEXTRACT_IMP + +/* + * Double precision complex functions + */ +double npy_cabs(npy_cdouble z); +double npy_carg(npy_cdouble z); + +npy_cdouble npy_cexp(npy_cdouble z); +npy_cdouble npy_clog(npy_cdouble z); +npy_cdouble npy_cpow(npy_cdouble x, npy_cdouble y); + +npy_cdouble npy_csqrt(npy_cdouble z); + +npy_cdouble npy_ccos(npy_cdouble z); +npy_cdouble npy_csin(npy_cdouble z); + +/* + * Single precision complex functions + */ +float npy_cabsf(npy_cfloat z); +float npy_cargf(npy_cfloat z); + +npy_cfloat npy_cexpf(npy_cfloat z); +npy_cfloat npy_clogf(npy_cfloat z); +npy_cfloat npy_cpowf(npy_cfloat x, npy_cfloat y); + +npy_cfloat npy_csqrtf(npy_cfloat z); + +npy_cfloat npy_ccosf(npy_cfloat z); +npy_cfloat npy_csinf(npy_cfloat z); + +/* + * Extended precision complex functions + */ +npy_longdouble npy_cabsl(npy_clongdouble z); +npy_longdouble npy_cargl(npy_clongdouble z); + +npy_clongdouble npy_cexpl(npy_clongdouble z); +npy_clongdouble npy_clogl(npy_clongdouble z); +npy_clongdouble npy_cpowl(npy_clongdouble x, npy_clongdouble y); + +npy_clongdouble npy_csqrtl(npy_clongdouble z); + +npy_clongdouble npy_ccosl(npy_clongdouble z); +npy_clongdouble npy_csinl(npy_clongdouble z); + +/* + * Functions that set the floating point error + * status word. + */ + +void npy_set_floatstatus_divbyzero(void); +void npy_set_floatstatus_overflow(void); +void npy_set_floatstatus_underflow(void); +void npy_set_floatstatus_invalid(void); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h new file mode 100644 index 000000000..6183dc278 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h @@ -0,0 +1,19 @@ +/* + * This include file is provided for inclusion in Cython *.pyd files where + * one would like to define the NPY_NO_DEPRECATED_API macro. It can be + * included by + * + * cdef extern from "npy_no_deprecated_api.h": pass + * + */ +#ifndef NPY_NO_DEPRECATED_API + +/* put this check here since there may be multiple includes in C extensions. */ +#if defined(NDARRAYTYPES_H) || defined(_NPY_DEPRECATED_API_H) || \ + defined(OLD_DEFINES_H) +#error "npy_no_deprecated_api.h" must be first among numpy includes. +#else +#define NPY_NO_DEPRECATED_API NPY_API_VERSION +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h new file mode 100644 index 000000000..9228c3916 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h @@ -0,0 +1,30 @@ +#ifndef _NPY_OS_H_ +#define _NPY_OS_H_ + +#if defined(linux) || defined(__linux) || defined(__linux__) + #define NPY_OS_LINUX +#elif defined(__FreeBSD__) || defined(__NetBSD__) || \ + defined(__OpenBSD__) || defined(__DragonFly__) + #define NPY_OS_BSD + #ifdef __FreeBSD__ + #define NPY_OS_FREEBSD + #elif defined(__NetBSD__) + #define NPY_OS_NETBSD + #elif defined(__OpenBSD__) + #define NPY_OS_OPENBSD + #elif defined(__DragonFly__) + #define NPY_OS_DRAGONFLY + #endif +#elif defined(sun) || defined(__sun) + #define NPY_OS_SOLARIS +#elif defined(__CYGWIN__) + #define NPY_OS_CYGWIN +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) + #define NPY_OS_WIN32 +#elif defined(__APPLE__) + #define NPY_OS_DARWIN +#else + #define NPY_OS_UNKNOWN +#endif + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h b/gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h new file mode 100644 index 000000000..5ca171f21 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h @@ -0,0 +1,34 @@ +#ifndef _NPY_NUMPYCONFIG_H_ +#define _NPY_NUMPYCONFIG_H_ + +#include "_numpyconfig.h" + +/* + * On Mac OS X, because there is only one configuration stage for all the archs + * in universal builds, any macro which depends on the arch needs to be + * harcoded + */ +#ifdef __APPLE__ + #undef NPY_SIZEOF_LONG + #undef NPY_SIZEOF_PY_INTPTR_T + + #ifdef __LP64__ + #define NPY_SIZEOF_LONG 8 + #define NPY_SIZEOF_PY_INTPTR_T 8 + #else + #define NPY_SIZEOF_LONG 4 + #define NPY_SIZEOF_PY_INTPTR_T 4 + #endif +#endif + +/** + * To help with the NPY_NO_DEPRECATED_API macro, we include API version + * numbers for specific versions of NumPy. To exclude all API that was + * deprecated as of 1.7, add the following before #including any NumPy + * headers: + * #define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION + */ +#define NPY_1_7_API_VERSION 0x00000007 +#define NPY_1_8_API_VERSION 0x00000008 + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h b/gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h new file mode 100644 index 000000000..abf81595a --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h @@ -0,0 +1,187 @@ +/* This header is deprecated as of NumPy 1.7 */ +#ifndef OLD_DEFINES_H +#define OLD_DEFINES_H + +#if defined(NPY_NO_DEPRECATED_API) && NPY_NO_DEPRECATED_API >= NPY_1_7_API_VERSION +#error The header "old_defines.h" is deprecated as of NumPy 1.7. +#endif + +#define NDARRAY_VERSION NPY_VERSION + +#define PyArray_MIN_BUFSIZE NPY_MIN_BUFSIZE +#define PyArray_MAX_BUFSIZE NPY_MAX_BUFSIZE +#define PyArray_BUFSIZE NPY_BUFSIZE + +#define PyArray_PRIORITY NPY_PRIORITY +#define PyArray_SUBTYPE_PRIORITY NPY_PRIORITY +#define PyArray_NUM_FLOATTYPE NPY_NUM_FLOATTYPE + +#define NPY_MAX PyArray_MAX +#define NPY_MIN PyArray_MIN + +#define PyArray_TYPES NPY_TYPES +#define PyArray_BOOL NPY_BOOL +#define PyArray_BYTE NPY_BYTE +#define PyArray_UBYTE NPY_UBYTE +#define PyArray_SHORT NPY_SHORT +#define PyArray_USHORT NPY_USHORT +#define PyArray_INT NPY_INT +#define PyArray_UINT NPY_UINT +#define PyArray_LONG NPY_LONG +#define PyArray_ULONG NPY_ULONG +#define PyArray_LONGLONG NPY_LONGLONG +#define PyArray_ULONGLONG NPY_ULONGLONG +#define PyArray_HALF NPY_HALF +#define PyArray_FLOAT NPY_FLOAT +#define PyArray_DOUBLE NPY_DOUBLE +#define PyArray_LONGDOUBLE NPY_LONGDOUBLE +#define PyArray_CFLOAT NPY_CFLOAT +#define PyArray_CDOUBLE NPY_CDOUBLE +#define PyArray_CLONGDOUBLE NPY_CLONGDOUBLE +#define PyArray_OBJECT NPY_OBJECT +#define PyArray_STRING NPY_STRING +#define PyArray_UNICODE NPY_UNICODE +#define PyArray_VOID NPY_VOID +#define PyArray_DATETIME NPY_DATETIME +#define PyArray_TIMEDELTA NPY_TIMEDELTA +#define PyArray_NTYPES NPY_NTYPES +#define PyArray_NOTYPE NPY_NOTYPE +#define PyArray_CHAR NPY_CHAR +#define PyArray_USERDEF NPY_USERDEF +#define PyArray_NUMUSERTYPES NPY_NUMUSERTYPES + +#define PyArray_INTP NPY_INTP +#define PyArray_UINTP NPY_UINTP + +#define PyArray_INT8 NPY_INT8 +#define PyArray_UINT8 NPY_UINT8 +#define PyArray_INT16 NPY_INT16 +#define PyArray_UINT16 NPY_UINT16 +#define PyArray_INT32 NPY_INT32 +#define PyArray_UINT32 NPY_UINT32 + +#ifdef NPY_INT64 +#define PyArray_INT64 NPY_INT64 +#define PyArray_UINT64 NPY_UINT64 +#endif + +#ifdef NPY_INT128 +#define PyArray_INT128 NPY_INT128 +#define PyArray_UINT128 NPY_UINT128 +#endif + +#ifdef NPY_FLOAT16 +#define PyArray_FLOAT16 NPY_FLOAT16 +#define PyArray_COMPLEX32 NPY_COMPLEX32 +#endif + +#ifdef NPY_FLOAT80 +#define PyArray_FLOAT80 NPY_FLOAT80 +#define PyArray_COMPLEX160 NPY_COMPLEX160 +#endif + +#ifdef NPY_FLOAT96 +#define PyArray_FLOAT96 NPY_FLOAT96 +#define PyArray_COMPLEX192 NPY_COMPLEX192 +#endif + +#ifdef NPY_FLOAT128 +#define PyArray_FLOAT128 NPY_FLOAT128 +#define PyArray_COMPLEX256 NPY_COMPLEX256 +#endif + +#define PyArray_FLOAT32 NPY_FLOAT32 +#define PyArray_COMPLEX64 NPY_COMPLEX64 +#define PyArray_FLOAT64 NPY_FLOAT64 +#define PyArray_COMPLEX128 NPY_COMPLEX128 + + +#define PyArray_TYPECHAR NPY_TYPECHAR +#define PyArray_BOOLLTR NPY_BOOLLTR +#define PyArray_BYTELTR NPY_BYTELTR +#define PyArray_UBYTELTR NPY_UBYTELTR +#define PyArray_SHORTLTR NPY_SHORTLTR +#define PyArray_USHORTLTR NPY_USHORTLTR +#define PyArray_INTLTR NPY_INTLTR +#define PyArray_UINTLTR NPY_UINTLTR +#define PyArray_LONGLTR NPY_LONGLTR +#define PyArray_ULONGLTR NPY_ULONGLTR +#define PyArray_LONGLONGLTR NPY_LONGLONGLTR +#define PyArray_ULONGLONGLTR NPY_ULONGLONGLTR +#define PyArray_HALFLTR NPY_HALFLTR +#define PyArray_FLOATLTR NPY_FLOATLTR +#define PyArray_DOUBLELTR NPY_DOUBLELTR +#define PyArray_LONGDOUBLELTR NPY_LONGDOUBLELTR +#define PyArray_CFLOATLTR NPY_CFLOATLTR +#define PyArray_CDOUBLELTR NPY_CDOUBLELTR +#define PyArray_CLONGDOUBLELTR NPY_CLONGDOUBLELTR +#define PyArray_OBJECTLTR NPY_OBJECTLTR +#define PyArray_STRINGLTR NPY_STRINGLTR +#define PyArray_STRINGLTR2 NPY_STRINGLTR2 +#define PyArray_UNICODELTR NPY_UNICODELTR +#define PyArray_VOIDLTR NPY_VOIDLTR +#define PyArray_DATETIMELTR NPY_DATETIMELTR +#define PyArray_TIMEDELTALTR NPY_TIMEDELTALTR +#define PyArray_CHARLTR NPY_CHARLTR +#define PyArray_INTPLTR NPY_INTPLTR +#define PyArray_UINTPLTR NPY_UINTPLTR +#define PyArray_GENBOOLLTR NPY_GENBOOLLTR +#define PyArray_SIGNEDLTR NPY_SIGNEDLTR +#define PyArray_UNSIGNEDLTR NPY_UNSIGNEDLTR +#define PyArray_FLOATINGLTR NPY_FLOATINGLTR +#define PyArray_COMPLEXLTR NPY_COMPLEXLTR + +#define PyArray_QUICKSORT NPY_QUICKSORT +#define PyArray_HEAPSORT NPY_HEAPSORT +#define PyArray_MERGESORT NPY_MERGESORT +#define PyArray_SORTKIND NPY_SORTKIND +#define PyArray_NSORTS NPY_NSORTS + +#define PyArray_NOSCALAR NPY_NOSCALAR +#define PyArray_BOOL_SCALAR NPY_BOOL_SCALAR +#define PyArray_INTPOS_SCALAR NPY_INTPOS_SCALAR +#define PyArray_INTNEG_SCALAR NPY_INTNEG_SCALAR +#define PyArray_FLOAT_SCALAR NPY_FLOAT_SCALAR +#define PyArray_COMPLEX_SCALAR NPY_COMPLEX_SCALAR +#define PyArray_OBJECT_SCALAR NPY_OBJECT_SCALAR +#define PyArray_SCALARKIND NPY_SCALARKIND +#define PyArray_NSCALARKINDS NPY_NSCALARKINDS + +#define PyArray_ANYORDER NPY_ANYORDER +#define PyArray_CORDER NPY_CORDER +#define PyArray_FORTRANORDER NPY_FORTRANORDER +#define PyArray_ORDER NPY_ORDER + +#define PyDescr_ISBOOL PyDataType_ISBOOL +#define PyDescr_ISUNSIGNED PyDataType_ISUNSIGNED +#define PyDescr_ISSIGNED PyDataType_ISSIGNED +#define PyDescr_ISINTEGER PyDataType_ISINTEGER +#define PyDescr_ISFLOAT PyDataType_ISFLOAT +#define PyDescr_ISNUMBER PyDataType_ISNUMBER +#define PyDescr_ISSTRING PyDataType_ISSTRING +#define PyDescr_ISCOMPLEX PyDataType_ISCOMPLEX +#define PyDescr_ISPYTHON PyDataType_ISPYTHON +#define PyDescr_ISFLEXIBLE PyDataType_ISFLEXIBLE +#define PyDescr_ISUSERDEF PyDataType_ISUSERDEF +#define PyDescr_ISEXTENDED PyDataType_ISEXTENDED +#define PyDescr_ISOBJECT PyDataType_ISOBJECT +#define PyDescr_HASFIELDS PyDataType_HASFIELDS + +#define PyArray_LITTLE NPY_LITTLE +#define PyArray_BIG NPY_BIG +#define PyArray_NATIVE NPY_NATIVE +#define PyArray_SWAP NPY_SWAP +#define PyArray_IGNORE NPY_IGNORE + +#define PyArray_NATBYTE NPY_NATBYTE +#define PyArray_OPPBYTE NPY_OPPBYTE + +#define PyArray_MAX_ELSIZE NPY_MAX_ELSIZE + +#define PyArray_USE_PYMEM NPY_USE_PYMEM + +#define PyArray_RemoveLargest PyArray_RemoveSmallest + +#define PyArray_UCS4 npy_ucs4 + +#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h b/gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h new file mode 100644 index 000000000..748f06da3 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h @@ -0,0 +1,23 @@ +#include "arrayobject.h" + +#ifndef REFCOUNT +# define REFCOUNT NPY_REFCOUNT +# define MAX_ELSIZE 16 +#endif + +#define PyArray_UNSIGNED_TYPES +#define PyArray_SBYTE NPY_BYTE +#define PyArray_CopyArray PyArray_CopyInto +#define _PyArray_multiply_list PyArray_MultiplyIntList +#define PyArray_ISSPACESAVER(m) NPY_FALSE +#define PyScalarArray_Check PyArray_CheckScalar + +#define CONTIGUOUS NPY_CONTIGUOUS +#define OWN_DIMENSIONS 0 +#define OWN_STRIDES 0 +#define OWN_DATA NPY_OWNDATA +#define SAVESPACE 0 +#define SAVESPACEBIT 0 + +#undef import_array +#define import_array() { if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); } } diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt b/gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt new file mode 100644 index 000000000..a90865d2f --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt @@ -0,0 +1,321 @@ + +================= +Numpy Ufunc C-API +================= +:: + + PyObject * + PyUFunc_FromFuncAndData(PyUFuncGenericFunction *func, void + **data, char *types, int ntypes, int nin, int + nout, int identity, char *name, char *doc, int + check_return) + + +:: + + int + PyUFunc_RegisterLoopForType(PyUFuncObject *ufunc, int + usertype, PyUFuncGenericFunction + function, int *arg_types, void *data) + + +:: + + int + PyUFunc_GenericFunction(PyUFuncObject *ufunc, PyObject *args, PyObject + *kwds, PyArrayObject **op) + + +This generic function is called with the ufunc object, the arguments to it, +and an array of (pointers to) PyArrayObjects which are NULL. + +'op' is an array of at least NPY_MAXARGS PyArrayObject *. + +:: + + void + PyUFunc_f_f_As_d_d(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_d_d(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_f_f(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_g_g(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_F_F_As_D_D(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_F_F(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_D_D(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_G_G(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_O_O(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_ff_f_As_dd_d(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_ff_f(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_dd_d(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_gg_g(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_FF_F_As_DD_D(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_DD_D(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_FF_F(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_GG_G(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_OO_O(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_O_O_method(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_OO_O_method(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_On_Om(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + int + PyUFunc_GetPyValues(char *name, int *bufsize, int *errmask, PyObject + **errobj) + + +On return, if errobj is populated with a non-NULL value, the caller +owns a new reference to errobj. + +:: + + int + PyUFunc_checkfperr(int errmask, PyObject *errobj, int *first) + + +:: + + void + PyUFunc_clearfperr() + + +:: + + int + PyUFunc_getfperr(void ) + + +:: + + int + PyUFunc_handlefperr(int errmask, PyObject *errobj, int retstatus, int + *first) + + +:: + + int + PyUFunc_ReplaceLoopBySignature(PyUFuncObject + *func, PyUFuncGenericFunction + newfunc, int + *signature, PyUFuncGenericFunction + *oldfunc) + + +:: + + PyObject * + PyUFunc_FromFuncAndDataAndSignature(PyUFuncGenericFunction *func, void + **data, char *types, int + ntypes, int nin, int nout, int + identity, char *name, char + *doc, int check_return, const char + *signature) + + +:: + + int + PyUFunc_SetUsesArraysAsData(void **data, size_t i) + + +:: + + void + PyUFunc_e_e(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_e_e_As_f_f(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_e_e_As_d_d(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_ee_e(char **args, npy_intp *dimensions, npy_intp *steps, void + *func) + + +:: + + void + PyUFunc_ee_e_As_ff_f(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + void + PyUFunc_ee_e_As_dd_d(char **args, npy_intp *dimensions, npy_intp + *steps, void *func) + + +:: + + int + PyUFunc_DefaultTypeResolver(PyUFuncObject *ufunc, NPY_CASTING + casting, PyArrayObject + **operands, PyObject + *type_tup, PyArray_Descr **out_dtypes) + + +This function applies the default type resolution rules +for the provided ufunc. + +Returns 0 on success, -1 on error. + +:: + + int + PyUFunc_ValidateCasting(PyUFuncObject *ufunc, NPY_CASTING + casting, PyArrayObject + **operands, PyArray_Descr **dtypes) + + +Validates that the input operands can be cast to +the input types, and the output types can be cast to +the output operands where provided. + +Returns 0 on success, -1 (with exception raised) on validation failure. + +:: + + int + PyUFunc_RegisterLoopForDescr(PyUFuncObject *ufunc, PyArray_Descr + *user_dtype, PyUFuncGenericFunction + function, PyArray_Descr + **arg_dtypes, void *data) + + diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h b/gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h new file mode 100644 index 000000000..423fbc279 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h @@ -0,0 +1,479 @@ +#ifndef Py_UFUNCOBJECT_H +#define Py_UFUNCOBJECT_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * The legacy generic inner loop for a standard element-wise or + * generalized ufunc. + */ +typedef void (*PyUFuncGenericFunction) + (char **args, + npy_intp *dimensions, + npy_intp *strides, + void *innerloopdata); + +/* + * The most generic one-dimensional inner loop for + * a standard element-wise ufunc. This typedef is also + * more consistent with the other NumPy function pointer typedefs + * than PyUFuncGenericFunction. + */ +typedef void (PyUFunc_StridedInnerLoopFunc)( + char **dataptrs, npy_intp *strides, + npy_intp count, + NpyAuxData *innerloopdata); + +/* + * The most generic one-dimensional inner loop for + * a masked standard element-wise ufunc. "Masked" here means that it skips + * doing calculations on any items for which the maskptr array has a true + * value. + */ +typedef void (PyUFunc_MaskedStridedInnerLoopFunc)( + char **dataptrs, npy_intp *strides, + char *maskptr, npy_intp mask_stride, + npy_intp count, + NpyAuxData *innerloopdata); + +/* Forward declaration for the type resolver and loop selector typedefs */ +struct _tagPyUFuncObject; + +/* + * Given the operands for calling a ufunc, should determine the + * calculation input and output data types and return an inner loop function. + * This function should validate that the casting rule is being followed, + * and fail if it is not. + * + * For backwards compatibility, the regular type resolution function does not + * support auxiliary data with object semantics. The type resolution call + * which returns a masked generic function returns a standard NpyAuxData + * object, for which the NPY_AUXDATA_FREE and NPY_AUXDATA_CLONE macros + * work. + * + * ufunc: The ufunc object. + * casting: The 'casting' parameter provided to the ufunc. + * operands: An array of length (ufunc->nin + ufunc->nout), + * with the output parameters possibly NULL. + * type_tup: Either NULL, or the type_tup passed to the ufunc. + * out_dtypes: An array which should be populated with new + * references to (ufunc->nin + ufunc->nout) new + * dtypes, one for each input and output. These + * dtypes should all be in native-endian format. + * + * Should return 0 on success, -1 on failure (with exception set), + * or -2 if Py_NotImplemented should be returned. + */ +typedef int (PyUFunc_TypeResolutionFunc)( + struct _tagPyUFuncObject *ufunc, + NPY_CASTING casting, + PyArrayObject **operands, + PyObject *type_tup, + PyArray_Descr **out_dtypes); + +/* + * Given an array of DTypes as returned by the PyUFunc_TypeResolutionFunc, + * and an array of fixed strides (the array will contain NPY_MAX_INTP for + * strides which are not necessarily fixed), returns an inner loop + * with associated auxiliary data. + * + * For backwards compatibility, there is a variant of the inner loop + * selection which returns an inner loop irrespective of the strides, + * and with a void* static auxiliary data instead of an NpyAuxData * + * dynamically allocatable auxiliary data. + * + * ufunc: The ufunc object. + * dtypes: An array which has been populated with dtypes, + * in most cases by the type resolution funciton + * for the same ufunc. + * fixed_strides: For each input/output, either the stride that + * will be used every time the function is called + * or NPY_MAX_INTP if the stride might change or + * is not known ahead of time. The loop selection + * function may use this stride to pick inner loops + * which are optimized for contiguous or 0-stride + * cases. + * out_innerloop: Should be populated with the correct ufunc inner + * loop for the given type. + * out_innerloopdata: Should be populated with the void* data to + * be passed into the out_innerloop function. + * out_needs_api: If the inner loop needs to use the Python API, + * should set the to 1, otherwise should leave + * this untouched. + */ +typedef int (PyUFunc_LegacyInnerLoopSelectionFunc)( + struct _tagPyUFuncObject *ufunc, + PyArray_Descr **dtypes, + PyUFuncGenericFunction *out_innerloop, + void **out_innerloopdata, + int *out_needs_api); +typedef int (PyUFunc_InnerLoopSelectionFunc)( + struct _tagPyUFuncObject *ufunc, + PyArray_Descr **dtypes, + npy_intp *fixed_strides, + PyUFunc_StridedInnerLoopFunc **out_innerloop, + NpyAuxData **out_innerloopdata, + int *out_needs_api); +typedef int (PyUFunc_MaskedInnerLoopSelectionFunc)( + struct _tagPyUFuncObject *ufunc, + PyArray_Descr **dtypes, + PyArray_Descr *mask_dtype, + npy_intp *fixed_strides, + npy_intp fixed_mask_stride, + PyUFunc_MaskedStridedInnerLoopFunc **out_innerloop, + NpyAuxData **out_innerloopdata, + int *out_needs_api); + +typedef struct _tagPyUFuncObject { + PyObject_HEAD + /* + * nin: Number of inputs + * nout: Number of outputs + * nargs: Always nin + nout (Why is it stored?) + */ + int nin, nout, nargs; + + /* Identity for reduction, either PyUFunc_One or PyUFunc_Zero */ + int identity; + + /* Array of one-dimensional core loops */ + PyUFuncGenericFunction *functions; + /* Array of funcdata that gets passed into the functions */ + void **data; + /* The number of elements in 'functions' and 'data' */ + int ntypes; + + /* Does not appear to be used */ + int check_return; + + /* The name of the ufunc */ + char *name; + + /* Array of type numbers, of size ('nargs' * 'ntypes') */ + char *types; + + /* Documentation string */ + char *doc; + + void *ptr; + PyObject *obj; + PyObject *userloops; + + /* generalized ufunc parameters */ + + /* 0 for scalar ufunc; 1 for generalized ufunc */ + int core_enabled; + /* number of distinct dimension names in signature */ + int core_num_dim_ix; + + /* + * dimension indices of input/output argument k are stored in + * core_dim_ixs[core_offsets[k]..core_offsets[k]+core_num_dims[k]-1] + */ + + /* numbers of core dimensions of each argument */ + int *core_num_dims; + /* + * dimension indices in a flatted form; indices + * are in the range of [0,core_num_dim_ix) + */ + int *core_dim_ixs; + /* + * positions of 1st core dimensions of each + * argument in core_dim_ixs + */ + int *core_offsets; + /* signature string for printing purpose */ + char *core_signature; + + /* + * A function which resolves the types and fills an array + * with the dtypes for the inputs and outputs. + */ + PyUFunc_TypeResolutionFunc *type_resolver; + /* + * A function which returns an inner loop written for + * NumPy 1.6 and earlier ufuncs. This is for backwards + * compatibility, and may be NULL if inner_loop_selector + * is specified. + */ + PyUFunc_LegacyInnerLoopSelectionFunc *legacy_inner_loop_selector; + /* + * A function which returns an inner loop for the new mechanism + * in NumPy 1.7 and later. If provided, this is used, otherwise + * if NULL the legacy_inner_loop_selector is used instead. + */ + PyUFunc_InnerLoopSelectionFunc *inner_loop_selector; + /* + * A function which returns a masked inner loop for the ufunc. + */ + PyUFunc_MaskedInnerLoopSelectionFunc *masked_inner_loop_selector; + + /* + * List of flags for each operand when ufunc is called by nditer object. + * These flags will be used in addition to the default flags for each + * operand set by nditer object. + */ + npy_uint32 *op_flags; + + /* + * List of global flags used when ufunc is called by nditer object. + * These flags will be used in addition to the default global flags + * set by nditer object. + */ + npy_uint32 iter_flags; +} PyUFuncObject; + +#include "arrayobject.h" + +#define UFUNC_ERR_IGNORE 0 +#define UFUNC_ERR_WARN 1 +#define UFUNC_ERR_RAISE 2 +#define UFUNC_ERR_CALL 3 +#define UFUNC_ERR_PRINT 4 +#define UFUNC_ERR_LOG 5 + + /* Python side integer mask */ + +#define UFUNC_MASK_DIVIDEBYZERO 0x07 +#define UFUNC_MASK_OVERFLOW 0x3f +#define UFUNC_MASK_UNDERFLOW 0x1ff +#define UFUNC_MASK_INVALID 0xfff + +#define UFUNC_SHIFT_DIVIDEBYZERO 0 +#define UFUNC_SHIFT_OVERFLOW 3 +#define UFUNC_SHIFT_UNDERFLOW 6 +#define UFUNC_SHIFT_INVALID 9 + + +/* platform-dependent code translates floating point + status to an integer sum of these values +*/ +#define UFUNC_FPE_DIVIDEBYZERO 1 +#define UFUNC_FPE_OVERFLOW 2 +#define UFUNC_FPE_UNDERFLOW 4 +#define UFUNC_FPE_INVALID 8 + +/* Error mode that avoids look-up (no checking) */ +#define UFUNC_ERR_DEFAULT 0 + +#define UFUNC_OBJ_ISOBJECT 1 +#define UFUNC_OBJ_NEEDS_API 2 + + /* Default user error mode */ +#define UFUNC_ERR_DEFAULT2 \ + (UFUNC_ERR_WARN << UFUNC_SHIFT_DIVIDEBYZERO) + \ + (UFUNC_ERR_WARN << UFUNC_SHIFT_OVERFLOW) + \ + (UFUNC_ERR_WARN << UFUNC_SHIFT_INVALID) + +#if NPY_ALLOW_THREADS +#define NPY_LOOP_BEGIN_THREADS do {if (!(loop->obj & UFUNC_OBJ_NEEDS_API)) _save = PyEval_SaveThread();} while (0); +#define NPY_LOOP_END_THREADS do {if (!(loop->obj & UFUNC_OBJ_NEEDS_API)) PyEval_RestoreThread(_save);} while (0); +#else +#define NPY_LOOP_BEGIN_THREADS +#define NPY_LOOP_END_THREADS +#endif + +/* + * UFunc has unit of 1, and the order of operations can be reordered + * This case allows reduction with multiple axes at once. + */ +#define PyUFunc_One 1 +/* + * UFunc has unit of 0, and the order of operations can be reordered + * This case allows reduction with multiple axes at once. + */ +#define PyUFunc_Zero 0 +/* + * UFunc has no unit, and the order of operations cannot be reordered. + * This case does not allow reduction with multiple axes at once. + */ +#define PyUFunc_None -1 +/* + * UFunc has no unit, and the order of operations can be reordered + * This case allows reduction with multiple axes at once. + */ +#define PyUFunc_ReorderableNone -2 + +#define UFUNC_REDUCE 0 +#define UFUNC_ACCUMULATE 1 +#define UFUNC_REDUCEAT 2 +#define UFUNC_OUTER 3 + + +typedef struct { + int nin; + int nout; + PyObject *callable; +} PyUFunc_PyFuncData; + +/* A linked-list of function information for + user-defined 1-d loops. + */ +typedef struct _loop1d_info { + PyUFuncGenericFunction func; + void *data; + int *arg_types; + struct _loop1d_info *next; + int nargs; + PyArray_Descr **arg_dtypes; +} PyUFunc_Loop1d; + + +#include "__ufunc_api.h" + +#define UFUNC_PYVALS_NAME "UFUNC_PYVALS" + +#define UFUNC_CHECK_ERROR(arg) \ + do {if ((((arg)->obj & UFUNC_OBJ_NEEDS_API) && PyErr_Occurred()) || \ + ((arg)->errormask && \ + PyUFunc_checkfperr((arg)->errormask, \ + (arg)->errobj, \ + &(arg)->first))) \ + goto fail;} while (0) + +/* This code checks the IEEE status flags in a platform-dependent way */ +/* Adapted from Numarray */ + +#if (defined(__unix__) || defined(unix)) && !defined(USG) +#include +#endif + +/* OSF/Alpha (Tru64) ---------------------------------------------*/ +#if defined(__osf__) && defined(__alpha) + +#include + +#define UFUNC_CHECK_STATUS(ret) { \ + unsigned long fpstatus; \ + \ + fpstatus = ieee_get_fp_control(); \ + /* clear status bits as well as disable exception mode if on */ \ + ieee_set_fp_control( 0 ); \ + ret = ((IEEE_STATUS_DZE & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ + | ((IEEE_STATUS_OVF & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ + | ((IEEE_STATUS_UNF & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ + | ((IEEE_STATUS_INV & fpstatus) ? UFUNC_FPE_INVALID : 0); \ + } + +/* MS Windows -----------------------------------------------------*/ +#elif defined(_MSC_VER) + +#include + +/* Clear the floating point exception default of Borland C++ */ +#if defined(__BORLANDC__) +#define UFUNC_NOFPE _control87(MCW_EM, MCW_EM); +#endif + +#if defined(_WIN64) +#define UFUNC_CHECK_STATUS(ret) { \ + int fpstatus = (int) _clearfp(); \ + \ + ret = ((SW_ZERODIVIDE & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ + | ((SW_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ + | ((SW_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ + | ((SW_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ + } +#else +/* windows enables sse on 32 bit, so check both flags */ +#define UFUNC_CHECK_STATUS(ret) { \ + int fpstatus, fpstatus2; \ + _statusfp2(&fpstatus, &fpstatus2); \ + _clearfp(); \ + fpstatus |= fpstatus2; \ + \ + ret = ((SW_ZERODIVIDE & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ + | ((SW_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ + | ((SW_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ + | ((SW_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ + } +#endif + +/* Solaris --------------------------------------------------------*/ +/* --------ignoring SunOS ieee_flags approach, someone else can +** deal with that! */ +#elif defined(sun) || defined(__BSD__) || defined(__OpenBSD__) || \ + (defined(__FreeBSD__) && (__FreeBSD_version < 502114)) || \ + defined(__NetBSD__) +#include + +#define UFUNC_CHECK_STATUS(ret) { \ + int fpstatus; \ + \ + fpstatus = (int) fpgetsticky(); \ + ret = ((FP_X_DZ & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ + | ((FP_X_OFL & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ + | ((FP_X_UFL & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ + | ((FP_X_INV & fpstatus) ? UFUNC_FPE_INVALID : 0); \ + (void) fpsetsticky(0); \ + } + +#elif defined(__GLIBC__) || defined(__APPLE__) || \ + defined(__CYGWIN__) || defined(__MINGW32__) || \ + (defined(__FreeBSD__) && (__FreeBSD_version >= 502114)) + +#if defined(__GLIBC__) || defined(__APPLE__) || \ + defined(__MINGW32__) || defined(__FreeBSD__) +#include +#elif defined(__CYGWIN__) +#include "numpy/fenv/fenv.h" +#endif + +#define UFUNC_CHECK_STATUS(ret) { \ + int fpstatus = (int) fetestexcept(FE_DIVBYZERO | FE_OVERFLOW | \ + FE_UNDERFLOW | FE_INVALID); \ + ret = ((FE_DIVBYZERO & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ + | ((FE_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ + | ((FE_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ + | ((FE_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ + (void) feclearexcept(FE_DIVBYZERO | FE_OVERFLOW | \ + FE_UNDERFLOW | FE_INVALID); \ +} + +#elif defined(_AIX) + +#include +#include + +#define UFUNC_CHECK_STATUS(ret) { \ + fpflag_t fpstatus; \ + \ + fpstatus = fp_read_flag(); \ + ret = ((FP_DIV_BY_ZERO & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ + | ((FP_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ + | ((FP_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ + | ((FP_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ + fp_swap_flag(0); \ +} + +#else + +#define NO_FLOATING_POINT_SUPPORT +#define UFUNC_CHECK_STATUS(ret) { \ + ret = 0; \ + } + +#endif + +/* + * THESE MACROS ARE DEPRECATED. + * Use npy_set_floatstatus_* in the npymath library. + */ +#define generate_divbyzero_error() npy_set_floatstatus_divbyzero() +#define generate_overflow_error() npy_set_floatstatus_overflow() + + /* Make sure it gets defined if it isn't already */ +#ifndef UFUNC_NOFPE +#define UFUNC_NOFPE +#endif + + +#ifdef __cplusplus +} +#endif +#endif /* !Py_UFUNCOBJECT_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/utils.h b/gtsam/3rdparty/numpy_c_api/include/numpy/utils.h new file mode 100644 index 000000000..cc968a354 --- /dev/null +++ b/gtsam/3rdparty/numpy_c_api/include/numpy/utils.h @@ -0,0 +1,19 @@ +#ifndef __NUMPY_UTILS_HEADER__ +#define __NUMPY_UTILS_HEADER__ + +#ifndef __COMP_NPY_UNUSED + #if defined(__GNUC__) + #define __COMP_NPY_UNUSED __attribute__ ((__unused__)) + # elif defined(__ICC) + #define __COMP_NPY_UNUSED __attribute__ ((__unused__)) + #else + #define __COMP_NPY_UNUSED + #endif +#endif + +/* Use this to tag a variable as not used. It will remove unused variable + * warning on support platforms (see __COM_NPY_UNUSED) and mangle the variable + * to avoid accidental use */ +#define NPY_UNUSED(x) (__NPY_UNUSED_TAGGED ## x) __COMP_NPY_UNUSED + +#endif diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 0e1a5f0dd..9c0ba1df8 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,3 +1,5 @@ +option(GTSAM_USE_SYSTEM_NUMPY_C_API "Find and use system-installed NumPy C-API. If 'off', use the one bundled with GTSAM" OFF) + # Guard to avoid breaking this code in ccmake if by accident GTSAM_PYTHON_VERSION is set to an empty string if(GTSAM_PYTHON_VERSION STREQUAL "") set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "Target python version for GTSAM python module. Use 'Default' to chose the default version" FORCE) @@ -29,7 +31,12 @@ else() endif() # Find NumPy C-API -find_package(NumPy) +if(GTSAM_USE_SYSTEM_NUMPY_C_API) + find_package(NumPy) + include_directories(${NUMPY_INCLUDE_DIRS}) +else() + include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_c_api/include/) +endif() # Find Python # First, be sure that python version can be found by FindPythonLibs.cmake @@ -47,7 +54,7 @@ endif() find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_STRING}) # Add handwritten directory if we found python and boost python -if(Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND AND PYTHONLIBS_FOUND AND NUMPY_FOUND) +if(Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND AND PYTHONLIBS_FOUND) include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) @@ -73,7 +80,3 @@ if(NOT Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND) message(WARNING "Boost Python for python ${GTSAM_PYTHON_VERSION} was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") endif() endif() - -if(NOT NUMPY_FOUND) - message(WARNING "NumPy C-API was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") -endif() \ No newline at end of file From dfc15a2f1705944a9aa693c8a019f58349dc3395 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 1 Dec 2015 14:11:39 +0100 Subject: [PATCH 056/105] Rename python module related cmake variables to improve readability --- python/CMakeLists.txt | 18 +++++++++--------- python/handwritten/CMakeLists.txt | 2 +- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 9c0ba1df8..98699cccc 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -21,13 +21,13 @@ endif() # Compose strings used to specify the boost python version. They will be empty if we want to use the defaut if(NOT GTSAM_PYTHON_VERSION STREQUAL "Default") - string(REPLACE "." "" BOOST_PYTHON_VERSION_STRING ${GTSAM_PYTHON_VERSION}) # Remove '.' from version - string(SUBSTRING ${BOOST_PYTHON_VERSION_STRING} 0 2 BOOST_PYTHON_VERSION_STRING) # Trim version number to 2 digits - set(BOOST_PYTHON_VERSION_STRING "-py${BOOST_PYTHON_VERSION_STRING}") # Add '-py' prefix - string(TOUPPER ${BOOST_PYTHON_VERSION_STRING} UPPER_BOOST_PYTHON_VERSION_STRING) # Get uppercase string + string(REPLACE "." "" BOOST_PYTHON_VERSION_SUFFIX ${GTSAM_PYTHON_VERSION}) # Remove '.' from version + string(SUBSTRING ${BOOST_PYTHON_VERSION_SUFFIX} 0 2 BOOST_PYTHON_VERSION_SUFFIX) # Trim version number to 2 digits + set(BOOST_PYTHON_VERSION_SUFFIX "-py${BOOST_PYTHON_VERSION_SUFFIX}") # Append '-py' prefix + string(TOUPPER ${BOOST_PYTHON_VERSION_SUFFIX} BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE) # Get uppercase string else() - set(BOOST_PYTHON_VERSION_STRING "") - set(UPPER_BOOST_PYTHON_VERSION_STRING "") + set(BOOST_PYTHON_VERSION_SUFFIX "") + set(BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE "") endif() # Find NumPy C-API @@ -51,10 +51,10 @@ else() endif() # Find Boost Python -find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_STRING}) +find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_SUFFIX}) # Add handwritten directory if we found python and boost python -if(Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND AND PYTHONLIBS_FOUND) +if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND) include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) @@ -73,7 +73,7 @@ if(NOT PYTHONLIBS_FOUND) endif() endif() -if(NOT Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_FOUND) +if(NOT Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND) if(GTSAM_PYTHON_VERSION STREQUAL "Default") message(WARNING "Default Boost python was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") else() diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index ffd970217..50c316759 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -18,7 +18,7 @@ set_target_properties(${moduleName}_python PROPERTIES OUTPUT_NAME ${moduleName}_python CLEAN_DIRECT_OUTPUT 1) -target_link_libraries(${moduleName}_python ${Boost_PYTHON${UPPER_BOOST_PYTHON_VERSION_STRING}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp +target_link_libraries(${moduleName}_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp # On OSX and Linux, the python library must end in the extension .so. Build this # filename here. From 57373c8c477acdf81d195434167e19aea012997f Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 1 Dec 2015 16:06:47 +0100 Subject: [PATCH 057/105] Wrap Cayley methods to python only if not using Quaternions --- python/handwritten/geometry/Rot3.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp index ff2b61b63..f278517e8 100644 --- a/python/handwritten/geometry/Rot3.cpp +++ b/python/handwritten/geometry/Rot3.cpp @@ -74,13 +74,15 @@ void exportRot3(){ .def("column", &Rot3::column) .def("conjugate", &Rot3::conjugate) .def("equals", &Rot3::equals, equals_overloads(args("q","tol"))) +#ifndef GTSAM_USE_QUATERNIONS .def("localCayley", &Rot3::localCayley) + .def("retractCayley", &Rot3::retractCayley) +#endif .def("matrix", &Rot3::matrix) .def("print", &Rot3::print, print_overloads(args("s"))) .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) From 2e4a96dc188671bd6c1b96c9865f1c2640d87e2f Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 1 Dec 2015 16:53:33 +0100 Subject: [PATCH 058/105] Do not store RPATH into _libgtsam_python.so Since we're copying the .so from the build dir to python/gtsam _outside_ the build dir, we should remove the rpath from the .so, so it will search the library in the system, and not in the build directory, after installed using setup.py --- python/handwritten/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 50c316759..b9f711f0b 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -16,6 +16,7 @@ add_library(${moduleName}_python SHARED exportgtsam.cpp ${gtsam_python_srcs}) set_target_properties(${moduleName}_python PROPERTIES OUTPUT_NAME ${moduleName}_python + SKIP_BUILD_RPATH TRUE CLEAN_DIRECT_OUTPUT 1) target_link_libraries(${moduleName}_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp From 888af6b94885e406e393d31f2a0fe7bc027de157 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 1 Dec 2015 22:10:31 +0100 Subject: [PATCH 059/105] Remove unused lines that generate warnings on CMake 3.4 --- python/handwritten/CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index b9f711f0b..d80af6dd2 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -23,9 +23,7 @@ target_link_libraries(${moduleName}_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_ # On OSX and Linux, the python library must end in the extension .so. Build this # filename here. -get_property(PYLIB_OUTPUT_FILE TARGET ${moduleName}_python PROPERTY LOCATION) set(PYLIB_OUTPUT_FILE $) -get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE) set(PYLIB_SO_NAME lib${moduleName}_python.so) # Installs the library in the gtsam folder, which is used by setup.py to create the gtsam package From 768c59429939cbd5c3183581610e4962a00eeb40 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 2 Dec 2015 00:09:52 +0100 Subject: [PATCH 060/105] Copy python/gtsam to build/python directory Not the best way since the gtsam module into build/python won't be updated if .py files change in the python module. --- python/CMakeLists.txt | 3 +++ python/gtsam/.gitignore | 1 - python/handwritten/CMakeLists.txt | 9 +-------- 3 files changed, 4 insertions(+), 9 deletions(-) delete mode 100644 python/gtsam/.gitignore diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 98699cccc..cd920776e 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -58,6 +58,9 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) + + file(COPY "gtsam" DESTINATION ".") + file(COPY "setup.py" DESTINATION ".") add_subdirectory(handwritten) # Disable python module if we didn't find required lybraries else() diff --git a/python/gtsam/.gitignore b/python/gtsam/.gitignore deleted file mode 100644 index 580cd8494..000000000 --- a/python/gtsam/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/_libgtsam_python.so diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index d80af6dd2..62da9d74b 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -21,16 +21,9 @@ set_target_properties(${moduleName}_python PROPERTIES target_link_libraries(${moduleName}_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp -# On OSX and Linux, the python library must end in the extension .so. Build this -# filename here. -set(PYLIB_OUTPUT_FILE $) -set(PYLIB_SO_NAME lib${moduleName}_python.so) - -# Installs the library in the gtsam folder, which is used by setup.py to create the gtsam package -set(PYTHON_MODULE_DIRECTORY ${CMAKE_SOURCE_DIR}/python/gtsam) # Cause the library to be output in the correct directory. add_custom_command(TARGET ${moduleName}_python POST_BUILD - COMMAND cp -v ${PYLIB_OUTPUT_FILE} ${PYTHON_MODULE_DIRECTORY}/_${PYLIB_SO_NAME} + COMMAND cp -v $ ${CMAKE_BINARY_DIR}/python/gtsam/_$ WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} COMMENT "Copying library files to python directory" ) From 4671b03e7430d57e3e5cbf0f13e55a1a15f500cf Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 2 Dec 2015 11:51:14 +0100 Subject: [PATCH 061/105] Only copy .py files if they've changed --- python/CMakeLists.txt | 21 ++++++++++++++++++--- 1 file changed, 18 insertions(+), 3 deletions(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index cd920776e..88566ed7b 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -53,15 +53,30 @@ endif() # Find Boost Python find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_SUFFIX}) -# Add handwritten directory if we found python and boost python +# Build python module library and setup the module inside build if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND) include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) - file(COPY "gtsam" DESTINATION ".") - file(COPY "setup.py" DESTINATION ".") + # Build the python module library add_subdirectory(handwritten) + + # Copy all .py files that changes since last build + file(GLOB_RECURSE GTSAM_PY_SRCS RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} "*.py") + foreach(PY_SRC ${GTSAM_PY_SRCS}) + string(REPLACE "/" "_" PY_SRC_TARGET_SUFFIX ${PY_SRC}) # Replace "/" with "_" + add_custom_command( + OUTPUT ${PY_SRC} + DEPENDS ${PY_SRC} + COMMAND ${CMAKE_COMMAND} -E copy_if_different ${CMAKE_CURRENT_SOURCE_DIR}/${PY_SRC} ${CMAKE_CURRENT_BINARY_DIR}/${PY_SRC} + COMMENT "Copying ${PY_SRC}" + ) + add_custom_target(copy_${PY_SRC_TARGET_SUFFIX} DEPENDS ${PY_SRC}) + # Add dependency so the copy is made BEFORE building the python module + add_dependencies(gtsam_python copy_${PY_SRC_TARGET_SUFFIX}) + endforeach() + # Disable python module if we didn't find required lybraries else() set(GTSAM_BUILD_PYTHON OFF CACHE BOOL "Build Python wrapper statically (increases build time)" FORCE) From 81a1fe1c3a647492698226cfbd180a800bf31da2 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 2 Dec 2015 13:27:20 +0100 Subject: [PATCH 062/105] Create a proper target to generate python/gtsam/_libgtsam_python.so in the build directory --- python/handwritten/CMakeLists.txt | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 62da9d74b..322b49584 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -22,8 +22,11 @@ set_target_properties(${moduleName}_python PROPERTIES target_link_libraries(${moduleName}_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp # Cause the library to be output in the correct directory. -add_custom_command(TARGET ${moduleName}_python - POST_BUILD - COMMAND cp -v $ ${CMAKE_BINARY_DIR}/python/gtsam/_$ - WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} - COMMENT "Copying library files to python directory" ) +# TODO: Change below to work on different systems (currently works only with Linux) +add_custom_command( + OUTPUT ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so + DEPENDS gtsam_python + COMMAND ${CMAKE_COMMAND} -E copy $ ${CMAKE_BINARY_DIR}/python/gtsam/_$ + COMMENT "Copying extension module to python/gtsam/_libgtsam_python.so" +) +add_custom_target(copy_gtsam_python_module ALL DEPENDS ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so) \ No newline at end of file From 4f509c2dff78b332e3f469ed87b25e37b1261886 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 2 Dec 2015 14:15:10 +0100 Subject: [PATCH 063/105] Improve printing when copying .py files --- python/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 88566ed7b..69fea5663 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -70,7 +70,7 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU OUTPUT ${PY_SRC} DEPENDS ${PY_SRC} COMMAND ${CMAKE_COMMAND} -E copy_if_different ${CMAKE_CURRENT_SOURCE_DIR}/${PY_SRC} ${CMAKE_CURRENT_BINARY_DIR}/${PY_SRC} - COMMENT "Copying ${PY_SRC}" + COMMENT "Copying python/${PY_SRC}" ) add_custom_target(copy_${PY_SRC_TARGET_SUFFIX} DEPENDS ${PY_SRC}) # Add dependency so the copy is made BEFORE building the python module From 87211319fb7ca64a722a5ea9df8986d411a05fd0 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 2 Dec 2015 14:35:51 +0100 Subject: [PATCH 064/105] Update python/README.md --- python/README.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/python/README.md b/python/README.md index c6e5ed37d..fc83ff702 100644 --- a/python/README.md +++ b/python/README.md @@ -3,15 +3,16 @@ Python Wrapper and Packaging This directory contains the basic setup script and directory structure for the gtsam python module. During the build of gtsam, when GTSAM_BUILD_PYTHON is enabled, the following instructions will run. -* Wrap parses gtsam.h and constructs a cpp file called ${moduleName}_python.cpp -* This file is then compiled and linked with BoostPython, generating a shared library which can then be imported by python -* The shared library is then copied to python/gtsam -* The user can use the setup.py script to build and install a python package, allowing easy importing into a python project. Examples: +* The python files that compose the module are copied from python/gtsam to $BUILD_DIR/python/gtsam +* The handwritten module source files are then compiled and linked with Boost Python, generating a shared library which can then be imported by python +* The shared library is then copied to $BUILD_DIR/python/gtsam and renamed with a "_" prefix +* The user can use the setup.py script inside $BUILD_DIR/python to build and install a python package, allowing easy importing into a python project. Examples (when run from $BUILD_DIR): * python setup.py sdist ---- Builds a tarball of the python package which can then be distributed * python setup.py install ---- Installs the package into the python dist-packages folder. Can then be imported from any python file. * python setup.py install --prefix="your/local/install/path"---- Installs the package into a local instalation folder. Can then be imported from any python file if _prefix_/lib/pythonX.Y/site-packages is present in your $PYTHONPATH * To run the unit tests, you must first install the package on your path (TODO: Make this easier) +The target version of Python to create the module can be set by defining GTSAM_PYTHON_VERSION to 'X.Y' (Example: 2.7 or 3.4), or 'Default' if you want to use the default python installed in your system. Note that if you specify a target version of python, you should also have the correspondent Boost Python version installed (Example: libboost_python-py27.so or libboost_python-py34.so on Linux). If you're using the default version, your default Boost Python library (Example: libboost_python.so on Linux) should correspond to the default python version in your system. TODO: There are many issues with this build system, but these are the basics. From 31a88ba910f9affb63ae1f95aa95d4b1d1ef3a4c Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Wed, 2 Dec 2015 15:29:07 +0100 Subject: [PATCH 065/105] Remove some variables to improve readbility --- python/handwritten/CMakeLists.txt | 19 ++++++++----------- 1 file changed, 8 insertions(+), 11 deletions(-) diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 322b49584..90eb1fc49 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -10,23 +10,20 @@ foreach(subdir ${SUBDIRS}) endforeach() # Create the library -set(moduleName gtsam) -set(gtsamLib gtsam) -add_library(${moduleName}_python SHARED exportgtsam.cpp ${gtsam_python_srcs}) - -set_target_properties(${moduleName}_python PROPERTIES - OUTPUT_NAME ${moduleName}_python - SKIP_BUILD_RPATH TRUE - CLEAN_DIRECT_OUTPUT 1) - -target_link_libraries(${moduleName}_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp +add_library(gtsam_python SHARED exportgtsam.cpp ${gtsam_python_srcs}) +set_target_properties(gtsam_python PROPERTIES + OUTPUT_NAME gtsam_python + SKIP_BUILD_RPATH TRUE + CLEAN_DIRECT_OUTPUT 1 +) +target_link_libraries(gtsam_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} ${PYTHON_LIBRARY} gtsam) # Cause the library to be output in the correct directory. # TODO: Change below to work on different systems (currently works only with Linux) add_custom_command( OUTPUT ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so DEPENDS gtsam_python - COMMAND ${CMAKE_COMMAND} -E copy $ ${CMAKE_BINARY_DIR}/python/gtsam/_$ + COMMAND ${CMAKE_COMMAND} -E copy $ ${CMAKE_BINARY_DIR}/python/gtsam/_$ COMMENT "Copying extension module to python/gtsam/_libgtsam_python.so" ) add_custom_target(copy_gtsam_python_module ALL DEPENDS ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so) \ No newline at end of file From 46178731c6d690c72f467e09791ebed853b75319 Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Thu, 3 Dec 2015 13:01:12 +0100 Subject: [PATCH 066/105] "cmake -E copy_if_different" -> "cmake -E copy" for .py files "cmake -E copy" is enough because it checks the timestamp to decide if it the copy should be made or not. --- python/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 69fea5663..85d7c6765 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -69,7 +69,7 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU add_custom_command( OUTPUT ${PY_SRC} DEPENDS ${PY_SRC} - COMMAND ${CMAKE_COMMAND} -E copy_if_different ${CMAKE_CURRENT_SOURCE_DIR}/${PY_SRC} ${CMAKE_CURRENT_BINARY_DIR}/${PY_SRC} + COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/${PY_SRC} ${CMAKE_CURRENT_BINARY_DIR}/${PY_SRC} COMMENT "Copying python/${PY_SRC}" ) add_custom_target(copy_${PY_SRC_TARGET_SUFFIX} DEPENDS ${PY_SRC}) From 2754613072dda176f0b466babf4db539244da41c Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Thu, 3 Dec 2015 13:04:47 +0100 Subject: [PATCH 067/105] Add support for int64 and uint64 as it was done in Schweizer-Messer See https://github.com/ethz-asl/Schweizer-Messer --- .../include/numpy_eigen/type_traits.hpp | 25 +++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp index 3b75c6b99..36fae1a03 100755 --- a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp @@ -28,6 +28,31 @@ template<> struct TypeToNumPy } }; +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_LONG }; + static const char * npyString() { return "NPY_LONG"; } + static const char * typeString() { return "long"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_LONG; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_UINT64 }; + static const char * npyString() { return "NPY_UINT64"; } + static const char * typeString() { return "uint64"; } + static bool canConvert(int type) + { + return type == NPY_UINT8 || type == NPY_USHORT || + type == NPY_UINT16 || type == NPY_UINT32 || + type == NPY_ULONG || type == NPY_ULONGLONG || + type == NPY_UINT64; + } +}; + template<> struct TypeToNumPy { enum { NpyType = NPY_UBYTE }; From 868f1511fcbb7b806033ebf74f5b82c4d02679ae Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Tue, 8 Dec 2015 14:31:24 +0100 Subject: [PATCH 068/105] Add Quaternion named constructor to Rot3 in the python module --- python/handwritten/geometry/Rot3.cpp | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp index f278517e8..f9dc8cdf5 100644 --- a/python/handwritten/geometry/Rot3.cpp +++ b/python/handwritten/geometry/Rot3.cpp @@ -25,6 +25,16 @@ using namespace boost::python; using namespace gtsam; +static Rot3 Quaternion_0(const Vector4& q) +{ + return Rot3(Quaternion(q[0],q[1],q[2],q[3])); +} + +static Rot3 Quaternion_1(double w, double x, double y, double z) +{ + return Rot3(Quaternion(w,x,y,z)); +} + // Prototypes used to perform overloading // See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html gtsam::Rot3 (*AxisAngle_0)(const Vector3&, double) = &Rot3::AxisAngle; @@ -40,11 +50,13 @@ BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Rot3::equals, 1, 2) void exportRot3(){ class_("Rot3") - .def(init<>()) .def(init()) .def(init()) .def(init()) .def(init()) + .def("Quaternion", Quaternion_0, arg("q"), "Creates a Rot3 from an array [w,x,y,z] representing a quaternion") + .def("Quaternion", Quaternion_1, (arg("w"),arg("x"),arg("y"),arg("z")) ) + .staticmethod("Quaternion") .def("AxisAngle", AxisAngle_0) .def("AxisAngle", AxisAngle_1) .staticmethod("AxisAngle") From 383986902ac9924f7445aeb296d425efde6a806d Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Fri, 11 Dec 2015 18:19:05 +0100 Subject: [PATCH 069/105] Add quaternion() method, use properly quaternion named constructor, and add some comments on RzRyRx --- python/handwritten/geometry/Rot3.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp index f9dc8cdf5..b4551ca5c 100644 --- a/python/handwritten/geometry/Rot3.cpp +++ b/python/handwritten/geometry/Rot3.cpp @@ -27,12 +27,12 @@ using namespace gtsam; static Rot3 Quaternion_0(const Vector4& q) { - return Rot3(Quaternion(q[0],q[1],q[2],q[3])); + return Rot3::quaternion(q[0],q[1],q[2],q[3]); } static Rot3 Quaternion_1(double w, double x, double y, double z) { - return Rot3(Quaternion(w,x,y,z)); + return Rot3::quaternion(w,x,y,z); } // Prototypes used to perform overloading @@ -43,6 +43,7 @@ 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; +Vector (Rot3::*quaternion_0)() const = &Rot3::quaternion; BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Rot3::print, 0, 1) BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Rot3::equals, 1, 2) @@ -77,8 +78,8 @@ void exportRot3(){ .staticmethod("Ry") .def("Rz", &Rot3::Rz) .staticmethod("Rz") - .def("RzRyRx", RzRyRx_0) - .def("RzRyRx", RzRyRx_1) + .def("RzRyRx", RzRyRx_0, (arg("x"),arg("y"),arg("z")), "Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis" ) + .def("RzRyRx", RzRyRx_1, arg("xyz"), "Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis" ) .staticmethod("RzRyRx") .def("identity", &Rot3::identity) .staticmethod("identity") @@ -99,6 +100,7 @@ void exportRot3(){ .def("slerp", &Rot3::slerp) .def("transpose", &Rot3::transpose) .def("xyz", &Rot3::xyz) + .def("quaternion", quaternion_0) .def(self * self) .def(self * other()) .def(self * other()) From 4f4d7c2af5d391bae3a3caff0b8f19573814199a Mon Sep 17 00:00:00 2001 From: Ellon Mendes Date: Fri, 11 Dec 2015 18:20:33 +0100 Subject: [PATCH 070/105] Add value_exists() and calculate_pose3_estimate to ISAM2 in python --- python/handwritten/nonlinear/ISAM2.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/python/handwritten/nonlinear/ISAM2.cpp b/python/handwritten/nonlinear/ISAM2.cpp index 7155c679d..f80c5df99 100644 --- a/python/handwritten/nonlinear/ISAM2.cpp +++ b/python/handwritten/nonlinear/ISAM2.cpp @@ -20,6 +20,7 @@ #include #include "gtsam/nonlinear/ISAM2.h" +#include "gtsam/geometry/Pose3.h" using namespace boost::python; using namespace gtsam; @@ -59,6 +60,8 @@ class_("ISAM2") // TODO(Ellon): wrap all optional values of update .def("update",&ISAM2::update, update_overloads()) .def("calculate_estimate", calculateEstimate_0) + .def("calculate_pose3_estimate", &ISAM2::calculateEstimate, (arg("self"), arg("key")) ) + .def("value_exists", &ISAM2::valueExists) ; } \ No newline at end of file From ba13d743630ee50cf68f8cdf5864968a5543a763 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 19 Jan 2016 09:56:36 -0800 Subject: [PATCH 071/105] Delete 3dparty numpy C-api --- .../include/numpy/__multiarray_api.h | 1721 ------------ .../numpy_c_api/include/numpy/__ufunc_api.h | 328 --- .../numpy/_neighborhood_iterator_imp.h | 90 - .../numpy_c_api/include/numpy/_numpyconfig.h | 32 - .../numpy_c_api/include/numpy/arrayobject.h | 11 - .../numpy_c_api/include/numpy/arrayscalars.h | 175 -- .../numpy_c_api/include/numpy/halffloat.h | 69 - .../include/numpy/multiarray_api.txt | 2430 ----------------- .../numpy_c_api/include/numpy/ndarrayobject.h | 237 -- .../numpy_c_api/include/numpy/ndarraytypes.h | 1777 ------------ .../numpy_c_api/include/numpy/noprefix.h | 209 -- .../include/numpy/npy_1_7_deprecated_api.h | 130 - .../numpy_c_api/include/numpy/npy_3kcompat.h | 502 ---- .../numpy_c_api/include/numpy/npy_common.h | 1005 ------- .../numpy_c_api/include/numpy/npy_cpu.h | 114 - .../numpy_c_api/include/numpy/npy_endian.h | 48 - .../numpy_c_api/include/numpy/npy_interrupt.h | 117 - .../numpy_c_api/include/numpy/npy_math.h | 468 ---- .../include/numpy/npy_no_deprecated_api.h | 19 - .../numpy_c_api/include/numpy/npy_os.h | 30 - .../numpy_c_api/include/numpy/numpyconfig.h | 34 - .../numpy_c_api/include/numpy/old_defines.h | 187 -- .../numpy_c_api/include/numpy/oldnumeric.h | 23 - .../numpy_c_api/include/numpy/ufunc_api.txt | 321 --- .../numpy_c_api/include/numpy/ufuncobject.h | 479 ---- .../numpy_c_api/include/numpy/utils.h | 19 - 26 files changed, 10575 deletions(-) delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h delete mode 100644 gtsam/3rdparty/numpy_c_api/include/numpy/utils.h diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h deleted file mode 100644 index bfa87d8df..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/__multiarray_api.h +++ /dev/null @@ -1,1721 +0,0 @@ - -#ifdef _MULTIARRAYMODULE - -typedef struct { - PyObject_HEAD - npy_bool obval; -} PyBoolScalarObject; - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION -extern NPY_NO_EXPORT PyTypeObject PyArrayMapIter_Type; -extern NPY_NO_EXPORT PyTypeObject PyArrayNeighborhoodIter_Type; -extern NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; -#else -NPY_NO_EXPORT PyTypeObject PyArrayMapIter_Type; -NPY_NO_EXPORT PyTypeObject PyArrayNeighborhoodIter_Type; -NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; -#endif - -NPY_NO_EXPORT unsigned int PyArray_GetNDArrayCVersion \ - (void); -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyBigArray_Type; -#else - NPY_NO_EXPORT PyTypeObject PyBigArray_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyArray_Type; -#else - NPY_NO_EXPORT PyTypeObject PyArray_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyArrayDescr_Type; -#else - NPY_NO_EXPORT PyTypeObject PyArrayDescr_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyArrayFlags_Type; -#else - NPY_NO_EXPORT PyTypeObject PyArrayFlags_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyArrayIter_Type; -#else - NPY_NO_EXPORT PyTypeObject PyArrayIter_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyArrayMultiIter_Type; -#else - NPY_NO_EXPORT PyTypeObject PyArrayMultiIter_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT int NPY_NUMUSERTYPES; -#else - NPY_NO_EXPORT int NPY_NUMUSERTYPES; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyBoolArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyBoolArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION -extern NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; -#else -NPY_NO_EXPORT PyBoolScalarObject _PyArrayScalar_BoolValues[2]; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyGenericArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyGenericArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyNumberArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyNumberArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyIntegerArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyIntegerArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PySignedIntegerArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PySignedIntegerArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyUnsignedIntegerArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyUnsignedIntegerArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyInexactArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyInexactArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyFloatingArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyFloatingArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyComplexFloatingArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyComplexFloatingArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyFlexibleArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyFlexibleArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyCharacterArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyCharacterArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyByteArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyByteArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyShortArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyShortArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyIntArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyIntArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyLongArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyLongArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyLongLongArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyLongLongArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyUByteArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyUByteArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyUShortArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyUShortArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyUIntArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyUIntArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyULongArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyULongArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyULongLongArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyULongLongArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyFloatArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyFloatArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyDoubleArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyDoubleArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyLongDoubleArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyLongDoubleArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyCFloatArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyCFloatArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyCDoubleArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyCDoubleArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyCLongDoubleArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyCLongDoubleArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyObjectArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyObjectArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyStringArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyStringArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyUnicodeArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyUnicodeArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyVoidArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyVoidArrType_Type; -#endif - -NPY_NO_EXPORT int PyArray_SetNumericOps \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_GetNumericOps \ - (void); -NPY_NO_EXPORT int PyArray_INCREF \ - (PyArrayObject *); -NPY_NO_EXPORT int PyArray_XDECREF \ - (PyArrayObject *); -NPY_NO_EXPORT void PyArray_SetStringFunction \ - (PyObject *, int); -NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromType \ - (int); -NPY_NO_EXPORT PyObject * PyArray_TypeObjectFromType \ - (int); -NPY_NO_EXPORT char * PyArray_Zero \ - (PyArrayObject *); -NPY_NO_EXPORT char * PyArray_One \ - (PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_CastToType \ - (PyArrayObject *, PyArray_Descr *, int); -NPY_NO_EXPORT int PyArray_CastTo \ - (PyArrayObject *, PyArrayObject *); -NPY_NO_EXPORT int PyArray_CastAnyTo \ - (PyArrayObject *, PyArrayObject *); -NPY_NO_EXPORT int PyArray_CanCastSafely \ - (int, int); -NPY_NO_EXPORT npy_bool PyArray_CanCastTo \ - (PyArray_Descr *, PyArray_Descr *); -NPY_NO_EXPORT int PyArray_ObjectType \ - (PyObject *, int); -NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromObject \ - (PyObject *, PyArray_Descr *); -NPY_NO_EXPORT PyArrayObject ** PyArray_ConvertToCommonType \ - (PyObject *, int *); -NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromScalar \ - (PyObject *); -NPY_NO_EXPORT PyArray_Descr * PyArray_DescrFromTypeObject \ - (PyObject *); -NPY_NO_EXPORT npy_intp PyArray_Size \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_Scalar \ - (void *, PyArray_Descr *, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_FromScalar \ - (PyObject *, PyArray_Descr *); -NPY_NO_EXPORT void PyArray_ScalarAsCtype \ - (PyObject *, void *); -NPY_NO_EXPORT int PyArray_CastScalarToCtype \ - (PyObject *, void *, PyArray_Descr *); -NPY_NO_EXPORT int PyArray_CastScalarDirect \ - (PyObject *, PyArray_Descr *, void *, int); -NPY_NO_EXPORT PyObject * PyArray_ScalarFromObject \ - (PyObject *); -NPY_NO_EXPORT PyArray_VectorUnaryFunc * PyArray_GetCastFunc \ - (PyArray_Descr *, int); -NPY_NO_EXPORT PyObject * PyArray_FromDims \ - (int, int *, int); -NPY_NO_EXPORT PyObject * PyArray_FromDimsAndDataAndDescr \ - (int, int *, PyArray_Descr *, char *); -NPY_NO_EXPORT PyObject * PyArray_FromAny \ - (PyObject *, PyArray_Descr *, int, int, int, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_EnsureArray \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_EnsureAnyArray \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_FromFile \ - (FILE *, PyArray_Descr *, npy_intp, char *); -NPY_NO_EXPORT PyObject * PyArray_FromString \ - (char *, npy_intp, PyArray_Descr *, npy_intp, char *); -NPY_NO_EXPORT PyObject * PyArray_FromBuffer \ - (PyObject *, PyArray_Descr *, npy_intp, npy_intp); -NPY_NO_EXPORT PyObject * PyArray_FromIter \ - (PyObject *, PyArray_Descr *, npy_intp); -NPY_NO_EXPORT PyObject * PyArray_Return \ - (PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_GetField \ - (PyArrayObject *, PyArray_Descr *, int); -NPY_NO_EXPORT int PyArray_SetField \ - (PyArrayObject *, PyArray_Descr *, int, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_Byteswap \ - (PyArrayObject *, npy_bool); -NPY_NO_EXPORT PyObject * PyArray_Resize \ - (PyArrayObject *, PyArray_Dims *, int, NPY_ORDER); -NPY_NO_EXPORT int PyArray_MoveInto \ - (PyArrayObject *, PyArrayObject *); -NPY_NO_EXPORT int PyArray_CopyInto \ - (PyArrayObject *, PyArrayObject *); -NPY_NO_EXPORT int PyArray_CopyAnyInto \ - (PyArrayObject *, PyArrayObject *); -NPY_NO_EXPORT int PyArray_CopyObject \ - (PyArrayObject *, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_NewCopy \ - (PyArrayObject *, NPY_ORDER); -NPY_NO_EXPORT PyObject * PyArray_ToList \ - (PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_ToString \ - (PyArrayObject *, NPY_ORDER); -NPY_NO_EXPORT int PyArray_ToFile \ - (PyArrayObject *, FILE *, char *, char *); -NPY_NO_EXPORT int PyArray_Dump \ - (PyObject *, PyObject *, int); -NPY_NO_EXPORT PyObject * PyArray_Dumps \ - (PyObject *, int); -NPY_NO_EXPORT int PyArray_ValidType \ - (int); -NPY_NO_EXPORT void PyArray_UpdateFlags \ - (PyArrayObject *, int); -NPY_NO_EXPORT PyObject * PyArray_New \ - (PyTypeObject *, int, npy_intp *, int, npy_intp *, void *, int, int, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_NewFromDescr \ - (PyTypeObject *, PyArray_Descr *, int, npy_intp *, npy_intp *, void *, int, PyObject *); -NPY_NO_EXPORT PyArray_Descr * PyArray_DescrNew \ - (PyArray_Descr *); -NPY_NO_EXPORT PyArray_Descr * PyArray_DescrNewFromType \ - (int); -NPY_NO_EXPORT double PyArray_GetPriority \ - (PyObject *, double); -NPY_NO_EXPORT PyObject * PyArray_IterNew \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_MultiIterNew \ - (int, ...); -NPY_NO_EXPORT int PyArray_PyIntAsInt \ - (PyObject *); -NPY_NO_EXPORT npy_intp PyArray_PyIntAsIntp \ - (PyObject *); -NPY_NO_EXPORT int PyArray_Broadcast \ - (PyArrayMultiIterObject *); -NPY_NO_EXPORT void PyArray_FillObjectArray \ - (PyArrayObject *, PyObject *); -NPY_NO_EXPORT int PyArray_FillWithScalar \ - (PyArrayObject *, PyObject *); -NPY_NO_EXPORT npy_bool PyArray_CheckStrides \ - (int, int, npy_intp, npy_intp, npy_intp *, npy_intp *); -NPY_NO_EXPORT PyArray_Descr * PyArray_DescrNewByteorder \ - (PyArray_Descr *, char); -NPY_NO_EXPORT PyObject * PyArray_IterAllButAxis \ - (PyObject *, int *); -NPY_NO_EXPORT PyObject * PyArray_CheckFromAny \ - (PyObject *, PyArray_Descr *, int, int, int, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_FromArray \ - (PyArrayObject *, PyArray_Descr *, int); -NPY_NO_EXPORT PyObject * PyArray_FromInterface \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_FromStructInterface \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_FromArrayAttr \ - (PyObject *, PyArray_Descr *, PyObject *); -NPY_NO_EXPORT NPY_SCALARKIND PyArray_ScalarKind \ - (int, PyArrayObject **); -NPY_NO_EXPORT int PyArray_CanCoerceScalar \ - (int, int, NPY_SCALARKIND); -NPY_NO_EXPORT PyObject * PyArray_NewFlagsObject \ - (PyObject *); -NPY_NO_EXPORT npy_bool PyArray_CanCastScalar \ - (PyTypeObject *, PyTypeObject *); -NPY_NO_EXPORT int PyArray_CompareUCS4 \ - (npy_ucs4 *, npy_ucs4 *, size_t); -NPY_NO_EXPORT int PyArray_RemoveSmallest \ - (PyArrayMultiIterObject *); -NPY_NO_EXPORT int PyArray_ElementStrides \ - (PyObject *); -NPY_NO_EXPORT void PyArray_Item_INCREF \ - (char *, PyArray_Descr *); -NPY_NO_EXPORT void PyArray_Item_XDECREF \ - (char *, PyArray_Descr *); -NPY_NO_EXPORT PyObject * PyArray_FieldNames \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_Transpose \ - (PyArrayObject *, PyArray_Dims *); -NPY_NO_EXPORT PyObject * PyArray_TakeFrom \ - (PyArrayObject *, PyObject *, int, PyArrayObject *, NPY_CLIPMODE); -NPY_NO_EXPORT PyObject * PyArray_PutTo \ - (PyArrayObject *, PyObject*, PyObject *, NPY_CLIPMODE); -NPY_NO_EXPORT PyObject * PyArray_PutMask \ - (PyArrayObject *, PyObject*, PyObject*); -NPY_NO_EXPORT PyObject * PyArray_Repeat \ - (PyArrayObject *, PyObject *, int); -NPY_NO_EXPORT PyObject * PyArray_Choose \ - (PyArrayObject *, PyObject *, PyArrayObject *, NPY_CLIPMODE); -NPY_NO_EXPORT int PyArray_Sort \ - (PyArrayObject *, int, NPY_SORTKIND); -NPY_NO_EXPORT PyObject * PyArray_ArgSort \ - (PyArrayObject *, int, NPY_SORTKIND); -NPY_NO_EXPORT PyObject * PyArray_SearchSorted \ - (PyArrayObject *, PyObject *, NPY_SEARCHSIDE, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_ArgMax \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_ArgMin \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Reshape \ - (PyArrayObject *, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_Newshape \ - (PyArrayObject *, PyArray_Dims *, NPY_ORDER); -NPY_NO_EXPORT PyObject * PyArray_Squeeze \ - (PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_View \ - (PyArrayObject *, PyArray_Descr *, PyTypeObject *); -NPY_NO_EXPORT PyObject * PyArray_SwapAxes \ - (PyArrayObject *, int, int); -NPY_NO_EXPORT PyObject * PyArray_Max \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Min \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Ptp \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Mean \ - (PyArrayObject *, int, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Trace \ - (PyArrayObject *, int, int, int, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Diagonal \ - (PyArrayObject *, int, int, int); -NPY_NO_EXPORT PyObject * PyArray_Clip \ - (PyArrayObject *, PyObject *, PyObject *, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Conjugate \ - (PyArrayObject *, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Nonzero \ - (PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Std \ - (PyArrayObject *, int, int, PyArrayObject *, int); -NPY_NO_EXPORT PyObject * PyArray_Sum \ - (PyArrayObject *, int, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_CumSum \ - (PyArrayObject *, int, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Prod \ - (PyArrayObject *, int, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_CumProd \ - (PyArrayObject *, int, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_All \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Any \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Compress \ - (PyArrayObject *, PyObject *, int, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_Flatten \ - (PyArrayObject *, NPY_ORDER); -NPY_NO_EXPORT PyObject * PyArray_Ravel \ - (PyArrayObject *, NPY_ORDER); -NPY_NO_EXPORT npy_intp PyArray_MultiplyList \ - (npy_intp *, int); -NPY_NO_EXPORT int PyArray_MultiplyIntList \ - (int *, int); -NPY_NO_EXPORT void * PyArray_GetPtr \ - (PyArrayObject *, npy_intp*); -NPY_NO_EXPORT int PyArray_CompareLists \ - (npy_intp *, npy_intp *, int); -NPY_NO_EXPORT int PyArray_AsCArray \ - (PyObject **, void *, npy_intp *, int, PyArray_Descr*); -NPY_NO_EXPORT int PyArray_As1D \ - (PyObject **, char **, int *, int); -NPY_NO_EXPORT int PyArray_As2D \ - (PyObject **, char ***, int *, int *, int); -NPY_NO_EXPORT int PyArray_Free \ - (PyObject *, void *); -NPY_NO_EXPORT int PyArray_Converter \ - (PyObject *, PyObject **); -NPY_NO_EXPORT int PyArray_IntpFromSequence \ - (PyObject *, npy_intp *, int); -NPY_NO_EXPORT PyObject * PyArray_Concatenate \ - (PyObject *, int); -NPY_NO_EXPORT PyObject * PyArray_InnerProduct \ - (PyObject *, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_MatrixProduct \ - (PyObject *, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_CopyAndTranspose \ - (PyObject *); -NPY_NO_EXPORT PyObject * PyArray_Correlate \ - (PyObject *, PyObject *, int); -NPY_NO_EXPORT int PyArray_TypestrConvert \ - (int, int); -NPY_NO_EXPORT int PyArray_DescrConverter \ - (PyObject *, PyArray_Descr **); -NPY_NO_EXPORT int PyArray_DescrConverter2 \ - (PyObject *, PyArray_Descr **); -NPY_NO_EXPORT int PyArray_IntpConverter \ - (PyObject *, PyArray_Dims *); -NPY_NO_EXPORT int PyArray_BufferConverter \ - (PyObject *, PyArray_Chunk *); -NPY_NO_EXPORT int PyArray_AxisConverter \ - (PyObject *, int *); -NPY_NO_EXPORT int PyArray_BoolConverter \ - (PyObject *, npy_bool *); -NPY_NO_EXPORT int PyArray_ByteorderConverter \ - (PyObject *, char *); -NPY_NO_EXPORT int PyArray_OrderConverter \ - (PyObject *, NPY_ORDER *); -NPY_NO_EXPORT unsigned char PyArray_EquivTypes \ - (PyArray_Descr *, PyArray_Descr *); -NPY_NO_EXPORT PyObject * PyArray_Zeros \ - (int, npy_intp *, PyArray_Descr *, int); -NPY_NO_EXPORT PyObject * PyArray_Empty \ - (int, npy_intp *, PyArray_Descr *, int); -NPY_NO_EXPORT PyObject * PyArray_Where \ - (PyObject *, PyObject *, PyObject *); -NPY_NO_EXPORT PyObject * PyArray_Arange \ - (double, double, double, int); -NPY_NO_EXPORT PyObject * PyArray_ArangeObj \ - (PyObject *, PyObject *, PyObject *, PyArray_Descr *); -NPY_NO_EXPORT int PyArray_SortkindConverter \ - (PyObject *, NPY_SORTKIND *); -NPY_NO_EXPORT PyObject * PyArray_LexSort \ - (PyObject *, int); -NPY_NO_EXPORT PyObject * PyArray_Round \ - (PyArrayObject *, int, PyArrayObject *); -NPY_NO_EXPORT unsigned char PyArray_EquivTypenums \ - (int, int); -NPY_NO_EXPORT int PyArray_RegisterDataType \ - (PyArray_Descr *); -NPY_NO_EXPORT int PyArray_RegisterCastFunc \ - (PyArray_Descr *, int, PyArray_VectorUnaryFunc *); -NPY_NO_EXPORT int PyArray_RegisterCanCast \ - (PyArray_Descr *, int, NPY_SCALARKIND); -NPY_NO_EXPORT void PyArray_InitArrFuncs \ - (PyArray_ArrFuncs *); -NPY_NO_EXPORT PyObject * PyArray_IntTupleFromIntp \ - (int, npy_intp *); -NPY_NO_EXPORT int PyArray_TypeNumFromName \ - (char *); -NPY_NO_EXPORT int PyArray_ClipmodeConverter \ - (PyObject *, NPY_CLIPMODE *); -NPY_NO_EXPORT int PyArray_OutputConverter \ - (PyObject *, PyArrayObject **); -NPY_NO_EXPORT PyObject * PyArray_BroadcastToShape \ - (PyObject *, npy_intp *, int); -NPY_NO_EXPORT void _PyArray_SigintHandler \ - (int); -NPY_NO_EXPORT void* _PyArray_GetSigintBuf \ - (void); -NPY_NO_EXPORT int PyArray_DescrAlignConverter \ - (PyObject *, PyArray_Descr **); -NPY_NO_EXPORT int PyArray_DescrAlignConverter2 \ - (PyObject *, PyArray_Descr **); -NPY_NO_EXPORT int PyArray_SearchsideConverter \ - (PyObject *, void *); -NPY_NO_EXPORT PyObject * PyArray_CheckAxis \ - (PyArrayObject *, int *, int); -NPY_NO_EXPORT npy_intp PyArray_OverflowMultiplyList \ - (npy_intp *, int); -NPY_NO_EXPORT int PyArray_CompareString \ - (char *, char *, size_t); -NPY_NO_EXPORT PyObject * PyArray_MultiIterFromObjects \ - (PyObject **, int, int, ...); -NPY_NO_EXPORT int PyArray_GetEndianness \ - (void); -NPY_NO_EXPORT unsigned int PyArray_GetNDArrayCFeatureVersion \ - (void); -NPY_NO_EXPORT PyObject * PyArray_Correlate2 \ - (PyObject *, PyObject *, int); -NPY_NO_EXPORT PyObject* PyArray_NeighborhoodIterNew \ - (PyArrayIterObject *, npy_intp *, int, PyArrayObject*); -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyTimeIntegerArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyTimeIntegerArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyDatetimeArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyDatetimeArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyTimedeltaArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyTimedeltaArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyHalfArrType_Type; -#else - NPY_NO_EXPORT PyTypeObject PyHalfArrType_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject NpyIter_Type; -#else - NPY_NO_EXPORT PyTypeObject NpyIter_Type; -#endif - -NPY_NO_EXPORT void PyArray_SetDatetimeParseFunction \ - (PyObject *); -NPY_NO_EXPORT void PyArray_DatetimeToDatetimeStruct \ - (npy_datetime, NPY_DATETIMEUNIT, npy_datetimestruct *); -NPY_NO_EXPORT void PyArray_TimedeltaToTimedeltaStruct \ - (npy_timedelta, NPY_DATETIMEUNIT, npy_timedeltastruct *); -NPY_NO_EXPORT npy_datetime PyArray_DatetimeStructToDatetime \ - (NPY_DATETIMEUNIT, npy_datetimestruct *); -NPY_NO_EXPORT npy_datetime PyArray_TimedeltaStructToTimedelta \ - (NPY_DATETIMEUNIT, npy_timedeltastruct *); -NPY_NO_EXPORT NpyIter * NpyIter_New \ - (PyArrayObject *, npy_uint32, NPY_ORDER, NPY_CASTING, PyArray_Descr*); -NPY_NO_EXPORT NpyIter * NpyIter_MultiNew \ - (int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **); -NPY_NO_EXPORT NpyIter * NpyIter_AdvancedNew \ - (int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **, int, int **, npy_intp *, npy_intp); -NPY_NO_EXPORT NpyIter * NpyIter_Copy \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_Deallocate \ - (NpyIter *); -NPY_NO_EXPORT npy_bool NpyIter_HasDelayedBufAlloc \ - (NpyIter *); -NPY_NO_EXPORT npy_bool NpyIter_HasExternalLoop \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_EnableExternalLoop \ - (NpyIter *); -NPY_NO_EXPORT npy_intp * NpyIter_GetInnerStrideArray \ - (NpyIter *); -NPY_NO_EXPORT npy_intp * NpyIter_GetInnerLoopSizePtr \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_Reset \ - (NpyIter *, char **); -NPY_NO_EXPORT int NpyIter_ResetBasePointers \ - (NpyIter *, char **, char **); -NPY_NO_EXPORT int NpyIter_ResetToIterIndexRange \ - (NpyIter *, npy_intp, npy_intp, char **); -NPY_NO_EXPORT int NpyIter_GetNDim \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_GetNOp \ - (NpyIter *); -NPY_NO_EXPORT NpyIter_IterNextFunc * NpyIter_GetIterNext \ - (NpyIter *, char **); -NPY_NO_EXPORT npy_intp NpyIter_GetIterSize \ - (NpyIter *); -NPY_NO_EXPORT void NpyIter_GetIterIndexRange \ - (NpyIter *, npy_intp *, npy_intp *); -NPY_NO_EXPORT npy_intp NpyIter_GetIterIndex \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_GotoIterIndex \ - (NpyIter *, npy_intp); -NPY_NO_EXPORT npy_bool NpyIter_HasMultiIndex \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_GetShape \ - (NpyIter *, npy_intp *); -NPY_NO_EXPORT NpyIter_GetMultiIndexFunc * NpyIter_GetGetMultiIndex \ - (NpyIter *, char **); -NPY_NO_EXPORT int NpyIter_GotoMultiIndex \ - (NpyIter *, npy_intp *); -NPY_NO_EXPORT int NpyIter_RemoveMultiIndex \ - (NpyIter *); -NPY_NO_EXPORT npy_bool NpyIter_HasIndex \ - (NpyIter *); -NPY_NO_EXPORT npy_bool NpyIter_IsBuffered \ - (NpyIter *); -NPY_NO_EXPORT npy_bool NpyIter_IsGrowInner \ - (NpyIter *); -NPY_NO_EXPORT npy_intp NpyIter_GetBufferSize \ - (NpyIter *); -NPY_NO_EXPORT npy_intp * NpyIter_GetIndexPtr \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_GotoIndex \ - (NpyIter *, npy_intp); -NPY_NO_EXPORT char ** NpyIter_GetDataPtrArray \ - (NpyIter *); -NPY_NO_EXPORT PyArray_Descr ** NpyIter_GetDescrArray \ - (NpyIter *); -NPY_NO_EXPORT PyArrayObject ** NpyIter_GetOperandArray \ - (NpyIter *); -NPY_NO_EXPORT PyArrayObject * NpyIter_GetIterView \ - (NpyIter *, npy_intp); -NPY_NO_EXPORT void NpyIter_GetReadFlags \ - (NpyIter *, char *); -NPY_NO_EXPORT void NpyIter_GetWriteFlags \ - (NpyIter *, char *); -NPY_NO_EXPORT void NpyIter_DebugPrint \ - (NpyIter *); -NPY_NO_EXPORT npy_bool NpyIter_IterationNeedsAPI \ - (NpyIter *); -NPY_NO_EXPORT void NpyIter_GetInnerFixedStrideArray \ - (NpyIter *, npy_intp *); -NPY_NO_EXPORT int NpyIter_RemoveAxis \ - (NpyIter *, int); -NPY_NO_EXPORT npy_intp * NpyIter_GetAxisStrideArray \ - (NpyIter *, int); -NPY_NO_EXPORT npy_bool NpyIter_RequiresBuffering \ - (NpyIter *); -NPY_NO_EXPORT char ** NpyIter_GetInitialDataPtrArray \ - (NpyIter *); -NPY_NO_EXPORT int NpyIter_CreateCompatibleStrides \ - (NpyIter *, npy_intp, npy_intp *); -NPY_NO_EXPORT int PyArray_CastingConverter \ - (PyObject *, NPY_CASTING *); -NPY_NO_EXPORT npy_intp PyArray_CountNonzero \ - (PyArrayObject *); -NPY_NO_EXPORT PyArray_Descr * PyArray_PromoteTypes \ - (PyArray_Descr *, PyArray_Descr *); -NPY_NO_EXPORT PyArray_Descr * PyArray_MinScalarType \ - (PyArrayObject *); -NPY_NO_EXPORT PyArray_Descr * PyArray_ResultType \ - (npy_intp, PyArrayObject **, npy_intp, PyArray_Descr **); -NPY_NO_EXPORT npy_bool PyArray_CanCastArrayTo \ - (PyArrayObject *, PyArray_Descr *, NPY_CASTING); -NPY_NO_EXPORT npy_bool PyArray_CanCastTypeTo \ - (PyArray_Descr *, PyArray_Descr *, NPY_CASTING); -NPY_NO_EXPORT PyArrayObject * PyArray_EinsteinSum \ - (char *, npy_intp, PyArrayObject **, PyArray_Descr *, NPY_ORDER, NPY_CASTING, PyArrayObject *); -NPY_NO_EXPORT PyObject * PyArray_NewLikeArray \ - (PyArrayObject *, NPY_ORDER, PyArray_Descr *, int); -NPY_NO_EXPORT int PyArray_GetArrayParamsFromObject \ - (PyObject *, PyArray_Descr *, npy_bool, PyArray_Descr **, int *, npy_intp *, PyArrayObject **, PyObject *); -NPY_NO_EXPORT int PyArray_ConvertClipmodeSequence \ - (PyObject *, NPY_CLIPMODE *, int); -NPY_NO_EXPORT PyObject * PyArray_MatrixProduct2 \ - (PyObject *, PyObject *, PyArrayObject*); -NPY_NO_EXPORT npy_bool NpyIter_IsFirstVisit \ - (NpyIter *, int); -NPY_NO_EXPORT int PyArray_SetBaseObject \ - (PyArrayObject *, PyObject *); -NPY_NO_EXPORT void PyArray_CreateSortedStridePerm \ - (int, npy_intp *, npy_stride_sort_item *); -NPY_NO_EXPORT void PyArray_RemoveAxesInPlace \ - (PyArrayObject *, npy_bool *); -NPY_NO_EXPORT void PyArray_DebugPrint \ - (PyArrayObject *); -NPY_NO_EXPORT int PyArray_FailUnlessWriteable \ - (PyArrayObject *, const char *); -NPY_NO_EXPORT int PyArray_SetUpdateIfCopyBase \ - (PyArrayObject *, PyArrayObject *); -NPY_NO_EXPORT void * PyDataMem_NEW \ - (size_t); -NPY_NO_EXPORT void PyDataMem_FREE \ - (void *); -NPY_NO_EXPORT void * PyDataMem_RENEW \ - (void *, size_t); -NPY_NO_EXPORT PyDataMem_EventHookFunc * PyDataMem_SetEventHook \ - (PyDataMem_EventHookFunc *, void *, void **); -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT NPY_CASTING NPY_DEFAULT_ASSIGN_CASTING; -#else - NPY_NO_EXPORT NPY_CASTING NPY_DEFAULT_ASSIGN_CASTING; -#endif - -NPY_NO_EXPORT void PyArray_MapIterSwapAxes \ - (PyArrayMapIterObject *, PyArrayObject **, int); -NPY_NO_EXPORT PyObject * PyArray_MapIterArray \ - (PyArrayObject *, PyObject *); -NPY_NO_EXPORT void PyArray_MapIterNext \ - (PyArrayMapIterObject *); -NPY_NO_EXPORT int PyArray_Partition \ - (PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND); -NPY_NO_EXPORT PyObject * PyArray_ArgPartition \ - (PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND); -NPY_NO_EXPORT int PyArray_SelectkindConverter \ - (PyObject *, NPY_SELECTKIND *); -NPY_NO_EXPORT void * PyDataMem_NEW_ZEROED \ - (size_t, size_t); - -#else - -#if defined(PY_ARRAY_UNIQUE_SYMBOL) -#define PyArray_API PY_ARRAY_UNIQUE_SYMBOL -#endif - -#if defined(NO_IMPORT) || defined(NO_IMPORT_ARRAY) -extern void **PyArray_API; -#else -#if defined(PY_ARRAY_UNIQUE_SYMBOL) -void **PyArray_API; -#else -static void **PyArray_API=NULL; -#endif -#endif - -#define PyArray_GetNDArrayCVersion \ - (*(unsigned int (*)(void)) \ - PyArray_API[0]) -#define PyBigArray_Type (*(PyTypeObject *)PyArray_API[1]) -#define PyArray_Type (*(PyTypeObject *)PyArray_API[2]) -#define PyArrayDescr_Type (*(PyTypeObject *)PyArray_API[3]) -#define PyArrayFlags_Type (*(PyTypeObject *)PyArray_API[4]) -#define PyArrayIter_Type (*(PyTypeObject *)PyArray_API[5]) -#define PyArrayMultiIter_Type (*(PyTypeObject *)PyArray_API[6]) -#define NPY_NUMUSERTYPES (*(int *)PyArray_API[7]) -#define PyBoolArrType_Type (*(PyTypeObject *)PyArray_API[8]) -#define _PyArrayScalar_BoolValues ((PyBoolScalarObject *)PyArray_API[9]) -#define PyGenericArrType_Type (*(PyTypeObject *)PyArray_API[10]) -#define PyNumberArrType_Type (*(PyTypeObject *)PyArray_API[11]) -#define PyIntegerArrType_Type (*(PyTypeObject *)PyArray_API[12]) -#define PySignedIntegerArrType_Type (*(PyTypeObject *)PyArray_API[13]) -#define PyUnsignedIntegerArrType_Type (*(PyTypeObject *)PyArray_API[14]) -#define PyInexactArrType_Type (*(PyTypeObject *)PyArray_API[15]) -#define PyFloatingArrType_Type (*(PyTypeObject *)PyArray_API[16]) -#define PyComplexFloatingArrType_Type (*(PyTypeObject *)PyArray_API[17]) -#define PyFlexibleArrType_Type (*(PyTypeObject *)PyArray_API[18]) -#define PyCharacterArrType_Type (*(PyTypeObject *)PyArray_API[19]) -#define PyByteArrType_Type (*(PyTypeObject *)PyArray_API[20]) -#define PyShortArrType_Type (*(PyTypeObject *)PyArray_API[21]) -#define PyIntArrType_Type (*(PyTypeObject *)PyArray_API[22]) -#define PyLongArrType_Type (*(PyTypeObject *)PyArray_API[23]) -#define PyLongLongArrType_Type (*(PyTypeObject *)PyArray_API[24]) -#define PyUByteArrType_Type (*(PyTypeObject *)PyArray_API[25]) -#define PyUShortArrType_Type (*(PyTypeObject *)PyArray_API[26]) -#define PyUIntArrType_Type (*(PyTypeObject *)PyArray_API[27]) -#define PyULongArrType_Type (*(PyTypeObject *)PyArray_API[28]) -#define PyULongLongArrType_Type (*(PyTypeObject *)PyArray_API[29]) -#define PyFloatArrType_Type (*(PyTypeObject *)PyArray_API[30]) -#define PyDoubleArrType_Type (*(PyTypeObject *)PyArray_API[31]) -#define PyLongDoubleArrType_Type (*(PyTypeObject *)PyArray_API[32]) -#define PyCFloatArrType_Type (*(PyTypeObject *)PyArray_API[33]) -#define PyCDoubleArrType_Type (*(PyTypeObject *)PyArray_API[34]) -#define PyCLongDoubleArrType_Type (*(PyTypeObject *)PyArray_API[35]) -#define PyObjectArrType_Type (*(PyTypeObject *)PyArray_API[36]) -#define PyStringArrType_Type (*(PyTypeObject *)PyArray_API[37]) -#define PyUnicodeArrType_Type (*(PyTypeObject *)PyArray_API[38]) -#define PyVoidArrType_Type (*(PyTypeObject *)PyArray_API[39]) -#define PyArray_SetNumericOps \ - (*(int (*)(PyObject *)) \ - PyArray_API[40]) -#define PyArray_GetNumericOps \ - (*(PyObject * (*)(void)) \ - PyArray_API[41]) -#define PyArray_INCREF \ - (*(int (*)(PyArrayObject *)) \ - PyArray_API[42]) -#define PyArray_XDECREF \ - (*(int (*)(PyArrayObject *)) \ - PyArray_API[43]) -#define PyArray_SetStringFunction \ - (*(void (*)(PyObject *, int)) \ - PyArray_API[44]) -#define PyArray_DescrFromType \ - (*(PyArray_Descr * (*)(int)) \ - PyArray_API[45]) -#define PyArray_TypeObjectFromType \ - (*(PyObject * (*)(int)) \ - PyArray_API[46]) -#define PyArray_Zero \ - (*(char * (*)(PyArrayObject *)) \ - PyArray_API[47]) -#define PyArray_One \ - (*(char * (*)(PyArrayObject *)) \ - PyArray_API[48]) -#define PyArray_CastToType \ - (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, int)) \ - PyArray_API[49]) -#define PyArray_CastTo \ - (*(int (*)(PyArrayObject *, PyArrayObject *)) \ - PyArray_API[50]) -#define PyArray_CastAnyTo \ - (*(int (*)(PyArrayObject *, PyArrayObject *)) \ - PyArray_API[51]) -#define PyArray_CanCastSafely \ - (*(int (*)(int, int)) \ - PyArray_API[52]) -#define PyArray_CanCastTo \ - (*(npy_bool (*)(PyArray_Descr *, PyArray_Descr *)) \ - PyArray_API[53]) -#define PyArray_ObjectType \ - (*(int (*)(PyObject *, int)) \ - PyArray_API[54]) -#define PyArray_DescrFromObject \ - (*(PyArray_Descr * (*)(PyObject *, PyArray_Descr *)) \ - PyArray_API[55]) -#define PyArray_ConvertToCommonType \ - (*(PyArrayObject ** (*)(PyObject *, int *)) \ - PyArray_API[56]) -#define PyArray_DescrFromScalar \ - (*(PyArray_Descr * (*)(PyObject *)) \ - PyArray_API[57]) -#define PyArray_DescrFromTypeObject \ - (*(PyArray_Descr * (*)(PyObject *)) \ - PyArray_API[58]) -#define PyArray_Size \ - (*(npy_intp (*)(PyObject *)) \ - PyArray_API[59]) -#define PyArray_Scalar \ - (*(PyObject * (*)(void *, PyArray_Descr *, PyObject *)) \ - PyArray_API[60]) -#define PyArray_FromScalar \ - (*(PyObject * (*)(PyObject *, PyArray_Descr *)) \ - PyArray_API[61]) -#define PyArray_ScalarAsCtype \ - (*(void (*)(PyObject *, void *)) \ - PyArray_API[62]) -#define PyArray_CastScalarToCtype \ - (*(int (*)(PyObject *, void *, PyArray_Descr *)) \ - PyArray_API[63]) -#define PyArray_CastScalarDirect \ - (*(int (*)(PyObject *, PyArray_Descr *, void *, int)) \ - PyArray_API[64]) -#define PyArray_ScalarFromObject \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[65]) -#define PyArray_GetCastFunc \ - (*(PyArray_VectorUnaryFunc * (*)(PyArray_Descr *, int)) \ - PyArray_API[66]) -#define PyArray_FromDims \ - (*(PyObject * (*)(int, int *, int)) \ - PyArray_API[67]) -#define PyArray_FromDimsAndDataAndDescr \ - (*(PyObject * (*)(int, int *, PyArray_Descr *, char *)) \ - PyArray_API[68]) -#define PyArray_FromAny \ - (*(PyObject * (*)(PyObject *, PyArray_Descr *, int, int, int, PyObject *)) \ - PyArray_API[69]) -#define PyArray_EnsureArray \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[70]) -#define PyArray_EnsureAnyArray \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[71]) -#define PyArray_FromFile \ - (*(PyObject * (*)(FILE *, PyArray_Descr *, npy_intp, char *)) \ - PyArray_API[72]) -#define PyArray_FromString \ - (*(PyObject * (*)(char *, npy_intp, PyArray_Descr *, npy_intp, char *)) \ - PyArray_API[73]) -#define PyArray_FromBuffer \ - (*(PyObject * (*)(PyObject *, PyArray_Descr *, npy_intp, npy_intp)) \ - PyArray_API[74]) -#define PyArray_FromIter \ - (*(PyObject * (*)(PyObject *, PyArray_Descr *, npy_intp)) \ - PyArray_API[75]) -#define PyArray_Return \ - (*(PyObject * (*)(PyArrayObject *)) \ - PyArray_API[76]) -#define PyArray_GetField \ - (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, int)) \ - PyArray_API[77]) -#define PyArray_SetField \ - (*(int (*)(PyArrayObject *, PyArray_Descr *, int, PyObject *)) \ - PyArray_API[78]) -#define PyArray_Byteswap \ - (*(PyObject * (*)(PyArrayObject *, npy_bool)) \ - PyArray_API[79]) -#define PyArray_Resize \ - (*(PyObject * (*)(PyArrayObject *, PyArray_Dims *, int, NPY_ORDER)) \ - PyArray_API[80]) -#define PyArray_MoveInto \ - (*(int (*)(PyArrayObject *, PyArrayObject *)) \ - PyArray_API[81]) -#define PyArray_CopyInto \ - (*(int (*)(PyArrayObject *, PyArrayObject *)) \ - PyArray_API[82]) -#define PyArray_CopyAnyInto \ - (*(int (*)(PyArrayObject *, PyArrayObject *)) \ - PyArray_API[83]) -#define PyArray_CopyObject \ - (*(int (*)(PyArrayObject *, PyObject *)) \ - PyArray_API[84]) -#define PyArray_NewCopy \ - (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ - PyArray_API[85]) -#define PyArray_ToList \ - (*(PyObject * (*)(PyArrayObject *)) \ - PyArray_API[86]) -#define PyArray_ToString \ - (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ - PyArray_API[87]) -#define PyArray_ToFile \ - (*(int (*)(PyArrayObject *, FILE *, char *, char *)) \ - PyArray_API[88]) -#define PyArray_Dump \ - (*(int (*)(PyObject *, PyObject *, int)) \ - PyArray_API[89]) -#define PyArray_Dumps \ - (*(PyObject * (*)(PyObject *, int)) \ - PyArray_API[90]) -#define PyArray_ValidType \ - (*(int (*)(int)) \ - PyArray_API[91]) -#define PyArray_UpdateFlags \ - (*(void (*)(PyArrayObject *, int)) \ - PyArray_API[92]) -#define PyArray_New \ - (*(PyObject * (*)(PyTypeObject *, int, npy_intp *, int, npy_intp *, void *, int, int, PyObject *)) \ - PyArray_API[93]) -#define PyArray_NewFromDescr \ - (*(PyObject * (*)(PyTypeObject *, PyArray_Descr *, int, npy_intp *, npy_intp *, void *, int, PyObject *)) \ - PyArray_API[94]) -#define PyArray_DescrNew \ - (*(PyArray_Descr * (*)(PyArray_Descr *)) \ - PyArray_API[95]) -#define PyArray_DescrNewFromType \ - (*(PyArray_Descr * (*)(int)) \ - PyArray_API[96]) -#define PyArray_GetPriority \ - (*(double (*)(PyObject *, double)) \ - PyArray_API[97]) -#define PyArray_IterNew \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[98]) -#define PyArray_MultiIterNew \ - (*(PyObject * (*)(int, ...)) \ - PyArray_API[99]) -#define PyArray_PyIntAsInt \ - (*(int (*)(PyObject *)) \ - PyArray_API[100]) -#define PyArray_PyIntAsIntp \ - (*(npy_intp (*)(PyObject *)) \ - PyArray_API[101]) -#define PyArray_Broadcast \ - (*(int (*)(PyArrayMultiIterObject *)) \ - PyArray_API[102]) -#define PyArray_FillObjectArray \ - (*(void (*)(PyArrayObject *, PyObject *)) \ - PyArray_API[103]) -#define PyArray_FillWithScalar \ - (*(int (*)(PyArrayObject *, PyObject *)) \ - PyArray_API[104]) -#define PyArray_CheckStrides \ - (*(npy_bool (*)(int, int, npy_intp, npy_intp, npy_intp *, npy_intp *)) \ - PyArray_API[105]) -#define PyArray_DescrNewByteorder \ - (*(PyArray_Descr * (*)(PyArray_Descr *, char)) \ - PyArray_API[106]) -#define PyArray_IterAllButAxis \ - (*(PyObject * (*)(PyObject *, int *)) \ - PyArray_API[107]) -#define PyArray_CheckFromAny \ - (*(PyObject * (*)(PyObject *, PyArray_Descr *, int, int, int, PyObject *)) \ - PyArray_API[108]) -#define PyArray_FromArray \ - (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, int)) \ - PyArray_API[109]) -#define PyArray_FromInterface \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[110]) -#define PyArray_FromStructInterface \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[111]) -#define PyArray_FromArrayAttr \ - (*(PyObject * (*)(PyObject *, PyArray_Descr *, PyObject *)) \ - PyArray_API[112]) -#define PyArray_ScalarKind \ - (*(NPY_SCALARKIND (*)(int, PyArrayObject **)) \ - PyArray_API[113]) -#define PyArray_CanCoerceScalar \ - (*(int (*)(int, int, NPY_SCALARKIND)) \ - PyArray_API[114]) -#define PyArray_NewFlagsObject \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[115]) -#define PyArray_CanCastScalar \ - (*(npy_bool (*)(PyTypeObject *, PyTypeObject *)) \ - PyArray_API[116]) -#define PyArray_CompareUCS4 \ - (*(int (*)(npy_ucs4 *, npy_ucs4 *, size_t)) \ - PyArray_API[117]) -#define PyArray_RemoveSmallest \ - (*(int (*)(PyArrayMultiIterObject *)) \ - PyArray_API[118]) -#define PyArray_ElementStrides \ - (*(int (*)(PyObject *)) \ - PyArray_API[119]) -#define PyArray_Item_INCREF \ - (*(void (*)(char *, PyArray_Descr *)) \ - PyArray_API[120]) -#define PyArray_Item_XDECREF \ - (*(void (*)(char *, PyArray_Descr *)) \ - PyArray_API[121]) -#define PyArray_FieldNames \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[122]) -#define PyArray_Transpose \ - (*(PyObject * (*)(PyArrayObject *, PyArray_Dims *)) \ - PyArray_API[123]) -#define PyArray_TakeFrom \ - (*(PyObject * (*)(PyArrayObject *, PyObject *, int, PyArrayObject *, NPY_CLIPMODE)) \ - PyArray_API[124]) -#define PyArray_PutTo \ - (*(PyObject * (*)(PyArrayObject *, PyObject*, PyObject *, NPY_CLIPMODE)) \ - PyArray_API[125]) -#define PyArray_PutMask \ - (*(PyObject * (*)(PyArrayObject *, PyObject*, PyObject*)) \ - PyArray_API[126]) -#define PyArray_Repeat \ - (*(PyObject * (*)(PyArrayObject *, PyObject *, int)) \ - PyArray_API[127]) -#define PyArray_Choose \ - (*(PyObject * (*)(PyArrayObject *, PyObject *, PyArrayObject *, NPY_CLIPMODE)) \ - PyArray_API[128]) -#define PyArray_Sort \ - (*(int (*)(PyArrayObject *, int, NPY_SORTKIND)) \ - PyArray_API[129]) -#define PyArray_ArgSort \ - (*(PyObject * (*)(PyArrayObject *, int, NPY_SORTKIND)) \ - PyArray_API[130]) -#define PyArray_SearchSorted \ - (*(PyObject * (*)(PyArrayObject *, PyObject *, NPY_SEARCHSIDE, PyObject *)) \ - PyArray_API[131]) -#define PyArray_ArgMax \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[132]) -#define PyArray_ArgMin \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[133]) -#define PyArray_Reshape \ - (*(PyObject * (*)(PyArrayObject *, PyObject *)) \ - PyArray_API[134]) -#define PyArray_Newshape \ - (*(PyObject * (*)(PyArrayObject *, PyArray_Dims *, NPY_ORDER)) \ - PyArray_API[135]) -#define PyArray_Squeeze \ - (*(PyObject * (*)(PyArrayObject *)) \ - PyArray_API[136]) -#define PyArray_View \ - (*(PyObject * (*)(PyArrayObject *, PyArray_Descr *, PyTypeObject *)) \ - PyArray_API[137]) -#define PyArray_SwapAxes \ - (*(PyObject * (*)(PyArrayObject *, int, int)) \ - PyArray_API[138]) -#define PyArray_Max \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[139]) -#define PyArray_Min \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[140]) -#define PyArray_Ptp \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[141]) -#define PyArray_Mean \ - (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ - PyArray_API[142]) -#define PyArray_Trace \ - (*(PyObject * (*)(PyArrayObject *, int, int, int, int, PyArrayObject *)) \ - PyArray_API[143]) -#define PyArray_Diagonal \ - (*(PyObject * (*)(PyArrayObject *, int, int, int)) \ - PyArray_API[144]) -#define PyArray_Clip \ - (*(PyObject * (*)(PyArrayObject *, PyObject *, PyObject *, PyArrayObject *)) \ - PyArray_API[145]) -#define PyArray_Conjugate \ - (*(PyObject * (*)(PyArrayObject *, PyArrayObject *)) \ - PyArray_API[146]) -#define PyArray_Nonzero \ - (*(PyObject * (*)(PyArrayObject *)) \ - PyArray_API[147]) -#define PyArray_Std \ - (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *, int)) \ - PyArray_API[148]) -#define PyArray_Sum \ - (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ - PyArray_API[149]) -#define PyArray_CumSum \ - (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ - PyArray_API[150]) -#define PyArray_Prod \ - (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ - PyArray_API[151]) -#define PyArray_CumProd \ - (*(PyObject * (*)(PyArrayObject *, int, int, PyArrayObject *)) \ - PyArray_API[152]) -#define PyArray_All \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[153]) -#define PyArray_Any \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[154]) -#define PyArray_Compress \ - (*(PyObject * (*)(PyArrayObject *, PyObject *, int, PyArrayObject *)) \ - PyArray_API[155]) -#define PyArray_Flatten \ - (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ - PyArray_API[156]) -#define PyArray_Ravel \ - (*(PyObject * (*)(PyArrayObject *, NPY_ORDER)) \ - PyArray_API[157]) -#define PyArray_MultiplyList \ - (*(npy_intp (*)(npy_intp *, int)) \ - PyArray_API[158]) -#define PyArray_MultiplyIntList \ - (*(int (*)(int *, int)) \ - PyArray_API[159]) -#define PyArray_GetPtr \ - (*(void * (*)(PyArrayObject *, npy_intp*)) \ - PyArray_API[160]) -#define PyArray_CompareLists \ - (*(int (*)(npy_intp *, npy_intp *, int)) \ - PyArray_API[161]) -#define PyArray_AsCArray \ - (*(int (*)(PyObject **, void *, npy_intp *, int, PyArray_Descr*)) \ - PyArray_API[162]) -#define PyArray_As1D \ - (*(int (*)(PyObject **, char **, int *, int)) \ - PyArray_API[163]) -#define PyArray_As2D \ - (*(int (*)(PyObject **, char ***, int *, int *, int)) \ - PyArray_API[164]) -#define PyArray_Free \ - (*(int (*)(PyObject *, void *)) \ - PyArray_API[165]) -#define PyArray_Converter \ - (*(int (*)(PyObject *, PyObject **)) \ - PyArray_API[166]) -#define PyArray_IntpFromSequence \ - (*(int (*)(PyObject *, npy_intp *, int)) \ - PyArray_API[167]) -#define PyArray_Concatenate \ - (*(PyObject * (*)(PyObject *, int)) \ - PyArray_API[168]) -#define PyArray_InnerProduct \ - (*(PyObject * (*)(PyObject *, PyObject *)) \ - PyArray_API[169]) -#define PyArray_MatrixProduct \ - (*(PyObject * (*)(PyObject *, PyObject *)) \ - PyArray_API[170]) -#define PyArray_CopyAndTranspose \ - (*(PyObject * (*)(PyObject *)) \ - PyArray_API[171]) -#define PyArray_Correlate \ - (*(PyObject * (*)(PyObject *, PyObject *, int)) \ - PyArray_API[172]) -#define PyArray_TypestrConvert \ - (*(int (*)(int, int)) \ - PyArray_API[173]) -#define PyArray_DescrConverter \ - (*(int (*)(PyObject *, PyArray_Descr **)) \ - PyArray_API[174]) -#define PyArray_DescrConverter2 \ - (*(int (*)(PyObject *, PyArray_Descr **)) \ - PyArray_API[175]) -#define PyArray_IntpConverter \ - (*(int (*)(PyObject *, PyArray_Dims *)) \ - PyArray_API[176]) -#define PyArray_BufferConverter \ - (*(int (*)(PyObject *, PyArray_Chunk *)) \ - PyArray_API[177]) -#define PyArray_AxisConverter \ - (*(int (*)(PyObject *, int *)) \ - PyArray_API[178]) -#define PyArray_BoolConverter \ - (*(int (*)(PyObject *, npy_bool *)) \ - PyArray_API[179]) -#define PyArray_ByteorderConverter \ - (*(int (*)(PyObject *, char *)) \ - PyArray_API[180]) -#define PyArray_OrderConverter \ - (*(int (*)(PyObject *, NPY_ORDER *)) \ - PyArray_API[181]) -#define PyArray_EquivTypes \ - (*(unsigned char (*)(PyArray_Descr *, PyArray_Descr *)) \ - PyArray_API[182]) -#define PyArray_Zeros \ - (*(PyObject * (*)(int, npy_intp *, PyArray_Descr *, int)) \ - PyArray_API[183]) -#define PyArray_Empty \ - (*(PyObject * (*)(int, npy_intp *, PyArray_Descr *, int)) \ - PyArray_API[184]) -#define PyArray_Where \ - (*(PyObject * (*)(PyObject *, PyObject *, PyObject *)) \ - PyArray_API[185]) -#define PyArray_Arange \ - (*(PyObject * (*)(double, double, double, int)) \ - PyArray_API[186]) -#define PyArray_ArangeObj \ - (*(PyObject * (*)(PyObject *, PyObject *, PyObject *, PyArray_Descr *)) \ - PyArray_API[187]) -#define PyArray_SortkindConverter \ - (*(int (*)(PyObject *, NPY_SORTKIND *)) \ - PyArray_API[188]) -#define PyArray_LexSort \ - (*(PyObject * (*)(PyObject *, int)) \ - PyArray_API[189]) -#define PyArray_Round \ - (*(PyObject * (*)(PyArrayObject *, int, PyArrayObject *)) \ - PyArray_API[190]) -#define PyArray_EquivTypenums \ - (*(unsigned char (*)(int, int)) \ - PyArray_API[191]) -#define PyArray_RegisterDataType \ - (*(int (*)(PyArray_Descr *)) \ - PyArray_API[192]) -#define PyArray_RegisterCastFunc \ - (*(int (*)(PyArray_Descr *, int, PyArray_VectorUnaryFunc *)) \ - PyArray_API[193]) -#define PyArray_RegisterCanCast \ - (*(int (*)(PyArray_Descr *, int, NPY_SCALARKIND)) \ - PyArray_API[194]) -#define PyArray_InitArrFuncs \ - (*(void (*)(PyArray_ArrFuncs *)) \ - PyArray_API[195]) -#define PyArray_IntTupleFromIntp \ - (*(PyObject * (*)(int, npy_intp *)) \ - PyArray_API[196]) -#define PyArray_TypeNumFromName \ - (*(int (*)(char *)) \ - PyArray_API[197]) -#define PyArray_ClipmodeConverter \ - (*(int (*)(PyObject *, NPY_CLIPMODE *)) \ - PyArray_API[198]) -#define PyArray_OutputConverter \ - (*(int (*)(PyObject *, PyArrayObject **)) \ - PyArray_API[199]) -#define PyArray_BroadcastToShape \ - (*(PyObject * (*)(PyObject *, npy_intp *, int)) \ - PyArray_API[200]) -#define _PyArray_SigintHandler \ - (*(void (*)(int)) \ - PyArray_API[201]) -#define _PyArray_GetSigintBuf \ - (*(void* (*)(void)) \ - PyArray_API[202]) -#define PyArray_DescrAlignConverter \ - (*(int (*)(PyObject *, PyArray_Descr **)) \ - PyArray_API[203]) -#define PyArray_DescrAlignConverter2 \ - (*(int (*)(PyObject *, PyArray_Descr **)) \ - PyArray_API[204]) -#define PyArray_SearchsideConverter \ - (*(int (*)(PyObject *, void *)) \ - PyArray_API[205]) -#define PyArray_CheckAxis \ - (*(PyObject * (*)(PyArrayObject *, int *, int)) \ - PyArray_API[206]) -#define PyArray_OverflowMultiplyList \ - (*(npy_intp (*)(npy_intp *, int)) \ - PyArray_API[207]) -#define PyArray_CompareString \ - (*(int (*)(char *, char *, size_t)) \ - PyArray_API[208]) -#define PyArray_MultiIterFromObjects \ - (*(PyObject * (*)(PyObject **, int, int, ...)) \ - PyArray_API[209]) -#define PyArray_GetEndianness \ - (*(int (*)(void)) \ - PyArray_API[210]) -#define PyArray_GetNDArrayCFeatureVersion \ - (*(unsigned int (*)(void)) \ - PyArray_API[211]) -#define PyArray_Correlate2 \ - (*(PyObject * (*)(PyObject *, PyObject *, int)) \ - PyArray_API[212]) -#define PyArray_NeighborhoodIterNew \ - (*(PyObject* (*)(PyArrayIterObject *, npy_intp *, int, PyArrayObject*)) \ - PyArray_API[213]) -#define PyTimeIntegerArrType_Type (*(PyTypeObject *)PyArray_API[214]) -#define PyDatetimeArrType_Type (*(PyTypeObject *)PyArray_API[215]) -#define PyTimedeltaArrType_Type (*(PyTypeObject *)PyArray_API[216]) -#define PyHalfArrType_Type (*(PyTypeObject *)PyArray_API[217]) -#define NpyIter_Type (*(PyTypeObject *)PyArray_API[218]) -#define PyArray_SetDatetimeParseFunction \ - (*(void (*)(PyObject *)) \ - PyArray_API[219]) -#define PyArray_DatetimeToDatetimeStruct \ - (*(void (*)(npy_datetime, NPY_DATETIMEUNIT, npy_datetimestruct *)) \ - PyArray_API[220]) -#define PyArray_TimedeltaToTimedeltaStruct \ - (*(void (*)(npy_timedelta, NPY_DATETIMEUNIT, npy_timedeltastruct *)) \ - PyArray_API[221]) -#define PyArray_DatetimeStructToDatetime \ - (*(npy_datetime (*)(NPY_DATETIMEUNIT, npy_datetimestruct *)) \ - PyArray_API[222]) -#define PyArray_TimedeltaStructToTimedelta \ - (*(npy_datetime (*)(NPY_DATETIMEUNIT, npy_timedeltastruct *)) \ - PyArray_API[223]) -#define NpyIter_New \ - (*(NpyIter * (*)(PyArrayObject *, npy_uint32, NPY_ORDER, NPY_CASTING, PyArray_Descr*)) \ - PyArray_API[224]) -#define NpyIter_MultiNew \ - (*(NpyIter * (*)(int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **)) \ - PyArray_API[225]) -#define NpyIter_AdvancedNew \ - (*(NpyIter * (*)(int, PyArrayObject **, npy_uint32, NPY_ORDER, NPY_CASTING, npy_uint32 *, PyArray_Descr **, int, int **, npy_intp *, npy_intp)) \ - PyArray_API[226]) -#define NpyIter_Copy \ - (*(NpyIter * (*)(NpyIter *)) \ - PyArray_API[227]) -#define NpyIter_Deallocate \ - (*(int (*)(NpyIter *)) \ - PyArray_API[228]) -#define NpyIter_HasDelayedBufAlloc \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[229]) -#define NpyIter_HasExternalLoop \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[230]) -#define NpyIter_EnableExternalLoop \ - (*(int (*)(NpyIter *)) \ - PyArray_API[231]) -#define NpyIter_GetInnerStrideArray \ - (*(npy_intp * (*)(NpyIter *)) \ - PyArray_API[232]) -#define NpyIter_GetInnerLoopSizePtr \ - (*(npy_intp * (*)(NpyIter *)) \ - PyArray_API[233]) -#define NpyIter_Reset \ - (*(int (*)(NpyIter *, char **)) \ - PyArray_API[234]) -#define NpyIter_ResetBasePointers \ - (*(int (*)(NpyIter *, char **, char **)) \ - PyArray_API[235]) -#define NpyIter_ResetToIterIndexRange \ - (*(int (*)(NpyIter *, npy_intp, npy_intp, char **)) \ - PyArray_API[236]) -#define NpyIter_GetNDim \ - (*(int (*)(NpyIter *)) \ - PyArray_API[237]) -#define NpyIter_GetNOp \ - (*(int (*)(NpyIter *)) \ - PyArray_API[238]) -#define NpyIter_GetIterNext \ - (*(NpyIter_IterNextFunc * (*)(NpyIter *, char **)) \ - PyArray_API[239]) -#define NpyIter_GetIterSize \ - (*(npy_intp (*)(NpyIter *)) \ - PyArray_API[240]) -#define NpyIter_GetIterIndexRange \ - (*(void (*)(NpyIter *, npy_intp *, npy_intp *)) \ - PyArray_API[241]) -#define NpyIter_GetIterIndex \ - (*(npy_intp (*)(NpyIter *)) \ - PyArray_API[242]) -#define NpyIter_GotoIterIndex \ - (*(int (*)(NpyIter *, npy_intp)) \ - PyArray_API[243]) -#define NpyIter_HasMultiIndex \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[244]) -#define NpyIter_GetShape \ - (*(int (*)(NpyIter *, npy_intp *)) \ - PyArray_API[245]) -#define NpyIter_GetGetMultiIndex \ - (*(NpyIter_GetMultiIndexFunc * (*)(NpyIter *, char **)) \ - PyArray_API[246]) -#define NpyIter_GotoMultiIndex \ - (*(int (*)(NpyIter *, npy_intp *)) \ - PyArray_API[247]) -#define NpyIter_RemoveMultiIndex \ - (*(int (*)(NpyIter *)) \ - PyArray_API[248]) -#define NpyIter_HasIndex \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[249]) -#define NpyIter_IsBuffered \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[250]) -#define NpyIter_IsGrowInner \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[251]) -#define NpyIter_GetBufferSize \ - (*(npy_intp (*)(NpyIter *)) \ - PyArray_API[252]) -#define NpyIter_GetIndexPtr \ - (*(npy_intp * (*)(NpyIter *)) \ - PyArray_API[253]) -#define NpyIter_GotoIndex \ - (*(int (*)(NpyIter *, npy_intp)) \ - PyArray_API[254]) -#define NpyIter_GetDataPtrArray \ - (*(char ** (*)(NpyIter *)) \ - PyArray_API[255]) -#define NpyIter_GetDescrArray \ - (*(PyArray_Descr ** (*)(NpyIter *)) \ - PyArray_API[256]) -#define NpyIter_GetOperandArray \ - (*(PyArrayObject ** (*)(NpyIter *)) \ - PyArray_API[257]) -#define NpyIter_GetIterView \ - (*(PyArrayObject * (*)(NpyIter *, npy_intp)) \ - PyArray_API[258]) -#define NpyIter_GetReadFlags \ - (*(void (*)(NpyIter *, char *)) \ - PyArray_API[259]) -#define NpyIter_GetWriteFlags \ - (*(void (*)(NpyIter *, char *)) \ - PyArray_API[260]) -#define NpyIter_DebugPrint \ - (*(void (*)(NpyIter *)) \ - PyArray_API[261]) -#define NpyIter_IterationNeedsAPI \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[262]) -#define NpyIter_GetInnerFixedStrideArray \ - (*(void (*)(NpyIter *, npy_intp *)) \ - PyArray_API[263]) -#define NpyIter_RemoveAxis \ - (*(int (*)(NpyIter *, int)) \ - PyArray_API[264]) -#define NpyIter_GetAxisStrideArray \ - (*(npy_intp * (*)(NpyIter *, int)) \ - PyArray_API[265]) -#define NpyIter_RequiresBuffering \ - (*(npy_bool (*)(NpyIter *)) \ - PyArray_API[266]) -#define NpyIter_GetInitialDataPtrArray \ - (*(char ** (*)(NpyIter *)) \ - PyArray_API[267]) -#define NpyIter_CreateCompatibleStrides \ - (*(int (*)(NpyIter *, npy_intp, npy_intp *)) \ - PyArray_API[268]) -#define PyArray_CastingConverter \ - (*(int (*)(PyObject *, NPY_CASTING *)) \ - PyArray_API[269]) -#define PyArray_CountNonzero \ - (*(npy_intp (*)(PyArrayObject *)) \ - PyArray_API[270]) -#define PyArray_PromoteTypes \ - (*(PyArray_Descr * (*)(PyArray_Descr *, PyArray_Descr *)) \ - PyArray_API[271]) -#define PyArray_MinScalarType \ - (*(PyArray_Descr * (*)(PyArrayObject *)) \ - PyArray_API[272]) -#define PyArray_ResultType \ - (*(PyArray_Descr * (*)(npy_intp, PyArrayObject **, npy_intp, PyArray_Descr **)) \ - PyArray_API[273]) -#define PyArray_CanCastArrayTo \ - (*(npy_bool (*)(PyArrayObject *, PyArray_Descr *, NPY_CASTING)) \ - PyArray_API[274]) -#define PyArray_CanCastTypeTo \ - (*(npy_bool (*)(PyArray_Descr *, PyArray_Descr *, NPY_CASTING)) \ - PyArray_API[275]) -#define PyArray_EinsteinSum \ - (*(PyArrayObject * (*)(char *, npy_intp, PyArrayObject **, PyArray_Descr *, NPY_ORDER, NPY_CASTING, PyArrayObject *)) \ - PyArray_API[276]) -#define PyArray_NewLikeArray \ - (*(PyObject * (*)(PyArrayObject *, NPY_ORDER, PyArray_Descr *, int)) \ - PyArray_API[277]) -#define PyArray_GetArrayParamsFromObject \ - (*(int (*)(PyObject *, PyArray_Descr *, npy_bool, PyArray_Descr **, int *, npy_intp *, PyArrayObject **, PyObject *)) \ - PyArray_API[278]) -#define PyArray_ConvertClipmodeSequence \ - (*(int (*)(PyObject *, NPY_CLIPMODE *, int)) \ - PyArray_API[279]) -#define PyArray_MatrixProduct2 \ - (*(PyObject * (*)(PyObject *, PyObject *, PyArrayObject*)) \ - PyArray_API[280]) -#define NpyIter_IsFirstVisit \ - (*(npy_bool (*)(NpyIter *, int)) \ - PyArray_API[281]) -#define PyArray_SetBaseObject \ - (*(int (*)(PyArrayObject *, PyObject *)) \ - PyArray_API[282]) -#define PyArray_CreateSortedStridePerm \ - (*(void (*)(int, npy_intp *, npy_stride_sort_item *)) \ - PyArray_API[283]) -#define PyArray_RemoveAxesInPlace \ - (*(void (*)(PyArrayObject *, npy_bool *)) \ - PyArray_API[284]) -#define PyArray_DebugPrint \ - (*(void (*)(PyArrayObject *)) \ - PyArray_API[285]) -#define PyArray_FailUnlessWriteable \ - (*(int (*)(PyArrayObject *, const char *)) \ - PyArray_API[286]) -#define PyArray_SetUpdateIfCopyBase \ - (*(int (*)(PyArrayObject *, PyArrayObject *)) \ - PyArray_API[287]) -#define PyDataMem_NEW \ - (*(void * (*)(size_t)) \ - PyArray_API[288]) -#define PyDataMem_FREE \ - (*(void (*)(void *)) \ - PyArray_API[289]) -#define PyDataMem_RENEW \ - (*(void * (*)(void *, size_t)) \ - PyArray_API[290]) -#define PyDataMem_SetEventHook \ - (*(PyDataMem_EventHookFunc * (*)(PyDataMem_EventHookFunc *, void *, void **)) \ - PyArray_API[291]) -#define NPY_DEFAULT_ASSIGN_CASTING (*(NPY_CASTING *)PyArray_API[292]) -#define PyArray_MapIterSwapAxes \ - (*(void (*)(PyArrayMapIterObject *, PyArrayObject **, int)) \ - PyArray_API[293]) -#define PyArray_MapIterArray \ - (*(PyObject * (*)(PyArrayObject *, PyObject *)) \ - PyArray_API[294]) -#define PyArray_MapIterNext \ - (*(void (*)(PyArrayMapIterObject *)) \ - PyArray_API[295]) -#define PyArray_Partition \ - (*(int (*)(PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND)) \ - PyArray_API[296]) -#define PyArray_ArgPartition \ - (*(PyObject * (*)(PyArrayObject *, PyArrayObject *, int, NPY_SELECTKIND)) \ - PyArray_API[297]) -#define PyArray_SelectkindConverter \ - (*(int (*)(PyObject *, NPY_SELECTKIND *)) \ - PyArray_API[298]) -#define PyDataMem_NEW_ZEROED \ - (*(void * (*)(size_t, size_t)) \ - PyArray_API[299]) - -#if !defined(NO_IMPORT_ARRAY) && !defined(NO_IMPORT) -static int -_import_array(void) -{ - int st; - PyObject *numpy = PyImport_ImportModule("numpy.core.multiarray"); - PyObject *c_api = NULL; - - if (numpy == NULL) { - PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); - return -1; - } - c_api = PyObject_GetAttrString(numpy, "_ARRAY_API"); - Py_DECREF(numpy); - if (c_api == NULL) { - PyErr_SetString(PyExc_AttributeError, "_ARRAY_API not found"); - return -1; - } - -#if PY_VERSION_HEX >= 0x03000000 - if (!PyCapsule_CheckExact(c_api)) { - PyErr_SetString(PyExc_RuntimeError, "_ARRAY_API is not PyCapsule object"); - Py_DECREF(c_api); - return -1; - } - PyArray_API = (void **)PyCapsule_GetPointer(c_api, NULL); -#else - if (!PyCObject_Check(c_api)) { - PyErr_SetString(PyExc_RuntimeError, "_ARRAY_API is not PyCObject object"); - Py_DECREF(c_api); - return -1; - } - PyArray_API = (void **)PyCObject_AsVoidPtr(c_api); -#endif - Py_DECREF(c_api); - if (PyArray_API == NULL) { - PyErr_SetString(PyExc_RuntimeError, "_ARRAY_API is NULL pointer"); - return -1; - } - - /* Perform runtime check of C API version */ - if (NPY_VERSION != PyArray_GetNDArrayCVersion()) { - PyErr_Format(PyExc_RuntimeError, "module compiled against "\ - "ABI version %x but this version of numpy is %x", \ - (int) NPY_VERSION, (int) PyArray_GetNDArrayCVersion()); - return -1; - } - if (NPY_FEATURE_VERSION > PyArray_GetNDArrayCFeatureVersion()) { - PyErr_Format(PyExc_RuntimeError, "module compiled against "\ - "API version %x but this version of numpy is %x", \ - (int) NPY_FEATURE_VERSION, (int) PyArray_GetNDArrayCFeatureVersion()); - return -1; - } - - /* - * Perform runtime check of endianness and check it matches the one set by - * the headers (npy_endian.h) as a safeguard - */ - st = PyArray_GetEndianness(); - if (st == NPY_CPU_UNKNOWN_ENDIAN) { - PyErr_Format(PyExc_RuntimeError, "FATAL: module compiled as unknown endian"); - return -1; - } -#if NPY_BYTE_ORDER == NPY_BIG_ENDIAN - if (st != NPY_CPU_BIG) { - PyErr_Format(PyExc_RuntimeError, "FATAL: module compiled as "\ - "big endian, but detected different endianness at runtime"); - return -1; - } -#elif NPY_BYTE_ORDER == NPY_LITTLE_ENDIAN - if (st != NPY_CPU_LITTLE) { - PyErr_Format(PyExc_RuntimeError, "FATAL: module compiled as "\ - "little endian, but detected different endianness at runtime"); - return -1; - } -#endif - - return 0; -} - -#if PY_VERSION_HEX >= 0x03000000 -#define NUMPY_IMPORT_ARRAY_RETVAL NULL -#else -#define NUMPY_IMPORT_ARRAY_RETVAL -#endif - -#define import_array() {if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); return NUMPY_IMPORT_ARRAY_RETVAL; } } - -#define import_array1(ret) {if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); return ret; } } - -#define import_array2(msg, ret) {if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, msg); return ret; } } - -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h deleted file mode 100644 index 358523193..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/__ufunc_api.h +++ /dev/null @@ -1,328 +0,0 @@ - -#ifdef _UMATHMODULE - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION -extern NPY_NO_EXPORT PyTypeObject PyUFunc_Type; -#else -NPY_NO_EXPORT PyTypeObject PyUFunc_Type; -#endif - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - extern NPY_NO_EXPORT PyTypeObject PyUFunc_Type; -#else - NPY_NO_EXPORT PyTypeObject PyUFunc_Type; -#endif - -NPY_NO_EXPORT PyObject * PyUFunc_FromFuncAndData \ - (PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int); -NPY_NO_EXPORT int PyUFunc_RegisterLoopForType \ - (PyUFuncObject *, int, PyUFuncGenericFunction, int *, void *); -NPY_NO_EXPORT int PyUFunc_GenericFunction \ - (PyUFuncObject *, PyObject *, PyObject *, PyArrayObject **); -NPY_NO_EXPORT void PyUFunc_f_f_As_d_d \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_d_d \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_f_f \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_g_g \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_F_F_As_D_D \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_F_F \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_D_D \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_G_G \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_O_O \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_ff_f_As_dd_d \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_ff_f \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_dd_d \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_gg_g \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_FF_F_As_DD_D \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_DD_D \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_FF_F \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_GG_G \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_OO_O \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_O_O_method \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_OO_O_method \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_On_Om \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT int PyUFunc_GetPyValues \ - (char *, int *, int *, PyObject **); -NPY_NO_EXPORT int PyUFunc_checkfperr \ - (int, PyObject *, int *); -NPY_NO_EXPORT void PyUFunc_clearfperr \ - (void); -NPY_NO_EXPORT int PyUFunc_getfperr \ - (void); -NPY_NO_EXPORT int PyUFunc_handlefperr \ - (int, PyObject *, int, int *); -NPY_NO_EXPORT int PyUFunc_ReplaceLoopBySignature \ - (PyUFuncObject *, PyUFuncGenericFunction, int *, PyUFuncGenericFunction *); -NPY_NO_EXPORT PyObject * PyUFunc_FromFuncAndDataAndSignature \ - (PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int, const char *); -NPY_NO_EXPORT int PyUFunc_SetUsesArraysAsData \ - (void **, size_t); -NPY_NO_EXPORT void PyUFunc_e_e \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_e_e_As_f_f \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_e_e_As_d_d \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_ee_e \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_ee_e_As_ff_f \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT void PyUFunc_ee_e_As_dd_d \ - (char **, npy_intp *, npy_intp *, void *); -NPY_NO_EXPORT int PyUFunc_DefaultTypeResolver \ - (PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyObject *, PyArray_Descr **); -NPY_NO_EXPORT int PyUFunc_ValidateCasting \ - (PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyArray_Descr **); -NPY_NO_EXPORT int PyUFunc_RegisterLoopForDescr \ - (PyUFuncObject *, PyArray_Descr *, PyUFuncGenericFunction, PyArray_Descr **, void *); - -#else - -#if defined(PY_UFUNC_UNIQUE_SYMBOL) -#define PyUFunc_API PY_UFUNC_UNIQUE_SYMBOL -#endif - -#if defined(NO_IMPORT) || defined(NO_IMPORT_UFUNC) -extern void **PyUFunc_API; -#else -#if defined(PY_UFUNC_UNIQUE_SYMBOL) -void **PyUFunc_API; -#else -static void **PyUFunc_API=NULL; -#endif -#endif - -#define PyUFunc_Type (*(PyTypeObject *)PyUFunc_API[0]) -#define PyUFunc_FromFuncAndData \ - (*(PyObject * (*)(PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int)) \ - PyUFunc_API[1]) -#define PyUFunc_RegisterLoopForType \ - (*(int (*)(PyUFuncObject *, int, PyUFuncGenericFunction, int *, void *)) \ - PyUFunc_API[2]) -#define PyUFunc_GenericFunction \ - (*(int (*)(PyUFuncObject *, PyObject *, PyObject *, PyArrayObject **)) \ - PyUFunc_API[3]) -#define PyUFunc_f_f_As_d_d \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[4]) -#define PyUFunc_d_d \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[5]) -#define PyUFunc_f_f \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[6]) -#define PyUFunc_g_g \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[7]) -#define PyUFunc_F_F_As_D_D \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[8]) -#define PyUFunc_F_F \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[9]) -#define PyUFunc_D_D \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[10]) -#define PyUFunc_G_G \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[11]) -#define PyUFunc_O_O \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[12]) -#define PyUFunc_ff_f_As_dd_d \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[13]) -#define PyUFunc_ff_f \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[14]) -#define PyUFunc_dd_d \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[15]) -#define PyUFunc_gg_g \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[16]) -#define PyUFunc_FF_F_As_DD_D \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[17]) -#define PyUFunc_DD_D \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[18]) -#define PyUFunc_FF_F \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[19]) -#define PyUFunc_GG_G \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[20]) -#define PyUFunc_OO_O \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[21]) -#define PyUFunc_O_O_method \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[22]) -#define PyUFunc_OO_O_method \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[23]) -#define PyUFunc_On_Om \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[24]) -#define PyUFunc_GetPyValues \ - (*(int (*)(char *, int *, int *, PyObject **)) \ - PyUFunc_API[25]) -#define PyUFunc_checkfperr \ - (*(int (*)(int, PyObject *, int *)) \ - PyUFunc_API[26]) -#define PyUFunc_clearfperr \ - (*(void (*)(void)) \ - PyUFunc_API[27]) -#define PyUFunc_getfperr \ - (*(int (*)(void)) \ - PyUFunc_API[28]) -#define PyUFunc_handlefperr \ - (*(int (*)(int, PyObject *, int, int *)) \ - PyUFunc_API[29]) -#define PyUFunc_ReplaceLoopBySignature \ - (*(int (*)(PyUFuncObject *, PyUFuncGenericFunction, int *, PyUFuncGenericFunction *)) \ - PyUFunc_API[30]) -#define PyUFunc_FromFuncAndDataAndSignature \ - (*(PyObject * (*)(PyUFuncGenericFunction *, void **, char *, int, int, int, int, char *, char *, int, const char *)) \ - PyUFunc_API[31]) -#define PyUFunc_SetUsesArraysAsData \ - (*(int (*)(void **, size_t)) \ - PyUFunc_API[32]) -#define PyUFunc_e_e \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[33]) -#define PyUFunc_e_e_As_f_f \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[34]) -#define PyUFunc_e_e_As_d_d \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[35]) -#define PyUFunc_ee_e \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[36]) -#define PyUFunc_ee_e_As_ff_f \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[37]) -#define PyUFunc_ee_e_As_dd_d \ - (*(void (*)(char **, npy_intp *, npy_intp *, void *)) \ - PyUFunc_API[38]) -#define PyUFunc_DefaultTypeResolver \ - (*(int (*)(PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyObject *, PyArray_Descr **)) \ - PyUFunc_API[39]) -#define PyUFunc_ValidateCasting \ - (*(int (*)(PyUFuncObject *, NPY_CASTING, PyArrayObject **, PyArray_Descr **)) \ - PyUFunc_API[40]) -#define PyUFunc_RegisterLoopForDescr \ - (*(int (*)(PyUFuncObject *, PyArray_Descr *, PyUFuncGenericFunction, PyArray_Descr **, void *)) \ - PyUFunc_API[41]) - -static int -_import_umath(void) -{ - PyObject *numpy = PyImport_ImportModule("numpy.core.umath"); - PyObject *c_api = NULL; - - if (numpy == NULL) { - PyErr_SetString(PyExc_ImportError, "numpy.core.umath failed to import"); - return -1; - } - c_api = PyObject_GetAttrString(numpy, "_UFUNC_API"); - Py_DECREF(numpy); - if (c_api == NULL) { - PyErr_SetString(PyExc_AttributeError, "_UFUNC_API not found"); - return -1; - } - -#if PY_VERSION_HEX >= 0x03000000 - if (!PyCapsule_CheckExact(c_api)) { - PyErr_SetString(PyExc_RuntimeError, "_UFUNC_API is not PyCapsule object"); - Py_DECREF(c_api); - return -1; - } - PyUFunc_API = (void **)PyCapsule_GetPointer(c_api, NULL); -#else - if (!PyCObject_Check(c_api)) { - PyErr_SetString(PyExc_RuntimeError, "_UFUNC_API is not PyCObject object"); - Py_DECREF(c_api); - return -1; - } - PyUFunc_API = (void **)PyCObject_AsVoidPtr(c_api); -#endif - Py_DECREF(c_api); - if (PyUFunc_API == NULL) { - PyErr_SetString(PyExc_RuntimeError, "_UFUNC_API is NULL pointer"); - return -1; - } - return 0; -} - -#if PY_VERSION_HEX >= 0x03000000 -#define NUMPY_IMPORT_UMATH_RETVAL NULL -#else -#define NUMPY_IMPORT_UMATH_RETVAL -#endif - -#define import_umath() \ - do {\ - UFUNC_NOFPE\ - if (_import_umath() < 0) {\ - PyErr_Print();\ - PyErr_SetString(PyExc_ImportError,\ - "numpy.core.umath failed to import");\ - return NUMPY_IMPORT_UMATH_RETVAL;\ - }\ - } while(0) - -#define import_umath1(ret) \ - do {\ - UFUNC_NOFPE\ - if (_import_umath() < 0) {\ - PyErr_Print();\ - PyErr_SetString(PyExc_ImportError,\ - "numpy.core.umath failed to import");\ - return ret;\ - }\ - } while(0) - -#define import_umath2(ret, msg) \ - do {\ - UFUNC_NOFPE\ - if (_import_umath() < 0) {\ - PyErr_Print();\ - PyErr_SetString(PyExc_ImportError, msg);\ - return ret;\ - }\ - } while(0) - -#define import_ufunc() \ - do {\ - UFUNC_NOFPE\ - if (_import_umath() < 0) {\ - PyErr_Print();\ - PyErr_SetString(PyExc_ImportError,\ - "numpy.core.umath failed to import");\ - }\ - } while(0) - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h b/gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h deleted file mode 100644 index e8860cbc7..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/_neighborhood_iterator_imp.h +++ /dev/null @@ -1,90 +0,0 @@ -#ifndef _NPY_INCLUDE_NEIGHBORHOOD_IMP -#error You should not include this header directly -#endif -/* - * Private API (here for inline) - */ -static NPY_INLINE int -_PyArrayNeighborhoodIter_IncrCoord(PyArrayNeighborhoodIterObject* iter); - -/* - * Update to next item of the iterator - * - * Note: this simply increment the coordinates vector, last dimension - * incremented first , i.e, for dimension 3 - * ... - * -1, -1, -1 - * -1, -1, 0 - * -1, -1, 1 - * .... - * -1, 0, -1 - * -1, 0, 0 - * .... - * 0, -1, -1 - * 0, -1, 0 - * .... - */ -#define _UPDATE_COORD_ITER(c) \ - wb = iter->coordinates[c] < iter->bounds[c][1]; \ - if (wb) { \ - iter->coordinates[c] += 1; \ - return 0; \ - } \ - else { \ - iter->coordinates[c] = iter->bounds[c][0]; \ - } - -static NPY_INLINE int -_PyArrayNeighborhoodIter_IncrCoord(PyArrayNeighborhoodIterObject* iter) -{ - npy_intp i, wb; - - for (i = iter->nd - 1; i >= 0; --i) { - _UPDATE_COORD_ITER(i) - } - - return 0; -} - -/* - * Version optimized for 2d arrays, manual loop unrolling - */ -static NPY_INLINE int -_PyArrayNeighborhoodIter_IncrCoord2D(PyArrayNeighborhoodIterObject* iter) -{ - npy_intp wb; - - _UPDATE_COORD_ITER(1) - _UPDATE_COORD_ITER(0) - - return 0; -} -#undef _UPDATE_COORD_ITER - -/* - * Advance to the next neighbour - */ -static NPY_INLINE int -PyArrayNeighborhoodIter_Next(PyArrayNeighborhoodIterObject* iter) -{ - _PyArrayNeighborhoodIter_IncrCoord (iter); - iter->dataptr = iter->translate((PyArrayIterObject*)iter, iter->coordinates); - - return 0; -} - -/* - * Reset functions - */ -static NPY_INLINE int -PyArrayNeighborhoodIter_Reset(PyArrayNeighborhoodIterObject* iter) -{ - npy_intp i; - - for (i = 0; i < iter->nd; ++i) { - iter->coordinates[i] = iter->bounds[i][0]; - } - iter->dataptr = iter->translate((PyArrayIterObject*)iter, iter->coordinates); - - return 0; -} diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h b/gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h deleted file mode 100644 index 79ccc2904..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/_numpyconfig.h +++ /dev/null @@ -1,32 +0,0 @@ -#define NPY_HAVE_ENDIAN_H 1 -#define NPY_SIZEOF_SHORT SIZEOF_SHORT -#define NPY_SIZEOF_INT SIZEOF_INT -#define NPY_SIZEOF_LONG SIZEOF_LONG -#define NPY_SIZEOF_FLOAT 4 -#define NPY_SIZEOF_COMPLEX_FLOAT 8 -#define NPY_SIZEOF_DOUBLE 8 -#define NPY_SIZEOF_COMPLEX_DOUBLE 16 -#define NPY_SIZEOF_LONGDOUBLE 16 -#define NPY_SIZEOF_COMPLEX_LONGDOUBLE 32 -#define NPY_SIZEOF_PY_INTPTR_T 8 -#define NPY_SIZEOF_OFF_T 8 -#define NPY_SIZEOF_PY_LONG_LONG 8 -#define NPY_SIZEOF_LONGLONG 8 -#define NPY_NO_SMP 0 -#define NPY_HAVE_DECL_ISNAN -#define NPY_HAVE_DECL_ISINF -#define NPY_HAVE_DECL_ISFINITE -#define NPY_HAVE_DECL_SIGNBIT -#define NPY_USE_C99_COMPLEX 1 -#define NPY_HAVE_COMPLEX_DOUBLE 1 -#define NPY_HAVE_COMPLEX_FLOAT 1 -#define NPY_HAVE_COMPLEX_LONG_DOUBLE 1 -#define NPY_ENABLE_SEPARATE_COMPILATION 1 -#define NPY_USE_C99_FORMATS 1 -#define NPY_VISIBILITY_HIDDEN __attribute__((visibility("hidden"))) -#define NPY_ABI_VERSION 0x01000009 -#define NPY_API_VERSION 0x00000009 - -#ifndef __STDC_FORMAT_MACROS -#define __STDC_FORMAT_MACROS 1 -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h b/gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h deleted file mode 100644 index 4f46d6b1a..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/arrayobject.h +++ /dev/null @@ -1,11 +0,0 @@ -#ifndef Py_ARRAYOBJECT_H -#define Py_ARRAYOBJECT_H - -#include "ndarrayobject.h" -#include "npy_interrupt.h" - -#ifdef NPY_NO_PREFIX -#include "noprefix.h" -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h b/gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h deleted file mode 100644 index 64450e713..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/arrayscalars.h +++ /dev/null @@ -1,175 +0,0 @@ -#ifndef _NPY_ARRAYSCALARS_H_ -#define _NPY_ARRAYSCALARS_H_ - -#ifndef _MULTIARRAYMODULE -typedef struct { - PyObject_HEAD - npy_bool obval; -} PyBoolScalarObject; -#endif - - -typedef struct { - PyObject_HEAD - signed char obval; -} PyByteScalarObject; - - -typedef struct { - PyObject_HEAD - short obval; -} PyShortScalarObject; - - -typedef struct { - PyObject_HEAD - int obval; -} PyIntScalarObject; - - -typedef struct { - PyObject_HEAD - long obval; -} PyLongScalarObject; - - -typedef struct { - PyObject_HEAD - npy_longlong obval; -} PyLongLongScalarObject; - - -typedef struct { - PyObject_HEAD - unsigned char obval; -} PyUByteScalarObject; - - -typedef struct { - PyObject_HEAD - unsigned short obval; -} PyUShortScalarObject; - - -typedef struct { - PyObject_HEAD - unsigned int obval; -} PyUIntScalarObject; - - -typedef struct { - PyObject_HEAD - unsigned long obval; -} PyULongScalarObject; - - -typedef struct { - PyObject_HEAD - npy_ulonglong obval; -} PyULongLongScalarObject; - - -typedef struct { - PyObject_HEAD - npy_half obval; -} PyHalfScalarObject; - - -typedef struct { - PyObject_HEAD - float obval; -} PyFloatScalarObject; - - -typedef struct { - PyObject_HEAD - double obval; -} PyDoubleScalarObject; - - -typedef struct { - PyObject_HEAD - npy_longdouble obval; -} PyLongDoubleScalarObject; - - -typedef struct { - PyObject_HEAD - npy_cfloat obval; -} PyCFloatScalarObject; - - -typedef struct { - PyObject_HEAD - npy_cdouble obval; -} PyCDoubleScalarObject; - - -typedef struct { - PyObject_HEAD - npy_clongdouble obval; -} PyCLongDoubleScalarObject; - - -typedef struct { - PyObject_HEAD - PyObject * obval; -} PyObjectScalarObject; - -typedef struct { - PyObject_HEAD - npy_datetime obval; - PyArray_DatetimeMetaData obmeta; -} PyDatetimeScalarObject; - -typedef struct { - PyObject_HEAD - npy_timedelta obval; - PyArray_DatetimeMetaData obmeta; -} PyTimedeltaScalarObject; - - -typedef struct { - PyObject_HEAD - char obval; -} PyScalarObject; - -#define PyStringScalarObject PyStringObject -#define PyUnicodeScalarObject PyUnicodeObject - -typedef struct { - PyObject_VAR_HEAD - char *obval; - PyArray_Descr *descr; - int flags; - PyObject *base; -} PyVoidScalarObject; - -/* Macros - PyScalarObject - PyArrType_Type - are defined in ndarrayobject.h -*/ - -#define PyArrayScalar_False ((PyObject *)(&(_PyArrayScalar_BoolValues[0]))) -#define PyArrayScalar_True ((PyObject *)(&(_PyArrayScalar_BoolValues[1]))) -#define PyArrayScalar_FromLong(i) \ - ((PyObject *)(&(_PyArrayScalar_BoolValues[((i)!=0)]))) -#define PyArrayScalar_RETURN_BOOL_FROM_LONG(i) \ - return Py_INCREF(PyArrayScalar_FromLong(i)), \ - PyArrayScalar_FromLong(i) -#define PyArrayScalar_RETURN_FALSE \ - return Py_INCREF(PyArrayScalar_False), \ - PyArrayScalar_False -#define PyArrayScalar_RETURN_TRUE \ - return Py_INCREF(PyArrayScalar_True), \ - PyArrayScalar_True - -#define PyArrayScalar_New(cls) \ - Py##cls##ArrType_Type.tp_alloc(&Py##cls##ArrType_Type, 0) -#define PyArrayScalar_VAL(obj, cls) \ - ((Py##cls##ScalarObject *)obj)->obval -#define PyArrayScalar_ASSIGN(obj, cls, val) \ - PyArrayScalar_VAL(obj, cls) = val - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h b/gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h deleted file mode 100644 index 944f0ea34..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/halffloat.h +++ /dev/null @@ -1,69 +0,0 @@ -#ifndef __NPY_HALFFLOAT_H__ -#define __NPY_HALFFLOAT_H__ - -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * Half-precision routines - */ - -/* Conversions */ -float npy_half_to_float(npy_half h); -double npy_half_to_double(npy_half h); -npy_half npy_float_to_half(float f); -npy_half npy_double_to_half(double d); -/* Comparisons */ -int npy_half_eq(npy_half h1, npy_half h2); -int npy_half_ne(npy_half h1, npy_half h2); -int npy_half_le(npy_half h1, npy_half h2); -int npy_half_lt(npy_half h1, npy_half h2); -int npy_half_ge(npy_half h1, npy_half h2); -int npy_half_gt(npy_half h1, npy_half h2); -/* faster *_nonan variants for when you know h1 and h2 are not NaN */ -int npy_half_eq_nonan(npy_half h1, npy_half h2); -int npy_half_lt_nonan(npy_half h1, npy_half h2); -int npy_half_le_nonan(npy_half h1, npy_half h2); -/* Miscellaneous functions */ -int npy_half_iszero(npy_half h); -int npy_half_isnan(npy_half h); -int npy_half_isinf(npy_half h); -int npy_half_isfinite(npy_half h); -int npy_half_signbit(npy_half h); -npy_half npy_half_copysign(npy_half x, npy_half y); -npy_half npy_half_spacing(npy_half h); -npy_half npy_half_nextafter(npy_half x, npy_half y); - -/* - * Half-precision constants - */ - -#define NPY_HALF_ZERO (0x0000u) -#define NPY_HALF_PZERO (0x0000u) -#define NPY_HALF_NZERO (0x8000u) -#define NPY_HALF_ONE (0x3c00u) -#define NPY_HALF_NEGONE (0xbc00u) -#define NPY_HALF_PINF (0x7c00u) -#define NPY_HALF_NINF (0xfc00u) -#define NPY_HALF_NAN (0x7e00u) - -#define NPY_MAX_HALF (0x7bffu) - -/* - * Bit-level conversions - */ - -npy_uint16 npy_floatbits_to_halfbits(npy_uint32 f); -npy_uint16 npy_doublebits_to_halfbits(npy_uint64 d); -npy_uint32 npy_halfbits_to_floatbits(npy_uint16 h); -npy_uint64 npy_halfbits_to_doublebits(npy_uint16 h); - -#ifdef __cplusplus -} -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt b/gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt deleted file mode 100644 index 33bc88ca9..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/multiarray_api.txt +++ /dev/null @@ -1,2430 +0,0 @@ - -=========== -Numpy C-API -=========== -:: - - unsigned int - PyArray_GetNDArrayCVersion(void ) - - -Included at the very first so not auto-grabbed and thus not labeled. - -:: - - int - PyArray_SetNumericOps(PyObject *dict) - -Set internal structure with number functions that all arrays will use - -:: - - PyObject * - PyArray_GetNumericOps(void ) - -Get dictionary showing number functions that all arrays will use - -:: - - int - PyArray_INCREF(PyArrayObject *mp) - -For object arrays, increment all internal references. - -:: - - int - PyArray_XDECREF(PyArrayObject *mp) - -Decrement all internal references for object arrays. -(or arrays with object fields) - -:: - - void - PyArray_SetStringFunction(PyObject *op, int repr) - -Set the array print function to be a Python function. - -:: - - PyArray_Descr * - PyArray_DescrFromType(int type) - -Get the PyArray_Descr structure for a type. - -:: - - PyObject * - PyArray_TypeObjectFromType(int type) - -Get a typeobject from a type-number -- can return NULL. - -New reference - -:: - - char * - PyArray_Zero(PyArrayObject *arr) - -Get pointer to zero of correct type for array. - -:: - - char * - PyArray_One(PyArrayObject *arr) - -Get pointer to one of correct type for array - -:: - - PyObject * - PyArray_CastToType(PyArrayObject *arr, PyArray_Descr *dtype, int - is_f_order) - -For backward compatibility - -Cast an array using typecode structure. -steals reference to at --- cannot be NULL - -This function always makes a copy of arr, even if the dtype -doesn't change. - -:: - - int - PyArray_CastTo(PyArrayObject *out, PyArrayObject *mp) - -Cast to an already created array. - -:: - - int - PyArray_CastAnyTo(PyArrayObject *out, PyArrayObject *mp) - -Cast to an already created array. Arrays don't have to be "broadcastable" -Only requirement is they have the same number of elements. - -:: - - int - PyArray_CanCastSafely(int fromtype, int totype) - -Check the type coercion rules. - -:: - - npy_bool - PyArray_CanCastTo(PyArray_Descr *from, PyArray_Descr *to) - -leaves reference count alone --- cannot be NULL - -PyArray_CanCastTypeTo is equivalent to this, but adds a 'casting' -parameter. - -:: - - int - PyArray_ObjectType(PyObject *op, int minimum_type) - -Return the typecode of the array a Python object would be converted to - -Returns the type number the result should have, or NPY_NOTYPE on error. - -:: - - PyArray_Descr * - PyArray_DescrFromObject(PyObject *op, PyArray_Descr *mintype) - -new reference -- accepts NULL for mintype - -:: - - PyArrayObject ** - PyArray_ConvertToCommonType(PyObject *op, int *retn) - - -:: - - PyArray_Descr * - PyArray_DescrFromScalar(PyObject *sc) - -Return descr object from array scalar. - -New reference - -:: - - PyArray_Descr * - PyArray_DescrFromTypeObject(PyObject *type) - - -:: - - npy_intp - PyArray_Size(PyObject *op) - -Compute the size of an array (in number of items) - -:: - - PyObject * - PyArray_Scalar(void *data, PyArray_Descr *descr, PyObject *base) - -Get scalar-equivalent to a region of memory described by a descriptor. - -:: - - PyObject * - PyArray_FromScalar(PyObject *scalar, PyArray_Descr *outcode) - -Get 0-dim array from scalar - -0-dim array from array-scalar object -always contains a copy of the data -unless outcode is NULL, it is of void type and the referrer does -not own it either. - -steals reference to outcode - -:: - - void - PyArray_ScalarAsCtype(PyObject *scalar, void *ctypeptr) - -Convert to c-type - -no error checking is performed -- ctypeptr must be same type as scalar -in case of flexible type, the data is not copied -into ctypeptr which is expected to be a pointer to pointer - -:: - - int - PyArray_CastScalarToCtype(PyObject *scalar, void - *ctypeptr, PyArray_Descr *outcode) - -Cast Scalar to c-type - -The output buffer must be large-enough to receive the value -Even for flexible types which is different from ScalarAsCtype -where only a reference for flexible types is returned - -This may not work right on narrow builds for NumPy unicode scalars. - -:: - - int - PyArray_CastScalarDirect(PyObject *scalar, PyArray_Descr - *indescr, void *ctypeptr, int outtype) - -Cast Scalar to c-type - -:: - - PyObject * - PyArray_ScalarFromObject(PyObject *object) - -Get an Array Scalar From a Python Object - -Returns NULL if unsuccessful but error is only set if another error occurred. -Currently only Numeric-like object supported. - -:: - - PyArray_VectorUnaryFunc * - PyArray_GetCastFunc(PyArray_Descr *descr, int type_num) - -Get a cast function to cast from the input descriptor to the -output type_number (must be a registered data-type). -Returns NULL if un-successful. - -:: - - PyObject * - PyArray_FromDims(int nd, int *d, int type) - -Construct an empty array from dimensions and typenum - -:: - - PyObject * - PyArray_FromDimsAndDataAndDescr(int nd, int *d, PyArray_Descr - *descr, char *data) - -Like FromDimsAndData but uses the Descr structure instead of typecode -as input. - -:: - - PyObject * - PyArray_FromAny(PyObject *op, PyArray_Descr *newtype, int - min_depth, int max_depth, int flags, PyObject - *context) - -Does not check for NPY_ARRAY_ENSURECOPY and NPY_ARRAY_NOTSWAPPED in flags -Steals a reference to newtype --- which can be NULL - -:: - - PyObject * - PyArray_EnsureArray(PyObject *op) - -This is a quick wrapper around PyArray_FromAny(op, NULL, 0, 0, ENSUREARRAY) -that special cases Arrays and PyArray_Scalars up front -It *steals a reference* to the object -It also guarantees that the result is PyArray_Type -Because it decrefs op if any conversion needs to take place -so it can be used like PyArray_EnsureArray(some_function(...)) - -:: - - PyObject * - PyArray_EnsureAnyArray(PyObject *op) - - -:: - - PyObject * - PyArray_FromFile(FILE *fp, PyArray_Descr *dtype, npy_intp num, char - *sep) - - -Given a ``FILE *`` pointer ``fp``, and a ``PyArray_Descr``, return an -array corresponding to the data encoded in that file. - -If the dtype is NULL, the default array type is used (double). -If non-null, the reference is stolen. - -The number of elements to read is given as ``num``; if it is < 0, then -then as many as possible are read. - -If ``sep`` is NULL or empty, then binary data is assumed, else -text data, with ``sep`` as the separator between elements. Whitespace in -the separator matches any length of whitespace in the text, and a match -for whitespace around the separator is added. - -For memory-mapped files, use the buffer interface. No more data than -necessary is read by this routine. - -:: - - PyObject * - PyArray_FromString(char *data, npy_intp slen, PyArray_Descr - *dtype, npy_intp num, char *sep) - - -Given a pointer to a string ``data``, a string length ``slen``, and -a ``PyArray_Descr``, return an array corresponding to the data -encoded in that string. - -If the dtype is NULL, the default array type is used (double). -If non-null, the reference is stolen. - -If ``slen`` is < 0, then the end of string is used for text data. -It is an error for ``slen`` to be < 0 for binary data (since embedded NULLs -would be the norm). - -The number of elements to read is given as ``num``; if it is < 0, then -then as many as possible are read. - -If ``sep`` is NULL or empty, then binary data is assumed, else -text data, with ``sep`` as the separator between elements. Whitespace in -the separator matches any length of whitespace in the text, and a match -for whitespace around the separator is added. - -:: - - PyObject * - PyArray_FromBuffer(PyObject *buf, PyArray_Descr *type, npy_intp - count, npy_intp offset) - - -:: - - PyObject * - PyArray_FromIter(PyObject *obj, PyArray_Descr *dtype, npy_intp count) - - -steals a reference to dtype (which cannot be NULL) - -:: - - PyObject * - PyArray_Return(PyArrayObject *mp) - - -Return either an array or the appropriate Python object if the array -is 0d and matches a Python type. - -:: - - PyObject * - PyArray_GetField(PyArrayObject *self, PyArray_Descr *typed, int - offset) - -Get a subset of bytes from each element of the array - -:: - - int - PyArray_SetField(PyArrayObject *self, PyArray_Descr *dtype, int - offset, PyObject *val) - -Set a subset of bytes from each element of the array - -:: - - PyObject * - PyArray_Byteswap(PyArrayObject *self, npy_bool inplace) - - -:: - - PyObject * - PyArray_Resize(PyArrayObject *self, PyArray_Dims *newshape, int - refcheck, NPY_ORDER order) - -Resize (reallocate data). Only works if nothing else is referencing this -array and it is contiguous. If refcheck is 0, then the reference count is -not checked and assumed to be 1. You still must own this data and have no -weak-references and no base object. - -:: - - int - PyArray_MoveInto(PyArrayObject *dst, PyArrayObject *src) - -Move the memory of one array into another, allowing for overlapping data. - -Returns 0 on success, negative on failure. - -:: - - int - PyArray_CopyInto(PyArrayObject *dst, PyArrayObject *src) - -Copy an Array into another array. -Broadcast to the destination shape if necessary. - -Returns 0 on success, -1 on failure. - -:: - - int - PyArray_CopyAnyInto(PyArrayObject *dst, PyArrayObject *src) - -Copy an Array into another array -- memory must not overlap -Does not require src and dest to have "broadcastable" shapes -(only the same number of elements). - -TODO: For NumPy 2.0, this could accept an order parameter which -only allows NPY_CORDER and NPY_FORDER. Could also rename -this to CopyAsFlat to make the name more intuitive. - -Returns 0 on success, -1 on error. - -:: - - int - PyArray_CopyObject(PyArrayObject *dest, PyObject *src_object) - - -:: - - PyObject * - PyArray_NewCopy(PyArrayObject *obj, NPY_ORDER order) - -Copy an array. - -:: - - PyObject * - PyArray_ToList(PyArrayObject *self) - -To List - -:: - - PyObject * - PyArray_ToString(PyArrayObject *self, NPY_ORDER order) - - -:: - - int - PyArray_ToFile(PyArrayObject *self, FILE *fp, char *sep, char *format) - -To File - -:: - - int - PyArray_Dump(PyObject *self, PyObject *file, int protocol) - - -:: - - PyObject * - PyArray_Dumps(PyObject *self, int protocol) - - -:: - - int - PyArray_ValidType(int type) - -Is the typenum valid? - -:: - - void - PyArray_UpdateFlags(PyArrayObject *ret, int flagmask) - -Update Several Flags at once. - -:: - - PyObject * - PyArray_New(PyTypeObject *subtype, int nd, npy_intp *dims, int - type_num, npy_intp *strides, void *data, int itemsize, int - flags, PyObject *obj) - -Generic new array creation routine. - -:: - - PyObject * - PyArray_NewFromDescr(PyTypeObject *subtype, PyArray_Descr *descr, int - nd, npy_intp *dims, npy_intp *strides, void - *data, int flags, PyObject *obj) - -Generic new array creation routine. - -steals a reference to descr (even on failure) - -:: - - PyArray_Descr * - PyArray_DescrNew(PyArray_Descr *base) - -base cannot be NULL - -:: - - PyArray_Descr * - PyArray_DescrNewFromType(int type_num) - - -:: - - double - PyArray_GetPriority(PyObject *obj, double default_) - -Get Priority from object - -:: - - PyObject * - PyArray_IterNew(PyObject *obj) - -Get Iterator. - -:: - - PyObject * - PyArray_MultiIterNew(int n, ... ) - -Get MultiIterator, - -:: - - int - PyArray_PyIntAsInt(PyObject *o) - - -:: - - npy_intp - PyArray_PyIntAsIntp(PyObject *o) - - -:: - - int - PyArray_Broadcast(PyArrayMultiIterObject *mit) - - -:: - - void - PyArray_FillObjectArray(PyArrayObject *arr, PyObject *obj) - -Assumes contiguous - -:: - - int - PyArray_FillWithScalar(PyArrayObject *arr, PyObject *obj) - - -:: - - npy_bool - PyArray_CheckStrides(int elsize, int nd, npy_intp numbytes, npy_intp - offset, npy_intp *dims, npy_intp *newstrides) - - -:: - - PyArray_Descr * - PyArray_DescrNewByteorder(PyArray_Descr *self, char newendian) - - -returns a copy of the PyArray_Descr structure with the byteorder -altered: -no arguments: The byteorder is swapped (in all subfields as well) -single argument: The byteorder is forced to the given state -(in all subfields as well) - -Valid states: ('big', '>') or ('little' or '<') -('native', or '=') - -If a descr structure with | is encountered it's own -byte-order is not changed but any fields are: - - -Deep bytorder change of a data-type descriptor -Leaves reference count of self unchanged --- does not DECREF self *** - -:: - - PyObject * - PyArray_IterAllButAxis(PyObject *obj, int *inaxis) - -Get Iterator that iterates over all but one axis (don't use this with -PyArray_ITER_GOTO1D). The axis will be over-written if negative -with the axis having the smallest stride. - -:: - - PyObject * - PyArray_CheckFromAny(PyObject *op, PyArray_Descr *descr, int - min_depth, int max_depth, int requires, PyObject - *context) - -steals a reference to descr -- accepts NULL - -:: - - PyObject * - PyArray_FromArray(PyArrayObject *arr, PyArray_Descr *newtype, int - flags) - -steals reference to newtype --- acc. NULL - -:: - - PyObject * - PyArray_FromInterface(PyObject *origin) - - -:: - - PyObject * - PyArray_FromStructInterface(PyObject *input) - - -:: - - PyObject * - PyArray_FromArrayAttr(PyObject *op, PyArray_Descr *typecode, PyObject - *context) - - -:: - - NPY_SCALARKIND - PyArray_ScalarKind(int typenum, PyArrayObject **arr) - -ScalarKind - -Returns the scalar kind of a type number, with an -optional tweak based on the scalar value itself. -If no scalar is provided, it returns INTPOS_SCALAR -for both signed and unsigned integers, otherwise -it checks the sign of any signed integer to choose -INTNEG_SCALAR when appropriate. - -:: - - int - PyArray_CanCoerceScalar(int thistype, int neededtype, NPY_SCALARKIND - scalar) - - -Determines whether the data type 'thistype', with -scalar kind 'scalar', can be coerced into 'neededtype'. - -:: - - PyObject * - PyArray_NewFlagsObject(PyObject *obj) - - -Get New ArrayFlagsObject - -:: - - npy_bool - PyArray_CanCastScalar(PyTypeObject *from, PyTypeObject *to) - -See if array scalars can be cast. - -TODO: For NumPy 2.0, add a NPY_CASTING parameter. - -:: - - int - PyArray_CompareUCS4(npy_ucs4 *s1, npy_ucs4 *s2, size_t len) - - -:: - - int - PyArray_RemoveSmallest(PyArrayMultiIterObject *multi) - -Adjusts previously broadcasted iterators so that the axis with -the smallest sum of iterator strides is not iterated over. -Returns dimension which is smallest in the range [0,multi->nd). -A -1 is returned if multi->nd == 0. - -don't use with PyArray_ITER_GOTO1D because factors are not adjusted - -:: - - int - PyArray_ElementStrides(PyObject *obj) - - -:: - - void - PyArray_Item_INCREF(char *data, PyArray_Descr *descr) - - -:: - - void - PyArray_Item_XDECREF(char *data, PyArray_Descr *descr) - - -:: - - PyObject * - PyArray_FieldNames(PyObject *fields) - -Return the tuple of ordered field names from a dictionary. - -:: - - PyObject * - PyArray_Transpose(PyArrayObject *ap, PyArray_Dims *permute) - -Return Transpose. - -:: - - PyObject * - PyArray_TakeFrom(PyArrayObject *self0, PyObject *indices0, int - axis, PyArrayObject *out, NPY_CLIPMODE clipmode) - -Take - -:: - - PyObject * - PyArray_PutTo(PyArrayObject *self, PyObject*values0, PyObject - *indices0, NPY_CLIPMODE clipmode) - -Put values into an array - -:: - - PyObject * - PyArray_PutMask(PyArrayObject *self, PyObject*values0, PyObject*mask0) - -Put values into an array according to a mask. - -:: - - PyObject * - PyArray_Repeat(PyArrayObject *aop, PyObject *op, int axis) - -Repeat the array. - -:: - - PyObject * - PyArray_Choose(PyArrayObject *ip, PyObject *op, PyArrayObject - *out, NPY_CLIPMODE clipmode) - - -:: - - int - PyArray_Sort(PyArrayObject *op, int axis, NPY_SORTKIND which) - -Sort an array in-place - -:: - - PyObject * - PyArray_ArgSort(PyArrayObject *op, int axis, NPY_SORTKIND which) - -ArgSort an array - -:: - - PyObject * - PyArray_SearchSorted(PyArrayObject *op1, PyObject *op2, NPY_SEARCHSIDE - side, PyObject *perm) - - -Search the sorted array op1 for the location of the items in op2. The -result is an array of indexes, one for each element in op2, such that if -the item were to be inserted in op1 just before that index the array -would still be in sorted order. - -Parameters ----------- -op1 : PyArrayObject * -Array to be searched, must be 1-D. -op2 : PyObject * -Array of items whose insertion indexes in op1 are wanted -side : {NPY_SEARCHLEFT, NPY_SEARCHRIGHT} -If NPY_SEARCHLEFT, return first valid insertion indexes -If NPY_SEARCHRIGHT, return last valid insertion indexes -perm : PyObject * -Permutation array that sorts op1 (optional) - -Returns -------- -ret : PyObject * -New reference to npy_intp array containing indexes where items in op2 -could be validly inserted into op1. NULL on error. - -Notes ------ -Binary search is used to find the indexes. - -:: - - PyObject * - PyArray_ArgMax(PyArrayObject *op, int axis, PyArrayObject *out) - -ArgMax - -:: - - PyObject * - PyArray_ArgMin(PyArrayObject *op, int axis, PyArrayObject *out) - -ArgMin - -:: - - PyObject * - PyArray_Reshape(PyArrayObject *self, PyObject *shape) - -Reshape - -:: - - PyObject * - PyArray_Newshape(PyArrayObject *self, PyArray_Dims *newdims, NPY_ORDER - order) - -New shape for an array - -:: - - PyObject * - PyArray_Squeeze(PyArrayObject *self) - - -return a new view of the array object with all of its unit-length -dimensions squeezed out if needed, otherwise -return the same array. - -:: - - PyObject * - PyArray_View(PyArrayObject *self, PyArray_Descr *type, PyTypeObject - *pytype) - -View -steals a reference to type -- accepts NULL - -:: - - PyObject * - PyArray_SwapAxes(PyArrayObject *ap, int a1, int a2) - -SwapAxes - -:: - - PyObject * - PyArray_Max(PyArrayObject *ap, int axis, PyArrayObject *out) - -Max - -:: - - PyObject * - PyArray_Min(PyArrayObject *ap, int axis, PyArrayObject *out) - -Min - -:: - - PyObject * - PyArray_Ptp(PyArrayObject *ap, int axis, PyArrayObject *out) - -Ptp - -:: - - PyObject * - PyArray_Mean(PyArrayObject *self, int axis, int rtype, PyArrayObject - *out) - -Mean - -:: - - PyObject * - PyArray_Trace(PyArrayObject *self, int offset, int axis1, int - axis2, int rtype, PyArrayObject *out) - -Trace - -:: - - PyObject * - PyArray_Diagonal(PyArrayObject *self, int offset, int axis1, int - axis2) - -Diagonal - -In NumPy versions prior to 1.7, this function always returned a copy of -the diagonal array. In 1.7, the code has been updated to compute a view -onto 'self', but it still copies this array before returning, as well as -setting the internal WARN_ON_WRITE flag. In a future version, it will -simply return a view onto self. - -:: - - PyObject * - PyArray_Clip(PyArrayObject *self, PyObject *min, PyObject - *max, PyArrayObject *out) - -Clip - -:: - - PyObject * - PyArray_Conjugate(PyArrayObject *self, PyArrayObject *out) - -Conjugate - -:: - - PyObject * - PyArray_Nonzero(PyArrayObject *self) - -Nonzero - -TODO: In NumPy 2.0, should make the iteration order a parameter. - -:: - - PyObject * - PyArray_Std(PyArrayObject *self, int axis, int rtype, PyArrayObject - *out, int variance) - -Set variance to 1 to by-pass square-root calculation and return variance -Std - -:: - - PyObject * - PyArray_Sum(PyArrayObject *self, int axis, int rtype, PyArrayObject - *out) - -Sum - -:: - - PyObject * - PyArray_CumSum(PyArrayObject *self, int axis, int rtype, PyArrayObject - *out) - -CumSum - -:: - - PyObject * - PyArray_Prod(PyArrayObject *self, int axis, int rtype, PyArrayObject - *out) - -Prod - -:: - - PyObject * - PyArray_CumProd(PyArrayObject *self, int axis, int - rtype, PyArrayObject *out) - -CumProd - -:: - - PyObject * - PyArray_All(PyArrayObject *self, int axis, PyArrayObject *out) - -All - -:: - - PyObject * - PyArray_Any(PyArrayObject *self, int axis, PyArrayObject *out) - -Any - -:: - - PyObject * - PyArray_Compress(PyArrayObject *self, PyObject *condition, int - axis, PyArrayObject *out) - -Compress - -:: - - PyObject * - PyArray_Flatten(PyArrayObject *a, NPY_ORDER order) - -Flatten - -:: - - PyObject * - PyArray_Ravel(PyArrayObject *arr, NPY_ORDER order) - -Ravel -Returns a contiguous array - -:: - - npy_intp - PyArray_MultiplyList(npy_intp *l1, int n) - -Multiply a List - -:: - - int - PyArray_MultiplyIntList(int *l1, int n) - -Multiply a List of ints - -:: - - void * - PyArray_GetPtr(PyArrayObject *obj, npy_intp*ind) - -Produce a pointer into array - -:: - - int - PyArray_CompareLists(npy_intp *l1, npy_intp *l2, int n) - -Compare Lists - -:: - - int - PyArray_AsCArray(PyObject **op, void *ptr, npy_intp *dims, int - nd, PyArray_Descr*typedescr) - -Simulate a C-array -steals a reference to typedescr -- can be NULL - -:: - - int - PyArray_As1D(PyObject **op, char **ptr, int *d1, int typecode) - -Convert to a 1D C-array - -:: - - int - PyArray_As2D(PyObject **op, char ***ptr, int *d1, int *d2, int - typecode) - -Convert to a 2D C-array - -:: - - int - PyArray_Free(PyObject *op, void *ptr) - -Free pointers created if As2D is called - -:: - - int - PyArray_Converter(PyObject *object, PyObject **address) - - -Useful to pass as converter function for O& processing in PyArgs_ParseTuple. - -This conversion function can be used with the "O&" argument for -PyArg_ParseTuple. It will immediately return an object of array type -or will convert to a NPY_ARRAY_CARRAY any other object. - -If you use PyArray_Converter, you must DECREF the array when finished -as you get a new reference to it. - -:: - - int - PyArray_IntpFromSequence(PyObject *seq, npy_intp *vals, int maxvals) - -PyArray_IntpFromSequence -Returns the number of integers converted or -1 if an error occurred. -vals must be large enough to hold maxvals - -:: - - PyObject * - PyArray_Concatenate(PyObject *op, int axis) - -Concatenate - -Concatenate an arbitrary Python sequence into an array. -op is a python object supporting the sequence interface. -Its elements will be concatenated together to form a single -multidimensional array. If axis is NPY_MAXDIMS or bigger, then -each sequence object will be flattened before concatenation - -:: - - PyObject * - PyArray_InnerProduct(PyObject *op1, PyObject *op2) - -Numeric.innerproduct(a,v) - -:: - - PyObject * - PyArray_MatrixProduct(PyObject *op1, PyObject *op2) - -Numeric.matrixproduct(a,v) -just like inner product but does the swapaxes stuff on the fly - -:: - - PyObject * - PyArray_CopyAndTranspose(PyObject *op) - -Copy and Transpose - -Could deprecate this function, as there isn't a speed benefit over -calling Transpose and then Copy. - -:: - - PyObject * - PyArray_Correlate(PyObject *op1, PyObject *op2, int mode) - -Numeric.correlate(a1,a2,mode) - -:: - - int - PyArray_TypestrConvert(int itemsize, int gentype) - -Typestr converter - -:: - - int - PyArray_DescrConverter(PyObject *obj, PyArray_Descr **at) - -Get typenum from an object -- None goes to NPY_DEFAULT_TYPE -This function takes a Python object representing a type and converts it -to a the correct PyArray_Descr * structure to describe the type. - -Many objects can be used to represent a data-type which in NumPy is -quite a flexible concept. - -This is the central code that converts Python objects to -Type-descriptor objects that are used throughout numpy. - -Returns a new reference in *at, but the returned should not be -modified as it may be one of the canonical immutable objects or -a reference to the input obj. - -:: - - int - PyArray_DescrConverter2(PyObject *obj, PyArray_Descr **at) - -Get typenum from an object -- None goes to NULL - -:: - - int - PyArray_IntpConverter(PyObject *obj, PyArray_Dims *seq) - -Get intp chunk from sequence - -This function takes a Python sequence object and allocates and -fills in an intp array with the converted values. - -Remember to free the pointer seq.ptr when done using -PyDimMem_FREE(seq.ptr)** - -:: - - int - PyArray_BufferConverter(PyObject *obj, PyArray_Chunk *buf) - -Get buffer chunk from object - -this function takes a Python object which exposes the (single-segment) -buffer interface and returns a pointer to the data segment - -You should increment the reference count by one of buf->base -if you will hang on to a reference - -You only get a borrowed reference to the object. Do not free the -memory... - -:: - - int - PyArray_AxisConverter(PyObject *obj, int *axis) - -Get axis from an object (possibly None) -- a converter function, - -See also PyArray_ConvertMultiAxis, which also handles a tuple of axes. - -:: - - int - PyArray_BoolConverter(PyObject *object, npy_bool *val) - -Convert an object to true / false - -:: - - int - PyArray_ByteorderConverter(PyObject *obj, char *endian) - -Convert object to endian - -:: - - int - PyArray_OrderConverter(PyObject *object, NPY_ORDER *val) - -Convert an object to FORTRAN / C / ANY / KEEP - -:: - - unsigned char - PyArray_EquivTypes(PyArray_Descr *type1, PyArray_Descr *type2) - - -This function returns true if the two typecodes are -equivalent (same basic kind and same itemsize). - -:: - - PyObject * - PyArray_Zeros(int nd, npy_intp *dims, PyArray_Descr *type, int - is_f_order) - -Zeros - -steal a reference -accepts NULL type - -:: - - PyObject * - PyArray_Empty(int nd, npy_intp *dims, PyArray_Descr *type, int - is_f_order) - -Empty - -accepts NULL type -steals referenct to type - -:: - - PyObject * - PyArray_Where(PyObject *condition, PyObject *x, PyObject *y) - -Where - -:: - - PyObject * - PyArray_Arange(double start, double stop, double step, int type_num) - -Arange, - -:: - - PyObject * - PyArray_ArangeObj(PyObject *start, PyObject *stop, PyObject - *step, PyArray_Descr *dtype) - - -ArangeObj, - -this doesn't change the references - -:: - - int - PyArray_SortkindConverter(PyObject *obj, NPY_SORTKIND *sortkind) - -Convert object to sort kind - -:: - - PyObject * - PyArray_LexSort(PyObject *sort_keys, int axis) - -LexSort an array providing indices that will sort a collection of arrays -lexicographically. The first key is sorted on first, followed by the second key --- requires that arg"merge"sort is available for each sort_key - -Returns an index array that shows the indexes for the lexicographic sort along -the given axis. - -:: - - PyObject * - PyArray_Round(PyArrayObject *a, int decimals, PyArrayObject *out) - -Round - -:: - - unsigned char - PyArray_EquivTypenums(int typenum1, int typenum2) - - -:: - - int - PyArray_RegisterDataType(PyArray_Descr *descr) - -Register Data type -Does not change the reference count of descr - -:: - - int - PyArray_RegisterCastFunc(PyArray_Descr *descr, int - totype, PyArray_VectorUnaryFunc *castfunc) - -Register Casting Function -Replaces any function currently stored. - -:: - - int - PyArray_RegisterCanCast(PyArray_Descr *descr, int - totype, NPY_SCALARKIND scalar) - -Register a type number indicating that a descriptor can be cast -to it safely - -:: - - void - PyArray_InitArrFuncs(PyArray_ArrFuncs *f) - -Initialize arrfuncs to NULL - -:: - - PyObject * - PyArray_IntTupleFromIntp(int len, npy_intp *vals) - -PyArray_IntTupleFromIntp - -:: - - int - PyArray_TypeNumFromName(char *str) - - -:: - - int - PyArray_ClipmodeConverter(PyObject *object, NPY_CLIPMODE *val) - -Convert an object to NPY_RAISE / NPY_CLIP / NPY_WRAP - -:: - - int - PyArray_OutputConverter(PyObject *object, PyArrayObject **address) - -Useful to pass as converter function for O& processing in -PyArgs_ParseTuple for output arrays - -:: - - PyObject * - PyArray_BroadcastToShape(PyObject *obj, npy_intp *dims, int nd) - -Get Iterator broadcast to a particular shape - -:: - - void - _PyArray_SigintHandler(int signum) - - -:: - - void* - _PyArray_GetSigintBuf(void ) - - -:: - - int - PyArray_DescrAlignConverter(PyObject *obj, PyArray_Descr **at) - - -Get type-descriptor from an object forcing alignment if possible -None goes to DEFAULT type. - -any object with the .fields attribute and/or .itemsize attribute (if the -.fields attribute does not give the total size -- i.e. a partial record -naming). If itemsize is given it must be >= size computed from fields - -The .fields attribute must return a convertible dictionary if present. -Result inherits from NPY_VOID. - -:: - - int - PyArray_DescrAlignConverter2(PyObject *obj, PyArray_Descr **at) - - -Get type-descriptor from an object forcing alignment if possible -None goes to NULL. - -:: - - int - PyArray_SearchsideConverter(PyObject *obj, void *addr) - -Convert object to searchsorted side - -:: - - PyObject * - PyArray_CheckAxis(PyArrayObject *arr, int *axis, int flags) - -PyArray_CheckAxis - -check that axis is valid -convert 0-d arrays to 1-d arrays - -:: - - npy_intp - PyArray_OverflowMultiplyList(npy_intp *l1, int n) - -Multiply a List of Non-negative numbers with over-flow detection. - -:: - - int - PyArray_CompareString(char *s1, char *s2, size_t len) - - -:: - - PyObject * - PyArray_MultiIterFromObjects(PyObject **mps, int n, int nadd, ... ) - -Get MultiIterator from array of Python objects and any additional - -PyObject **mps -- array of PyObjects -int n - number of PyObjects in the array -int nadd - number of additional arrays to include in the iterator. - -Returns a multi-iterator object. - -:: - - int - PyArray_GetEndianness(void ) - - -:: - - unsigned int - PyArray_GetNDArrayCFeatureVersion(void ) - -Returns the built-in (at compilation time) C API version - -:: - - PyObject * - PyArray_Correlate2(PyObject *op1, PyObject *op2, int mode) - -correlate(a1,a2,mode) - -This function computes the usual correlation (correlate(a1, a2) != -correlate(a2, a1), and conjugate the second argument for complex inputs - -:: - - PyObject* - PyArray_NeighborhoodIterNew(PyArrayIterObject *x, npy_intp - *bounds, int mode, PyArrayObject*fill) - -A Neighborhood Iterator object. - -:: - - void - PyArray_SetDatetimeParseFunction(PyObject *op) - -This function is scheduled to be removed - -TO BE REMOVED - NOT USED INTERNALLY. - -:: - - void - PyArray_DatetimeToDatetimeStruct(npy_datetime val, NPY_DATETIMEUNIT - fr, npy_datetimestruct *result) - -Fill the datetime struct from the value and resolution unit. - -TO BE REMOVED - NOT USED INTERNALLY. - -:: - - void - PyArray_TimedeltaToTimedeltaStruct(npy_timedelta val, NPY_DATETIMEUNIT - fr, npy_timedeltastruct *result) - -Fill the timedelta struct from the timedelta value and resolution unit. - -TO BE REMOVED - NOT USED INTERNALLY. - -:: - - npy_datetime - PyArray_DatetimeStructToDatetime(NPY_DATETIMEUNIT - fr, npy_datetimestruct *d) - -Create a datetime value from a filled datetime struct and resolution unit. - -TO BE REMOVED - NOT USED INTERNALLY. - -:: - - npy_datetime - PyArray_TimedeltaStructToTimedelta(NPY_DATETIMEUNIT - fr, npy_timedeltastruct *d) - -Create a timdelta value from a filled timedelta struct and resolution unit. - -TO BE REMOVED - NOT USED INTERNALLY. - -:: - - NpyIter * - NpyIter_New(PyArrayObject *op, npy_uint32 flags, NPY_ORDER - order, NPY_CASTING casting, PyArray_Descr*dtype) - -Allocate a new iterator for one array object. - -:: - - NpyIter * - NpyIter_MultiNew(int nop, PyArrayObject **op_in, npy_uint32 - flags, NPY_ORDER order, NPY_CASTING - casting, npy_uint32 *op_flags, PyArray_Descr - **op_request_dtypes) - -Allocate a new iterator for more than one array object, using -standard NumPy broadcasting rules and the default buffer size. - -:: - - NpyIter * - NpyIter_AdvancedNew(int nop, PyArrayObject **op_in, npy_uint32 - flags, NPY_ORDER order, NPY_CASTING - casting, npy_uint32 *op_flags, PyArray_Descr - **op_request_dtypes, int oa_ndim, int - **op_axes, npy_intp *itershape, npy_intp - buffersize) - -Allocate a new iterator for multiple array objects, and advanced -options for controlling the broadcasting, shape, and buffer size. - -:: - - NpyIter * - NpyIter_Copy(NpyIter *iter) - -Makes a copy of the iterator - -:: - - int - NpyIter_Deallocate(NpyIter *iter) - -Deallocate an iterator - -:: - - npy_bool - NpyIter_HasDelayedBufAlloc(NpyIter *iter) - -Whether the buffer allocation is being delayed - -:: - - npy_bool - NpyIter_HasExternalLoop(NpyIter *iter) - -Whether the iterator handles the inner loop - -:: - - int - NpyIter_EnableExternalLoop(NpyIter *iter) - -Removes the inner loop handling (so HasExternalLoop returns true) - -:: - - npy_intp * - NpyIter_GetInnerStrideArray(NpyIter *iter) - -Get the array of strides for the inner loop (when HasExternalLoop is true) - -This function may be safely called without holding the Python GIL. - -:: - - npy_intp * - NpyIter_GetInnerLoopSizePtr(NpyIter *iter) - -Get a pointer to the size of the inner loop (when HasExternalLoop is true) - -This function may be safely called without holding the Python GIL. - -:: - - int - NpyIter_Reset(NpyIter *iter, char **errmsg) - -Resets the iterator to its initial state - -If errmsg is non-NULL, it should point to a variable which will -receive the error message, and no Python exception will be set. -This is so that the function can be called from code not holding -the GIL. - -:: - - int - NpyIter_ResetBasePointers(NpyIter *iter, char **baseptrs, char - **errmsg) - -Resets the iterator to its initial state, with new base data pointers. -This function requires great caution. - -If errmsg is non-NULL, it should point to a variable which will -receive the error message, and no Python exception will be set. -This is so that the function can be called from code not holding -the GIL. - -:: - - int - NpyIter_ResetToIterIndexRange(NpyIter *iter, npy_intp istart, npy_intp - iend, char **errmsg) - -Resets the iterator to a new iterator index range - -If errmsg is non-NULL, it should point to a variable which will -receive the error message, and no Python exception will be set. -This is so that the function can be called from code not holding -the GIL. - -:: - - int - NpyIter_GetNDim(NpyIter *iter) - -Gets the number of dimensions being iterated - -:: - - int - NpyIter_GetNOp(NpyIter *iter) - -Gets the number of operands being iterated - -:: - - NpyIter_IterNextFunc * - NpyIter_GetIterNext(NpyIter *iter, char **errmsg) - -Compute the specialized iteration function for an iterator - -If errmsg is non-NULL, it should point to a variable which will -receive the error message, and no Python exception will be set. -This is so that the function can be called from code not holding -the GIL. - -:: - - npy_intp - NpyIter_GetIterSize(NpyIter *iter) - -Gets the number of elements being iterated - -:: - - void - NpyIter_GetIterIndexRange(NpyIter *iter, npy_intp *istart, npy_intp - *iend) - -Gets the range of iteration indices being iterated - -:: - - npy_intp - NpyIter_GetIterIndex(NpyIter *iter) - -Gets the current iteration index - -:: - - int - NpyIter_GotoIterIndex(NpyIter *iter, npy_intp iterindex) - -Sets the iterator position to the specified iterindex, -which matches the iteration order of the iterator. - -Returns NPY_SUCCEED on success, NPY_FAIL on failure. - -:: - - npy_bool - NpyIter_HasMultiIndex(NpyIter *iter) - -Whether the iterator is tracking a multi-index - -:: - - int - NpyIter_GetShape(NpyIter *iter, npy_intp *outshape) - -Gets the broadcast shape if a multi-index is being tracked by the iterator, -otherwise gets the shape of the iteration as Fortran-order -(fastest-changing index first). - -The reason Fortran-order is returned when a multi-index -is not enabled is that this is providing a direct view into how -the iterator traverses the n-dimensional space. The iterator organizes -its memory from fastest index to slowest index, and when -a multi-index is enabled, it uses a permutation to recover the original -order. - -Returns NPY_SUCCEED or NPY_FAIL. - -:: - - NpyIter_GetMultiIndexFunc * - NpyIter_GetGetMultiIndex(NpyIter *iter, char **errmsg) - -Compute a specialized get_multi_index function for the iterator - -If errmsg is non-NULL, it should point to a variable which will -receive the error message, and no Python exception will be set. -This is so that the function can be called from code not holding -the GIL. - -:: - - int - NpyIter_GotoMultiIndex(NpyIter *iter, npy_intp *multi_index) - -Sets the iterator to the specified multi-index, which must have the -correct number of entries for 'ndim'. It is only valid -when NPY_ITER_MULTI_INDEX was passed to the constructor. This operation -fails if the multi-index is out of bounds. - -Returns NPY_SUCCEED on success, NPY_FAIL on failure. - -:: - - int - NpyIter_RemoveMultiIndex(NpyIter *iter) - -Removes multi-index support from an iterator. - -Returns NPY_SUCCEED or NPY_FAIL. - -:: - - npy_bool - NpyIter_HasIndex(NpyIter *iter) - -Whether the iterator is tracking an index - -:: - - npy_bool - NpyIter_IsBuffered(NpyIter *iter) - -Whether the iterator is buffered - -:: - - npy_bool - NpyIter_IsGrowInner(NpyIter *iter) - -Whether the inner loop can grow if buffering is unneeded - -:: - - npy_intp - NpyIter_GetBufferSize(NpyIter *iter) - -Gets the size of the buffer, or 0 if buffering is not enabled - -:: - - npy_intp * - NpyIter_GetIndexPtr(NpyIter *iter) - -Get a pointer to the index, if it is being tracked - -:: - - int - NpyIter_GotoIndex(NpyIter *iter, npy_intp flat_index) - -If the iterator is tracking an index, sets the iterator -to the specified index. - -Returns NPY_SUCCEED on success, NPY_FAIL on failure. - -:: - - char ** - NpyIter_GetDataPtrArray(NpyIter *iter) - -Get the array of data pointers (1 per object being iterated) - -This function may be safely called without holding the Python GIL. - -:: - - PyArray_Descr ** - NpyIter_GetDescrArray(NpyIter *iter) - -Get the array of data type pointers (1 per object being iterated) - -:: - - PyArrayObject ** - NpyIter_GetOperandArray(NpyIter *iter) - -Get the array of objects being iterated - -:: - - PyArrayObject * - NpyIter_GetIterView(NpyIter *iter, npy_intp i) - -Returns a view to the i-th object with the iterator's internal axes - -:: - - void - NpyIter_GetReadFlags(NpyIter *iter, char *outreadflags) - -Gets an array of read flags (1 per object being iterated) - -:: - - void - NpyIter_GetWriteFlags(NpyIter *iter, char *outwriteflags) - -Gets an array of write flags (1 per object being iterated) - -:: - - void - NpyIter_DebugPrint(NpyIter *iter) - -For debugging - -:: - - npy_bool - NpyIter_IterationNeedsAPI(NpyIter *iter) - -Whether the iteration loop, and in particular the iternext() -function, needs API access. If this is true, the GIL must -be retained while iterating. - -:: - - void - NpyIter_GetInnerFixedStrideArray(NpyIter *iter, npy_intp *out_strides) - -Get an array of strides which are fixed. Any strides which may -change during iteration receive the value NPY_MAX_INTP. Once -the iterator is ready to iterate, call this to get the strides -which will always be fixed in the inner loop, then choose optimized -inner loop functions which take advantage of those fixed strides. - -This function may be safely called without holding the Python GIL. - -:: - - int - NpyIter_RemoveAxis(NpyIter *iter, int axis) - -Removes an axis from iteration. This requires that NPY_ITER_MULTI_INDEX -was set for iterator creation, and does not work if buffering is -enabled. This function also resets the iterator to its initial state. - -Returns NPY_SUCCEED or NPY_FAIL. - -:: - - npy_intp * - NpyIter_GetAxisStrideArray(NpyIter *iter, int axis) - -Gets the array of strides for the specified axis. -If the iterator is tracking a multi-index, gets the strides -for the axis specified, otherwise gets the strides for -the iteration axis as Fortran order (fastest-changing axis first). - -Returns NULL if an error occurs. - -:: - - npy_bool - NpyIter_RequiresBuffering(NpyIter *iter) - -Whether the iteration could be done with no buffering. - -:: - - char ** - NpyIter_GetInitialDataPtrArray(NpyIter *iter) - -Get the array of data pointers (1 per object being iterated), -directly into the arrays (never pointing to a buffer), for starting -unbuffered iteration. This always returns the addresses for the -iterator position as reset to iterator index 0. - -These pointers are different from the pointers accepted by -NpyIter_ResetBasePointers, because the direction along some -axes may have been reversed, requiring base offsets. - -This function may be safely called without holding the Python GIL. - -:: - - int - NpyIter_CreateCompatibleStrides(NpyIter *iter, npy_intp - itemsize, npy_intp *outstrides) - -Builds a set of strides which are the same as the strides of an -output array created using the NPY_ITER_ALLOCATE flag, where NULL -was passed for op_axes. This is for data packed contiguously, -but not necessarily in C or Fortran order. This should be used -together with NpyIter_GetShape and NpyIter_GetNDim. - -A use case for this function is to match the shape and layout of -the iterator and tack on one or more dimensions. For example, -in order to generate a vector per input value for a numerical gradient, -you pass in ndim*itemsize for itemsize, then add another dimension to -the end with size ndim and stride itemsize. To do the Hessian matrix, -you do the same thing but add two dimensions, or take advantage of -the symmetry and pack it into 1 dimension with a particular encoding. - -This function may only be called if the iterator is tracking a multi-index -and if NPY_ITER_DONT_NEGATE_STRIDES was used to prevent an axis from -being iterated in reverse order. - -If an array is created with this method, simply adding 'itemsize' -for each iteration will traverse the new array matching the -iterator. - -Returns NPY_SUCCEED or NPY_FAIL. - -:: - - int - PyArray_CastingConverter(PyObject *obj, NPY_CASTING *casting) - -Convert any Python object, *obj*, to an NPY_CASTING enum. - -:: - - npy_intp - PyArray_CountNonzero(PyArrayObject *self) - -Counts the number of non-zero elements in the array. - -Returns -1 on error. - -:: - - PyArray_Descr * - PyArray_PromoteTypes(PyArray_Descr *type1, PyArray_Descr *type2) - -Produces the smallest size and lowest kind type to which both -input types can be cast. - -:: - - PyArray_Descr * - PyArray_MinScalarType(PyArrayObject *arr) - -If arr is a scalar (has 0 dimensions) with a built-in number data type, -finds the smallest type size/kind which can still represent its data. -Otherwise, returns the array's data type. - - -:: - - PyArray_Descr * - PyArray_ResultType(npy_intp narrs, PyArrayObject **arr, npy_intp - ndtypes, PyArray_Descr **dtypes) - -Produces the result type of a bunch of inputs, using the UFunc -type promotion rules. Use this function when you have a set of -input arrays, and need to determine an output array dtype. - -If all the inputs are scalars (have 0 dimensions) or the maximum "kind" -of the scalars is greater than the maximum "kind" of the arrays, does -a regular type promotion. - -Otherwise, does a type promotion on the MinScalarType -of all the inputs. Data types passed directly are treated as array -types. - - -:: - - npy_bool - PyArray_CanCastArrayTo(PyArrayObject *arr, PyArray_Descr - *to, NPY_CASTING casting) - -Returns 1 if the array object may be cast to the given data type using -the casting rule, 0 otherwise. This differs from PyArray_CanCastTo in -that it handles scalar arrays (0 dimensions) specially, by checking -their value. - -:: - - npy_bool - PyArray_CanCastTypeTo(PyArray_Descr *from, PyArray_Descr - *to, NPY_CASTING casting) - -Returns true if data of type 'from' may be cast to data of type -'to' according to the rule 'casting'. - -:: - - PyArrayObject * - PyArray_EinsteinSum(char *subscripts, npy_intp nop, PyArrayObject - **op_in, PyArray_Descr *dtype, NPY_ORDER - order, NPY_CASTING casting, PyArrayObject *out) - -This function provides summation of array elements according to -the Einstein summation convention. For example: -- trace(a) -> einsum("ii", a) -- transpose(a) -> einsum("ji", a) -- multiply(a,b) -> einsum(",", a, b) -- inner(a,b) -> einsum("i,i", a, b) -- outer(a,b) -> einsum("i,j", a, b) -- matvec(a,b) -> einsum("ij,j", a, b) -- matmat(a,b) -> einsum("ij,jk", a, b) - -subscripts: The string of subscripts for einstein summation. -nop: The number of operands -op_in: The array of operands -dtype: Either NULL, or the data type to force the calculation as. -order: The order for the calculation/the output axes. -casting: What kind of casts should be permitted. -out: Either NULL, or an array into which the output should be placed. - -By default, the labels get placed in alphabetical order -at the end of the output. So, if c = einsum("i,j", a, b) -then c[i,j] == a[i]*b[j], but if c = einsum("j,i", a, b) -then c[i,j] = a[j]*b[i]. - -Alternatively, you can control the output order or prevent -an axis from being summed/force an axis to be summed by providing -indices for the output. This allows us to turn 'trace' into -'diag', for example. -- diag(a) -> einsum("ii->i", a) -- sum(a, axis=0) -> einsum("i...->", a) - -Subscripts at the beginning and end may be specified by -putting an ellipsis "..." in the middle. For example, -the function einsum("i...i", a) takes the diagonal of -the first and last dimensions of the operand, and -einsum("ij...,jk...->ik...") takes the matrix product using -the first two indices of each operand instead of the last two. - -When there is only one operand, no axes being summed, and -no output parameter, this function returns a view -into the operand instead of making a copy. - -:: - - PyObject * - PyArray_NewLikeArray(PyArrayObject *prototype, NPY_ORDER - order, PyArray_Descr *dtype, int subok) - -Creates a new array with the same shape as the provided one, -with possible memory layout order and data type changes. - -prototype - The array the new one should be like. -order - NPY_CORDER - C-contiguous result. -NPY_FORTRANORDER - Fortran-contiguous result. -NPY_ANYORDER - Fortran if prototype is Fortran, C otherwise. -NPY_KEEPORDER - Keeps the axis ordering of prototype. -dtype - If not NULL, overrides the data type of the result. -subok - If 1, use the prototype's array subtype, otherwise -always create a base-class array. - -NOTE: If dtype is not NULL, steals the dtype reference. - -:: - - int - PyArray_GetArrayParamsFromObject(PyObject *op, PyArray_Descr - *requested_dtype, npy_bool - writeable, PyArray_Descr - **out_dtype, int *out_ndim, npy_intp - *out_dims, PyArrayObject - **out_arr, PyObject *context) - -Retrieves the array parameters for viewing/converting an arbitrary -PyObject* to a NumPy array. This allows the "innate type and shape" -of Python list-of-lists to be discovered without -actually converting to an array. - -In some cases, such as structured arrays and the __array__ interface, -a data type needs to be used to make sense of the object. When -this is needed, provide a Descr for 'requested_dtype', otherwise -provide NULL. This reference is not stolen. Also, if the requested -dtype doesn't modify the interpretation of the input, out_dtype will -still get the "innate" dtype of the object, not the dtype passed -in 'requested_dtype'. - -If writing to the value in 'op' is desired, set the boolean -'writeable' to 1. This raises an error when 'op' is a scalar, list -of lists, or other non-writeable 'op'. - -Result: When success (0 return value) is returned, either out_arr -is filled with a non-NULL PyArrayObject and -the rest of the parameters are untouched, or out_arr is -filled with NULL, and the rest of the parameters are -filled. - -Typical usage: - -PyArrayObject *arr = NULL; -PyArray_Descr *dtype = NULL; -int ndim = 0; -npy_intp dims[NPY_MAXDIMS]; - -if (PyArray_GetArrayParamsFromObject(op, NULL, 1, &dtype, -&ndim, &dims, &arr, NULL) < 0) { -return NULL; -} -if (arr == NULL) { -... validate/change dtype, validate flags, ndim, etc ... -// Could make custom strides here too -arr = PyArray_NewFromDescr(&PyArray_Type, dtype, ndim, -dims, NULL, -is_f_order ? NPY_ARRAY_F_CONTIGUOUS : 0, -NULL); -if (arr == NULL) { -return NULL; -} -if (PyArray_CopyObject(arr, op) < 0) { -Py_DECREF(arr); -return NULL; -} -} -else { -... in this case the other parameters weren't filled, just -validate and possibly copy arr itself ... -} -... use arr ... - -:: - - int - PyArray_ConvertClipmodeSequence(PyObject *object, NPY_CLIPMODE - *modes, int n) - -Convert an object to an array of n NPY_CLIPMODE values. -This is intended to be used in functions where a different mode -could be applied to each axis, like in ravel_multi_index. - -:: - - PyObject * - PyArray_MatrixProduct2(PyObject *op1, PyObject - *op2, PyArrayObject*out) - -Numeric.matrixproduct(a,v,out) -just like inner product but does the swapaxes stuff on the fly - -:: - - npy_bool - NpyIter_IsFirstVisit(NpyIter *iter, int iop) - -Checks to see whether this is the first time the elements -of the specified reduction operand which the iterator points at are -being seen for the first time. The function returns -a reasonable answer for reduction operands and when buffering is -disabled. The answer may be incorrect for buffered non-reduction -operands. - -This function is intended to be used in EXTERNAL_LOOP mode only, -and will produce some wrong answers when that mode is not enabled. - -If this function returns true, the caller should also -check the inner loop stride of the operand, because if -that stride is 0, then only the first element of the innermost -external loop is being visited for the first time. - -WARNING: For performance reasons, 'iop' is not bounds-checked, -it is not confirmed that 'iop' is actually a reduction -operand, and it is not confirmed that EXTERNAL_LOOP -mode is enabled. These checks are the responsibility of -the caller, and should be done outside of any inner loops. - -:: - - int - PyArray_SetBaseObject(PyArrayObject *arr, PyObject *obj) - -Sets the 'base' attribute of the array. This steals a reference -to 'obj'. - -Returns 0 on success, -1 on failure. - -:: - - void - PyArray_CreateSortedStridePerm(int ndim, npy_intp - *strides, npy_stride_sort_item - *out_strideperm) - - -This function populates the first ndim elements -of strideperm with sorted descending by their absolute values. -For example, the stride array (4, -2, 12) becomes -[(2, 12), (0, 4), (1, -2)]. - -:: - - void - PyArray_RemoveAxesInPlace(PyArrayObject *arr, npy_bool *flags) - - -Removes the axes flagged as True from the array, -modifying it in place. If an axis flagged for removal -has a shape entry bigger than one, this effectively selects -index zero for that axis. - -WARNING: If an axis flagged for removal has a shape equal to zero, -the array will point to invalid memory. The caller must -validate this! -If an axis flagged for removal has a shape larger then one, -the aligned flag (and in the future the contiguous flags), -may need explicite update. -(check also NPY_RELAXED_STRIDES_CHECKING) - -For example, this can be used to remove the reduction axes -from a reduction result once its computation is complete. - -:: - - void - PyArray_DebugPrint(PyArrayObject *obj) - -Prints the raw data of the ndarray in a form useful for debugging -low-level C issues. - -:: - - int - PyArray_FailUnlessWriteable(PyArrayObject *obj, const char *name) - - -This function does nothing if obj is writeable, and raises an exception -(and returns -1) if obj is not writeable. It may also do other -house-keeping, such as issuing warnings on arrays which are transitioning -to become views. Always call this function at some point before writing to -an array. - -'name' is a name for the array, used to give better error -messages. Something like "assignment destination", "output array", or even -just "array". - -:: - - int - PyArray_SetUpdateIfCopyBase(PyArrayObject *arr, PyArrayObject *base) - - -Precondition: 'arr' is a copy of 'base' (though possibly with different -strides, ordering, etc.). This function sets the UPDATEIFCOPY flag and the -->base pointer on 'arr', so that when 'arr' is destructed, it will copy any -changes back to 'base'. - -Steals a reference to 'base'. - -Returns 0 on success, -1 on failure. - -:: - - void * - PyDataMem_NEW(size_t size) - -Allocates memory for array data. - -:: - - void - PyDataMem_FREE(void *ptr) - -Free memory for array data. - -:: - - void * - PyDataMem_RENEW(void *ptr, size_t size) - -Reallocate/resize memory for array data. - -:: - - PyDataMem_EventHookFunc * - PyDataMem_SetEventHook(PyDataMem_EventHookFunc *newhook, void - *user_data, void **old_data) - -Sets the allocation event hook for numpy array data. -Takes a PyDataMem_EventHookFunc *, which has the signature: -void hook(void *old, void *new, size_t size, void *user_data). -Also takes a void *user_data, and void **old_data. - -Returns a pointer to the previous hook or NULL. If old_data is -non-NULL, the previous user_data pointer will be copied to it. - -If not NULL, hook will be called at the end of each PyDataMem_NEW/FREE/RENEW: -result = PyDataMem_NEW(size) -> (*hook)(NULL, result, size, user_data) -PyDataMem_FREE(ptr) -> (*hook)(ptr, NULL, 0, user_data) -result = PyDataMem_RENEW(ptr, size) -> (*hook)(ptr, result, size, user_data) - -When the hook is called, the GIL will be held by the calling -thread. The hook should be written to be reentrant, if it performs -operations that might cause new allocation events (such as the -creation/descruction numpy objects, or creating/destroying Python -objects which might cause a gc) - -:: - - void - PyArray_MapIterSwapAxes(PyArrayMapIterObject *mit, PyArrayObject - **ret, int getmap) - - -:: - - PyObject * - PyArray_MapIterArray(PyArrayObject *a, PyObject *index) - - -:: - - void - PyArray_MapIterNext(PyArrayMapIterObject *mit) - -This function needs to update the state of the map iterator -and point mit->dataptr to the memory-location of the next object - -:: - - int - PyArray_Partition(PyArrayObject *op, PyArrayObject *ktharray, int - axis, NPY_SELECTKIND which) - -Partition an array in-place - -:: - - PyObject * - PyArray_ArgPartition(PyArrayObject *op, PyArrayObject *ktharray, int - axis, NPY_SELECTKIND which) - -ArgPartition an array - -:: - - int - PyArray_SelectkindConverter(PyObject *obj, NPY_SELECTKIND *selectkind) - -Convert object to select kind - -:: - - void * - PyDataMem_NEW_ZEROED(size_t size, size_t elsize) - -Allocates zeroed memory for array data. - diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h b/gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h deleted file mode 100644 index b8c7c3a2d..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/ndarrayobject.h +++ /dev/null @@ -1,237 +0,0 @@ -/* - * DON'T INCLUDE THIS DIRECTLY. - */ - -#ifndef NPY_NDARRAYOBJECT_H -#define NPY_NDARRAYOBJECT_H -#ifdef __cplusplus -#define CONFUSE_EMACS { -#define CONFUSE_EMACS2 } -extern "C" CONFUSE_EMACS -#undef CONFUSE_EMACS -#undef CONFUSE_EMACS2 -/* ... otherwise a semi-smart identer (like emacs) tries to indent - everything when you're typing */ -#endif - -#include "ndarraytypes.h" - -/* Includes the "function" C-API -- these are all stored in a - list of pointers --- one for each file - The two lists are concatenated into one in multiarray. - - They are available as import_array() -*/ - -#include "__multiarray_api.h" - - -/* C-API that requries previous API to be defined */ - -#define PyArray_DescrCheck(op) (((PyObject*)(op))->ob_type==&PyArrayDescr_Type) - -#define PyArray_Check(op) PyObject_TypeCheck(op, &PyArray_Type) -#define PyArray_CheckExact(op) (((PyObject*)(op))->ob_type == &PyArray_Type) - -#define PyArray_HasArrayInterfaceType(op, type, context, out) \ - ((((out)=PyArray_FromStructInterface(op)) != Py_NotImplemented) || \ - (((out)=PyArray_FromInterface(op)) != Py_NotImplemented) || \ - (((out)=PyArray_FromArrayAttr(op, type, context)) != \ - Py_NotImplemented)) - -#define PyArray_HasArrayInterface(op, out) \ - PyArray_HasArrayInterfaceType(op, NULL, NULL, out) - -#define PyArray_IsZeroDim(op) (PyArray_Check(op) && \ - (PyArray_NDIM((PyArrayObject *)op) == 0)) - -#define PyArray_IsScalar(obj, cls) \ - (PyObject_TypeCheck(obj, &Py##cls##ArrType_Type)) - -#define PyArray_CheckScalar(m) (PyArray_IsScalar(m, Generic) || \ - PyArray_IsZeroDim(m)) - -#define PyArray_IsPythonNumber(obj) \ - (PyInt_Check(obj) || PyFloat_Check(obj) || PyComplex_Check(obj) || \ - PyLong_Check(obj) || PyBool_Check(obj)) - -#define PyArray_IsPythonScalar(obj) \ - (PyArray_IsPythonNumber(obj) || PyString_Check(obj) || \ - PyUnicode_Check(obj)) - -#define PyArray_IsAnyScalar(obj) \ - (PyArray_IsScalar(obj, Generic) || PyArray_IsPythonScalar(obj)) - -#define PyArray_CheckAnyScalar(obj) (PyArray_IsPythonScalar(obj) || \ - PyArray_CheckScalar(obj)) - -#define PyArray_IsIntegerScalar(obj) (PyInt_Check(obj) \ - || PyLong_Check(obj) \ - || PyArray_IsScalar((obj), Integer)) - - -#define PyArray_GETCONTIGUOUS(m) (PyArray_ISCONTIGUOUS(m) ? \ - Py_INCREF(m), (m) : \ - (PyArrayObject *)(PyArray_Copy(m))) - -#define PyArray_SAMESHAPE(a1,a2) ((PyArray_NDIM(a1) == PyArray_NDIM(a2)) && \ - PyArray_CompareLists(PyArray_DIMS(a1), \ - PyArray_DIMS(a2), \ - PyArray_NDIM(a1))) - -#define PyArray_SIZE(m) PyArray_MultiplyList(PyArray_DIMS(m), PyArray_NDIM(m)) -#define PyArray_NBYTES(m) (PyArray_ITEMSIZE(m) * PyArray_SIZE(m)) -#define PyArray_FROM_O(m) PyArray_FromAny(m, NULL, 0, 0, 0, NULL) - -#define PyArray_FROM_OF(m,flags) PyArray_CheckFromAny(m, NULL, 0, 0, flags, \ - NULL) - -#define PyArray_FROM_OT(m,type) PyArray_FromAny(m, \ - PyArray_DescrFromType(type), 0, 0, 0, NULL); - -#define PyArray_FROM_OTF(m, type, flags) \ - PyArray_FromAny(m, PyArray_DescrFromType(type), 0, 0, \ - (((flags) & NPY_ARRAY_ENSURECOPY) ? \ - ((flags) | NPY_ARRAY_DEFAULT) : (flags)), NULL) - -#define PyArray_FROMANY(m, type, min, max, flags) \ - PyArray_FromAny(m, PyArray_DescrFromType(type), min, max, \ - (((flags) & NPY_ARRAY_ENSURECOPY) ? \ - (flags) | NPY_ARRAY_DEFAULT : (flags)), NULL) - -#define PyArray_ZEROS(m, dims, type, is_f_order) \ - PyArray_Zeros(m, dims, PyArray_DescrFromType(type), is_f_order) - -#define PyArray_EMPTY(m, dims, type, is_f_order) \ - PyArray_Empty(m, dims, PyArray_DescrFromType(type), is_f_order) - -#define PyArray_FILLWBYTE(obj, val) memset(PyArray_DATA(obj), val, \ - PyArray_NBYTES(obj)) - -#define PyArray_REFCOUNT(obj) (((PyObject *)(obj))->ob_refcnt) -#define NPY_REFCOUNT PyArray_REFCOUNT -#define NPY_MAX_ELSIZE (2 * NPY_SIZEOF_LONGDOUBLE) - -#define PyArray_ContiguousFromAny(op, type, min_depth, max_depth) \ - PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ - max_depth, NPY_ARRAY_DEFAULT, NULL) - -#define PyArray_EquivArrTypes(a1, a2) \ - PyArray_EquivTypes(PyArray_DESCR(a1), PyArray_DESCR(a2)) - -#define PyArray_EquivByteorders(b1, b2) \ - (((b1) == (b2)) || (PyArray_ISNBO(b1) == PyArray_ISNBO(b2))) - -#define PyArray_SimpleNew(nd, dims, typenum) \ - PyArray_New(&PyArray_Type, nd, dims, typenum, NULL, NULL, 0, 0, NULL) - -#define PyArray_SimpleNewFromData(nd, dims, typenum, data) \ - PyArray_New(&PyArray_Type, nd, dims, typenum, NULL, \ - data, 0, NPY_ARRAY_CARRAY, NULL) - -#define PyArray_SimpleNewFromDescr(nd, dims, descr) \ - PyArray_NewFromDescr(&PyArray_Type, descr, nd, dims, \ - NULL, NULL, 0, NULL) - -#define PyArray_ToScalar(data, arr) \ - PyArray_Scalar(data, PyArray_DESCR(arr), (PyObject *)arr) - - -/* These might be faster without the dereferencing of obj - going on inside -- of course an optimizing compiler should - inline the constants inside a for loop making it a moot point -*/ - -#define PyArray_GETPTR1(obj, i) ((void *)(PyArray_BYTES(obj) + \ - (i)*PyArray_STRIDES(obj)[0])) - -#define PyArray_GETPTR2(obj, i, j) ((void *)(PyArray_BYTES(obj) + \ - (i)*PyArray_STRIDES(obj)[0] + \ - (j)*PyArray_STRIDES(obj)[1])) - -#define PyArray_GETPTR3(obj, i, j, k) ((void *)(PyArray_BYTES(obj) + \ - (i)*PyArray_STRIDES(obj)[0] + \ - (j)*PyArray_STRIDES(obj)[1] + \ - (k)*PyArray_STRIDES(obj)[2])) - -#define PyArray_GETPTR4(obj, i, j, k, l) ((void *)(PyArray_BYTES(obj) + \ - (i)*PyArray_STRIDES(obj)[0] + \ - (j)*PyArray_STRIDES(obj)[1] + \ - (k)*PyArray_STRIDES(obj)[2] + \ - (l)*PyArray_STRIDES(obj)[3])) - -static NPY_INLINE void -PyArray_XDECREF_ERR(PyArrayObject *arr) -{ - if (arr != NULL) { - if (PyArray_FLAGS(arr) & NPY_ARRAY_UPDATEIFCOPY) { - PyArrayObject *base = (PyArrayObject *)PyArray_BASE(arr); - PyArray_ENABLEFLAGS(base, NPY_ARRAY_WRITEABLE); - PyArray_CLEARFLAGS(arr, NPY_ARRAY_UPDATEIFCOPY); - } - Py_DECREF(arr); - } -} - -#define PyArray_DESCR_REPLACE(descr) do { \ - PyArray_Descr *_new_; \ - _new_ = PyArray_DescrNew(descr); \ - Py_XDECREF(descr); \ - descr = _new_; \ - } while(0) - -/* Copy should always return contiguous array */ -#define PyArray_Copy(obj) PyArray_NewCopy(obj, NPY_CORDER) - -#define PyArray_FromObject(op, type, min_depth, max_depth) \ - PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ - max_depth, NPY_ARRAY_BEHAVED | \ - NPY_ARRAY_ENSUREARRAY, NULL) - -#define PyArray_ContiguousFromObject(op, type, min_depth, max_depth) \ - PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ - max_depth, NPY_ARRAY_DEFAULT | \ - NPY_ARRAY_ENSUREARRAY, NULL) - -#define PyArray_CopyFromObject(op, type, min_depth, max_depth) \ - PyArray_FromAny(op, PyArray_DescrFromType(type), min_depth, \ - max_depth, NPY_ARRAY_ENSURECOPY | \ - NPY_ARRAY_DEFAULT | \ - NPY_ARRAY_ENSUREARRAY, NULL) - -#define PyArray_Cast(mp, type_num) \ - PyArray_CastToType(mp, PyArray_DescrFromType(type_num), 0) - -#define PyArray_Take(ap, items, axis) \ - PyArray_TakeFrom(ap, items, axis, NULL, NPY_RAISE) - -#define PyArray_Put(ap, items, values) \ - PyArray_PutTo(ap, items, values, NPY_RAISE) - -/* Compatibility with old Numeric stuff -- don't use in new code */ - -#define PyArray_FromDimsAndData(nd, d, type, data) \ - PyArray_FromDimsAndDataAndDescr(nd, d, PyArray_DescrFromType(type), \ - data) - - -/* - Check to see if this key in the dictionary is the "title" - entry of the tuple (i.e. a duplicate dictionary entry in the fields - dict. -*/ - -#define NPY_TITLE_KEY(key, value) ((PyTuple_GET_SIZE((value))==3) && \ - (PyTuple_GET_ITEM((value), 2) == (key))) - - -#define DEPRECATE(msg) PyErr_WarnEx(PyExc_DeprecationWarning,msg,1) -#define DEPRECATE_FUTUREWARNING(msg) PyErr_WarnEx(PyExc_FutureWarning,msg,1) - - -#ifdef __cplusplus -} -#endif - - -#endif /* NPY_NDARRAYOBJECT_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h b/gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h deleted file mode 100644 index 373a4df53..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/ndarraytypes.h +++ /dev/null @@ -1,1777 +0,0 @@ -#ifndef NDARRAYTYPES_H -#define NDARRAYTYPES_H - -#include "npy_common.h" -#include "npy_endian.h" -#include "npy_cpu.h" -#include "utils.h" - -#ifdef NPY_ENABLE_SEPARATE_COMPILATION - #define NPY_NO_EXPORT NPY_VISIBILITY_HIDDEN -#else - #define NPY_NO_EXPORT static -#endif - -/* Only use thread if configured in config and python supports it */ -#if defined WITH_THREAD && !NPY_NO_SMP - #define NPY_ALLOW_THREADS 1 -#else - #define NPY_ALLOW_THREADS 0 -#endif - - - -/* - * There are several places in the code where an array of dimensions - * is allocated statically. This is the size of that static - * allocation. - * - * The array creation itself could have arbitrary dimensions but all - * the places where static allocation is used would need to be changed - * to dynamic (including inside of several structures) - */ - -#define NPY_MAXDIMS 32 -#define NPY_MAXARGS 32 - -/* Used for Converter Functions "O&" code in ParseTuple */ -#define NPY_FAIL 0 -#define NPY_SUCCEED 1 - -/* - * Binary compatibility version number. This number is increased - * whenever the C-API is changed such that binary compatibility is - * broken, i.e. whenever a recompile of extension modules is needed. - */ -#define NPY_VERSION NPY_ABI_VERSION - -/* - * Minor API version. This number is increased whenever a change is - * made to the C-API -- whether it breaks binary compatibility or not. - * Some changes, such as adding a function pointer to the end of the - * function table, can be made without breaking binary compatibility. - * In this case, only the NPY_FEATURE_VERSION (*not* NPY_VERSION) - * would be increased. Whenever binary compatibility is broken, both - * NPY_VERSION and NPY_FEATURE_VERSION should be increased. - */ -#define NPY_FEATURE_VERSION NPY_API_VERSION - -enum NPY_TYPES { NPY_BOOL=0, - NPY_BYTE, NPY_UBYTE, - NPY_SHORT, NPY_USHORT, - NPY_INT, NPY_UINT, - NPY_LONG, NPY_ULONG, - NPY_LONGLONG, NPY_ULONGLONG, - NPY_FLOAT, NPY_DOUBLE, NPY_LONGDOUBLE, - NPY_CFLOAT, NPY_CDOUBLE, NPY_CLONGDOUBLE, - NPY_OBJECT=17, - NPY_STRING, NPY_UNICODE, - NPY_VOID, - /* - * New 1.6 types appended, may be integrated - * into the above in 2.0. - */ - NPY_DATETIME, NPY_TIMEDELTA, NPY_HALF, - - NPY_NTYPES, - NPY_NOTYPE, - NPY_CHAR, /* special flag */ - NPY_USERDEF=256, /* leave room for characters */ - - /* The number of types not including the new 1.6 types */ - NPY_NTYPES_ABI_COMPATIBLE=21 -}; - -/* basetype array priority */ -#define NPY_PRIORITY 0.0 - -/* default subtype priority */ -#define NPY_SUBTYPE_PRIORITY 1.0 - -/* default scalar priority */ -#define NPY_SCALAR_PRIORITY -1000000.0 - -/* How many floating point types are there (excluding half) */ -#define NPY_NUM_FLOATTYPE 3 - -/* - * These characters correspond to the array type and the struct - * module - */ - -enum NPY_TYPECHAR { - NPY_BOOLLTR = '?', - NPY_BYTELTR = 'b', - NPY_UBYTELTR = 'B', - NPY_SHORTLTR = 'h', - NPY_USHORTLTR = 'H', - NPY_INTLTR = 'i', - NPY_UINTLTR = 'I', - NPY_LONGLTR = 'l', - NPY_ULONGLTR = 'L', - NPY_LONGLONGLTR = 'q', - NPY_ULONGLONGLTR = 'Q', - NPY_HALFLTR = 'e', - NPY_FLOATLTR = 'f', - NPY_DOUBLELTR = 'd', - NPY_LONGDOUBLELTR = 'g', - NPY_CFLOATLTR = 'F', - NPY_CDOUBLELTR = 'D', - NPY_CLONGDOUBLELTR = 'G', - NPY_OBJECTLTR = 'O', - NPY_STRINGLTR = 'S', - NPY_STRINGLTR2 = 'a', - NPY_UNICODELTR = 'U', - NPY_VOIDLTR = 'V', - NPY_DATETIMELTR = 'M', - NPY_TIMEDELTALTR = 'm', - NPY_CHARLTR = 'c', - - /* - * No Descriptor, just a define -- this let's - * Python users specify an array of integers - * large enough to hold a pointer on the - * platform - */ - NPY_INTPLTR = 'p', - NPY_UINTPLTR = 'P', - - /* - * These are for dtype 'kinds', not dtype 'typecodes' - * as the above are for. - */ - NPY_GENBOOLLTR ='b', - NPY_SIGNEDLTR = 'i', - NPY_UNSIGNEDLTR = 'u', - NPY_FLOATINGLTR = 'f', - NPY_COMPLEXLTR = 'c' -}; - -typedef enum { - NPY_QUICKSORT=0, - NPY_HEAPSORT=1, - NPY_MERGESORT=2 -} NPY_SORTKIND; -#define NPY_NSORTS (NPY_MERGESORT + 1) - - -typedef enum { - NPY_INTROSELECT=0, -} NPY_SELECTKIND; -#define NPY_NSELECTS (NPY_INTROSELECT + 1) - - -typedef enum { - NPY_SEARCHLEFT=0, - NPY_SEARCHRIGHT=1 -} NPY_SEARCHSIDE; -#define NPY_NSEARCHSIDES (NPY_SEARCHRIGHT + 1) - - -typedef enum { - NPY_NOSCALAR=-1, - NPY_BOOL_SCALAR, - NPY_INTPOS_SCALAR, - NPY_INTNEG_SCALAR, - NPY_FLOAT_SCALAR, - NPY_COMPLEX_SCALAR, - NPY_OBJECT_SCALAR -} NPY_SCALARKIND; -#define NPY_NSCALARKINDS (NPY_OBJECT_SCALAR + 1) - -/* For specifying array memory layout or iteration order */ -typedef enum { - /* Fortran order if inputs are all Fortran, C otherwise */ - NPY_ANYORDER=-1, - /* C order */ - NPY_CORDER=0, - /* Fortran order */ - NPY_FORTRANORDER=1, - /* An order as close to the inputs as possible */ - NPY_KEEPORDER=2 -} NPY_ORDER; - -/* For specifying allowed casting in operations which support it */ -typedef enum { - /* Only allow identical types */ - NPY_NO_CASTING=0, - /* Allow identical and byte swapped types */ - NPY_EQUIV_CASTING=1, - /* Only allow safe casts */ - NPY_SAFE_CASTING=2, - /* Allow safe casts or casts within the same kind */ - NPY_SAME_KIND_CASTING=3, - /* Allow any casts */ - NPY_UNSAFE_CASTING=4, - - /* - * Temporary internal definition only, will be removed in upcoming - * release, see below - * */ - NPY_INTERNAL_UNSAFE_CASTING_BUT_WARN_UNLESS_SAME_KIND = 100, -} NPY_CASTING; - -typedef enum { - NPY_CLIP=0, - NPY_WRAP=1, - NPY_RAISE=2 -} NPY_CLIPMODE; - -/* The special not-a-time (NaT) value */ -#define NPY_DATETIME_NAT NPY_MIN_INT64 - -/* - * Upper bound on the length of a DATETIME ISO 8601 string - * YEAR: 21 (64-bit year) - * MONTH: 3 - * DAY: 3 - * HOURS: 3 - * MINUTES: 3 - * SECONDS: 3 - * ATTOSECONDS: 1 + 3*6 - * TIMEZONE: 5 - * NULL TERMINATOR: 1 - */ -#define NPY_DATETIME_MAX_ISO8601_STRLEN (21+3*5+1+3*6+6+1) - -typedef enum { - NPY_FR_Y = 0, /* Years */ - NPY_FR_M = 1, /* Months */ - NPY_FR_W = 2, /* Weeks */ - /* Gap where 1.6 NPY_FR_B (value 3) was */ - NPY_FR_D = 4, /* Days */ - NPY_FR_h = 5, /* hours */ - NPY_FR_m = 6, /* minutes */ - NPY_FR_s = 7, /* seconds */ - NPY_FR_ms = 8, /* milliseconds */ - NPY_FR_us = 9, /* microseconds */ - NPY_FR_ns = 10,/* nanoseconds */ - NPY_FR_ps = 11,/* picoseconds */ - NPY_FR_fs = 12,/* femtoseconds */ - NPY_FR_as = 13,/* attoseconds */ - NPY_FR_GENERIC = 14 /* Generic, unbound units, can convert to anything */ -} NPY_DATETIMEUNIT; - -/* - * NOTE: With the NPY_FR_B gap for 1.6 ABI compatibility, NPY_DATETIME_NUMUNITS - * is technically one more than the actual number of units. - */ -#define NPY_DATETIME_NUMUNITS (NPY_FR_GENERIC + 1) -#define NPY_DATETIME_DEFAULTUNIT NPY_FR_GENERIC - -/* - * Business day conventions for mapping invalid business - * days to valid business days. - */ -typedef enum { - /* Go forward in time to the following business day. */ - NPY_BUSDAY_FORWARD, - NPY_BUSDAY_FOLLOWING = NPY_BUSDAY_FORWARD, - /* Go backward in time to the preceding business day. */ - NPY_BUSDAY_BACKWARD, - NPY_BUSDAY_PRECEDING = NPY_BUSDAY_BACKWARD, - /* - * Go forward in time to the following business day, unless it - * crosses a month boundary, in which case go backward - */ - NPY_BUSDAY_MODIFIEDFOLLOWING, - /* - * Go backward in time to the preceding business day, unless it - * crosses a month boundary, in which case go forward. - */ - NPY_BUSDAY_MODIFIEDPRECEDING, - /* Produce a NaT for non-business days. */ - NPY_BUSDAY_NAT, - /* Raise an exception for non-business days. */ - NPY_BUSDAY_RAISE -} NPY_BUSDAY_ROLL; - -/************************************************************ - * NumPy Auxiliary Data for inner loops, sort functions, etc. - ************************************************************/ - -/* - * When creating an auxiliary data struct, this should always appear - * as the first member, like this: - * - * typedef struct { - * NpyAuxData base; - * double constant; - * } constant_multiplier_aux_data; - */ -typedef struct NpyAuxData_tag NpyAuxData; - -/* Function pointers for freeing or cloning auxiliary data */ -typedef void (NpyAuxData_FreeFunc) (NpyAuxData *); -typedef NpyAuxData *(NpyAuxData_CloneFunc) (NpyAuxData *); - -struct NpyAuxData_tag { - NpyAuxData_FreeFunc *free; - NpyAuxData_CloneFunc *clone; - /* To allow for a bit of expansion without breaking the ABI */ - void *reserved[2]; -}; - -/* Macros to use for freeing and cloning auxiliary data */ -#define NPY_AUXDATA_FREE(auxdata) \ - do { \ - if ((auxdata) != NULL) { \ - (auxdata)->free(auxdata); \ - } \ - } while(0) -#define NPY_AUXDATA_CLONE(auxdata) \ - ((auxdata)->clone(auxdata)) - -#define NPY_ERR(str) fprintf(stderr, #str); fflush(stderr); -#define NPY_ERR2(str) fprintf(stderr, str); fflush(stderr); - -#define NPY_STRINGIFY(x) #x -#define NPY_TOSTRING(x) NPY_STRINGIFY(x) - - /* - * Macros to define how array, and dimension/strides data is - * allocated. - */ - - /* Data buffer - PyDataMem_NEW/FREE/RENEW are in multiarraymodule.c */ - -#define NPY_USE_PYMEM 1 - -#if NPY_USE_PYMEM == 1 -#define PyArray_malloc PyMem_Malloc -#define PyArray_free PyMem_Free -#define PyArray_realloc PyMem_Realloc -#else -#define PyArray_malloc malloc -#define PyArray_free free -#define PyArray_realloc realloc -#endif - -/* Dimensions and strides */ -#define PyDimMem_NEW(size) \ - ((npy_intp *)PyArray_malloc(size*sizeof(npy_intp))) - -#define PyDimMem_FREE(ptr) PyArray_free(ptr) - -#define PyDimMem_RENEW(ptr,size) \ - ((npy_intp *)PyArray_realloc(ptr,size*sizeof(npy_intp))) - -/* forward declaration */ -struct _PyArray_Descr; - -/* These must deal with unaligned and swapped data if necessary */ -typedef PyObject * (PyArray_GetItemFunc) (void *, void *); -typedef int (PyArray_SetItemFunc)(PyObject *, void *, void *); - -typedef void (PyArray_CopySwapNFunc)(void *, npy_intp, void *, npy_intp, - npy_intp, int, void *); - -typedef void (PyArray_CopySwapFunc)(void *, void *, int, void *); -typedef npy_bool (PyArray_NonzeroFunc)(void *, void *); - - -/* - * These assume aligned and notswapped data -- a buffer will be used - * before or contiguous data will be obtained - */ - -typedef int (PyArray_CompareFunc)(const void *, const void *, void *); -typedef int (PyArray_ArgFunc)(void*, npy_intp, npy_intp*, void *); - -typedef void (PyArray_DotFunc)(void *, npy_intp, void *, npy_intp, void *, - npy_intp, void *); - -typedef void (PyArray_VectorUnaryFunc)(void *, void *, npy_intp, void *, - void *); - -/* - * XXX the ignore argument should be removed next time the API version - * is bumped. It used to be the separator. - */ -typedef int (PyArray_ScanFunc)(FILE *fp, void *dptr, - char *ignore, struct _PyArray_Descr *); -typedef int (PyArray_FromStrFunc)(char *s, void *dptr, char **endptr, - struct _PyArray_Descr *); - -typedef int (PyArray_FillFunc)(void *, npy_intp, void *); - -typedef int (PyArray_SortFunc)(void *, npy_intp, void *); -typedef int (PyArray_ArgSortFunc)(void *, npy_intp *, npy_intp, void *); -typedef int (PyArray_PartitionFunc)(void *, npy_intp, npy_intp, - npy_intp *, npy_intp *, - void *); -typedef int (PyArray_ArgPartitionFunc)(void *, npy_intp *, npy_intp, npy_intp, - npy_intp *, npy_intp *, - void *); - -typedef int (PyArray_FillWithScalarFunc)(void *, npy_intp, void *, void *); - -typedef int (PyArray_ScalarKindFunc)(void *); - -typedef void (PyArray_FastClipFunc)(void *in, npy_intp n_in, void *min, - void *max, void *out); -typedef void (PyArray_FastPutmaskFunc)(void *in, void *mask, npy_intp n_in, - void *values, npy_intp nv); -typedef int (PyArray_FastTakeFunc)(void *dest, void *src, npy_intp *indarray, - npy_intp nindarray, npy_intp n_outer, - npy_intp m_middle, npy_intp nelem, - NPY_CLIPMODE clipmode); - -typedef struct { - npy_intp *ptr; - int len; -} PyArray_Dims; - -typedef struct { - /* - * Functions to cast to most other standard types - * Can have some NULL entries. The types - * DATETIME, TIMEDELTA, and HALF go into the castdict - * even though they are built-in. - */ - PyArray_VectorUnaryFunc *cast[NPY_NTYPES_ABI_COMPATIBLE]; - - /* The next four functions *cannot* be NULL */ - - /* - * Functions to get and set items with standard Python types - * -- not array scalars - */ - PyArray_GetItemFunc *getitem; - PyArray_SetItemFunc *setitem; - - /* - * Copy and/or swap data. Memory areas may not overlap - * Use memmove first if they might - */ - PyArray_CopySwapNFunc *copyswapn; - PyArray_CopySwapFunc *copyswap; - - /* - * Function to compare items - * Can be NULL - */ - PyArray_CompareFunc *compare; - - /* - * Function to select largest - * Can be NULL - */ - PyArray_ArgFunc *argmax; - - /* - * Function to compute dot product - * Can be NULL - */ - PyArray_DotFunc *dotfunc; - - /* - * Function to scan an ASCII file and - * place a single value plus possible separator - * Can be NULL - */ - PyArray_ScanFunc *scanfunc; - - /* - * Function to read a single value from a string - * and adjust the pointer; Can be NULL - */ - PyArray_FromStrFunc *fromstr; - - /* - * Function to determine if data is zero or not - * If NULL a default version is - * used at Registration time. - */ - PyArray_NonzeroFunc *nonzero; - - /* - * Used for arange. - * Can be NULL. - */ - PyArray_FillFunc *fill; - - /* - * Function to fill arrays with scalar values - * Can be NULL - */ - PyArray_FillWithScalarFunc *fillwithscalar; - - /* - * Sorting functions - * Can be NULL - */ - PyArray_SortFunc *sort[NPY_NSORTS]; - PyArray_ArgSortFunc *argsort[NPY_NSORTS]; - - /* - * Dictionary of additional casting functions - * PyArray_VectorUnaryFuncs - * which can be populated to support casting - * to other registered types. Can be NULL - */ - PyObject *castdict; - - /* - * Functions useful for generalizing - * the casting rules. - * Can be NULL; - */ - PyArray_ScalarKindFunc *scalarkind; - int **cancastscalarkindto; - int *cancastto; - - PyArray_FastClipFunc *fastclip; - PyArray_FastPutmaskFunc *fastputmask; - PyArray_FastTakeFunc *fasttake; - - /* - * Function to select smallest - * Can be NULL - */ - PyArray_ArgFunc *argmin; - -} PyArray_ArrFuncs; - -/* The item must be reference counted when it is inserted or extracted. */ -#define NPY_ITEM_REFCOUNT 0x01 -/* Same as needing REFCOUNT */ -#define NPY_ITEM_HASOBJECT 0x01 -/* Convert to list for pickling */ -#define NPY_LIST_PICKLE 0x02 -/* The item is a POINTER */ -#define NPY_ITEM_IS_POINTER 0x04 -/* memory needs to be initialized for this data-type */ -#define NPY_NEEDS_INIT 0x08 -/* operations need Python C-API so don't give-up thread. */ -#define NPY_NEEDS_PYAPI 0x10 -/* Use f.getitem when extracting elements of this data-type */ -#define NPY_USE_GETITEM 0x20 -/* Use f.setitem when setting creating 0-d array from this data-type.*/ -#define NPY_USE_SETITEM 0x40 -/* A sticky flag specifically for structured arrays */ -#define NPY_ALIGNED_STRUCT 0x80 - -/* - *These are inherited for global data-type if any data-types in the - * field have them - */ -#define NPY_FROM_FIELDS (NPY_NEEDS_INIT | NPY_LIST_PICKLE | \ - NPY_ITEM_REFCOUNT | NPY_NEEDS_PYAPI) - -#define NPY_OBJECT_DTYPE_FLAGS (NPY_LIST_PICKLE | NPY_USE_GETITEM | \ - NPY_ITEM_IS_POINTER | NPY_ITEM_REFCOUNT | \ - NPY_NEEDS_INIT | NPY_NEEDS_PYAPI) - -#define PyDataType_FLAGCHK(dtype, flag) \ - (((dtype)->flags & (flag)) == (flag)) - -#define PyDataType_REFCHK(dtype) \ - PyDataType_FLAGCHK(dtype, NPY_ITEM_REFCOUNT) - -typedef struct _PyArray_Descr { - PyObject_HEAD - /* - * the type object representing an - * instance of this type -- should not - * be two type_numbers with the same type - * object. - */ - PyTypeObject *typeobj; - /* kind for this type */ - char kind; - /* unique-character representing this type */ - char type; - /* - * '>' (big), '<' (little), '|' - * (not-applicable), or '=' (native). - */ - char byteorder; - /* flags describing data type */ - char flags; - /* number representing this type */ - int type_num; - /* element size (itemsize) for this type */ - int elsize; - /* alignment needed for this type */ - int alignment; - /* - * Non-NULL if this type is - * is an array (C-contiguous) - * of some other type - */ - struct _arr_descr *subarray; - /* - * The fields dictionary for this type - * For statically defined descr this - * is always Py_None - */ - PyObject *fields; - /* - * An ordered tuple of field names or NULL - * if no fields are defined - */ - PyObject *names; - /* - * a table of functions specific for each - * basic data descriptor - */ - PyArray_ArrFuncs *f; - /* Metadata about this dtype */ - PyObject *metadata; - /* - * Metadata specific to the C implementation - * of the particular dtype. This was added - * for NumPy 1.7.0. - */ - NpyAuxData *c_metadata; -} PyArray_Descr; - -typedef struct _arr_descr { - PyArray_Descr *base; - PyObject *shape; /* a tuple */ -} PyArray_ArrayDescr; - -/* - * The main array object structure. - * - * It has been recommended to use the inline functions defined below - * (PyArray_DATA and friends) to access fields here for a number of - * releases. Direct access to the members themselves is deprecated. - * To ensure that your code does not use deprecated access, - * #define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION - * (or NPY_1_8_API_VERSION or higher as required). - */ -/* This struct will be moved to a private header in a future release */ -typedef struct tagPyArrayObject_fields { - PyObject_HEAD - /* Pointer to the raw data buffer */ - char *data; - /* The number of dimensions, also called 'ndim' */ - int nd; - /* The size in each dimension, also called 'shape' */ - npy_intp *dimensions; - /* - * Number of bytes to jump to get to the - * next element in each dimension - */ - npy_intp *strides; - /* - * This object is decref'd upon - * deletion of array. Except in the - * case of UPDATEIFCOPY which has - * special handling. - * - * For views it points to the original - * array, collapsed so no chains of - * views occur. - * - * For creation from buffer object it - * points to an object that shold be - * decref'd on deletion - * - * For UPDATEIFCOPY flag this is an - * array to-be-updated upon deletion - * of this one - */ - PyObject *base; - /* Pointer to type structure */ - PyArray_Descr *descr; - /* Flags describing array -- see below */ - int flags; - /* For weak references */ - PyObject *weakreflist; -} PyArrayObject_fields; - -/* - * To hide the implementation details, we only expose - * the Python struct HEAD. - */ -#if !defined(NPY_NO_DEPRECATED_API) || \ - (NPY_NO_DEPRECATED_API < NPY_1_7_API_VERSION) -/* - * Can't put this in npy_deprecated_api.h like the others. - * PyArrayObject field access is deprecated as of NumPy 1.7. - */ -typedef PyArrayObject_fields PyArrayObject; -#else -typedef struct tagPyArrayObject { - PyObject_HEAD -} PyArrayObject; -#endif - -#define NPY_SIZEOF_PYARRAYOBJECT (sizeof(PyArrayObject_fields)) - -/* Array Flags Object */ -typedef struct PyArrayFlagsObject { - PyObject_HEAD - PyObject *arr; - int flags; -} PyArrayFlagsObject; - -/* Mirrors buffer object to ptr */ - -typedef struct { - PyObject_HEAD - PyObject *base; - void *ptr; - npy_intp len; - int flags; -} PyArray_Chunk; - -typedef struct { - NPY_DATETIMEUNIT base; - int num; -} PyArray_DatetimeMetaData; - -typedef struct { - NpyAuxData base; - PyArray_DatetimeMetaData meta; -} PyArray_DatetimeDTypeMetaData; - -/* - * This structure contains an exploded view of a date-time value. - * NaT is represented by year == NPY_DATETIME_NAT. - */ -typedef struct { - npy_int64 year; - npy_int32 month, day, hour, min, sec, us, ps, as; -} npy_datetimestruct; - -/* This is not used internally. */ -typedef struct { - npy_int64 day; - npy_int32 sec, us, ps, as; -} npy_timedeltastruct; - -typedef int (PyArray_FinalizeFunc)(PyArrayObject *, PyObject *); - -/* - * Means c-style contiguous (last index varies the fastest). The data - * elements right after each other. - * - * This flag may be requested in constructor functions. - * This flag may be tested for in PyArray_FLAGS(arr). - */ -#define NPY_ARRAY_C_CONTIGUOUS 0x0001 - -/* - * Set if array is a contiguous Fortran array: the first index varies - * the fastest in memory (strides array is reverse of C-contiguous - * array) - * - * This flag may be requested in constructor functions. - * This flag may be tested for in PyArray_FLAGS(arr). - */ -#define NPY_ARRAY_F_CONTIGUOUS 0x0002 - -/* - * Note: all 0-d arrays are C_CONTIGUOUS and F_CONTIGUOUS. If a - * 1-d array is C_CONTIGUOUS it is also F_CONTIGUOUS. Arrays with - * more then one dimension can be C_CONTIGUOUS and F_CONTIGUOUS - * at the same time if they have either zero or one element. - * If NPY_RELAXED_STRIDES_CHECKING is set, a higher dimensional - * array is always C_CONTIGUOUS and F_CONTIGUOUS if it has zero elements - * and the array is contiguous if ndarray.squeeze() is contiguous. - * I.e. dimensions for which `ndarray.shape[dimension] == 1` are - * ignored. - */ - -/* - * If set, the array owns the data: it will be free'd when the array - * is deleted. - * - * This flag may be tested for in PyArray_FLAGS(arr). - */ -#define NPY_ARRAY_OWNDATA 0x0004 - -/* - * An array never has the next four set; they're only used as parameter - * flags to the the various FromAny functions - * - * This flag may be requested in constructor functions. - */ - -/* Cause a cast to occur regardless of whether or not it is safe. */ -#define NPY_ARRAY_FORCECAST 0x0010 - -/* - * Always copy the array. Returned arrays are always CONTIGUOUS, - * ALIGNED, and WRITEABLE. - * - * This flag may be requested in constructor functions. - */ -#define NPY_ARRAY_ENSURECOPY 0x0020 - -/* - * Make sure the returned array is a base-class ndarray - * - * This flag may be requested in constructor functions. - */ -#define NPY_ARRAY_ENSUREARRAY 0x0040 - -/* - * Make sure that the strides are in units of the element size Needed - * for some operations with record-arrays. - * - * This flag may be requested in constructor functions. - */ -#define NPY_ARRAY_ELEMENTSTRIDES 0x0080 - -/* - * Array data is aligned on the appropiate memory address for the type - * stored according to how the compiler would align things (e.g., an - * array of integers (4 bytes each) starts on a memory address that's - * a multiple of 4) - * - * This flag may be requested in constructor functions. - * This flag may be tested for in PyArray_FLAGS(arr). - */ -#define NPY_ARRAY_ALIGNED 0x0100 - -/* - * Array data has the native endianness - * - * This flag may be requested in constructor functions. - */ -#define NPY_ARRAY_NOTSWAPPED 0x0200 - -/* - * Array data is writeable - * - * This flag may be requested in constructor functions. - * This flag may be tested for in PyArray_FLAGS(arr). - */ -#define NPY_ARRAY_WRITEABLE 0x0400 - -/* - * If this flag is set, then base contains a pointer to an array of - * the same size that should be updated with the current contents of - * this array when this array is deallocated - * - * This flag may be requested in constructor functions. - * This flag may be tested for in PyArray_FLAGS(arr). - */ -#define NPY_ARRAY_UPDATEIFCOPY 0x1000 - -/* - * NOTE: there are also internal flags defined in multiarray/arrayobject.h, - * which start at bit 31 and work down. - */ - -#define NPY_ARRAY_BEHAVED (NPY_ARRAY_ALIGNED | \ - NPY_ARRAY_WRITEABLE) -#define NPY_ARRAY_BEHAVED_NS (NPY_ARRAY_ALIGNED | \ - NPY_ARRAY_WRITEABLE | \ - NPY_ARRAY_NOTSWAPPED) -#define NPY_ARRAY_CARRAY (NPY_ARRAY_C_CONTIGUOUS | \ - NPY_ARRAY_BEHAVED) -#define NPY_ARRAY_CARRAY_RO (NPY_ARRAY_C_CONTIGUOUS | \ - NPY_ARRAY_ALIGNED) -#define NPY_ARRAY_FARRAY (NPY_ARRAY_F_CONTIGUOUS | \ - NPY_ARRAY_BEHAVED) -#define NPY_ARRAY_FARRAY_RO (NPY_ARRAY_F_CONTIGUOUS | \ - NPY_ARRAY_ALIGNED) -#define NPY_ARRAY_DEFAULT (NPY_ARRAY_CARRAY) -#define NPY_ARRAY_IN_ARRAY (NPY_ARRAY_CARRAY_RO) -#define NPY_ARRAY_OUT_ARRAY (NPY_ARRAY_CARRAY) -#define NPY_ARRAY_INOUT_ARRAY (NPY_ARRAY_CARRAY | \ - NPY_ARRAY_UPDATEIFCOPY) -#define NPY_ARRAY_IN_FARRAY (NPY_ARRAY_FARRAY_RO) -#define NPY_ARRAY_OUT_FARRAY (NPY_ARRAY_FARRAY) -#define NPY_ARRAY_INOUT_FARRAY (NPY_ARRAY_FARRAY | \ - NPY_ARRAY_UPDATEIFCOPY) - -#define NPY_ARRAY_UPDATE_ALL (NPY_ARRAY_C_CONTIGUOUS | \ - NPY_ARRAY_F_CONTIGUOUS | \ - NPY_ARRAY_ALIGNED) - -/* This flag is for the array interface, not PyArrayObject */ -#define NPY_ARR_HAS_DESCR 0x0800 - - - - -/* - * Size of internal buffers used for alignment Make BUFSIZE a multiple - * of sizeof(npy_cdouble) -- usually 16 so that ufunc buffers are aligned - */ -#define NPY_MIN_BUFSIZE ((int)sizeof(npy_cdouble)) -#define NPY_MAX_BUFSIZE (((int)sizeof(npy_cdouble))*1000000) -#define NPY_BUFSIZE 8192 -/* buffer stress test size: */ -/*#define NPY_BUFSIZE 17*/ - -#define PyArray_MAX(a,b) (((a)>(b))?(a):(b)) -#define PyArray_MIN(a,b) (((a)<(b))?(a):(b)) -#define PyArray_CLT(p,q) ((((p).real==(q).real) ? ((p).imag < (q).imag) : \ - ((p).real < (q).real))) -#define PyArray_CGT(p,q) ((((p).real==(q).real) ? ((p).imag > (q).imag) : \ - ((p).real > (q).real))) -#define PyArray_CLE(p,q) ((((p).real==(q).real) ? ((p).imag <= (q).imag) : \ - ((p).real <= (q).real))) -#define PyArray_CGE(p,q) ((((p).real==(q).real) ? ((p).imag >= (q).imag) : \ - ((p).real >= (q).real))) -#define PyArray_CEQ(p,q) (((p).real==(q).real) && ((p).imag == (q).imag)) -#define PyArray_CNE(p,q) (((p).real!=(q).real) || ((p).imag != (q).imag)) - -/* - * C API: consists of Macros and functions. The MACROS are defined - * here. - */ - - -#define PyArray_ISCONTIGUOUS(m) PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS) -#define PyArray_ISWRITEABLE(m) PyArray_CHKFLAGS(m, NPY_ARRAY_WRITEABLE) -#define PyArray_ISALIGNED(m) PyArray_CHKFLAGS(m, NPY_ARRAY_ALIGNED) - -#define PyArray_IS_C_CONTIGUOUS(m) PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS) -#define PyArray_IS_F_CONTIGUOUS(m) PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS) - -#if NPY_ALLOW_THREADS -#define NPY_BEGIN_ALLOW_THREADS Py_BEGIN_ALLOW_THREADS -#define NPY_END_ALLOW_THREADS Py_END_ALLOW_THREADS -#define NPY_BEGIN_THREADS_DEF PyThreadState *_save=NULL; -#define NPY_BEGIN_THREADS do {_save = PyEval_SaveThread();} while (0); -#define NPY_END_THREADS do {if (_save) PyEval_RestoreThread(_save);} while (0); -#define NPY_BEGIN_THREADS_THRESHOLDED(loop_size) do { if (loop_size > 500) \ - { _save = PyEval_SaveThread();} } while (0); - -#define NPY_BEGIN_THREADS_DESCR(dtype) \ - do {if (!(PyDataType_FLAGCHK(dtype, NPY_NEEDS_PYAPI))) \ - NPY_BEGIN_THREADS;} while (0); - -#define NPY_END_THREADS_DESCR(dtype) \ - do {if (!(PyDataType_FLAGCHK(dtype, NPY_NEEDS_PYAPI))) \ - NPY_END_THREADS; } while (0); - -#define NPY_ALLOW_C_API_DEF PyGILState_STATE __save__; -#define NPY_ALLOW_C_API do {__save__ = PyGILState_Ensure();} while (0); -#define NPY_DISABLE_C_API do {PyGILState_Release(__save__);} while (0); -#else -#define NPY_BEGIN_ALLOW_THREADS -#define NPY_END_ALLOW_THREADS -#define NPY_BEGIN_THREADS_DEF -#define NPY_BEGIN_THREADS -#define NPY_END_THREADS -#define NPY_BEGIN_THREADS_THRESHOLDED(loop_size) -#define NPY_BEGIN_THREADS_DESCR(dtype) -#define NPY_END_THREADS_DESCR(dtype) -#define NPY_ALLOW_C_API_DEF -#define NPY_ALLOW_C_API -#define NPY_DISABLE_C_API -#endif - -/********************************** - * The nditer object, added in 1.6 - **********************************/ - -/* The actual structure of the iterator is an internal detail */ -typedef struct NpyIter_InternalOnly NpyIter; - -/* Iterator function pointers that may be specialized */ -typedef int (NpyIter_IterNextFunc)(NpyIter *iter); -typedef void (NpyIter_GetMultiIndexFunc)(NpyIter *iter, - npy_intp *outcoords); - -/*** Global flags that may be passed to the iterator constructors ***/ - -/* Track an index representing C order */ -#define NPY_ITER_C_INDEX 0x00000001 -/* Track an index representing Fortran order */ -#define NPY_ITER_F_INDEX 0x00000002 -/* Track a multi-index */ -#define NPY_ITER_MULTI_INDEX 0x00000004 -/* User code external to the iterator does the 1-dimensional innermost loop */ -#define NPY_ITER_EXTERNAL_LOOP 0x00000008 -/* Convert all the operands to a common data type */ -#define NPY_ITER_COMMON_DTYPE 0x00000010 -/* Operands may hold references, requiring API access during iteration */ -#define NPY_ITER_REFS_OK 0x00000020 -/* Zero-sized operands should be permitted, iteration checks IterSize for 0 */ -#define NPY_ITER_ZEROSIZE_OK 0x00000040 -/* Permits reductions (size-0 stride with dimension size > 1) */ -#define NPY_ITER_REDUCE_OK 0x00000080 -/* Enables sub-range iteration */ -#define NPY_ITER_RANGED 0x00000100 -/* Enables buffering */ -#define NPY_ITER_BUFFERED 0x00000200 -/* When buffering is enabled, grows the inner loop if possible */ -#define NPY_ITER_GROWINNER 0x00000400 -/* Delay allocation of buffers until first Reset* call */ -#define NPY_ITER_DELAY_BUFALLOC 0x00000800 -/* When NPY_KEEPORDER is specified, disable reversing negative-stride axes */ -#define NPY_ITER_DONT_NEGATE_STRIDES 0x00001000 - -/*** Per-operand flags that may be passed to the iterator constructors ***/ - -/* The operand will be read from and written to */ -#define NPY_ITER_READWRITE 0x00010000 -/* The operand will only be read from */ -#define NPY_ITER_READONLY 0x00020000 -/* The operand will only be written to */ -#define NPY_ITER_WRITEONLY 0x00040000 -/* The operand's data must be in native byte order */ -#define NPY_ITER_NBO 0x00080000 -/* The operand's data must be aligned */ -#define NPY_ITER_ALIGNED 0x00100000 -/* The operand's data must be contiguous (within the inner loop) */ -#define NPY_ITER_CONTIG 0x00200000 -/* The operand may be copied to satisfy requirements */ -#define NPY_ITER_COPY 0x00400000 -/* The operand may be copied with UPDATEIFCOPY to satisfy requirements */ -#define NPY_ITER_UPDATEIFCOPY 0x00800000 -/* Allocate the operand if it is NULL */ -#define NPY_ITER_ALLOCATE 0x01000000 -/* If an operand is allocated, don't use any subtype */ -#define NPY_ITER_NO_SUBTYPE 0x02000000 -/* This is a virtual array slot, operand is NULL but temporary data is there */ -#define NPY_ITER_VIRTUAL 0x04000000 -/* Require that the dimension match the iterator dimensions exactly */ -#define NPY_ITER_NO_BROADCAST 0x08000000 -/* A mask is being used on this array, affects buffer -> array copy */ -#define NPY_ITER_WRITEMASKED 0x10000000 -/* This array is the mask for all WRITEMASKED operands */ -#define NPY_ITER_ARRAYMASK 0x20000000 - -#define NPY_ITER_GLOBAL_FLAGS 0x0000ffff -#define NPY_ITER_PER_OP_FLAGS 0xffff0000 - - -/***************************** - * Basic iterator object - *****************************/ - -/* FWD declaration */ -typedef struct PyArrayIterObject_tag PyArrayIterObject; - -/* - * type of the function which translates a set of coordinates to a - * pointer to the data - */ -typedef char* (*npy_iter_get_dataptr_t)(PyArrayIterObject* iter, npy_intp*); - -struct PyArrayIterObject_tag { - PyObject_HEAD - int nd_m1; /* number of dimensions - 1 */ - npy_intp index, size; - npy_intp coordinates[NPY_MAXDIMS];/* N-dimensional loop */ - npy_intp dims_m1[NPY_MAXDIMS]; /* ao->dimensions - 1 */ - npy_intp strides[NPY_MAXDIMS]; /* ao->strides or fake */ - npy_intp backstrides[NPY_MAXDIMS];/* how far to jump back */ - npy_intp factors[NPY_MAXDIMS]; /* shape factors */ - PyArrayObject *ao; - char *dataptr; /* pointer to current item*/ - npy_bool contiguous; - - npy_intp bounds[NPY_MAXDIMS][2]; - npy_intp limits[NPY_MAXDIMS][2]; - npy_intp limits_sizes[NPY_MAXDIMS]; - npy_iter_get_dataptr_t translate; -} ; - - -/* Iterator API */ -#define PyArrayIter_Check(op) PyObject_TypeCheck(op, &PyArrayIter_Type) - -#define _PyAIT(it) ((PyArrayIterObject *)(it)) -#define PyArray_ITER_RESET(it) do { \ - _PyAIT(it)->index = 0; \ - _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao); \ - memset(_PyAIT(it)->coordinates, 0, \ - (_PyAIT(it)->nd_m1+1)*sizeof(npy_intp)); \ -} while (0) - -#define _PyArray_ITER_NEXT1(it) do { \ - (it)->dataptr += _PyAIT(it)->strides[0]; \ - (it)->coordinates[0]++; \ -} while (0) - -#define _PyArray_ITER_NEXT2(it) do { \ - if ((it)->coordinates[1] < (it)->dims_m1[1]) { \ - (it)->coordinates[1]++; \ - (it)->dataptr += (it)->strides[1]; \ - } \ - else { \ - (it)->coordinates[1] = 0; \ - (it)->coordinates[0]++; \ - (it)->dataptr += (it)->strides[0] - \ - (it)->backstrides[1]; \ - } \ -} while (0) - -#define _PyArray_ITER_NEXT3(it) do { \ - if ((it)->coordinates[2] < (it)->dims_m1[2]) { \ - (it)->coordinates[2]++; \ - (it)->dataptr += (it)->strides[2]; \ - } \ - else { \ - (it)->coordinates[2] = 0; \ - (it)->dataptr -= (it)->backstrides[2]; \ - if ((it)->coordinates[1] < (it)->dims_m1[1]) { \ - (it)->coordinates[1]++; \ - (it)->dataptr += (it)->strides[1]; \ - } \ - else { \ - (it)->coordinates[1] = 0; \ - (it)->coordinates[0]++; \ - (it)->dataptr += (it)->strides[0] \ - (it)->backstrides[1]; \ - } \ - } \ -} while (0) - -#define PyArray_ITER_NEXT(it) do { \ - _PyAIT(it)->index++; \ - if (_PyAIT(it)->nd_m1 == 0) { \ - _PyArray_ITER_NEXT1(_PyAIT(it)); \ - } \ - else if (_PyAIT(it)->contiguous) \ - _PyAIT(it)->dataptr += PyArray_DESCR(_PyAIT(it)->ao)->elsize; \ - else if (_PyAIT(it)->nd_m1 == 1) { \ - _PyArray_ITER_NEXT2(_PyAIT(it)); \ - } \ - else { \ - int __npy_i; \ - for (__npy_i=_PyAIT(it)->nd_m1; __npy_i >= 0; __npy_i--) { \ - if (_PyAIT(it)->coordinates[__npy_i] < \ - _PyAIT(it)->dims_m1[__npy_i]) { \ - _PyAIT(it)->coordinates[__npy_i]++; \ - _PyAIT(it)->dataptr += \ - _PyAIT(it)->strides[__npy_i]; \ - break; \ - } \ - else { \ - _PyAIT(it)->coordinates[__npy_i] = 0; \ - _PyAIT(it)->dataptr -= \ - _PyAIT(it)->backstrides[__npy_i]; \ - } \ - } \ - } \ -} while (0) - -#define PyArray_ITER_GOTO(it, destination) do { \ - int __npy_i; \ - _PyAIT(it)->index = 0; \ - _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao); \ - for (__npy_i = _PyAIT(it)->nd_m1; __npy_i>=0; __npy_i--) { \ - if (destination[__npy_i] < 0) { \ - destination[__npy_i] += \ - _PyAIT(it)->dims_m1[__npy_i]+1; \ - } \ - _PyAIT(it)->dataptr += destination[__npy_i] * \ - _PyAIT(it)->strides[__npy_i]; \ - _PyAIT(it)->coordinates[__npy_i] = \ - destination[__npy_i]; \ - _PyAIT(it)->index += destination[__npy_i] * \ - ( __npy_i==_PyAIT(it)->nd_m1 ? 1 : \ - _PyAIT(it)->dims_m1[__npy_i+1]+1) ; \ - } \ -} while (0) - -#define PyArray_ITER_GOTO1D(it, ind) do { \ - int __npy_i; \ - npy_intp __npy_ind = (npy_intp) (ind); \ - if (__npy_ind < 0) __npy_ind += _PyAIT(it)->size; \ - _PyAIT(it)->index = __npy_ind; \ - if (_PyAIT(it)->nd_m1 == 0) { \ - _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao) + \ - __npy_ind * _PyAIT(it)->strides[0]; \ - } \ - else if (_PyAIT(it)->contiguous) \ - _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao) + \ - __npy_ind * PyArray_DESCR(_PyAIT(it)->ao)->elsize; \ - else { \ - _PyAIT(it)->dataptr = PyArray_BYTES(_PyAIT(it)->ao); \ - for (__npy_i = 0; __npy_i<=_PyAIT(it)->nd_m1; \ - __npy_i++) { \ - _PyAIT(it)->dataptr += \ - (__npy_ind / _PyAIT(it)->factors[__npy_i]) \ - * _PyAIT(it)->strides[__npy_i]; \ - __npy_ind %= _PyAIT(it)->factors[__npy_i]; \ - } \ - } \ -} while (0) - -#define PyArray_ITER_DATA(it) ((void *)(_PyAIT(it)->dataptr)) - -#define PyArray_ITER_NOTDONE(it) (_PyAIT(it)->index < _PyAIT(it)->size) - - -/* - * Any object passed to PyArray_Broadcast must be binary compatible - * with this structure. - */ - -typedef struct { - PyObject_HEAD - int numiter; /* number of iters */ - npy_intp size; /* broadcasted size */ - npy_intp index; /* current index */ - int nd; /* number of dims */ - npy_intp dimensions[NPY_MAXDIMS]; /* dimensions */ - PyArrayIterObject *iters[NPY_MAXARGS]; /* iterators */ -} PyArrayMultiIterObject; - -#define _PyMIT(m) ((PyArrayMultiIterObject *)(m)) -#define PyArray_MultiIter_RESET(multi) do { \ - int __npy_mi; \ - _PyMIT(multi)->index = 0; \ - for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ - PyArray_ITER_RESET(_PyMIT(multi)->iters[__npy_mi]); \ - } \ -} while (0) - -#define PyArray_MultiIter_NEXT(multi) do { \ - int __npy_mi; \ - _PyMIT(multi)->index++; \ - for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ - PyArray_ITER_NEXT(_PyMIT(multi)->iters[__npy_mi]); \ - } \ -} while (0) - -#define PyArray_MultiIter_GOTO(multi, dest) do { \ - int __npy_mi; \ - for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ - PyArray_ITER_GOTO(_PyMIT(multi)->iters[__npy_mi], dest); \ - } \ - _PyMIT(multi)->index = _PyMIT(multi)->iters[0]->index; \ -} while (0) - -#define PyArray_MultiIter_GOTO1D(multi, ind) do { \ - int __npy_mi; \ - for (__npy_mi=0; __npy_mi < _PyMIT(multi)->numiter; __npy_mi++) { \ - PyArray_ITER_GOTO1D(_PyMIT(multi)->iters[__npy_mi], ind); \ - } \ - _PyMIT(multi)->index = _PyMIT(multi)->iters[0]->index; \ -} while (0) - -#define PyArray_MultiIter_DATA(multi, i) \ - ((void *)(_PyMIT(multi)->iters[i]->dataptr)) - -#define PyArray_MultiIter_NEXTi(multi, i) \ - PyArray_ITER_NEXT(_PyMIT(multi)->iters[i]) - -#define PyArray_MultiIter_NOTDONE(multi) \ - (_PyMIT(multi)->index < _PyMIT(multi)->size) - -/* Store the information needed for fancy-indexing over an array */ - -typedef struct { - PyObject_HEAD - /* - * Multi-iterator portion --- needs to be present in this - * order to work with PyArray_Broadcast - */ - - int numiter; /* number of index-array - iterators */ - npy_intp size; /* size of broadcasted - result */ - npy_intp index; /* current index */ - int nd; /* number of dims */ - npy_intp dimensions[NPY_MAXDIMS]; /* dimensions */ - PyArrayIterObject *iters[NPY_MAXDIMS]; /* index object - iterators */ - PyArrayIterObject *ait; /* flat Iterator for - underlying array */ - - /* flat iterator for subspace (when numiter < nd) */ - PyArrayIterObject *subspace; - - /* - * if subspace iteration, then this is the array of axes in - * the underlying array represented by the index objects - */ - int iteraxes[NPY_MAXDIMS]; - /* - * if subspace iteration, the these are the coordinates to the - * start of the subspace. - */ - npy_intp bscoord[NPY_MAXDIMS]; - - PyObject *indexobj; /* creating obj */ - /* - * consec is first used to indicate wether fancy indices are - * consecutive and then denotes at which axis they are inserted - */ - int consec; - char *dataptr; - -} PyArrayMapIterObject; - -enum { - NPY_NEIGHBORHOOD_ITER_ZERO_PADDING, - NPY_NEIGHBORHOOD_ITER_ONE_PADDING, - NPY_NEIGHBORHOOD_ITER_CONSTANT_PADDING, - NPY_NEIGHBORHOOD_ITER_CIRCULAR_PADDING, - NPY_NEIGHBORHOOD_ITER_MIRROR_PADDING -}; - -typedef struct { - PyObject_HEAD - - /* - * PyArrayIterObject part: keep this in this exact order - */ - int nd_m1; /* number of dimensions - 1 */ - npy_intp index, size; - npy_intp coordinates[NPY_MAXDIMS];/* N-dimensional loop */ - npy_intp dims_m1[NPY_MAXDIMS]; /* ao->dimensions - 1 */ - npy_intp strides[NPY_MAXDIMS]; /* ao->strides or fake */ - npy_intp backstrides[NPY_MAXDIMS];/* how far to jump back */ - npy_intp factors[NPY_MAXDIMS]; /* shape factors */ - PyArrayObject *ao; - char *dataptr; /* pointer to current item*/ - npy_bool contiguous; - - npy_intp bounds[NPY_MAXDIMS][2]; - npy_intp limits[NPY_MAXDIMS][2]; - npy_intp limits_sizes[NPY_MAXDIMS]; - npy_iter_get_dataptr_t translate; - - /* - * New members - */ - npy_intp nd; - - /* Dimensions is the dimension of the array */ - npy_intp dimensions[NPY_MAXDIMS]; - - /* - * Neighborhood points coordinates are computed relatively to the - * point pointed by _internal_iter - */ - PyArrayIterObject* _internal_iter; - /* - * To keep a reference to the representation of the constant value - * for constant padding - */ - char* constant; - - int mode; -} PyArrayNeighborhoodIterObject; - -/* - * Neighborhood iterator API - */ - -/* General: those work for any mode */ -static NPY_INLINE int -PyArrayNeighborhoodIter_Reset(PyArrayNeighborhoodIterObject* iter); -static NPY_INLINE int -PyArrayNeighborhoodIter_Next(PyArrayNeighborhoodIterObject* iter); -#if 0 -static NPY_INLINE int -PyArrayNeighborhoodIter_Next2D(PyArrayNeighborhoodIterObject* iter); -#endif - -/* - * Include inline implementations - functions defined there are not - * considered public API - */ -#define _NPY_INCLUDE_NEIGHBORHOOD_IMP -#include "_neighborhood_iterator_imp.h" -#undef _NPY_INCLUDE_NEIGHBORHOOD_IMP - -/* The default array type */ -#define NPY_DEFAULT_TYPE NPY_DOUBLE - -/* - * All sorts of useful ways to look into a PyArrayObject. It is recommended - * to use PyArrayObject * objects instead of always casting from PyObject *, - * for improved type checking. - * - * In many cases here the macro versions of the accessors are deprecated, - * but can't be immediately changed to inline functions because the - * preexisting macros accept PyObject * and do automatic casts. Inline - * functions accepting PyArrayObject * provides for some compile-time - * checking of correctness when working with these objects in C. - */ - -#define PyArray_ISONESEGMENT(m) (PyArray_NDIM(m) == 0 || \ - PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS) || \ - PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS)) - -#define PyArray_ISFORTRAN(m) (PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS) && \ - (!PyArray_CHKFLAGS(m, NPY_ARRAY_C_CONTIGUOUS))) - -#define PyArray_FORTRAN_IF(m) ((PyArray_CHKFLAGS(m, NPY_ARRAY_F_CONTIGUOUS) ? \ - NPY_ARRAY_F_CONTIGUOUS : 0)) - -#if (defined(NPY_NO_DEPRECATED_API) && (NPY_1_7_API_VERSION <= NPY_NO_DEPRECATED_API)) -/* - * Changing access macros into functions, to allow for future hiding - * of the internal memory layout. This later hiding will allow the 2.x series - * to change the internal representation of arrays without affecting - * ABI compatibility. - */ - -static NPY_INLINE int -PyArray_NDIM(const PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->nd; -} - -static NPY_INLINE void * -PyArray_DATA(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->data; -} - -static NPY_INLINE char * -PyArray_BYTES(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->data; -} - -static NPY_INLINE npy_intp * -PyArray_DIMS(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->dimensions; -} - -static NPY_INLINE npy_intp * -PyArray_STRIDES(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->strides; -} - -static NPY_INLINE npy_intp -PyArray_DIM(const PyArrayObject *arr, int idim) -{ - return ((PyArrayObject_fields *)arr)->dimensions[idim]; -} - -static NPY_INLINE npy_intp -PyArray_STRIDE(const PyArrayObject *arr, int istride) -{ - return ((PyArrayObject_fields *)arr)->strides[istride]; -} - -static NPY_INLINE PyObject * -PyArray_BASE(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->base; -} - -static NPY_INLINE PyArray_Descr * -PyArray_DESCR(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->descr; -} - -static NPY_INLINE int -PyArray_FLAGS(const PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->flags; -} - -static NPY_INLINE npy_intp -PyArray_ITEMSIZE(const PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->descr->elsize; -} - -static NPY_INLINE int -PyArray_TYPE(const PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->descr->type_num; -} - -static NPY_INLINE int -PyArray_CHKFLAGS(const PyArrayObject *arr, int flags) -{ - return (PyArray_FLAGS(arr) & flags) == flags; -} - -static NPY_INLINE PyObject * -PyArray_GETITEM(const PyArrayObject *arr, const char *itemptr) -{ - return ((PyArrayObject_fields *)arr)->descr->f->getitem( - (void *)itemptr, (PyArrayObject *)arr); -} - -static NPY_INLINE int -PyArray_SETITEM(PyArrayObject *arr, char *itemptr, PyObject *v) -{ - return ((PyArrayObject_fields *)arr)->descr->f->setitem( - v, itemptr, arr); -} - -#else - -/* These macros are deprecated as of NumPy 1.7. */ -#define PyArray_NDIM(obj) (((PyArrayObject_fields *)(obj))->nd) -#define PyArray_BYTES(obj) (((PyArrayObject_fields *)(obj))->data) -#define PyArray_DATA(obj) ((void *)((PyArrayObject_fields *)(obj))->data) -#define PyArray_DIMS(obj) (((PyArrayObject_fields *)(obj))->dimensions) -#define PyArray_STRIDES(obj) (((PyArrayObject_fields *)(obj))->strides) -#define PyArray_DIM(obj,n) (PyArray_DIMS(obj)[n]) -#define PyArray_STRIDE(obj,n) (PyArray_STRIDES(obj)[n]) -#define PyArray_BASE(obj) (((PyArrayObject_fields *)(obj))->base) -#define PyArray_DESCR(obj) (((PyArrayObject_fields *)(obj))->descr) -#define PyArray_FLAGS(obj) (((PyArrayObject_fields *)(obj))->flags) -#define PyArray_CHKFLAGS(m, FLAGS) \ - ((((PyArrayObject_fields *)(m))->flags & (FLAGS)) == (FLAGS)) -#define PyArray_ITEMSIZE(obj) \ - (((PyArrayObject_fields *)(obj))->descr->elsize) -#define PyArray_TYPE(obj) \ - (((PyArrayObject_fields *)(obj))->descr->type_num) -#define PyArray_GETITEM(obj,itemptr) \ - PyArray_DESCR(obj)->f->getitem((char *)(itemptr), \ - (PyArrayObject *)(obj)) - -#define PyArray_SETITEM(obj,itemptr,v) \ - PyArray_DESCR(obj)->f->setitem((PyObject *)(v), \ - (char *)(itemptr), \ - (PyArrayObject *)(obj)) -#endif - -static NPY_INLINE PyArray_Descr * -PyArray_DTYPE(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->descr; -} - -static NPY_INLINE npy_intp * -PyArray_SHAPE(PyArrayObject *arr) -{ - return ((PyArrayObject_fields *)arr)->dimensions; -} - -/* - * Enables the specified array flags. Does no checking, - * assumes you know what you're doing. - */ -static NPY_INLINE void -PyArray_ENABLEFLAGS(PyArrayObject *arr, int flags) -{ - ((PyArrayObject_fields *)arr)->flags |= flags; -} - -/* - * Clears the specified array flags. Does no checking, - * assumes you know what you're doing. - */ -static NPY_INLINE void -PyArray_CLEARFLAGS(PyArrayObject *arr, int flags) -{ - ((PyArrayObject_fields *)arr)->flags &= ~flags; -} - -#define PyTypeNum_ISBOOL(type) ((type) == NPY_BOOL) - -#define PyTypeNum_ISUNSIGNED(type) (((type) == NPY_UBYTE) || \ - ((type) == NPY_USHORT) || \ - ((type) == NPY_UINT) || \ - ((type) == NPY_ULONG) || \ - ((type) == NPY_ULONGLONG)) - -#define PyTypeNum_ISSIGNED(type) (((type) == NPY_BYTE) || \ - ((type) == NPY_SHORT) || \ - ((type) == NPY_INT) || \ - ((type) == NPY_LONG) || \ - ((type) == NPY_LONGLONG)) - -#define PyTypeNum_ISINTEGER(type) (((type) >= NPY_BYTE) && \ - ((type) <= NPY_ULONGLONG)) - -#define PyTypeNum_ISFLOAT(type) ((((type) >= NPY_FLOAT) && \ - ((type) <= NPY_LONGDOUBLE)) || \ - ((type) == NPY_HALF)) - -#define PyTypeNum_ISNUMBER(type) (((type) <= NPY_CLONGDOUBLE) || \ - ((type) == NPY_HALF)) - -#define PyTypeNum_ISSTRING(type) (((type) == NPY_STRING) || \ - ((type) == NPY_UNICODE)) - -#define PyTypeNum_ISCOMPLEX(type) (((type) >= NPY_CFLOAT) && \ - ((type) <= NPY_CLONGDOUBLE)) - -#define PyTypeNum_ISPYTHON(type) (((type) == NPY_LONG) || \ - ((type) == NPY_DOUBLE) || \ - ((type) == NPY_CDOUBLE) || \ - ((type) == NPY_BOOL) || \ - ((type) == NPY_OBJECT )) - -#define PyTypeNum_ISFLEXIBLE(type) (((type) >=NPY_STRING) && \ - ((type) <=NPY_VOID)) - -#define PyTypeNum_ISDATETIME(type) (((type) >=NPY_DATETIME) && \ - ((type) <=NPY_TIMEDELTA)) - -#define PyTypeNum_ISUSERDEF(type) (((type) >= NPY_USERDEF) && \ - ((type) < NPY_USERDEF+ \ - NPY_NUMUSERTYPES)) - -#define PyTypeNum_ISEXTENDED(type) (PyTypeNum_ISFLEXIBLE(type) || \ - PyTypeNum_ISUSERDEF(type)) - -#define PyTypeNum_ISOBJECT(type) ((type) == NPY_OBJECT) - - -#define PyDataType_ISBOOL(obj) PyTypeNum_ISBOOL(_PyADt(obj)) -#define PyDataType_ISUNSIGNED(obj) PyTypeNum_ISUNSIGNED(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISSIGNED(obj) PyTypeNum_ISSIGNED(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISINTEGER(obj) PyTypeNum_ISINTEGER(((PyArray_Descr*)(obj))->type_num ) -#define PyDataType_ISFLOAT(obj) PyTypeNum_ISFLOAT(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISNUMBER(obj) PyTypeNum_ISNUMBER(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISSTRING(obj) PyTypeNum_ISSTRING(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISCOMPLEX(obj) PyTypeNum_ISCOMPLEX(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISPYTHON(obj) PyTypeNum_ISPYTHON(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISFLEXIBLE(obj) PyTypeNum_ISFLEXIBLE(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISDATETIME(obj) PyTypeNum_ISDATETIME(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISUSERDEF(obj) PyTypeNum_ISUSERDEF(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISEXTENDED(obj) PyTypeNum_ISEXTENDED(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_ISOBJECT(obj) PyTypeNum_ISOBJECT(((PyArray_Descr*)(obj))->type_num) -#define PyDataType_HASFIELDS(obj) (((PyArray_Descr *)(obj))->names != NULL) -#define PyDataType_HASSUBARRAY(dtype) ((dtype)->subarray != NULL) - -#define PyArray_ISBOOL(obj) PyTypeNum_ISBOOL(PyArray_TYPE(obj)) -#define PyArray_ISUNSIGNED(obj) PyTypeNum_ISUNSIGNED(PyArray_TYPE(obj)) -#define PyArray_ISSIGNED(obj) PyTypeNum_ISSIGNED(PyArray_TYPE(obj)) -#define PyArray_ISINTEGER(obj) PyTypeNum_ISINTEGER(PyArray_TYPE(obj)) -#define PyArray_ISFLOAT(obj) PyTypeNum_ISFLOAT(PyArray_TYPE(obj)) -#define PyArray_ISNUMBER(obj) PyTypeNum_ISNUMBER(PyArray_TYPE(obj)) -#define PyArray_ISSTRING(obj) PyTypeNum_ISSTRING(PyArray_TYPE(obj)) -#define PyArray_ISCOMPLEX(obj) PyTypeNum_ISCOMPLEX(PyArray_TYPE(obj)) -#define PyArray_ISPYTHON(obj) PyTypeNum_ISPYTHON(PyArray_TYPE(obj)) -#define PyArray_ISFLEXIBLE(obj) PyTypeNum_ISFLEXIBLE(PyArray_TYPE(obj)) -#define PyArray_ISDATETIME(obj) PyTypeNum_ISDATETIME(PyArray_TYPE(obj)) -#define PyArray_ISUSERDEF(obj) PyTypeNum_ISUSERDEF(PyArray_TYPE(obj)) -#define PyArray_ISEXTENDED(obj) PyTypeNum_ISEXTENDED(PyArray_TYPE(obj)) -#define PyArray_ISOBJECT(obj) PyTypeNum_ISOBJECT(PyArray_TYPE(obj)) -#define PyArray_HASFIELDS(obj) PyDataType_HASFIELDS(PyArray_DESCR(obj)) - - /* - * FIXME: This should check for a flag on the data-type that - * states whether or not it is variable length. Because the - * ISFLEXIBLE check is hard-coded to the built-in data-types. - */ -#define PyArray_ISVARIABLE(obj) PyTypeNum_ISFLEXIBLE(PyArray_TYPE(obj)) - -#define PyArray_SAFEALIGNEDCOPY(obj) (PyArray_ISALIGNED(obj) && !PyArray_ISVARIABLE(obj)) - - -#define NPY_LITTLE '<' -#define NPY_BIG '>' -#define NPY_NATIVE '=' -#define NPY_SWAP 's' -#define NPY_IGNORE '|' - -#if NPY_BYTE_ORDER == NPY_BIG_ENDIAN -#define NPY_NATBYTE NPY_BIG -#define NPY_OPPBYTE NPY_LITTLE -#else -#define NPY_NATBYTE NPY_LITTLE -#define NPY_OPPBYTE NPY_BIG -#endif - -#define PyArray_ISNBO(arg) ((arg) != NPY_OPPBYTE) -#define PyArray_IsNativeByteOrder PyArray_ISNBO -#define PyArray_ISNOTSWAPPED(m) PyArray_ISNBO(PyArray_DESCR(m)->byteorder) -#define PyArray_ISBYTESWAPPED(m) (!PyArray_ISNOTSWAPPED(m)) - -#define PyArray_FLAGSWAP(m, flags) (PyArray_CHKFLAGS(m, flags) && \ - PyArray_ISNOTSWAPPED(m)) - -#define PyArray_ISCARRAY(m) PyArray_FLAGSWAP(m, NPY_ARRAY_CARRAY) -#define PyArray_ISCARRAY_RO(m) PyArray_FLAGSWAP(m, NPY_ARRAY_CARRAY_RO) -#define PyArray_ISFARRAY(m) PyArray_FLAGSWAP(m, NPY_ARRAY_FARRAY) -#define PyArray_ISFARRAY_RO(m) PyArray_FLAGSWAP(m, NPY_ARRAY_FARRAY_RO) -#define PyArray_ISBEHAVED(m) PyArray_FLAGSWAP(m, NPY_ARRAY_BEHAVED) -#define PyArray_ISBEHAVED_RO(m) PyArray_FLAGSWAP(m, NPY_ARRAY_ALIGNED) - - -#define PyDataType_ISNOTSWAPPED(d) PyArray_ISNBO(((PyArray_Descr *)(d))->byteorder) -#define PyDataType_ISBYTESWAPPED(d) (!PyDataType_ISNOTSWAPPED(d)) - -/************************************************************ - * A struct used by PyArray_CreateSortedStridePerm, new in 1.7. - ************************************************************/ - -typedef struct { - npy_intp perm, stride; -} npy_stride_sort_item; - -/************************************************************ - * This is the form of the struct that's returned pointed by the - * PyCObject attribute of an array __array_struct__. See - * http://docs.scipy.org/doc/numpy/reference/arrays.interface.html for the full - * documentation. - ************************************************************/ -typedef struct { - int two; /* - * contains the integer 2 as a sanity - * check - */ - - int nd; /* number of dimensions */ - - char typekind; /* - * kind in array --- character code of - * typestr - */ - - int itemsize; /* size of each element */ - - int flags; /* - * how should be data interpreted. Valid - * flags are CONTIGUOUS (1), F_CONTIGUOUS (2), - * ALIGNED (0x100), NOTSWAPPED (0x200), and - * WRITEABLE (0x400). ARR_HAS_DESCR (0x800) - * states that arrdescr field is present in - * structure - */ - - npy_intp *shape; /* - * A length-nd array of shape - * information - */ - - npy_intp *strides; /* A length-nd array of stride information */ - - void *data; /* A pointer to the first element of the array */ - - PyObject *descr; /* - * A list of fields or NULL (ignored if flags - * does not have ARR_HAS_DESCR flag set) - */ -} PyArrayInterface; - -/* - * This is a function for hooking into the PyDataMem_NEW/FREE/RENEW functions. - * See the documentation for PyDataMem_SetEventHook. - */ -typedef void (PyDataMem_EventHookFunc)(void *inp, void *outp, size_t size, - void *user_data); - -/* - * Use the keyword NPY_DEPRECATED_INCLUDES to ensure that the header files - * npy_*_*_deprecated_api.h are only included from here and nowhere else. - */ -#ifdef NPY_DEPRECATED_INCLUDES -#error "Do not use the reserved keyword NPY_DEPRECATED_INCLUDES." -#endif -#define NPY_DEPRECATED_INCLUDES -#if !defined(NPY_NO_DEPRECATED_API) || \ - (NPY_NO_DEPRECATED_API < NPY_1_7_API_VERSION) -#include "npy_1_7_deprecated_api.h" -#endif -/* - * There is no file npy_1_8_deprecated_api.h since there are no additional - * deprecated API features in NumPy 1.8. - * - * Note to maintainers: insert code like the following in future NumPy - * versions. - * - * #if !defined(NPY_NO_DEPRECATED_API) || \ - * (NPY_NO_DEPRECATED_API < NPY_1_9_API_VERSION) - * #include "npy_1_9_deprecated_api.h" - * #endif - */ -#undef NPY_DEPRECATED_INCLUDES - -#endif /* NPY_ARRAYTYPES_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h b/gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h deleted file mode 100644 index 830617087..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/noprefix.h +++ /dev/null @@ -1,209 +0,0 @@ -#ifndef NPY_NOPREFIX_H -#define NPY_NOPREFIX_H - -/* - * You can directly include noprefix.h as a backward - * compatibility measure - */ -#ifndef NPY_NO_PREFIX -#include "ndarrayobject.h" -#include "npy_interrupt.h" -#endif - -#define SIGSETJMP NPY_SIGSETJMP -#define SIGLONGJMP NPY_SIGLONGJMP -#define SIGJMP_BUF NPY_SIGJMP_BUF - -#define MAX_DIMS NPY_MAXDIMS - -#define longlong npy_longlong -#define ulonglong npy_ulonglong -#define Bool npy_bool -#define longdouble npy_longdouble -#define byte npy_byte - -#ifndef _BSD_SOURCE -#define ushort npy_ushort -#define uint npy_uint -#define ulong npy_ulong -#endif - -#define ubyte npy_ubyte -#define ushort npy_ushort -#define uint npy_uint -#define ulong npy_ulong -#define cfloat npy_cfloat -#define cdouble npy_cdouble -#define clongdouble npy_clongdouble -#define Int8 npy_int8 -#define UInt8 npy_uint8 -#define Int16 npy_int16 -#define UInt16 npy_uint16 -#define Int32 npy_int32 -#define UInt32 npy_uint32 -#define Int64 npy_int64 -#define UInt64 npy_uint64 -#define Int128 npy_int128 -#define UInt128 npy_uint128 -#define Int256 npy_int256 -#define UInt256 npy_uint256 -#define Float16 npy_float16 -#define Complex32 npy_complex32 -#define Float32 npy_float32 -#define Complex64 npy_complex64 -#define Float64 npy_float64 -#define Complex128 npy_complex128 -#define Float80 npy_float80 -#define Complex160 npy_complex160 -#define Float96 npy_float96 -#define Complex192 npy_complex192 -#define Float128 npy_float128 -#define Complex256 npy_complex256 -#define intp npy_intp -#define uintp npy_uintp -#define datetime npy_datetime -#define timedelta npy_timedelta - -#define SIZEOF_LONGLONG NPY_SIZEOF_LONGLONG -#define SIZEOF_INTP NPY_SIZEOF_INTP -#define SIZEOF_UINTP NPY_SIZEOF_UINTP -#define SIZEOF_HALF NPY_SIZEOF_HALF -#define SIZEOF_LONGDOUBLE NPY_SIZEOF_LONGDOUBLE -#define SIZEOF_DATETIME NPY_SIZEOF_DATETIME -#define SIZEOF_TIMEDELTA NPY_SIZEOF_TIMEDELTA - -#define LONGLONG_FMT NPY_LONGLONG_FMT -#define ULONGLONG_FMT NPY_ULONGLONG_FMT -#define LONGLONG_SUFFIX NPY_LONGLONG_SUFFIX -#define ULONGLONG_SUFFIX NPY_ULONGLONG_SUFFIX - -#define MAX_INT8 127 -#define MIN_INT8 -128 -#define MAX_UINT8 255 -#define MAX_INT16 32767 -#define MIN_INT16 -32768 -#define MAX_UINT16 65535 -#define MAX_INT32 2147483647 -#define MIN_INT32 (-MAX_INT32 - 1) -#define MAX_UINT32 4294967295U -#define MAX_INT64 LONGLONG_SUFFIX(9223372036854775807) -#define MIN_INT64 (-MAX_INT64 - LONGLONG_SUFFIX(1)) -#define MAX_UINT64 ULONGLONG_SUFFIX(18446744073709551615) -#define MAX_INT128 LONGLONG_SUFFIX(85070591730234615865843651857942052864) -#define MIN_INT128 (-MAX_INT128 - LONGLONG_SUFFIX(1)) -#define MAX_UINT128 ULONGLONG_SUFFIX(170141183460469231731687303715884105728) -#define MAX_INT256 LONGLONG_SUFFIX(57896044618658097711785492504343953926634992332820282019728792003956564819967) -#define MIN_INT256 (-MAX_INT256 - LONGLONG_SUFFIX(1)) -#define MAX_UINT256 ULONGLONG_SUFFIX(115792089237316195423570985008687907853269984665640564039457584007913129639935) - -#define MAX_BYTE NPY_MAX_BYTE -#define MIN_BYTE NPY_MIN_BYTE -#define MAX_UBYTE NPY_MAX_UBYTE -#define MAX_SHORT NPY_MAX_SHORT -#define MIN_SHORT NPY_MIN_SHORT -#define MAX_USHORT NPY_MAX_USHORT -#define MAX_INT NPY_MAX_INT -#define MIN_INT NPY_MIN_INT -#define MAX_UINT NPY_MAX_UINT -#define MAX_LONG NPY_MAX_LONG -#define MIN_LONG NPY_MIN_LONG -#define MAX_ULONG NPY_MAX_ULONG -#define MAX_LONGLONG NPY_MAX_LONGLONG -#define MIN_LONGLONG NPY_MIN_LONGLONG -#define MAX_ULONGLONG NPY_MAX_ULONGLONG -#define MIN_DATETIME NPY_MIN_DATETIME -#define MAX_DATETIME NPY_MAX_DATETIME -#define MIN_TIMEDELTA NPY_MIN_TIMEDELTA -#define MAX_TIMEDELTA NPY_MAX_TIMEDELTA - -#define BITSOF_BOOL NPY_BITSOF_BOOL -#define BITSOF_CHAR NPY_BITSOF_CHAR -#define BITSOF_SHORT NPY_BITSOF_SHORT -#define BITSOF_INT NPY_BITSOF_INT -#define BITSOF_LONG NPY_BITSOF_LONG -#define BITSOF_LONGLONG NPY_BITSOF_LONGLONG -#define BITSOF_HALF NPY_BITSOF_HALF -#define BITSOF_FLOAT NPY_BITSOF_FLOAT -#define BITSOF_DOUBLE NPY_BITSOF_DOUBLE -#define BITSOF_LONGDOUBLE NPY_BITSOF_LONGDOUBLE -#define BITSOF_DATETIME NPY_BITSOF_DATETIME -#define BITSOF_TIMEDELTA NPY_BITSOF_TIMEDELTA - -#define _pya_malloc PyArray_malloc -#define _pya_free PyArray_free -#define _pya_realloc PyArray_realloc - -#define BEGIN_THREADS_DEF NPY_BEGIN_THREADS_DEF -#define BEGIN_THREADS NPY_BEGIN_THREADS -#define END_THREADS NPY_END_THREADS -#define ALLOW_C_API_DEF NPY_ALLOW_C_API_DEF -#define ALLOW_C_API NPY_ALLOW_C_API -#define DISABLE_C_API NPY_DISABLE_C_API - -#define PY_FAIL NPY_FAIL -#define PY_SUCCEED NPY_SUCCEED - -#ifndef TRUE -#define TRUE NPY_TRUE -#endif - -#ifndef FALSE -#define FALSE NPY_FALSE -#endif - -#define LONGDOUBLE_FMT NPY_LONGDOUBLE_FMT - -#define CONTIGUOUS NPY_CONTIGUOUS -#define C_CONTIGUOUS NPY_C_CONTIGUOUS -#define FORTRAN NPY_FORTRAN -#define F_CONTIGUOUS NPY_F_CONTIGUOUS -#define OWNDATA NPY_OWNDATA -#define FORCECAST NPY_FORCECAST -#define ENSURECOPY NPY_ENSURECOPY -#define ENSUREARRAY NPY_ENSUREARRAY -#define ELEMENTSTRIDES NPY_ELEMENTSTRIDES -#define ALIGNED NPY_ALIGNED -#define NOTSWAPPED NPY_NOTSWAPPED -#define WRITEABLE NPY_WRITEABLE -#define UPDATEIFCOPY NPY_UPDATEIFCOPY -#define ARR_HAS_DESCR NPY_ARR_HAS_DESCR -#define BEHAVED NPY_BEHAVED -#define BEHAVED_NS NPY_BEHAVED_NS -#define CARRAY NPY_CARRAY -#define CARRAY_RO NPY_CARRAY_RO -#define FARRAY NPY_FARRAY -#define FARRAY_RO NPY_FARRAY_RO -#define DEFAULT NPY_DEFAULT -#define IN_ARRAY NPY_IN_ARRAY -#define OUT_ARRAY NPY_OUT_ARRAY -#define INOUT_ARRAY NPY_INOUT_ARRAY -#define IN_FARRAY NPY_IN_FARRAY -#define OUT_FARRAY NPY_OUT_FARRAY -#define INOUT_FARRAY NPY_INOUT_FARRAY -#define UPDATE_ALL NPY_UPDATE_ALL - -#define OWN_DATA NPY_OWNDATA -#define BEHAVED_FLAGS NPY_BEHAVED -#define BEHAVED_FLAGS_NS NPY_BEHAVED_NS -#define CARRAY_FLAGS_RO NPY_CARRAY_RO -#define CARRAY_FLAGS NPY_CARRAY -#define FARRAY_FLAGS NPY_FARRAY -#define FARRAY_FLAGS_RO NPY_FARRAY_RO -#define DEFAULT_FLAGS NPY_DEFAULT -#define UPDATE_ALL_FLAGS NPY_UPDATE_ALL_FLAGS - -#ifndef MIN -#define MIN PyArray_MIN -#endif -#ifndef MAX -#define MAX PyArray_MAX -#endif -#define MAX_INTP NPY_MAX_INTP -#define MIN_INTP NPY_MIN_INTP -#define MAX_UINTP NPY_MAX_UINTP -#define INTP_FMT NPY_INTP_FMT - -#define REFCOUNT PyArray_REFCOUNT -#define MAX_ELSIZE NPY_MAX_ELSIZE - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h deleted file mode 100644 index 4c318bc47..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_1_7_deprecated_api.h +++ /dev/null @@ -1,130 +0,0 @@ -#ifndef _NPY_1_7_DEPRECATED_API_H -#define _NPY_1_7_DEPRECATED_API_H - -#ifndef NPY_DEPRECATED_INCLUDES -#error "Should never include npy_*_*_deprecated_api directly." -#endif - -#if defined(_WIN32) -#define _WARN___STR2__(x) #x -#define _WARN___STR1__(x) _WARN___STR2__(x) -#define _WARN___LOC__ __FILE__ "(" _WARN___STR1__(__LINE__) ") : Warning Msg: " -#pragma message(_WARN___LOC__"Using deprecated NumPy API, disable it by " \ - "#defining NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION") -#elif defined(__GNUC__) -#warning "Using deprecated NumPy API, disable it by " \ - "#defining NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION" -#endif -/* TODO: How to do this warning message for other compilers? */ - -/* - * This header exists to collect all dangerous/deprecated NumPy API - * as of NumPy 1.7. - * - * This is an attempt to remove bad API, the proliferation of macros, - * and namespace pollution currently produced by the NumPy headers. - */ - -/* These array flags are deprecated as of NumPy 1.7 */ -#define NPY_CONTIGUOUS NPY_ARRAY_C_CONTIGUOUS -#define NPY_FORTRAN NPY_ARRAY_F_CONTIGUOUS - -/* - * The consistent NPY_ARRAY_* names which don't pollute the NPY_* - * namespace were added in NumPy 1.7. - * - * These versions of the carray flags are deprecated, but - * probably should only be removed after two releases instead of one. - */ -#define NPY_C_CONTIGUOUS NPY_ARRAY_C_CONTIGUOUS -#define NPY_F_CONTIGUOUS NPY_ARRAY_F_CONTIGUOUS -#define NPY_OWNDATA NPY_ARRAY_OWNDATA -#define NPY_FORCECAST NPY_ARRAY_FORCECAST -#define NPY_ENSURECOPY NPY_ARRAY_ENSURECOPY -#define NPY_ENSUREARRAY NPY_ARRAY_ENSUREARRAY -#define NPY_ELEMENTSTRIDES NPY_ARRAY_ELEMENTSTRIDES -#define NPY_ALIGNED NPY_ARRAY_ALIGNED -#define NPY_NOTSWAPPED NPY_ARRAY_NOTSWAPPED -#define NPY_WRITEABLE NPY_ARRAY_WRITEABLE -#define NPY_UPDATEIFCOPY NPY_ARRAY_UPDATEIFCOPY -#define NPY_BEHAVED NPY_ARRAY_BEHAVED -#define NPY_BEHAVED_NS NPY_ARRAY_BEHAVED_NS -#define NPY_CARRAY NPY_ARRAY_CARRAY -#define NPY_CARRAY_RO NPY_ARRAY_CARRAY_RO -#define NPY_FARRAY NPY_ARRAY_FARRAY -#define NPY_FARRAY_RO NPY_ARRAY_FARRAY_RO -#define NPY_DEFAULT NPY_ARRAY_DEFAULT -#define NPY_IN_ARRAY NPY_ARRAY_IN_ARRAY -#define NPY_OUT_ARRAY NPY_ARRAY_OUT_ARRAY -#define NPY_INOUT_ARRAY NPY_ARRAY_INOUT_ARRAY -#define NPY_IN_FARRAY NPY_ARRAY_IN_FARRAY -#define NPY_OUT_FARRAY NPY_ARRAY_OUT_FARRAY -#define NPY_INOUT_FARRAY NPY_ARRAY_INOUT_FARRAY -#define NPY_UPDATE_ALL NPY_ARRAY_UPDATE_ALL - -/* This way of accessing the default type is deprecated as of NumPy 1.7 */ -#define PyArray_DEFAULT NPY_DEFAULT_TYPE - -/* These DATETIME bits aren't used internally */ -#if PY_VERSION_HEX >= 0x03000000 -#define PyDataType_GetDatetimeMetaData(descr) \ - ((descr->metadata == NULL) ? NULL : \ - ((PyArray_DatetimeMetaData *)(PyCapsule_GetPointer( \ - PyDict_GetItemString( \ - descr->metadata, NPY_METADATA_DTSTR), NULL)))) -#else -#define PyDataType_GetDatetimeMetaData(descr) \ - ((descr->metadata == NULL) ? NULL : \ - ((PyArray_DatetimeMetaData *)(PyCObject_AsVoidPtr( \ - PyDict_GetItemString(descr->metadata, NPY_METADATA_DTSTR))))) -#endif - -/* - * Deprecated as of NumPy 1.7, this kind of shortcut doesn't - * belong in the public API. - */ -#define NPY_AO PyArrayObject - -/* - * Deprecated as of NumPy 1.7, an all-lowercase macro doesn't - * belong in the public API. - */ -#define fortran fortran_ - -/* - * Deprecated as of NumPy 1.7, as it is a namespace-polluting - * macro. - */ -#define FORTRAN_IF PyArray_FORTRAN_IF - -/* Deprecated as of NumPy 1.7, datetime64 uses c_metadata instead */ -#define NPY_METADATA_DTSTR "__timeunit__" - -/* - * Deprecated as of NumPy 1.7. - * The reasoning: - * - These are for datetime, but there's no datetime "namespace". - * - They just turn NPY_STR_ into "", which is just - * making something simple be indirected. - */ -#define NPY_STR_Y "Y" -#define NPY_STR_M "M" -#define NPY_STR_W "W" -#define NPY_STR_D "D" -#define NPY_STR_h "h" -#define NPY_STR_m "m" -#define NPY_STR_s "s" -#define NPY_STR_ms "ms" -#define NPY_STR_us "us" -#define NPY_STR_ns "ns" -#define NPY_STR_ps "ps" -#define NPY_STR_fs "fs" -#define NPY_STR_as "as" - -/* - * The macros in old_defines.h are Deprecated as of NumPy 1.7 and will be - * removed in the next major release. - */ -#include "old_defines.h" - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h deleted file mode 100644 index de2bf6a54..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_3kcompat.h +++ /dev/null @@ -1,502 +0,0 @@ -/* - * This is a convenience header file providing compatibility utilities - * for supporting Python 2 and Python 3 in the same code base. - * - * If you want to use this for your own projects, it's recommended to make a - * copy of it. Although the stuff below is unlikely to change, we don't provide - * strong backwards compatibility guarantees at the moment. - */ - -#ifndef _NPY_3KCOMPAT_H_ -#define _NPY_3KCOMPAT_H_ - -#include -#include - -#if PY_VERSION_HEX >= 0x03000000 -#ifndef NPY_PY3K -#define NPY_PY3K 1 -#endif -#endif - -#include "numpy/npy_common.h" -#include "numpy/ndarrayobject.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * PyInt -> PyLong - */ - -#if defined(NPY_PY3K) -/* Return True only if the long fits in a C long */ -static NPY_INLINE int PyInt_Check(PyObject *op) { - int overflow = 0; - if (!PyLong_Check(op)) { - return 0; - } - PyLong_AsLongAndOverflow(op, &overflow); - return (overflow == 0); -} - -#define PyInt_FromLong PyLong_FromLong -#define PyInt_AsLong PyLong_AsLong -#define PyInt_AS_LONG PyLong_AsLong -#define PyInt_AsSsize_t PyLong_AsSsize_t - -/* NOTE: - * - * Since the PyLong type is very different from the fixed-range PyInt, - * we don't define PyInt_Type -> PyLong_Type. - */ -#endif /* NPY_PY3K */ - -/* - * PyString -> PyBytes - */ - -#if defined(NPY_PY3K) - -#define PyString_Type PyBytes_Type -#define PyString_Check PyBytes_Check -#define PyStringObject PyBytesObject -#define PyString_FromString PyBytes_FromString -#define PyString_FromStringAndSize PyBytes_FromStringAndSize -#define PyString_AS_STRING PyBytes_AS_STRING -#define PyString_AsStringAndSize PyBytes_AsStringAndSize -#define PyString_FromFormat PyBytes_FromFormat -#define PyString_Concat PyBytes_Concat -#define PyString_ConcatAndDel PyBytes_ConcatAndDel -#define PyString_AsString PyBytes_AsString -#define PyString_GET_SIZE PyBytes_GET_SIZE -#define PyString_Size PyBytes_Size - -#define PyUString_Type PyUnicode_Type -#define PyUString_Check PyUnicode_Check -#define PyUStringObject PyUnicodeObject -#define PyUString_FromString PyUnicode_FromString -#define PyUString_FromStringAndSize PyUnicode_FromStringAndSize -#define PyUString_FromFormat PyUnicode_FromFormat -#define PyUString_Concat PyUnicode_Concat2 -#define PyUString_ConcatAndDel PyUnicode_ConcatAndDel -#define PyUString_GET_SIZE PyUnicode_GET_SIZE -#define PyUString_Size PyUnicode_Size -#define PyUString_InternFromString PyUnicode_InternFromString -#define PyUString_Format PyUnicode_Format - -#else - -#define PyBytes_Type PyString_Type -#define PyBytes_Check PyString_Check -#define PyBytesObject PyStringObject -#define PyBytes_FromString PyString_FromString -#define PyBytes_FromStringAndSize PyString_FromStringAndSize -#define PyBytes_AS_STRING PyString_AS_STRING -#define PyBytes_AsStringAndSize PyString_AsStringAndSize -#define PyBytes_FromFormat PyString_FromFormat -#define PyBytes_Concat PyString_Concat -#define PyBytes_ConcatAndDel PyString_ConcatAndDel -#define PyBytes_AsString PyString_AsString -#define PyBytes_GET_SIZE PyString_GET_SIZE -#define PyBytes_Size PyString_Size - -#define PyUString_Type PyString_Type -#define PyUString_Check PyString_Check -#define PyUStringObject PyStringObject -#define PyUString_FromString PyString_FromString -#define PyUString_FromStringAndSize PyString_FromStringAndSize -#define PyUString_FromFormat PyString_FromFormat -#define PyUString_Concat PyString_Concat -#define PyUString_ConcatAndDel PyString_ConcatAndDel -#define PyUString_GET_SIZE PyString_GET_SIZE -#define PyUString_Size PyString_Size -#define PyUString_InternFromString PyString_InternFromString -#define PyUString_Format PyString_Format - -#endif /* NPY_PY3K */ - - -static NPY_INLINE void -PyUnicode_ConcatAndDel(PyObject **left, PyObject *right) -{ - PyObject *newobj; - newobj = PyUnicode_Concat(*left, right); - Py_DECREF(*left); - Py_DECREF(right); - *left = newobj; -} - -static NPY_INLINE void -PyUnicode_Concat2(PyObject **left, PyObject *right) -{ - PyObject *newobj; - newobj = PyUnicode_Concat(*left, right); - Py_DECREF(*left); - *left = newobj; -} - -/* - * PyFile_* compatibility - */ -#if defined(NPY_PY3K) -/* - * Get a FILE* handle to the file represented by the Python object - */ -static NPY_INLINE FILE* -npy_PyFile_Dup2(PyObject *file, char *mode, npy_off_t *orig_pos) -{ - int fd, fd2; - PyObject *ret, *os; - npy_off_t pos; - FILE *handle; - - /* Flush first to ensure things end up in the file in the correct order */ - ret = PyObject_CallMethod(file, "flush", ""); - if (ret == NULL) { - return NULL; - } - Py_DECREF(ret); - fd = PyObject_AsFileDescriptor(file); - if (fd == -1) { - return NULL; - } - - /* The handle needs to be dup'd because we have to call fclose - at the end */ - os = PyImport_ImportModule("os"); - if (os == NULL) { - return NULL; - } - ret = PyObject_CallMethod(os, "dup", "i", fd); - Py_DECREF(os); - if (ret == NULL) { - return NULL; - } - fd2 = PyNumber_AsSsize_t(ret, NULL); - Py_DECREF(ret); - - /* Convert to FILE* handle */ -#ifdef _WIN32 - handle = _fdopen(fd2, mode); -#else - handle = fdopen(fd2, mode); -#endif - if (handle == NULL) { - PyErr_SetString(PyExc_IOError, - "Getting a FILE* from a Python file object failed"); - } - - /* Record the original raw file handle position */ - *orig_pos = npy_ftell(handle); - if (*orig_pos == -1) { - PyErr_SetString(PyExc_IOError, "obtaining file position failed"); - fclose(handle); - return NULL; - } - - /* Seek raw handle to the Python-side position */ - ret = PyObject_CallMethod(file, "tell", ""); - if (ret == NULL) { - fclose(handle); - return NULL; - } - pos = PyLong_AsLongLong(ret); - Py_DECREF(ret); - if (PyErr_Occurred()) { - fclose(handle); - return NULL; - } - if (npy_fseek(handle, pos, SEEK_SET) == -1) { - PyErr_SetString(PyExc_IOError, "seeking file failed"); - fclose(handle); - return NULL; - } - return handle; -} - -/* - * Close the dup-ed file handle, and seek the Python one to the current position - */ -static NPY_INLINE int -npy_PyFile_DupClose2(PyObject *file, FILE* handle, npy_off_t orig_pos) -{ - int fd; - PyObject *ret; - npy_off_t position; - - position = npy_ftell(handle); - - /* Close the FILE* handle */ - fclose(handle); - - /* Restore original file handle position, in order to not confuse - Python-side data structures */ - fd = PyObject_AsFileDescriptor(file); - if (fd == -1) { - return -1; - } - if (npy_lseek(fd, orig_pos, SEEK_SET) == -1) { - PyErr_SetString(PyExc_IOError, "seeking file failed"); - return -1; - } - - if (position == -1) { - PyErr_SetString(PyExc_IOError, "obtaining file position failed"); - return -1; - } - - /* Seek Python-side handle to the FILE* handle position */ - ret = PyObject_CallMethod(file, "seek", NPY_OFF_T_PYFMT "i", position, 0); - if (ret == NULL) { - return -1; - } - Py_DECREF(ret); - return 0; -} - -static NPY_INLINE int -npy_PyFile_Check(PyObject *file) -{ - int fd; - fd = PyObject_AsFileDescriptor(file); - if (fd == -1) { - PyErr_Clear(); - return 0; - } - return 1; -} - -/* - * DEPRECATED DO NOT USE - * use npy_PyFile_Dup2 instead - * this function will mess ups python3 internal file object buffering - * Get a FILE* handle to the file represented by the Python object - */ -static NPY_INLINE FILE* -npy_PyFile_Dup(PyObject *file, char *mode) -{ - npy_off_t orig; - if (DEPRECATE("npy_PyFile_Dup is deprecated, use " - "npy_PyFile_Dup2") < 0) { - return NULL; - } - - return npy_PyFile_Dup2(file, mode, &orig); -} - -/* - * DEPRECATED DO NOT USE - * use npy_PyFile_DupClose2 instead - * this function will mess ups python3 internal file object buffering - * Close the dup-ed file handle, and seek the Python one to the current position - */ -static NPY_INLINE int -npy_PyFile_DupClose(PyObject *file, FILE* handle) -{ - PyObject *ret; - Py_ssize_t position; - position = npy_ftell(handle); - fclose(handle); - - ret = PyObject_CallMethod(file, "seek", NPY_SSIZE_T_PYFMT "i", position, 0); - if (ret == NULL) { - return -1; - } - Py_DECREF(ret); - return 0; -} - - -#else - -/* DEPRECATED DO NOT USE */ -#define npy_PyFile_Dup(file, mode) PyFile_AsFile(file) -#define npy_PyFile_DupClose(file, handle) (0) -/* use these */ -#define npy_PyFile_Dup2(file, mode, orig_pos_p) PyFile_AsFile(file) -#define npy_PyFile_DupClose2(file, handle, orig_pos) (0) -#define npy_PyFile_Check PyFile_Check - -#endif - -static NPY_INLINE PyObject* -npy_PyFile_OpenFile(PyObject *filename, const char *mode) -{ - PyObject *open; - open = PyDict_GetItemString(PyEval_GetBuiltins(), "open"); - if (open == NULL) { - return NULL; - } - return PyObject_CallFunction(open, "Os", filename, mode); -} - -static NPY_INLINE int -npy_PyFile_CloseFile(PyObject *file) -{ - PyObject *ret; - - ret = PyObject_CallMethod(file, "close", NULL); - if (ret == NULL) { - return -1; - } - Py_DECREF(ret); - return 0; -} - -/* - * PyObject_Cmp - */ -#if defined(NPY_PY3K) -static NPY_INLINE int -PyObject_Cmp(PyObject *i1, PyObject *i2, int *cmp) -{ - int v; - v = PyObject_RichCompareBool(i1, i2, Py_LT); - if (v == 0) { - *cmp = -1; - return 1; - } - else if (v == -1) { - return -1; - } - - v = PyObject_RichCompareBool(i1, i2, Py_GT); - if (v == 0) { - *cmp = 1; - return 1; - } - else if (v == -1) { - return -1; - } - - v = PyObject_RichCompareBool(i1, i2, Py_EQ); - if (v == 0) { - *cmp = 0; - return 1; - } - else { - *cmp = 0; - return -1; - } -} -#endif - -/* - * PyCObject functions adapted to PyCapsules. - * - * The main job here is to get rid of the improved error handling - * of PyCapsules. It's a shame... - */ -#if PY_VERSION_HEX >= 0x03000000 - -static NPY_INLINE PyObject * -NpyCapsule_FromVoidPtr(void *ptr, void (*dtor)(PyObject *)) -{ - PyObject *ret = PyCapsule_New(ptr, NULL, dtor); - if (ret == NULL) { - PyErr_Clear(); - } - return ret; -} - -static NPY_INLINE PyObject * -NpyCapsule_FromVoidPtrAndDesc(void *ptr, void* context, void (*dtor)(PyObject *)) -{ - PyObject *ret = NpyCapsule_FromVoidPtr(ptr, dtor); - if (ret != NULL && PyCapsule_SetContext(ret, context) != 0) { - PyErr_Clear(); - Py_DECREF(ret); - ret = NULL; - } - return ret; -} - -static NPY_INLINE void * -NpyCapsule_AsVoidPtr(PyObject *obj) -{ - void *ret = PyCapsule_GetPointer(obj, NULL); - if (ret == NULL) { - PyErr_Clear(); - } - return ret; -} - -static NPY_INLINE void * -NpyCapsule_GetDesc(PyObject *obj) -{ - return PyCapsule_GetContext(obj); -} - -static NPY_INLINE int -NpyCapsule_Check(PyObject *ptr) -{ - return PyCapsule_CheckExact(ptr); -} - -static NPY_INLINE void -simple_capsule_dtor(PyObject *cap) -{ - PyArray_free(PyCapsule_GetPointer(cap, NULL)); -} - -#else - -static NPY_INLINE PyObject * -NpyCapsule_FromVoidPtr(void *ptr, void (*dtor)(void *)) -{ - return PyCObject_FromVoidPtr(ptr, dtor); -} - -static NPY_INLINE PyObject * -NpyCapsule_FromVoidPtrAndDesc(void *ptr, void* context, - void (*dtor)(void *, void *)) -{ - return PyCObject_FromVoidPtrAndDesc(ptr, context, dtor); -} - -static NPY_INLINE void * -NpyCapsule_AsVoidPtr(PyObject *ptr) -{ - return PyCObject_AsVoidPtr(ptr); -} - -static NPY_INLINE void * -NpyCapsule_GetDesc(PyObject *obj) -{ - return PyCObject_GetDesc(obj); -} - -static NPY_INLINE int -NpyCapsule_Check(PyObject *ptr) -{ - return PyCObject_Check(ptr); -} - -static NPY_INLINE void -simple_capsule_dtor(void *ptr) -{ - PyArray_free(ptr); -} - -#endif - -/* - * Hash value compatibility. - * As of Python 3.2 hash values are of type Py_hash_t. - * Previous versions use C long. - */ -#if PY_VERSION_HEX < 0x03020000 -typedef long npy_hash_t; -#define NPY_SIZEOF_HASH_T NPY_SIZEOF_LONG -#else -typedef Py_hash_t npy_hash_t; -#define NPY_SIZEOF_HASH_T NPY_SIZEOF_INTP -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* _NPY_3KCOMPAT_H_ */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h deleted file mode 100644 index c257f216d..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_common.h +++ /dev/null @@ -1,1005 +0,0 @@ -#ifndef _NPY_COMMON_H_ -#define _NPY_COMMON_H_ - -/* numpconfig.h is auto-generated */ -#include "numpyconfig.h" -#ifdef HAVE_NPY_CONFIG_H -#include -#endif - -/* - * gcc does not unroll even with -O3 - * use with care, unrolling on modern cpus rarely speeds things up - */ -#ifdef HAVE_ATTRIBUTE_OPTIMIZE_UNROLL_LOOPS -#define NPY_GCC_UNROLL_LOOPS \ - __attribute__((optimize("unroll-loops"))) -#else -#define NPY_GCC_UNROLL_LOOPS -#endif - -#if defined HAVE_XMMINTRIN_H && defined HAVE__MM_LOAD_PS -#define NPY_HAVE_SSE_INTRINSICS -#endif - -#if defined HAVE_EMMINTRIN_H && defined HAVE__MM_LOAD_PD -#define NPY_HAVE_SSE2_INTRINSICS -#endif - -/* - * give a hint to the compiler which branch is more likely or unlikely - * to occur, e.g. rare error cases: - * - * if (NPY_UNLIKELY(failure == 0)) - * return NULL; - * - * the double !! is to cast the expression (e.g. NULL) to a boolean required by - * the intrinsic - */ -#ifdef HAVE___BUILTIN_EXPECT -#define NPY_LIKELY(x) __builtin_expect(!!(x), 1) -#define NPY_UNLIKELY(x) __builtin_expect(!!(x), 0) -#else -#define NPY_LIKELY(x) (x) -#define NPY_UNLIKELY(x) (x) -#endif - -#if defined(_MSC_VER) - #define NPY_INLINE __inline -#elif defined(__GNUC__) - #if defined(__STRICT_ANSI__) - #define NPY_INLINE __inline__ - #else - #define NPY_INLINE inline - #endif -#else - #define NPY_INLINE -#endif - -/* 64 bit file position support, also on win-amd64. Ticket #1660 */ -#if defined(_MSC_VER) && defined(_WIN64) && (_MSC_VER > 1400) || \ - defined(__MINGW32__) || defined(__MINGW64__) - #include - -/* mingw based on 3.4.5 has lseek but not ftell/fseek */ -#if defined(__MINGW32__) || defined(__MINGW64__) -extern int __cdecl _fseeki64(FILE *, long long, int); -extern long long __cdecl _ftelli64(FILE *); -#endif - - #define npy_fseek _fseeki64 - #define npy_ftell _ftelli64 - #define npy_lseek _lseeki64 - #define npy_off_t npy_int64 - - #if NPY_SIZEOF_INT == 8 - #define NPY_OFF_T_PYFMT "i" - #elif NPY_SIZEOF_LONG == 8 - #define NPY_OFF_T_PYFMT "l" - #elif NPY_SIZEOF_LONGLONG == 8 - #define NPY_OFF_T_PYFMT "L" - #else - #error Unsupported size for type off_t - #endif -#else -#ifdef HAVE_FSEEKO - #define npy_fseek fseeko -#else - #define npy_fseek fseek -#endif -#ifdef HAVE_FTELLO - #define npy_ftell ftello -#else - #define npy_ftell ftell -#endif - #define npy_lseek lseek - #define npy_off_t off_t - - #if NPY_SIZEOF_OFF_T == NPY_SIZEOF_SHORT - #define NPY_OFF_T_PYFMT "h" - #elif NPY_SIZEOF_OFF_T == NPY_SIZEOF_INT - #define NPY_OFF_T_PYFMT "i" - #elif NPY_SIZEOF_OFF_T == NPY_SIZEOF_LONG - #define NPY_OFF_T_PYFMT "l" - #elif NPY_SIZEOF_OFF_T == NPY_SIZEOF_LONGLONG - #define NPY_OFF_T_PYFMT "L" - #else - #error Unsupported size for type off_t - #endif -#endif - -/* enums for detected endianness */ -enum { - NPY_CPU_UNKNOWN_ENDIAN, - NPY_CPU_LITTLE, - NPY_CPU_BIG -}; - -/* - * This is to typedef npy_intp to the appropriate pointer size for this - * platform. Py_intptr_t, Py_uintptr_t are defined in pyport.h. - */ -typedef Py_intptr_t npy_intp; -typedef Py_uintptr_t npy_uintp; - -/* - * Define sizes that were not defined in numpyconfig.h. - */ -#define NPY_SIZEOF_CHAR 1 -#define NPY_SIZEOF_BYTE 1 -#define NPY_SIZEOF_DATETIME 8 -#define NPY_SIZEOF_TIMEDELTA 8 -#define NPY_SIZEOF_INTP NPY_SIZEOF_PY_INTPTR_T -#define NPY_SIZEOF_UINTP NPY_SIZEOF_PY_INTPTR_T -#define NPY_SIZEOF_HALF 2 -#define NPY_SIZEOF_CFLOAT NPY_SIZEOF_COMPLEX_FLOAT -#define NPY_SIZEOF_CDOUBLE NPY_SIZEOF_COMPLEX_DOUBLE -#define NPY_SIZEOF_CLONGDOUBLE NPY_SIZEOF_COMPLEX_LONGDOUBLE - -#ifdef constchar -#undef constchar -#endif - -#define NPY_SSIZE_T_PYFMT "n" -#define constchar char - -/* NPY_INTP_FMT Note: - * Unlike the other NPY_*_FMT macros which are used with - * PyOS_snprintf, NPY_INTP_FMT is used with PyErr_Format and - * PyString_Format. These functions use different formatting - * codes which are portably specified according to the Python - * documentation. See ticket #1795. - * - * On Windows x64, the LONGLONG formatter should be used, but - * in Python 2.6 the %lld formatter is not supported. In this - * case we work around the problem by using the %zd formatter. - */ -#if NPY_SIZEOF_PY_INTPTR_T == NPY_SIZEOF_INT - #define NPY_INTP NPY_INT - #define NPY_UINTP NPY_UINT - #define PyIntpArrType_Type PyIntArrType_Type - #define PyUIntpArrType_Type PyUIntArrType_Type - #define NPY_MAX_INTP NPY_MAX_INT - #define NPY_MIN_INTP NPY_MIN_INT - #define NPY_MAX_UINTP NPY_MAX_UINT - #define NPY_INTP_FMT "d" -#elif NPY_SIZEOF_PY_INTPTR_T == NPY_SIZEOF_LONG - #define NPY_INTP NPY_LONG - #define NPY_UINTP NPY_ULONG - #define PyIntpArrType_Type PyLongArrType_Type - #define PyUIntpArrType_Type PyULongArrType_Type - #define NPY_MAX_INTP NPY_MAX_LONG - #define NPY_MIN_INTP NPY_MIN_LONG - #define NPY_MAX_UINTP NPY_MAX_ULONG - #define NPY_INTP_FMT "ld" -#elif defined(PY_LONG_LONG) && (NPY_SIZEOF_PY_INTPTR_T == NPY_SIZEOF_LONGLONG) - #define NPY_INTP NPY_LONGLONG - #define NPY_UINTP NPY_ULONGLONG - #define PyIntpArrType_Type PyLongLongArrType_Type - #define PyUIntpArrType_Type PyULongLongArrType_Type - #define NPY_MAX_INTP NPY_MAX_LONGLONG - #define NPY_MIN_INTP NPY_MIN_LONGLONG - #define NPY_MAX_UINTP NPY_MAX_ULONGLONG - #if (PY_VERSION_HEX >= 0x02070000) - #define NPY_INTP_FMT "lld" - #else - #define NPY_INTP_FMT "zd" - #endif -#endif - -/* - * We can only use C99 formats for npy_int_p if it is the same as - * intp_t, hence the condition on HAVE_UNITPTR_T - */ -#if (NPY_USE_C99_FORMATS) == 1 \ - && (defined HAVE_UINTPTR_T) \ - && (defined HAVE_INTTYPES_H) - #include - #undef NPY_INTP_FMT - #define NPY_INTP_FMT PRIdPTR -#endif - - -/* - * Some platforms don't define bool, long long, or long double. - * Handle that here. - */ -#define NPY_BYTE_FMT "hhd" -#define NPY_UBYTE_FMT "hhu" -#define NPY_SHORT_FMT "hd" -#define NPY_USHORT_FMT "hu" -#define NPY_INT_FMT "d" -#define NPY_UINT_FMT "u" -#define NPY_LONG_FMT "ld" -#define NPY_ULONG_FMT "lu" -#define NPY_HALF_FMT "g" -#define NPY_FLOAT_FMT "g" -#define NPY_DOUBLE_FMT "g" - - -#ifdef PY_LONG_LONG -typedef PY_LONG_LONG npy_longlong; -typedef unsigned PY_LONG_LONG npy_ulonglong; -# ifdef _MSC_VER -# define NPY_LONGLONG_FMT "I64d" -# define NPY_ULONGLONG_FMT "I64u" -# elif defined(__APPLE__) || defined(__FreeBSD__) -/* "%Ld" only parses 4 bytes -- "L" is floating modifier on MacOS X/BSD */ -# define NPY_LONGLONG_FMT "lld" -# define NPY_ULONGLONG_FMT "llu" -/* - another possible variant -- *quad_t works on *BSD, but is deprecated: - #define LONGLONG_FMT "qd" - #define ULONGLONG_FMT "qu" -*/ -# else -# define NPY_LONGLONG_FMT "Ld" -# define NPY_ULONGLONG_FMT "Lu" -# endif -# ifdef _MSC_VER -# define NPY_LONGLONG_SUFFIX(x) (x##i64) -# define NPY_ULONGLONG_SUFFIX(x) (x##Ui64) -# else -# define NPY_LONGLONG_SUFFIX(x) (x##LL) -# define NPY_ULONGLONG_SUFFIX(x) (x##ULL) -# endif -#else -typedef long npy_longlong; -typedef unsigned long npy_ulonglong; -# define NPY_LONGLONG_SUFFIX(x) (x##L) -# define NPY_ULONGLONG_SUFFIX(x) (x##UL) -#endif - - -typedef unsigned char npy_bool; -#define NPY_FALSE 0 -#define NPY_TRUE 1 - - -#if NPY_SIZEOF_LONGDOUBLE == NPY_SIZEOF_DOUBLE - typedef double npy_longdouble; - #define NPY_LONGDOUBLE_FMT "g" -#else - typedef long double npy_longdouble; - #define NPY_LONGDOUBLE_FMT "Lg" -#endif - -#ifndef Py_USING_UNICODE -#error Must use Python with unicode enabled. -#endif - - -typedef signed char npy_byte; -typedef unsigned char npy_ubyte; -typedef unsigned short npy_ushort; -typedef unsigned int npy_uint; -typedef unsigned long npy_ulong; - -/* These are for completeness */ -typedef char npy_char; -typedef short npy_short; -typedef int npy_int; -typedef long npy_long; -typedef float npy_float; -typedef double npy_double; - -/* - * Disabling C99 complex usage: a lot of C code in numpy/scipy rely on being - * able to do .real/.imag. Will have to convert code first. - */ -#if 0 -#if defined(NPY_USE_C99_COMPLEX) && defined(NPY_HAVE_COMPLEX_DOUBLE) -typedef complex npy_cdouble; -#else -typedef struct { double real, imag; } npy_cdouble; -#endif - -#if defined(NPY_USE_C99_COMPLEX) && defined(NPY_HAVE_COMPLEX_FLOAT) -typedef complex float npy_cfloat; -#else -typedef struct { float real, imag; } npy_cfloat; -#endif - -#if defined(NPY_USE_C99_COMPLEX) && defined(NPY_HAVE_COMPLEX_LONG_DOUBLE) -typedef complex long double npy_clongdouble; -#else -typedef struct {npy_longdouble real, imag;} npy_clongdouble; -#endif -#endif -#if NPY_SIZEOF_COMPLEX_DOUBLE != 2 * NPY_SIZEOF_DOUBLE -#error npy_cdouble definition is not compatible with C99 complex definition ! \ - Please contact Numpy maintainers and give detailed information about your \ - compiler and platform -#endif -typedef struct { double real, imag; } npy_cdouble; - -#if NPY_SIZEOF_COMPLEX_FLOAT != 2 * NPY_SIZEOF_FLOAT -#error npy_cfloat definition is not compatible with C99 complex definition ! \ - Please contact Numpy maintainers and give detailed information about your \ - compiler and platform -#endif -typedef struct { float real, imag; } npy_cfloat; - -#if NPY_SIZEOF_COMPLEX_LONGDOUBLE != 2 * NPY_SIZEOF_LONGDOUBLE -#error npy_clongdouble definition is not compatible with C99 complex definition ! \ - Please contact Numpy maintainers and give detailed information about your \ - compiler and platform -#endif -typedef struct { npy_longdouble real, imag; } npy_clongdouble; - -/* - * numarray-style bit-width typedefs - */ -#define NPY_MAX_INT8 127 -#define NPY_MIN_INT8 -128 -#define NPY_MAX_UINT8 255 -#define NPY_MAX_INT16 32767 -#define NPY_MIN_INT16 -32768 -#define NPY_MAX_UINT16 65535 -#define NPY_MAX_INT32 2147483647 -#define NPY_MIN_INT32 (-NPY_MAX_INT32 - 1) -#define NPY_MAX_UINT32 4294967295U -#define NPY_MAX_INT64 NPY_LONGLONG_SUFFIX(9223372036854775807) -#define NPY_MIN_INT64 (-NPY_MAX_INT64 - NPY_LONGLONG_SUFFIX(1)) -#define NPY_MAX_UINT64 NPY_ULONGLONG_SUFFIX(18446744073709551615) -#define NPY_MAX_INT128 NPY_LONGLONG_SUFFIX(85070591730234615865843651857942052864) -#define NPY_MIN_INT128 (-NPY_MAX_INT128 - NPY_LONGLONG_SUFFIX(1)) -#define NPY_MAX_UINT128 NPY_ULONGLONG_SUFFIX(170141183460469231731687303715884105728) -#define NPY_MAX_INT256 NPY_LONGLONG_SUFFIX(57896044618658097711785492504343953926634992332820282019728792003956564819967) -#define NPY_MIN_INT256 (-NPY_MAX_INT256 - NPY_LONGLONG_SUFFIX(1)) -#define NPY_MAX_UINT256 NPY_ULONGLONG_SUFFIX(115792089237316195423570985008687907853269984665640564039457584007913129639935) -#define NPY_MIN_DATETIME NPY_MIN_INT64 -#define NPY_MAX_DATETIME NPY_MAX_INT64 -#define NPY_MIN_TIMEDELTA NPY_MIN_INT64 -#define NPY_MAX_TIMEDELTA NPY_MAX_INT64 - - /* Need to find the number of bits for each type and - make definitions accordingly. - - C states that sizeof(char) == 1 by definition - - So, just using the sizeof keyword won't help. - - It also looks like Python itself uses sizeof(char) quite a - bit, which by definition should be 1 all the time. - - Idea: Make Use of CHAR_BIT which should tell us how many - BITS per CHARACTER - */ - - /* Include platform definitions -- These are in the C89/90 standard */ -#include -#define NPY_MAX_BYTE SCHAR_MAX -#define NPY_MIN_BYTE SCHAR_MIN -#define NPY_MAX_UBYTE UCHAR_MAX -#define NPY_MAX_SHORT SHRT_MAX -#define NPY_MIN_SHORT SHRT_MIN -#define NPY_MAX_USHORT USHRT_MAX -#define NPY_MAX_INT INT_MAX -#ifndef INT_MIN -#define INT_MIN (-INT_MAX - 1) -#endif -#define NPY_MIN_INT INT_MIN -#define NPY_MAX_UINT UINT_MAX -#define NPY_MAX_LONG LONG_MAX -#define NPY_MIN_LONG LONG_MIN -#define NPY_MAX_ULONG ULONG_MAX - -#define NPY_BITSOF_BOOL (sizeof(npy_bool) * CHAR_BIT) -#define NPY_BITSOF_CHAR CHAR_BIT -#define NPY_BITSOF_BYTE (NPY_SIZEOF_BYTE * CHAR_BIT) -#define NPY_BITSOF_SHORT (NPY_SIZEOF_SHORT * CHAR_BIT) -#define NPY_BITSOF_INT (NPY_SIZEOF_INT * CHAR_BIT) -#define NPY_BITSOF_LONG (NPY_SIZEOF_LONG * CHAR_BIT) -#define NPY_BITSOF_LONGLONG (NPY_SIZEOF_LONGLONG * CHAR_BIT) -#define NPY_BITSOF_INTP (NPY_SIZEOF_INTP * CHAR_BIT) -#define NPY_BITSOF_HALF (NPY_SIZEOF_HALF * CHAR_BIT) -#define NPY_BITSOF_FLOAT (NPY_SIZEOF_FLOAT * CHAR_BIT) -#define NPY_BITSOF_DOUBLE (NPY_SIZEOF_DOUBLE * CHAR_BIT) -#define NPY_BITSOF_LONGDOUBLE (NPY_SIZEOF_LONGDOUBLE * CHAR_BIT) -#define NPY_BITSOF_CFLOAT (NPY_SIZEOF_CFLOAT * CHAR_BIT) -#define NPY_BITSOF_CDOUBLE (NPY_SIZEOF_CDOUBLE * CHAR_BIT) -#define NPY_BITSOF_CLONGDOUBLE (NPY_SIZEOF_CLONGDOUBLE * CHAR_BIT) -#define NPY_BITSOF_DATETIME (NPY_SIZEOF_DATETIME * CHAR_BIT) -#define NPY_BITSOF_TIMEDELTA (NPY_SIZEOF_TIMEDELTA * CHAR_BIT) - -#if NPY_BITSOF_LONG == 8 -#define NPY_INT8 NPY_LONG -#define NPY_UINT8 NPY_ULONG - typedef long npy_int8; - typedef unsigned long npy_uint8; -#define PyInt8ScalarObject PyLongScalarObject -#define PyInt8ArrType_Type PyLongArrType_Type -#define PyUInt8ScalarObject PyULongScalarObject -#define PyUInt8ArrType_Type PyULongArrType_Type -#define NPY_INT8_FMT NPY_LONG_FMT -#define NPY_UINT8_FMT NPY_ULONG_FMT -#elif NPY_BITSOF_LONG == 16 -#define NPY_INT16 NPY_LONG -#define NPY_UINT16 NPY_ULONG - typedef long npy_int16; - typedef unsigned long npy_uint16; -#define PyInt16ScalarObject PyLongScalarObject -#define PyInt16ArrType_Type PyLongArrType_Type -#define PyUInt16ScalarObject PyULongScalarObject -#define PyUInt16ArrType_Type PyULongArrType_Type -#define NPY_INT16_FMT NPY_LONG_FMT -#define NPY_UINT16_FMT NPY_ULONG_FMT -#elif NPY_BITSOF_LONG == 32 -#define NPY_INT32 NPY_LONG -#define NPY_UINT32 NPY_ULONG - typedef long npy_int32; - typedef unsigned long npy_uint32; - typedef unsigned long npy_ucs4; -#define PyInt32ScalarObject PyLongScalarObject -#define PyInt32ArrType_Type PyLongArrType_Type -#define PyUInt32ScalarObject PyULongScalarObject -#define PyUInt32ArrType_Type PyULongArrType_Type -#define NPY_INT32_FMT NPY_LONG_FMT -#define NPY_UINT32_FMT NPY_ULONG_FMT -#elif NPY_BITSOF_LONG == 64 -#define NPY_INT64 NPY_LONG -#define NPY_UINT64 NPY_ULONG - typedef long npy_int64; - typedef unsigned long npy_uint64; -#define PyInt64ScalarObject PyLongScalarObject -#define PyInt64ArrType_Type PyLongArrType_Type -#define PyUInt64ScalarObject PyULongScalarObject -#define PyUInt64ArrType_Type PyULongArrType_Type -#define NPY_INT64_FMT NPY_LONG_FMT -#define NPY_UINT64_FMT NPY_ULONG_FMT -#define MyPyLong_FromInt64 PyLong_FromLong -#define MyPyLong_AsInt64 PyLong_AsLong -#elif NPY_BITSOF_LONG == 128 -#define NPY_INT128 NPY_LONG -#define NPY_UINT128 NPY_ULONG - typedef long npy_int128; - typedef unsigned long npy_uint128; -#define PyInt128ScalarObject PyLongScalarObject -#define PyInt128ArrType_Type PyLongArrType_Type -#define PyUInt128ScalarObject PyULongScalarObject -#define PyUInt128ArrType_Type PyULongArrType_Type -#define NPY_INT128_FMT NPY_LONG_FMT -#define NPY_UINT128_FMT NPY_ULONG_FMT -#endif - -#if NPY_BITSOF_LONGLONG == 8 -# ifndef NPY_INT8 -# define NPY_INT8 NPY_LONGLONG -# define NPY_UINT8 NPY_ULONGLONG - typedef npy_longlong npy_int8; - typedef npy_ulonglong npy_uint8; -# define PyInt8ScalarObject PyLongLongScalarObject -# define PyInt8ArrType_Type PyLongLongArrType_Type -# define PyUInt8ScalarObject PyULongLongScalarObject -# define PyUInt8ArrType_Type PyULongLongArrType_Type -#define NPY_INT8_FMT NPY_LONGLONG_FMT -#define NPY_UINT8_FMT NPY_ULONGLONG_FMT -# endif -# define NPY_MAX_LONGLONG NPY_MAX_INT8 -# define NPY_MIN_LONGLONG NPY_MIN_INT8 -# define NPY_MAX_ULONGLONG NPY_MAX_UINT8 -#elif NPY_BITSOF_LONGLONG == 16 -# ifndef NPY_INT16 -# define NPY_INT16 NPY_LONGLONG -# define NPY_UINT16 NPY_ULONGLONG - typedef npy_longlong npy_int16; - typedef npy_ulonglong npy_uint16; -# define PyInt16ScalarObject PyLongLongScalarObject -# define PyInt16ArrType_Type PyLongLongArrType_Type -# define PyUInt16ScalarObject PyULongLongScalarObject -# define PyUInt16ArrType_Type PyULongLongArrType_Type -#define NPY_INT16_FMT NPY_LONGLONG_FMT -#define NPY_UINT16_FMT NPY_ULONGLONG_FMT -# endif -# define NPY_MAX_LONGLONG NPY_MAX_INT16 -# define NPY_MIN_LONGLONG NPY_MIN_INT16 -# define NPY_MAX_ULONGLONG NPY_MAX_UINT16 -#elif NPY_BITSOF_LONGLONG == 32 -# ifndef NPY_INT32 -# define NPY_INT32 NPY_LONGLONG -# define NPY_UINT32 NPY_ULONGLONG - typedef npy_longlong npy_int32; - typedef npy_ulonglong npy_uint32; - typedef npy_ulonglong npy_ucs4; -# define PyInt32ScalarObject PyLongLongScalarObject -# define PyInt32ArrType_Type PyLongLongArrType_Type -# define PyUInt32ScalarObject PyULongLongScalarObject -# define PyUInt32ArrType_Type PyULongLongArrType_Type -#define NPY_INT32_FMT NPY_LONGLONG_FMT -#define NPY_UINT32_FMT NPY_ULONGLONG_FMT -# endif -# define NPY_MAX_LONGLONG NPY_MAX_INT32 -# define NPY_MIN_LONGLONG NPY_MIN_INT32 -# define NPY_MAX_ULONGLONG NPY_MAX_UINT32 -#elif NPY_BITSOF_LONGLONG == 64 -# ifndef NPY_INT64 -# define NPY_INT64 NPY_LONGLONG -# define NPY_UINT64 NPY_ULONGLONG - typedef npy_longlong npy_int64; - typedef npy_ulonglong npy_uint64; -# define PyInt64ScalarObject PyLongLongScalarObject -# define PyInt64ArrType_Type PyLongLongArrType_Type -# define PyUInt64ScalarObject PyULongLongScalarObject -# define PyUInt64ArrType_Type PyULongLongArrType_Type -#define NPY_INT64_FMT NPY_LONGLONG_FMT -#define NPY_UINT64_FMT NPY_ULONGLONG_FMT -# define MyPyLong_FromInt64 PyLong_FromLongLong -# define MyPyLong_AsInt64 PyLong_AsLongLong -# endif -# define NPY_MAX_LONGLONG NPY_MAX_INT64 -# define NPY_MIN_LONGLONG NPY_MIN_INT64 -# define NPY_MAX_ULONGLONG NPY_MAX_UINT64 -#elif NPY_BITSOF_LONGLONG == 128 -# ifndef NPY_INT128 -# define NPY_INT128 NPY_LONGLONG -# define NPY_UINT128 NPY_ULONGLONG - typedef npy_longlong npy_int128; - typedef npy_ulonglong npy_uint128; -# define PyInt128ScalarObject PyLongLongScalarObject -# define PyInt128ArrType_Type PyLongLongArrType_Type -# define PyUInt128ScalarObject PyULongLongScalarObject -# define PyUInt128ArrType_Type PyULongLongArrType_Type -#define NPY_INT128_FMT NPY_LONGLONG_FMT -#define NPY_UINT128_FMT NPY_ULONGLONG_FMT -# endif -# define NPY_MAX_LONGLONG NPY_MAX_INT128 -# define NPY_MIN_LONGLONG NPY_MIN_INT128 -# define NPY_MAX_ULONGLONG NPY_MAX_UINT128 -#elif NPY_BITSOF_LONGLONG == 256 -# define NPY_INT256 NPY_LONGLONG -# define NPY_UINT256 NPY_ULONGLONG - typedef npy_longlong npy_int256; - typedef npy_ulonglong npy_uint256; -# define PyInt256ScalarObject PyLongLongScalarObject -# define PyInt256ArrType_Type PyLongLongArrType_Type -# define PyUInt256ScalarObject PyULongLongScalarObject -# define PyUInt256ArrType_Type PyULongLongArrType_Type -#define NPY_INT256_FMT NPY_LONGLONG_FMT -#define NPY_UINT256_FMT NPY_ULONGLONG_FMT -# define NPY_MAX_LONGLONG NPY_MAX_INT256 -# define NPY_MIN_LONGLONG NPY_MIN_INT256 -# define NPY_MAX_ULONGLONG NPY_MAX_UINT256 -#endif - -#if NPY_BITSOF_INT == 8 -#ifndef NPY_INT8 -#define NPY_INT8 NPY_INT -#define NPY_UINT8 NPY_UINT - typedef int npy_int8; - typedef unsigned int npy_uint8; -# define PyInt8ScalarObject PyIntScalarObject -# define PyInt8ArrType_Type PyIntArrType_Type -# define PyUInt8ScalarObject PyUIntScalarObject -# define PyUInt8ArrType_Type PyUIntArrType_Type -#define NPY_INT8_FMT NPY_INT_FMT -#define NPY_UINT8_FMT NPY_UINT_FMT -#endif -#elif NPY_BITSOF_INT == 16 -#ifndef NPY_INT16 -#define NPY_INT16 NPY_INT -#define NPY_UINT16 NPY_UINT - typedef int npy_int16; - typedef unsigned int npy_uint16; -# define PyInt16ScalarObject PyIntScalarObject -# define PyInt16ArrType_Type PyIntArrType_Type -# define PyUInt16ScalarObject PyIntUScalarObject -# define PyUInt16ArrType_Type PyIntUArrType_Type -#define NPY_INT16_FMT NPY_INT_FMT -#define NPY_UINT16_FMT NPY_UINT_FMT -#endif -#elif NPY_BITSOF_INT == 32 -#ifndef NPY_INT32 -#define NPY_INT32 NPY_INT -#define NPY_UINT32 NPY_UINT - typedef int npy_int32; - typedef unsigned int npy_uint32; - typedef unsigned int npy_ucs4; -# define PyInt32ScalarObject PyIntScalarObject -# define PyInt32ArrType_Type PyIntArrType_Type -# define PyUInt32ScalarObject PyUIntScalarObject -# define PyUInt32ArrType_Type PyUIntArrType_Type -#define NPY_INT32_FMT NPY_INT_FMT -#define NPY_UINT32_FMT NPY_UINT_FMT -#endif -#elif NPY_BITSOF_INT == 64 -#ifndef NPY_INT64 -#define NPY_INT64 NPY_INT -#define NPY_UINT64 NPY_UINT - typedef int npy_int64; - typedef unsigned int npy_uint64; -# define PyInt64ScalarObject PyIntScalarObject -# define PyInt64ArrType_Type PyIntArrType_Type -# define PyUInt64ScalarObject PyUIntScalarObject -# define PyUInt64ArrType_Type PyUIntArrType_Type -#define NPY_INT64_FMT NPY_INT_FMT -#define NPY_UINT64_FMT NPY_UINT_FMT -# define MyPyLong_FromInt64 PyLong_FromLong -# define MyPyLong_AsInt64 PyLong_AsLong -#endif -#elif NPY_BITSOF_INT == 128 -#ifndef NPY_INT128 -#define NPY_INT128 NPY_INT -#define NPY_UINT128 NPY_UINT - typedef int npy_int128; - typedef unsigned int npy_uint128; -# define PyInt128ScalarObject PyIntScalarObject -# define PyInt128ArrType_Type PyIntArrType_Type -# define PyUInt128ScalarObject PyUIntScalarObject -# define PyUInt128ArrType_Type PyUIntArrType_Type -#define NPY_INT128_FMT NPY_INT_FMT -#define NPY_UINT128_FMT NPY_UINT_FMT -#endif -#endif - -#if NPY_BITSOF_SHORT == 8 -#ifndef NPY_INT8 -#define NPY_INT8 NPY_SHORT -#define NPY_UINT8 NPY_USHORT - typedef short npy_int8; - typedef unsigned short npy_uint8; -# define PyInt8ScalarObject PyShortScalarObject -# define PyInt8ArrType_Type PyShortArrType_Type -# define PyUInt8ScalarObject PyUShortScalarObject -# define PyUInt8ArrType_Type PyUShortArrType_Type -#define NPY_INT8_FMT NPY_SHORT_FMT -#define NPY_UINT8_FMT NPY_USHORT_FMT -#endif -#elif NPY_BITSOF_SHORT == 16 -#ifndef NPY_INT16 -#define NPY_INT16 NPY_SHORT -#define NPY_UINT16 NPY_USHORT - typedef short npy_int16; - typedef unsigned short npy_uint16; -# define PyInt16ScalarObject PyShortScalarObject -# define PyInt16ArrType_Type PyShortArrType_Type -# define PyUInt16ScalarObject PyUShortScalarObject -# define PyUInt16ArrType_Type PyUShortArrType_Type -#define NPY_INT16_FMT NPY_SHORT_FMT -#define NPY_UINT16_FMT NPY_USHORT_FMT -#endif -#elif NPY_BITSOF_SHORT == 32 -#ifndef NPY_INT32 -#define NPY_INT32 NPY_SHORT -#define NPY_UINT32 NPY_USHORT - typedef short npy_int32; - typedef unsigned short npy_uint32; - typedef unsigned short npy_ucs4; -# define PyInt32ScalarObject PyShortScalarObject -# define PyInt32ArrType_Type PyShortArrType_Type -# define PyUInt32ScalarObject PyUShortScalarObject -# define PyUInt32ArrType_Type PyUShortArrType_Type -#define NPY_INT32_FMT NPY_SHORT_FMT -#define NPY_UINT32_FMT NPY_USHORT_FMT -#endif -#elif NPY_BITSOF_SHORT == 64 -#ifndef NPY_INT64 -#define NPY_INT64 NPY_SHORT -#define NPY_UINT64 NPY_USHORT - typedef short npy_int64; - typedef unsigned short npy_uint64; -# define PyInt64ScalarObject PyShortScalarObject -# define PyInt64ArrType_Type PyShortArrType_Type -# define PyUInt64ScalarObject PyUShortScalarObject -# define PyUInt64ArrType_Type PyUShortArrType_Type -#define NPY_INT64_FMT NPY_SHORT_FMT -#define NPY_UINT64_FMT NPY_USHORT_FMT -# define MyPyLong_FromInt64 PyLong_FromLong -# define MyPyLong_AsInt64 PyLong_AsLong -#endif -#elif NPY_BITSOF_SHORT == 128 -#ifndef NPY_INT128 -#define NPY_INT128 NPY_SHORT -#define NPY_UINT128 NPY_USHORT - typedef short npy_int128; - typedef unsigned short npy_uint128; -# define PyInt128ScalarObject PyShortScalarObject -# define PyInt128ArrType_Type PyShortArrType_Type -# define PyUInt128ScalarObject PyUShortScalarObject -# define PyUInt128ArrType_Type PyUShortArrType_Type -#define NPY_INT128_FMT NPY_SHORT_FMT -#define NPY_UINT128_FMT NPY_USHORT_FMT -#endif -#endif - - -#if NPY_BITSOF_CHAR == 8 -#ifndef NPY_INT8 -#define NPY_INT8 NPY_BYTE -#define NPY_UINT8 NPY_UBYTE - typedef signed char npy_int8; - typedef unsigned char npy_uint8; -# define PyInt8ScalarObject PyByteScalarObject -# define PyInt8ArrType_Type PyByteArrType_Type -# define PyUInt8ScalarObject PyUByteScalarObject -# define PyUInt8ArrType_Type PyUByteArrType_Type -#define NPY_INT8_FMT NPY_BYTE_FMT -#define NPY_UINT8_FMT NPY_UBYTE_FMT -#endif -#elif NPY_BITSOF_CHAR == 16 -#ifndef NPY_INT16 -#define NPY_INT16 NPY_BYTE -#define NPY_UINT16 NPY_UBYTE - typedef signed char npy_int16; - typedef unsigned char npy_uint16; -# define PyInt16ScalarObject PyByteScalarObject -# define PyInt16ArrType_Type PyByteArrType_Type -# define PyUInt16ScalarObject PyUByteScalarObject -# define PyUInt16ArrType_Type PyUByteArrType_Type -#define NPY_INT16_FMT NPY_BYTE_FMT -#define NPY_UINT16_FMT NPY_UBYTE_FMT -#endif -#elif NPY_BITSOF_CHAR == 32 -#ifndef NPY_INT32 -#define NPY_INT32 NPY_BYTE -#define NPY_UINT32 NPY_UBYTE - typedef signed char npy_int32; - typedef unsigned char npy_uint32; - typedef unsigned char npy_ucs4; -# define PyInt32ScalarObject PyByteScalarObject -# define PyInt32ArrType_Type PyByteArrType_Type -# define PyUInt32ScalarObject PyUByteScalarObject -# define PyUInt32ArrType_Type PyUByteArrType_Type -#define NPY_INT32_FMT NPY_BYTE_FMT -#define NPY_UINT32_FMT NPY_UBYTE_FMT -#endif -#elif NPY_BITSOF_CHAR == 64 -#ifndef NPY_INT64 -#define NPY_INT64 NPY_BYTE -#define NPY_UINT64 NPY_UBYTE - typedef signed char npy_int64; - typedef unsigned char npy_uint64; -# define PyInt64ScalarObject PyByteScalarObject -# define PyInt64ArrType_Type PyByteArrType_Type -# define PyUInt64ScalarObject PyUByteScalarObject -# define PyUInt64ArrType_Type PyUByteArrType_Type -#define NPY_INT64_FMT NPY_BYTE_FMT -#define NPY_UINT64_FMT NPY_UBYTE_FMT -# define MyPyLong_FromInt64 PyLong_FromLong -# define MyPyLong_AsInt64 PyLong_AsLong -#endif -#elif NPY_BITSOF_CHAR == 128 -#ifndef NPY_INT128 -#define NPY_INT128 NPY_BYTE -#define NPY_UINT128 NPY_UBYTE - typedef signed char npy_int128; - typedef unsigned char npy_uint128; -# define PyInt128ScalarObject PyByteScalarObject -# define PyInt128ArrType_Type PyByteArrType_Type -# define PyUInt128ScalarObject PyUByteScalarObject -# define PyUInt128ArrType_Type PyUByteArrType_Type -#define NPY_INT128_FMT NPY_BYTE_FMT -#define NPY_UINT128_FMT NPY_UBYTE_FMT -#endif -#endif - - - -#if NPY_BITSOF_DOUBLE == 32 -#ifndef NPY_FLOAT32 -#define NPY_FLOAT32 NPY_DOUBLE -#define NPY_COMPLEX64 NPY_CDOUBLE - typedef double npy_float32; - typedef npy_cdouble npy_complex64; -# define PyFloat32ScalarObject PyDoubleScalarObject -# define PyComplex64ScalarObject PyCDoubleScalarObject -# define PyFloat32ArrType_Type PyDoubleArrType_Type -# define PyComplex64ArrType_Type PyCDoubleArrType_Type -#define NPY_FLOAT32_FMT NPY_DOUBLE_FMT -#define NPY_COMPLEX64_FMT NPY_CDOUBLE_FMT -#endif -#elif NPY_BITSOF_DOUBLE == 64 -#ifndef NPY_FLOAT64 -#define NPY_FLOAT64 NPY_DOUBLE -#define NPY_COMPLEX128 NPY_CDOUBLE - typedef double npy_float64; - typedef npy_cdouble npy_complex128; -# define PyFloat64ScalarObject PyDoubleScalarObject -# define PyComplex128ScalarObject PyCDoubleScalarObject -# define PyFloat64ArrType_Type PyDoubleArrType_Type -# define PyComplex128ArrType_Type PyCDoubleArrType_Type -#define NPY_FLOAT64_FMT NPY_DOUBLE_FMT -#define NPY_COMPLEX128_FMT NPY_CDOUBLE_FMT -#endif -#elif NPY_BITSOF_DOUBLE == 80 -#ifndef NPY_FLOAT80 -#define NPY_FLOAT80 NPY_DOUBLE -#define NPY_COMPLEX160 NPY_CDOUBLE - typedef double npy_float80; - typedef npy_cdouble npy_complex160; -# define PyFloat80ScalarObject PyDoubleScalarObject -# define PyComplex160ScalarObject PyCDoubleScalarObject -# define PyFloat80ArrType_Type PyDoubleArrType_Type -# define PyComplex160ArrType_Type PyCDoubleArrType_Type -#define NPY_FLOAT80_FMT NPY_DOUBLE_FMT -#define NPY_COMPLEX160_FMT NPY_CDOUBLE_FMT -#endif -#elif NPY_BITSOF_DOUBLE == 96 -#ifndef NPY_FLOAT96 -#define NPY_FLOAT96 NPY_DOUBLE -#define NPY_COMPLEX192 NPY_CDOUBLE - typedef double npy_float96; - typedef npy_cdouble npy_complex192; -# define PyFloat96ScalarObject PyDoubleScalarObject -# define PyComplex192ScalarObject PyCDoubleScalarObject -# define PyFloat96ArrType_Type PyDoubleArrType_Type -# define PyComplex192ArrType_Type PyCDoubleArrType_Type -#define NPY_FLOAT96_FMT NPY_DOUBLE_FMT -#define NPY_COMPLEX192_FMT NPY_CDOUBLE_FMT -#endif -#elif NPY_BITSOF_DOUBLE == 128 -#ifndef NPY_FLOAT128 -#define NPY_FLOAT128 NPY_DOUBLE -#define NPY_COMPLEX256 NPY_CDOUBLE - typedef double npy_float128; - typedef npy_cdouble npy_complex256; -# define PyFloat128ScalarObject PyDoubleScalarObject -# define PyComplex256ScalarObject PyCDoubleScalarObject -# define PyFloat128ArrType_Type PyDoubleArrType_Type -# define PyComplex256ArrType_Type PyCDoubleArrType_Type -#define NPY_FLOAT128_FMT NPY_DOUBLE_FMT -#define NPY_COMPLEX256_FMT NPY_CDOUBLE_FMT -#endif -#endif - - - -#if NPY_BITSOF_FLOAT == 32 -#ifndef NPY_FLOAT32 -#define NPY_FLOAT32 NPY_FLOAT -#define NPY_COMPLEX64 NPY_CFLOAT - typedef float npy_float32; - typedef npy_cfloat npy_complex64; -# define PyFloat32ScalarObject PyFloatScalarObject -# define PyComplex64ScalarObject PyCFloatScalarObject -# define PyFloat32ArrType_Type PyFloatArrType_Type -# define PyComplex64ArrType_Type PyCFloatArrType_Type -#define NPY_FLOAT32_FMT NPY_FLOAT_FMT -#define NPY_COMPLEX64_FMT NPY_CFLOAT_FMT -#endif -#elif NPY_BITSOF_FLOAT == 64 -#ifndef NPY_FLOAT64 -#define NPY_FLOAT64 NPY_FLOAT -#define NPY_COMPLEX128 NPY_CFLOAT - typedef float npy_float64; - typedef npy_cfloat npy_complex128; -# define PyFloat64ScalarObject PyFloatScalarObject -# define PyComplex128ScalarObject PyCFloatScalarObject -# define PyFloat64ArrType_Type PyFloatArrType_Type -# define PyComplex128ArrType_Type PyCFloatArrType_Type -#define NPY_FLOAT64_FMT NPY_FLOAT_FMT -#define NPY_COMPLEX128_FMT NPY_CFLOAT_FMT -#endif -#elif NPY_BITSOF_FLOAT == 80 -#ifndef NPY_FLOAT80 -#define NPY_FLOAT80 NPY_FLOAT -#define NPY_COMPLEX160 NPY_CFLOAT - typedef float npy_float80; - typedef npy_cfloat npy_complex160; -# define PyFloat80ScalarObject PyFloatScalarObject -# define PyComplex160ScalarObject PyCFloatScalarObject -# define PyFloat80ArrType_Type PyFloatArrType_Type -# define PyComplex160ArrType_Type PyCFloatArrType_Type -#define NPY_FLOAT80_FMT NPY_FLOAT_FMT -#define NPY_COMPLEX160_FMT NPY_CFLOAT_FMT -#endif -#elif NPY_BITSOF_FLOAT == 96 -#ifndef NPY_FLOAT96 -#define NPY_FLOAT96 NPY_FLOAT -#define NPY_COMPLEX192 NPY_CFLOAT - typedef float npy_float96; - typedef npy_cfloat npy_complex192; -# define PyFloat96ScalarObject PyFloatScalarObject -# define PyComplex192ScalarObject PyCFloatScalarObject -# define PyFloat96ArrType_Type PyFloatArrType_Type -# define PyComplex192ArrType_Type PyCFloatArrType_Type -#define NPY_FLOAT96_FMT NPY_FLOAT_FMT -#define NPY_COMPLEX192_FMT NPY_CFLOAT_FMT -#endif -#elif NPY_BITSOF_FLOAT == 128 -#ifndef NPY_FLOAT128 -#define NPY_FLOAT128 NPY_FLOAT -#define NPY_COMPLEX256 NPY_CFLOAT - typedef float npy_float128; - typedef npy_cfloat npy_complex256; -# define PyFloat128ScalarObject PyFloatScalarObject -# define PyComplex256ScalarObject PyCFloatScalarObject -# define PyFloat128ArrType_Type PyFloatArrType_Type -# define PyComplex256ArrType_Type PyCFloatArrType_Type -#define NPY_FLOAT128_FMT NPY_FLOAT_FMT -#define NPY_COMPLEX256_FMT NPY_CFLOAT_FMT -#endif -#endif - -/* half/float16 isn't a floating-point type in C */ -#define NPY_FLOAT16 NPY_HALF -typedef npy_uint16 npy_half; -typedef npy_half npy_float16; - -#if NPY_BITSOF_LONGDOUBLE == 32 -#ifndef NPY_FLOAT32 -#define NPY_FLOAT32 NPY_LONGDOUBLE -#define NPY_COMPLEX64 NPY_CLONGDOUBLE - typedef npy_longdouble npy_float32; - typedef npy_clongdouble npy_complex64; -# define PyFloat32ScalarObject PyLongDoubleScalarObject -# define PyComplex64ScalarObject PyCLongDoubleScalarObject -# define PyFloat32ArrType_Type PyLongDoubleArrType_Type -# define PyComplex64ArrType_Type PyCLongDoubleArrType_Type -#define NPY_FLOAT32_FMT NPY_LONGDOUBLE_FMT -#define NPY_COMPLEX64_FMT NPY_CLONGDOUBLE_FMT -#endif -#elif NPY_BITSOF_LONGDOUBLE == 64 -#ifndef NPY_FLOAT64 -#define NPY_FLOAT64 NPY_LONGDOUBLE -#define NPY_COMPLEX128 NPY_CLONGDOUBLE - typedef npy_longdouble npy_float64; - typedef npy_clongdouble npy_complex128; -# define PyFloat64ScalarObject PyLongDoubleScalarObject -# define PyComplex128ScalarObject PyCLongDoubleScalarObject -# define PyFloat64ArrType_Type PyLongDoubleArrType_Type -# define PyComplex128ArrType_Type PyCLongDoubleArrType_Type -#define NPY_FLOAT64_FMT NPY_LONGDOUBLE_FMT -#define NPY_COMPLEX128_FMT NPY_CLONGDOUBLE_FMT -#endif -#elif NPY_BITSOF_LONGDOUBLE == 80 -#ifndef NPY_FLOAT80 -#define NPY_FLOAT80 NPY_LONGDOUBLE -#define NPY_COMPLEX160 NPY_CLONGDOUBLE - typedef npy_longdouble npy_float80; - typedef npy_clongdouble npy_complex160; -# define PyFloat80ScalarObject PyLongDoubleScalarObject -# define PyComplex160ScalarObject PyCLongDoubleScalarObject -# define PyFloat80ArrType_Type PyLongDoubleArrType_Type -# define PyComplex160ArrType_Type PyCLongDoubleArrType_Type -#define NPY_FLOAT80_FMT NPY_LONGDOUBLE_FMT -#define NPY_COMPLEX160_FMT NPY_CLONGDOUBLE_FMT -#endif -#elif NPY_BITSOF_LONGDOUBLE == 96 -#ifndef NPY_FLOAT96 -#define NPY_FLOAT96 NPY_LONGDOUBLE -#define NPY_COMPLEX192 NPY_CLONGDOUBLE - typedef npy_longdouble npy_float96; - typedef npy_clongdouble npy_complex192; -# define PyFloat96ScalarObject PyLongDoubleScalarObject -# define PyComplex192ScalarObject PyCLongDoubleScalarObject -# define PyFloat96ArrType_Type PyLongDoubleArrType_Type -# define PyComplex192ArrType_Type PyCLongDoubleArrType_Type -#define NPY_FLOAT96_FMT NPY_LONGDOUBLE_FMT -#define NPY_COMPLEX192_FMT NPY_CLONGDOUBLE_FMT -#endif -#elif NPY_BITSOF_LONGDOUBLE == 128 -#ifndef NPY_FLOAT128 -#define NPY_FLOAT128 NPY_LONGDOUBLE -#define NPY_COMPLEX256 NPY_CLONGDOUBLE - typedef npy_longdouble npy_float128; - typedef npy_clongdouble npy_complex256; -# define PyFloat128ScalarObject PyLongDoubleScalarObject -# define PyComplex256ScalarObject PyCLongDoubleScalarObject -# define PyFloat128ArrType_Type PyLongDoubleArrType_Type -# define PyComplex256ArrType_Type PyCLongDoubleArrType_Type -#define NPY_FLOAT128_FMT NPY_LONGDOUBLE_FMT -#define NPY_COMPLEX256_FMT NPY_CLONGDOUBLE_FMT -#endif -#elif NPY_BITSOF_LONGDOUBLE == 256 -#define NPY_FLOAT256 NPY_LONGDOUBLE -#define NPY_COMPLEX512 NPY_CLONGDOUBLE - typedef npy_longdouble npy_float256; - typedef npy_clongdouble npy_complex512; -# define PyFloat256ScalarObject PyLongDoubleScalarObject -# define PyComplex512ScalarObject PyCLongDoubleScalarObject -# define PyFloat256ArrType_Type PyLongDoubleArrType_Type -# define PyComplex512ArrType_Type PyCLongDoubleArrType_Type -#define NPY_FLOAT256_FMT NPY_LONGDOUBLE_FMT -#define NPY_COMPLEX512_FMT NPY_CLONGDOUBLE_FMT -#endif - -/* datetime typedefs */ -typedef npy_int64 npy_timedelta; -typedef npy_int64 npy_datetime; -#define NPY_DATETIME_FMT NPY_INT64_FMT -#define NPY_TIMEDELTA_FMT NPY_INT64_FMT - -/* End of typedefs for numarray style bit-width names */ - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h deleted file mode 100644 index 7958dc208..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_cpu.h +++ /dev/null @@ -1,114 +0,0 @@ -/* - * This set (target) cpu specific macros: - * - Possible values: - * NPY_CPU_X86 - * NPY_CPU_AMD64 - * NPY_CPU_PPC - * NPY_CPU_PPC64 - * NPY_CPU_PPC64LE - * NPY_CPU_SPARC - * NPY_CPU_S390 - * NPY_CPU_IA64 - * NPY_CPU_HPPA - * NPY_CPU_ALPHA - * NPY_CPU_ARMEL - * NPY_CPU_ARMEB - * NPY_CPU_SH_LE - * NPY_CPU_SH_BE - */ -#ifndef _NPY_CPUARCH_H_ -#define _NPY_CPUARCH_H_ - -#include "numpyconfig.h" - -#if defined( __i386__ ) || defined(i386) || defined(_M_IX86) - /* - * __i386__ is defined by gcc and Intel compiler on Linux, - * _M_IX86 by VS compiler, - * i386 by Sun compilers on opensolaris at least - */ - #define NPY_CPU_X86 -#elif defined(__x86_64__) || defined(__amd64__) || defined(__x86_64) || defined(_M_AMD64) - /* - * both __x86_64__ and __amd64__ are defined by gcc - * __x86_64 defined by sun compiler on opensolaris at least - * _M_AMD64 defined by MS compiler - */ - #define NPY_CPU_AMD64 -#elif defined(__ppc__) || defined(__powerpc__) || defined(_ARCH_PPC) - /* - * __ppc__ is defined by gcc, I remember having seen __powerpc__ once, - * but can't find it ATM - * _ARCH_PPC is used by at least gcc on AIX - */ - #define NPY_CPU_PPC -#elif defined(__ppc64le__) - #define NPY_CPU_PPC64LE -#elif defined(__ppc64__) - #define NPY_CPU_PPC64 -#elif defined(__sparc__) || defined(__sparc) - /* __sparc__ is defined by gcc and Forte (e.g. Sun) compilers */ - #define NPY_CPU_SPARC -#elif defined(__s390__) - #define NPY_CPU_S390 -#elif defined(__ia64) - #define NPY_CPU_IA64 -#elif defined(__hppa) - #define NPY_CPU_HPPA -#elif defined(__alpha__) - #define NPY_CPU_ALPHA -#elif defined(__arm__) && defined(__ARMEL__) - #define NPY_CPU_ARMEL -#elif defined(__arm__) && defined(__ARMEB__) - #define NPY_CPU_ARMEB -#elif defined(__sh__) && defined(__LITTLE_ENDIAN__) - #define NPY_CPU_SH_LE -#elif defined(__sh__) && defined(__BIG_ENDIAN__) - #define NPY_CPU_SH_BE -#elif defined(__MIPSEL__) - #define NPY_CPU_MIPSEL -#elif defined(__MIPSEB__) - #define NPY_CPU_MIPSEB -#elif defined(__aarch64__) - #define NPY_CPU_AARCH64 -#elif defined(__mc68000__) - #define NPY_CPU_M68K -#else - #error Unknown CPU, please report this to numpy maintainers with \ - information about your platform (OS, CPU and compiler) -#endif - -/* - This "white-lists" the architectures that we know don't require - pointer alignment. We white-list, since the memcpy version will - work everywhere, whereas assignment will only work where pointer - dereferencing doesn't require alignment. - - TODO: There may be more architectures we can white list. -*/ -#if defined(NPY_CPU_X86) || defined(NPY_CPU_AMD64) - #define NPY_COPY_PYOBJECT_PTR(dst, src) (*((PyObject **)(dst)) = *((PyObject **)(src))) -#else - #if NPY_SIZEOF_PY_INTPTR_T == 4 - #define NPY_COPY_PYOBJECT_PTR(dst, src) \ - ((char*)(dst))[0] = ((char*)(src))[0]; \ - ((char*)(dst))[1] = ((char*)(src))[1]; \ - ((char*)(dst))[2] = ((char*)(src))[2]; \ - ((char*)(dst))[3] = ((char*)(src))[3]; - #elif NPY_SIZEOF_PY_INTPTR_T == 8 - #define NPY_COPY_PYOBJECT_PTR(dst, src) \ - ((char*)(dst))[0] = ((char*)(src))[0]; \ - ((char*)(dst))[1] = ((char*)(src))[1]; \ - ((char*)(dst))[2] = ((char*)(src))[2]; \ - ((char*)(dst))[3] = ((char*)(src))[3]; \ - ((char*)(dst))[4] = ((char*)(src))[4]; \ - ((char*)(dst))[5] = ((char*)(src))[5]; \ - ((char*)(dst))[6] = ((char*)(src))[6]; \ - ((char*)(dst))[7] = ((char*)(src))[7]; - #else - #error Unknown architecture, please report this to numpy maintainers with \ - information about your platform (OS, CPU and compiler) - #endif -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h deleted file mode 100644 index 44d4326b1..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_endian.h +++ /dev/null @@ -1,48 +0,0 @@ -#ifndef _NPY_ENDIAN_H_ -#define _NPY_ENDIAN_H_ - -/* - * NPY_BYTE_ORDER is set to the same value as BYTE_ORDER set by glibc in - * endian.h - */ - -#ifdef NPY_HAVE_ENDIAN_H - /* Use endian.h if available */ - #include - - #define NPY_BYTE_ORDER __BYTE_ORDER - #define NPY_LITTLE_ENDIAN __LITTLE_ENDIAN - #define NPY_BIG_ENDIAN __BIG_ENDIAN -#else - /* Set endianness info using target CPU */ - #include "npy_cpu.h" - - #define NPY_LITTLE_ENDIAN 1234 - #define NPY_BIG_ENDIAN 4321 - - #if defined(NPY_CPU_X86) \ - || defined(NPY_CPU_AMD64) \ - || defined(NPY_CPU_IA64) \ - || defined(NPY_CPU_ALPHA) \ - || defined(NPY_CPU_ARMEL) \ - || defined(NPY_CPU_AARCH64) \ - || defined(NPY_CPU_SH_LE) \ - || defined(NPY_CPU_MIPSEL) \ - || defined(NPY_CPU_PPC64LE) - #define NPY_BYTE_ORDER NPY_LITTLE_ENDIAN - #elif defined(NPY_CPU_PPC) \ - || defined(NPY_CPU_SPARC) \ - || defined(NPY_CPU_S390) \ - || defined(NPY_CPU_HPPA) \ - || defined(NPY_CPU_PPC64) \ - || defined(NPY_CPU_ARMEB) \ - || defined(NPY_CPU_SH_BE) \ - || defined(NPY_CPU_MIPSEB) \ - || defined(NPY_CPU_M68K) - #define NPY_BYTE_ORDER NPY_BIG_ENDIAN - #else - #error Unknown CPU: can not set endianness - #endif -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h deleted file mode 100644 index f71fd689e..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_interrupt.h +++ /dev/null @@ -1,117 +0,0 @@ - -/* Signal handling: - -This header file defines macros that allow your code to handle -interrupts received during processing. Interrupts that -could reasonably be handled: - -SIGINT, SIGABRT, SIGALRM, SIGSEGV - -****Warning*************** - -Do not allow code that creates temporary memory or increases reference -counts of Python objects to be interrupted unless you handle it -differently. - -************************** - -The mechanism for handling interrupts is conceptually simple: - - - replace the signal handler with our own home-grown version - and store the old one. - - run the code to be interrupted -- if an interrupt occurs - the handler should basically just cause a return to the - calling function for finish work. - - restore the old signal handler - -Of course, every code that allows interrupts must account for -returning via the interrupt and handle clean-up correctly. But, -even still, the simple paradigm is complicated by at least three -factors. - - 1) platform portability (i.e. Microsoft says not to use longjmp - to return from signal handling. They have a __try and __except - extension to C instead but what about mingw?). - - 2) how to handle threads: apparently whether signals are delivered to - every thread of the process or the "invoking" thread is platform - dependent. --- we don't handle threads for now. - - 3) do we need to worry about re-entrance. For now, assume the - code will not call-back into itself. - -Ideas: - - 1) Start by implementing an approach that works on platforms that - can use setjmp and longjmp functionality and does nothing - on other platforms. - - 2) Ignore threads --- i.e. do not mix interrupt handling and threads - - 3) Add a default signal_handler function to the C-API but have the rest - use macros. - - -Simple Interface: - - -In your C-extension: around a block of code you want to be interruptable -with a SIGINT - -NPY_SIGINT_ON -[code] -NPY_SIGINT_OFF - -In order for this to work correctly, the -[code] block must not allocate any memory or alter the reference count of any -Python objects. In other words [code] must be interruptible so that continuation -after NPY_SIGINT_OFF will only be "missing some computations" - -Interrupt handling does not work well with threads. - -*/ - -/* Add signal handling macros - Make the global variable and signal handler part of the C-API -*/ - -#ifndef NPY_INTERRUPT_H -#define NPY_INTERRUPT_H - -#ifndef NPY_NO_SIGNAL - -#include -#include - -#ifndef sigsetjmp - -#define NPY_SIGSETJMP(arg1, arg2) setjmp(arg1) -#define NPY_SIGLONGJMP(arg1, arg2) longjmp(arg1, arg2) -#define NPY_SIGJMP_BUF jmp_buf - -#else - -#define NPY_SIGSETJMP(arg1, arg2) sigsetjmp(arg1, arg2) -#define NPY_SIGLONGJMP(arg1, arg2) siglongjmp(arg1, arg2) -#define NPY_SIGJMP_BUF sigjmp_buf - -#endif - -# define NPY_SIGINT_ON { \ - PyOS_sighandler_t _npy_sig_save; \ - _npy_sig_save = PyOS_setsig(SIGINT, _PyArray_SigintHandler); \ - if (NPY_SIGSETJMP(*((NPY_SIGJMP_BUF *)_PyArray_GetSigintBuf()), \ - 1) == 0) { \ - -# define NPY_SIGINT_OFF } \ - PyOS_setsig(SIGINT, _npy_sig_save); \ - } - -#else /* NPY_NO_SIGNAL */ - -#define NPY_SIGINT_ON -#define NPY_SIGINT_OFF - -#endif /* HAVE_SIGSETJMP */ - -#endif /* NPY_INTERRUPT_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h deleted file mode 100644 index 094286181..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_math.h +++ /dev/null @@ -1,468 +0,0 @@ -#ifndef __NPY_MATH_C99_H_ -#define __NPY_MATH_C99_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#ifdef __SUNPRO_CC -#include -#endif -#ifdef HAVE_NPY_CONFIG_H -#include -#endif -#include - - -/* - * NAN and INFINITY like macros (same behavior as glibc for NAN, same as C99 - * for INFINITY) - * - * XXX: I should test whether INFINITY and NAN are available on the platform - */ -NPY_INLINE static float __npy_inff(void) -{ - const union { npy_uint32 __i; float __f;} __bint = {0x7f800000UL}; - return __bint.__f; -} - -NPY_INLINE static float __npy_nanf(void) -{ - const union { npy_uint32 __i; float __f;} __bint = {0x7fc00000UL}; - return __bint.__f; -} - -NPY_INLINE static float __npy_pzerof(void) -{ - const union { npy_uint32 __i; float __f;} __bint = {0x00000000UL}; - return __bint.__f; -} - -NPY_INLINE static float __npy_nzerof(void) -{ - const union { npy_uint32 __i; float __f;} __bint = {0x80000000UL}; - return __bint.__f; -} - -#define NPY_INFINITYF __npy_inff() -#define NPY_NANF __npy_nanf() -#define NPY_PZEROF __npy_pzerof() -#define NPY_NZEROF __npy_nzerof() - -#define NPY_INFINITY ((npy_double)NPY_INFINITYF) -#define NPY_NAN ((npy_double)NPY_NANF) -#define NPY_PZERO ((npy_double)NPY_PZEROF) -#define NPY_NZERO ((npy_double)NPY_NZEROF) - -#define NPY_INFINITYL ((npy_longdouble)NPY_INFINITYF) -#define NPY_NANL ((npy_longdouble)NPY_NANF) -#define NPY_PZEROL ((npy_longdouble)NPY_PZEROF) -#define NPY_NZEROL ((npy_longdouble)NPY_NZEROF) - -/* - * Useful constants - */ -#define NPY_E 2.718281828459045235360287471352662498 /* e */ -#define NPY_LOG2E 1.442695040888963407359924681001892137 /* log_2 e */ -#define NPY_LOG10E 0.434294481903251827651128918916605082 /* log_10 e */ -#define NPY_LOGE2 0.693147180559945309417232121458176568 /* log_e 2 */ -#define NPY_LOGE10 2.302585092994045684017991454684364208 /* log_e 10 */ -#define NPY_PI 3.141592653589793238462643383279502884 /* pi */ -#define NPY_PI_2 1.570796326794896619231321691639751442 /* pi/2 */ -#define NPY_PI_4 0.785398163397448309615660845819875721 /* pi/4 */ -#define NPY_1_PI 0.318309886183790671537767526745028724 /* 1/pi */ -#define NPY_2_PI 0.636619772367581343075535053490057448 /* 2/pi */ -#define NPY_EULER 0.577215664901532860606512090082402431 /* Euler constant */ -#define NPY_SQRT2 1.414213562373095048801688724209698079 /* sqrt(2) */ -#define NPY_SQRT1_2 0.707106781186547524400844362104849039 /* 1/sqrt(2) */ - -#define NPY_Ef 2.718281828459045235360287471352662498F /* e */ -#define NPY_LOG2Ef 1.442695040888963407359924681001892137F /* log_2 e */ -#define NPY_LOG10Ef 0.434294481903251827651128918916605082F /* log_10 e */ -#define NPY_LOGE2f 0.693147180559945309417232121458176568F /* log_e 2 */ -#define NPY_LOGE10f 2.302585092994045684017991454684364208F /* log_e 10 */ -#define NPY_PIf 3.141592653589793238462643383279502884F /* pi */ -#define NPY_PI_2f 1.570796326794896619231321691639751442F /* pi/2 */ -#define NPY_PI_4f 0.785398163397448309615660845819875721F /* pi/4 */ -#define NPY_1_PIf 0.318309886183790671537767526745028724F /* 1/pi */ -#define NPY_2_PIf 0.636619772367581343075535053490057448F /* 2/pi */ -#define NPY_EULERf 0.577215664901532860606512090082402431F /* Euler constan*/ -#define NPY_SQRT2f 1.414213562373095048801688724209698079F /* sqrt(2) */ -#define NPY_SQRT1_2f 0.707106781186547524400844362104849039F /* 1/sqrt(2) */ - -#define NPY_El 2.718281828459045235360287471352662498L /* e */ -#define NPY_LOG2El 1.442695040888963407359924681001892137L /* log_2 e */ -#define NPY_LOG10El 0.434294481903251827651128918916605082L /* log_10 e */ -#define NPY_LOGE2l 0.693147180559945309417232121458176568L /* log_e 2 */ -#define NPY_LOGE10l 2.302585092994045684017991454684364208L /* log_e 10 */ -#define NPY_PIl 3.141592653589793238462643383279502884L /* pi */ -#define NPY_PI_2l 1.570796326794896619231321691639751442L /* pi/2 */ -#define NPY_PI_4l 0.785398163397448309615660845819875721L /* pi/4 */ -#define NPY_1_PIl 0.318309886183790671537767526745028724L /* 1/pi */ -#define NPY_2_PIl 0.636619772367581343075535053490057448L /* 2/pi */ -#define NPY_EULERl 0.577215664901532860606512090082402431L /* Euler constan*/ -#define NPY_SQRT2l 1.414213562373095048801688724209698079L /* sqrt(2) */ -#define NPY_SQRT1_2l 0.707106781186547524400844362104849039L /* 1/sqrt(2) */ - -/* - * C99 double math funcs - */ -double npy_sin(double x); -double npy_cos(double x); -double npy_tan(double x); -double npy_sinh(double x); -double npy_cosh(double x); -double npy_tanh(double x); - -double npy_asin(double x); -double npy_acos(double x); -double npy_atan(double x); -double npy_aexp(double x); -double npy_alog(double x); -double npy_asqrt(double x); -double npy_afabs(double x); - -double npy_log(double x); -double npy_log10(double x); -double npy_exp(double x); -double npy_sqrt(double x); - -double npy_fabs(double x); -double npy_ceil(double x); -double npy_fmod(double x, double y); -double npy_floor(double x); - -double npy_expm1(double x); -double npy_log1p(double x); -double npy_hypot(double x, double y); -double npy_acosh(double x); -double npy_asinh(double xx); -double npy_atanh(double x); -double npy_rint(double x); -double npy_trunc(double x); -double npy_exp2(double x); -double npy_log2(double x); - -double npy_atan2(double x, double y); -double npy_pow(double x, double y); -double npy_modf(double x, double* y); - -double npy_copysign(double x, double y); -double npy_nextafter(double x, double y); -double npy_spacing(double x); - -/* - * IEEE 754 fpu handling. Those are guaranteed to be macros - */ - -/* use builtins to avoid function calls in tight loops - * only available if npy_config.h is available (= numpys own build) */ -#if HAVE___BUILTIN_ISNAN - #define npy_isnan(x) __builtin_isnan(x) -#else - #ifndef NPY_HAVE_DECL_ISNAN - #define npy_isnan(x) ((x) != (x)) - #else - #ifdef _MSC_VER - #define npy_isnan(x) _isnan((x)) - #else - #define npy_isnan(x) isnan(x) - #endif - #endif -#endif - - -/* only available if npy_config.h is available (= numpys own build) */ -#if HAVE___BUILTIN_ISFINITE - #define npy_isfinite(x) __builtin_isfinite(x) -#else - #ifndef NPY_HAVE_DECL_ISFINITE - #ifdef _MSC_VER - #define npy_isfinite(x) _finite((x)) - #else - #define npy_isfinite(x) !npy_isnan((x) + (-x)) - #endif - #else - #define npy_isfinite(x) isfinite((x)) - #endif -#endif - -/* only available if npy_config.h is available (= numpys own build) */ -#if HAVE___BUILTIN_ISINF - #define npy_isinf(x) __builtin_isinf(x) -#else - #ifndef NPY_HAVE_DECL_ISINF - #define npy_isinf(x) (!npy_isfinite(x) && !npy_isnan(x)) - #else - #ifdef _MSC_VER - #define npy_isinf(x) (!_finite((x)) && !_isnan((x))) - #else - #define npy_isinf(x) isinf((x)) - #endif - #endif -#endif - -#ifndef NPY_HAVE_DECL_SIGNBIT - int _npy_signbit_f(float x); - int _npy_signbit_d(double x); - int _npy_signbit_ld(long double x); - #define npy_signbit(x) \ - (sizeof (x) == sizeof (long double) ? _npy_signbit_ld (x) \ - : sizeof (x) == sizeof (double) ? _npy_signbit_d (x) \ - : _npy_signbit_f (x)) -#else - #define npy_signbit(x) signbit((x)) -#endif - -/* - * float C99 math functions - */ - -float npy_sinf(float x); -float npy_cosf(float x); -float npy_tanf(float x); -float npy_sinhf(float x); -float npy_coshf(float x); -float npy_tanhf(float x); -float npy_fabsf(float x); -float npy_floorf(float x); -float npy_ceilf(float x); -float npy_rintf(float x); -float npy_truncf(float x); -float npy_sqrtf(float x); -float npy_log10f(float x); -float npy_logf(float x); -float npy_expf(float x); -float npy_expm1f(float x); -float npy_asinf(float x); -float npy_acosf(float x); -float npy_atanf(float x); -float npy_asinhf(float x); -float npy_acoshf(float x); -float npy_atanhf(float x); -float npy_log1pf(float x); -float npy_exp2f(float x); -float npy_log2f(float x); - -float npy_atan2f(float x, float y); -float npy_hypotf(float x, float y); -float npy_powf(float x, float y); -float npy_fmodf(float x, float y); - -float npy_modff(float x, float* y); - -float npy_copysignf(float x, float y); -float npy_nextafterf(float x, float y); -float npy_spacingf(float x); - -/* - * float C99 math functions - */ - -npy_longdouble npy_sinl(npy_longdouble x); -npy_longdouble npy_cosl(npy_longdouble x); -npy_longdouble npy_tanl(npy_longdouble x); -npy_longdouble npy_sinhl(npy_longdouble x); -npy_longdouble npy_coshl(npy_longdouble x); -npy_longdouble npy_tanhl(npy_longdouble x); -npy_longdouble npy_fabsl(npy_longdouble x); -npy_longdouble npy_floorl(npy_longdouble x); -npy_longdouble npy_ceill(npy_longdouble x); -npy_longdouble npy_rintl(npy_longdouble x); -npy_longdouble npy_truncl(npy_longdouble x); -npy_longdouble npy_sqrtl(npy_longdouble x); -npy_longdouble npy_log10l(npy_longdouble x); -npy_longdouble npy_logl(npy_longdouble x); -npy_longdouble npy_expl(npy_longdouble x); -npy_longdouble npy_expm1l(npy_longdouble x); -npy_longdouble npy_asinl(npy_longdouble x); -npy_longdouble npy_acosl(npy_longdouble x); -npy_longdouble npy_atanl(npy_longdouble x); -npy_longdouble npy_asinhl(npy_longdouble x); -npy_longdouble npy_acoshl(npy_longdouble x); -npy_longdouble npy_atanhl(npy_longdouble x); -npy_longdouble npy_log1pl(npy_longdouble x); -npy_longdouble npy_exp2l(npy_longdouble x); -npy_longdouble npy_log2l(npy_longdouble x); - -npy_longdouble npy_atan2l(npy_longdouble x, npy_longdouble y); -npy_longdouble npy_hypotl(npy_longdouble x, npy_longdouble y); -npy_longdouble npy_powl(npy_longdouble x, npy_longdouble y); -npy_longdouble npy_fmodl(npy_longdouble x, npy_longdouble y); - -npy_longdouble npy_modfl(npy_longdouble x, npy_longdouble* y); - -npy_longdouble npy_copysignl(npy_longdouble x, npy_longdouble y); -npy_longdouble npy_nextafterl(npy_longdouble x, npy_longdouble y); -npy_longdouble npy_spacingl(npy_longdouble x); - -/* - * Non standard functions - */ -double npy_deg2rad(double x); -double npy_rad2deg(double x); -double npy_logaddexp(double x, double y); -double npy_logaddexp2(double x, double y); - -float npy_deg2radf(float x); -float npy_rad2degf(float x); -float npy_logaddexpf(float x, float y); -float npy_logaddexp2f(float x, float y); - -npy_longdouble npy_deg2radl(npy_longdouble x); -npy_longdouble npy_rad2degl(npy_longdouble x); -npy_longdouble npy_logaddexpl(npy_longdouble x, npy_longdouble y); -npy_longdouble npy_logaddexp2l(npy_longdouble x, npy_longdouble y); - -#define npy_degrees npy_rad2deg -#define npy_degreesf npy_rad2degf -#define npy_degreesl npy_rad2degl - -#define npy_radians npy_deg2rad -#define npy_radiansf npy_deg2radf -#define npy_radiansl npy_deg2radl - -/* - * Complex declarations - */ - -/* - * C99 specifies that complex numbers have the same representation as - * an array of two elements, where the first element is the real part - * and the second element is the imaginary part. - */ -#define __NPY_CPACK_IMP(x, y, type, ctype) \ - union { \ - ctype z; \ - type a[2]; \ - } z1;; \ - \ - z1.a[0] = (x); \ - z1.a[1] = (y); \ - \ - return z1.z; - -static NPY_INLINE npy_cdouble npy_cpack(double x, double y) -{ - __NPY_CPACK_IMP(x, y, double, npy_cdouble); -} - -static NPY_INLINE npy_cfloat npy_cpackf(float x, float y) -{ - __NPY_CPACK_IMP(x, y, float, npy_cfloat); -} - -static NPY_INLINE npy_clongdouble npy_cpackl(npy_longdouble x, npy_longdouble y) -{ - __NPY_CPACK_IMP(x, y, npy_longdouble, npy_clongdouble); -} -#undef __NPY_CPACK_IMP - -/* - * Same remark as above, but in the other direction: extract first/second - * member of complex number, assuming a C99-compatible representation - * - * Those are defineds as static inline, and such as a reasonable compiler would - * most likely compile this to one or two instructions (on CISC at least) - */ -#define __NPY_CEXTRACT_IMP(z, index, type, ctype) \ - union { \ - ctype z; \ - type a[2]; \ - } __z_repr; \ - __z_repr.z = z; \ - \ - return __z_repr.a[index]; - -static NPY_INLINE double npy_creal(npy_cdouble z) -{ - __NPY_CEXTRACT_IMP(z, 0, double, npy_cdouble); -} - -static NPY_INLINE double npy_cimag(npy_cdouble z) -{ - __NPY_CEXTRACT_IMP(z, 1, double, npy_cdouble); -} - -static NPY_INLINE float npy_crealf(npy_cfloat z) -{ - __NPY_CEXTRACT_IMP(z, 0, float, npy_cfloat); -} - -static NPY_INLINE float npy_cimagf(npy_cfloat z) -{ - __NPY_CEXTRACT_IMP(z, 1, float, npy_cfloat); -} - -static NPY_INLINE npy_longdouble npy_creall(npy_clongdouble z) -{ - __NPY_CEXTRACT_IMP(z, 0, npy_longdouble, npy_clongdouble); -} - -static NPY_INLINE npy_longdouble npy_cimagl(npy_clongdouble z) -{ - __NPY_CEXTRACT_IMP(z, 1, npy_longdouble, npy_clongdouble); -} -#undef __NPY_CEXTRACT_IMP - -/* - * Double precision complex functions - */ -double npy_cabs(npy_cdouble z); -double npy_carg(npy_cdouble z); - -npy_cdouble npy_cexp(npy_cdouble z); -npy_cdouble npy_clog(npy_cdouble z); -npy_cdouble npy_cpow(npy_cdouble x, npy_cdouble y); - -npy_cdouble npy_csqrt(npy_cdouble z); - -npy_cdouble npy_ccos(npy_cdouble z); -npy_cdouble npy_csin(npy_cdouble z); - -/* - * Single precision complex functions - */ -float npy_cabsf(npy_cfloat z); -float npy_cargf(npy_cfloat z); - -npy_cfloat npy_cexpf(npy_cfloat z); -npy_cfloat npy_clogf(npy_cfloat z); -npy_cfloat npy_cpowf(npy_cfloat x, npy_cfloat y); - -npy_cfloat npy_csqrtf(npy_cfloat z); - -npy_cfloat npy_ccosf(npy_cfloat z); -npy_cfloat npy_csinf(npy_cfloat z); - -/* - * Extended precision complex functions - */ -npy_longdouble npy_cabsl(npy_clongdouble z); -npy_longdouble npy_cargl(npy_clongdouble z); - -npy_clongdouble npy_cexpl(npy_clongdouble z); -npy_clongdouble npy_clogl(npy_clongdouble z); -npy_clongdouble npy_cpowl(npy_clongdouble x, npy_clongdouble y); - -npy_clongdouble npy_csqrtl(npy_clongdouble z); - -npy_clongdouble npy_ccosl(npy_clongdouble z); -npy_clongdouble npy_csinl(npy_clongdouble z); - -/* - * Functions that set the floating point error - * status word. - */ - -void npy_set_floatstatus_divbyzero(void); -void npy_set_floatstatus_overflow(void); -void npy_set_floatstatus_underflow(void); -void npy_set_floatstatus_invalid(void); - -#ifdef __cplusplus -} -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h deleted file mode 100644 index 6183dc278..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_no_deprecated_api.h +++ /dev/null @@ -1,19 +0,0 @@ -/* - * This include file is provided for inclusion in Cython *.pyd files where - * one would like to define the NPY_NO_DEPRECATED_API macro. It can be - * included by - * - * cdef extern from "npy_no_deprecated_api.h": pass - * - */ -#ifndef NPY_NO_DEPRECATED_API - -/* put this check here since there may be multiple includes in C extensions. */ -#if defined(NDARRAYTYPES_H) || defined(_NPY_DEPRECATED_API_H) || \ - defined(OLD_DEFINES_H) -#error "npy_no_deprecated_api.h" must be first among numpy includes. -#else -#define NPY_NO_DEPRECATED_API NPY_API_VERSION -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h b/gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h deleted file mode 100644 index 9228c3916..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/npy_os.h +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef _NPY_OS_H_ -#define _NPY_OS_H_ - -#if defined(linux) || defined(__linux) || defined(__linux__) - #define NPY_OS_LINUX -#elif defined(__FreeBSD__) || defined(__NetBSD__) || \ - defined(__OpenBSD__) || defined(__DragonFly__) - #define NPY_OS_BSD - #ifdef __FreeBSD__ - #define NPY_OS_FREEBSD - #elif defined(__NetBSD__) - #define NPY_OS_NETBSD - #elif defined(__OpenBSD__) - #define NPY_OS_OPENBSD - #elif defined(__DragonFly__) - #define NPY_OS_DRAGONFLY - #endif -#elif defined(sun) || defined(__sun) - #define NPY_OS_SOLARIS -#elif defined(__CYGWIN__) - #define NPY_OS_CYGWIN -#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) - #define NPY_OS_WIN32 -#elif defined(__APPLE__) - #define NPY_OS_DARWIN -#else - #define NPY_OS_UNKNOWN -#endif - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h b/gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h deleted file mode 100644 index 5ca171f21..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/numpyconfig.h +++ /dev/null @@ -1,34 +0,0 @@ -#ifndef _NPY_NUMPYCONFIG_H_ -#define _NPY_NUMPYCONFIG_H_ - -#include "_numpyconfig.h" - -/* - * On Mac OS X, because there is only one configuration stage for all the archs - * in universal builds, any macro which depends on the arch needs to be - * harcoded - */ -#ifdef __APPLE__ - #undef NPY_SIZEOF_LONG - #undef NPY_SIZEOF_PY_INTPTR_T - - #ifdef __LP64__ - #define NPY_SIZEOF_LONG 8 - #define NPY_SIZEOF_PY_INTPTR_T 8 - #else - #define NPY_SIZEOF_LONG 4 - #define NPY_SIZEOF_PY_INTPTR_T 4 - #endif -#endif - -/** - * To help with the NPY_NO_DEPRECATED_API macro, we include API version - * numbers for specific versions of NumPy. To exclude all API that was - * deprecated as of 1.7, add the following before #including any NumPy - * headers: - * #define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION - */ -#define NPY_1_7_API_VERSION 0x00000007 -#define NPY_1_8_API_VERSION 0x00000008 - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h b/gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h deleted file mode 100644 index abf81595a..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/old_defines.h +++ /dev/null @@ -1,187 +0,0 @@ -/* This header is deprecated as of NumPy 1.7 */ -#ifndef OLD_DEFINES_H -#define OLD_DEFINES_H - -#if defined(NPY_NO_DEPRECATED_API) && NPY_NO_DEPRECATED_API >= NPY_1_7_API_VERSION -#error The header "old_defines.h" is deprecated as of NumPy 1.7. -#endif - -#define NDARRAY_VERSION NPY_VERSION - -#define PyArray_MIN_BUFSIZE NPY_MIN_BUFSIZE -#define PyArray_MAX_BUFSIZE NPY_MAX_BUFSIZE -#define PyArray_BUFSIZE NPY_BUFSIZE - -#define PyArray_PRIORITY NPY_PRIORITY -#define PyArray_SUBTYPE_PRIORITY NPY_PRIORITY -#define PyArray_NUM_FLOATTYPE NPY_NUM_FLOATTYPE - -#define NPY_MAX PyArray_MAX -#define NPY_MIN PyArray_MIN - -#define PyArray_TYPES NPY_TYPES -#define PyArray_BOOL NPY_BOOL -#define PyArray_BYTE NPY_BYTE -#define PyArray_UBYTE NPY_UBYTE -#define PyArray_SHORT NPY_SHORT -#define PyArray_USHORT NPY_USHORT -#define PyArray_INT NPY_INT -#define PyArray_UINT NPY_UINT -#define PyArray_LONG NPY_LONG -#define PyArray_ULONG NPY_ULONG -#define PyArray_LONGLONG NPY_LONGLONG -#define PyArray_ULONGLONG NPY_ULONGLONG -#define PyArray_HALF NPY_HALF -#define PyArray_FLOAT NPY_FLOAT -#define PyArray_DOUBLE NPY_DOUBLE -#define PyArray_LONGDOUBLE NPY_LONGDOUBLE -#define PyArray_CFLOAT NPY_CFLOAT -#define PyArray_CDOUBLE NPY_CDOUBLE -#define PyArray_CLONGDOUBLE NPY_CLONGDOUBLE -#define PyArray_OBJECT NPY_OBJECT -#define PyArray_STRING NPY_STRING -#define PyArray_UNICODE NPY_UNICODE -#define PyArray_VOID NPY_VOID -#define PyArray_DATETIME NPY_DATETIME -#define PyArray_TIMEDELTA NPY_TIMEDELTA -#define PyArray_NTYPES NPY_NTYPES -#define PyArray_NOTYPE NPY_NOTYPE -#define PyArray_CHAR NPY_CHAR -#define PyArray_USERDEF NPY_USERDEF -#define PyArray_NUMUSERTYPES NPY_NUMUSERTYPES - -#define PyArray_INTP NPY_INTP -#define PyArray_UINTP NPY_UINTP - -#define PyArray_INT8 NPY_INT8 -#define PyArray_UINT8 NPY_UINT8 -#define PyArray_INT16 NPY_INT16 -#define PyArray_UINT16 NPY_UINT16 -#define PyArray_INT32 NPY_INT32 -#define PyArray_UINT32 NPY_UINT32 - -#ifdef NPY_INT64 -#define PyArray_INT64 NPY_INT64 -#define PyArray_UINT64 NPY_UINT64 -#endif - -#ifdef NPY_INT128 -#define PyArray_INT128 NPY_INT128 -#define PyArray_UINT128 NPY_UINT128 -#endif - -#ifdef NPY_FLOAT16 -#define PyArray_FLOAT16 NPY_FLOAT16 -#define PyArray_COMPLEX32 NPY_COMPLEX32 -#endif - -#ifdef NPY_FLOAT80 -#define PyArray_FLOAT80 NPY_FLOAT80 -#define PyArray_COMPLEX160 NPY_COMPLEX160 -#endif - -#ifdef NPY_FLOAT96 -#define PyArray_FLOAT96 NPY_FLOAT96 -#define PyArray_COMPLEX192 NPY_COMPLEX192 -#endif - -#ifdef NPY_FLOAT128 -#define PyArray_FLOAT128 NPY_FLOAT128 -#define PyArray_COMPLEX256 NPY_COMPLEX256 -#endif - -#define PyArray_FLOAT32 NPY_FLOAT32 -#define PyArray_COMPLEX64 NPY_COMPLEX64 -#define PyArray_FLOAT64 NPY_FLOAT64 -#define PyArray_COMPLEX128 NPY_COMPLEX128 - - -#define PyArray_TYPECHAR NPY_TYPECHAR -#define PyArray_BOOLLTR NPY_BOOLLTR -#define PyArray_BYTELTR NPY_BYTELTR -#define PyArray_UBYTELTR NPY_UBYTELTR -#define PyArray_SHORTLTR NPY_SHORTLTR -#define PyArray_USHORTLTR NPY_USHORTLTR -#define PyArray_INTLTR NPY_INTLTR -#define PyArray_UINTLTR NPY_UINTLTR -#define PyArray_LONGLTR NPY_LONGLTR -#define PyArray_ULONGLTR NPY_ULONGLTR -#define PyArray_LONGLONGLTR NPY_LONGLONGLTR -#define PyArray_ULONGLONGLTR NPY_ULONGLONGLTR -#define PyArray_HALFLTR NPY_HALFLTR -#define PyArray_FLOATLTR NPY_FLOATLTR -#define PyArray_DOUBLELTR NPY_DOUBLELTR -#define PyArray_LONGDOUBLELTR NPY_LONGDOUBLELTR -#define PyArray_CFLOATLTR NPY_CFLOATLTR -#define PyArray_CDOUBLELTR NPY_CDOUBLELTR -#define PyArray_CLONGDOUBLELTR NPY_CLONGDOUBLELTR -#define PyArray_OBJECTLTR NPY_OBJECTLTR -#define PyArray_STRINGLTR NPY_STRINGLTR -#define PyArray_STRINGLTR2 NPY_STRINGLTR2 -#define PyArray_UNICODELTR NPY_UNICODELTR -#define PyArray_VOIDLTR NPY_VOIDLTR -#define PyArray_DATETIMELTR NPY_DATETIMELTR -#define PyArray_TIMEDELTALTR NPY_TIMEDELTALTR -#define PyArray_CHARLTR NPY_CHARLTR -#define PyArray_INTPLTR NPY_INTPLTR -#define PyArray_UINTPLTR NPY_UINTPLTR -#define PyArray_GENBOOLLTR NPY_GENBOOLLTR -#define PyArray_SIGNEDLTR NPY_SIGNEDLTR -#define PyArray_UNSIGNEDLTR NPY_UNSIGNEDLTR -#define PyArray_FLOATINGLTR NPY_FLOATINGLTR -#define PyArray_COMPLEXLTR NPY_COMPLEXLTR - -#define PyArray_QUICKSORT NPY_QUICKSORT -#define PyArray_HEAPSORT NPY_HEAPSORT -#define PyArray_MERGESORT NPY_MERGESORT -#define PyArray_SORTKIND NPY_SORTKIND -#define PyArray_NSORTS NPY_NSORTS - -#define PyArray_NOSCALAR NPY_NOSCALAR -#define PyArray_BOOL_SCALAR NPY_BOOL_SCALAR -#define PyArray_INTPOS_SCALAR NPY_INTPOS_SCALAR -#define PyArray_INTNEG_SCALAR NPY_INTNEG_SCALAR -#define PyArray_FLOAT_SCALAR NPY_FLOAT_SCALAR -#define PyArray_COMPLEX_SCALAR NPY_COMPLEX_SCALAR -#define PyArray_OBJECT_SCALAR NPY_OBJECT_SCALAR -#define PyArray_SCALARKIND NPY_SCALARKIND -#define PyArray_NSCALARKINDS NPY_NSCALARKINDS - -#define PyArray_ANYORDER NPY_ANYORDER -#define PyArray_CORDER NPY_CORDER -#define PyArray_FORTRANORDER NPY_FORTRANORDER -#define PyArray_ORDER NPY_ORDER - -#define PyDescr_ISBOOL PyDataType_ISBOOL -#define PyDescr_ISUNSIGNED PyDataType_ISUNSIGNED -#define PyDescr_ISSIGNED PyDataType_ISSIGNED -#define PyDescr_ISINTEGER PyDataType_ISINTEGER -#define PyDescr_ISFLOAT PyDataType_ISFLOAT -#define PyDescr_ISNUMBER PyDataType_ISNUMBER -#define PyDescr_ISSTRING PyDataType_ISSTRING -#define PyDescr_ISCOMPLEX PyDataType_ISCOMPLEX -#define PyDescr_ISPYTHON PyDataType_ISPYTHON -#define PyDescr_ISFLEXIBLE PyDataType_ISFLEXIBLE -#define PyDescr_ISUSERDEF PyDataType_ISUSERDEF -#define PyDescr_ISEXTENDED PyDataType_ISEXTENDED -#define PyDescr_ISOBJECT PyDataType_ISOBJECT -#define PyDescr_HASFIELDS PyDataType_HASFIELDS - -#define PyArray_LITTLE NPY_LITTLE -#define PyArray_BIG NPY_BIG -#define PyArray_NATIVE NPY_NATIVE -#define PyArray_SWAP NPY_SWAP -#define PyArray_IGNORE NPY_IGNORE - -#define PyArray_NATBYTE NPY_NATBYTE -#define PyArray_OPPBYTE NPY_OPPBYTE - -#define PyArray_MAX_ELSIZE NPY_MAX_ELSIZE - -#define PyArray_USE_PYMEM NPY_USE_PYMEM - -#define PyArray_RemoveLargest PyArray_RemoveSmallest - -#define PyArray_UCS4 npy_ucs4 - -#endif diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h b/gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h deleted file mode 100644 index 748f06da3..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/oldnumeric.h +++ /dev/null @@ -1,23 +0,0 @@ -#include "arrayobject.h" - -#ifndef REFCOUNT -# define REFCOUNT NPY_REFCOUNT -# define MAX_ELSIZE 16 -#endif - -#define PyArray_UNSIGNED_TYPES -#define PyArray_SBYTE NPY_BYTE -#define PyArray_CopyArray PyArray_CopyInto -#define _PyArray_multiply_list PyArray_MultiplyIntList -#define PyArray_ISSPACESAVER(m) NPY_FALSE -#define PyScalarArray_Check PyArray_CheckScalar - -#define CONTIGUOUS NPY_CONTIGUOUS -#define OWN_DIMENSIONS 0 -#define OWN_STRIDES 0 -#define OWN_DATA NPY_OWNDATA -#define SAVESPACE 0 -#define SAVESPACEBIT 0 - -#undef import_array -#define import_array() { if (_import_array() < 0) {PyErr_Print(); PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import"); } } diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt b/gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt deleted file mode 100644 index a90865d2f..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/ufunc_api.txt +++ /dev/null @@ -1,321 +0,0 @@ - -================= -Numpy Ufunc C-API -================= -:: - - PyObject * - PyUFunc_FromFuncAndData(PyUFuncGenericFunction *func, void - **data, char *types, int ntypes, int nin, int - nout, int identity, char *name, char *doc, int - check_return) - - -:: - - int - PyUFunc_RegisterLoopForType(PyUFuncObject *ufunc, int - usertype, PyUFuncGenericFunction - function, int *arg_types, void *data) - - -:: - - int - PyUFunc_GenericFunction(PyUFuncObject *ufunc, PyObject *args, PyObject - *kwds, PyArrayObject **op) - - -This generic function is called with the ufunc object, the arguments to it, -and an array of (pointers to) PyArrayObjects which are NULL. - -'op' is an array of at least NPY_MAXARGS PyArrayObject *. - -:: - - void - PyUFunc_f_f_As_d_d(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_d_d(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_f_f(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_g_g(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_F_F_As_D_D(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_F_F(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_D_D(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_G_G(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_O_O(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_ff_f_As_dd_d(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_ff_f(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_dd_d(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_gg_g(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_FF_F_As_DD_D(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_DD_D(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_FF_F(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_GG_G(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_OO_O(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_O_O_method(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_OO_O_method(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_On_Om(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - int - PyUFunc_GetPyValues(char *name, int *bufsize, int *errmask, PyObject - **errobj) - - -On return, if errobj is populated with a non-NULL value, the caller -owns a new reference to errobj. - -:: - - int - PyUFunc_checkfperr(int errmask, PyObject *errobj, int *first) - - -:: - - void - PyUFunc_clearfperr() - - -:: - - int - PyUFunc_getfperr(void ) - - -:: - - int - PyUFunc_handlefperr(int errmask, PyObject *errobj, int retstatus, int - *first) - - -:: - - int - PyUFunc_ReplaceLoopBySignature(PyUFuncObject - *func, PyUFuncGenericFunction - newfunc, int - *signature, PyUFuncGenericFunction - *oldfunc) - - -:: - - PyObject * - PyUFunc_FromFuncAndDataAndSignature(PyUFuncGenericFunction *func, void - **data, char *types, int - ntypes, int nin, int nout, int - identity, char *name, char - *doc, int check_return, const char - *signature) - - -:: - - int - PyUFunc_SetUsesArraysAsData(void **data, size_t i) - - -:: - - void - PyUFunc_e_e(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_e_e_As_f_f(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_e_e_As_d_d(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_ee_e(char **args, npy_intp *dimensions, npy_intp *steps, void - *func) - - -:: - - void - PyUFunc_ee_e_As_ff_f(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - void - PyUFunc_ee_e_As_dd_d(char **args, npy_intp *dimensions, npy_intp - *steps, void *func) - - -:: - - int - PyUFunc_DefaultTypeResolver(PyUFuncObject *ufunc, NPY_CASTING - casting, PyArrayObject - **operands, PyObject - *type_tup, PyArray_Descr **out_dtypes) - - -This function applies the default type resolution rules -for the provided ufunc. - -Returns 0 on success, -1 on error. - -:: - - int - PyUFunc_ValidateCasting(PyUFuncObject *ufunc, NPY_CASTING - casting, PyArrayObject - **operands, PyArray_Descr **dtypes) - - -Validates that the input operands can be cast to -the input types, and the output types can be cast to -the output operands where provided. - -Returns 0 on success, -1 (with exception raised) on validation failure. - -:: - - int - PyUFunc_RegisterLoopForDescr(PyUFuncObject *ufunc, PyArray_Descr - *user_dtype, PyUFuncGenericFunction - function, PyArray_Descr - **arg_dtypes, void *data) - - diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h b/gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h deleted file mode 100644 index 423fbc279..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/ufuncobject.h +++ /dev/null @@ -1,479 +0,0 @@ -#ifndef Py_UFUNCOBJECT_H -#define Py_UFUNCOBJECT_H - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * The legacy generic inner loop for a standard element-wise or - * generalized ufunc. - */ -typedef void (*PyUFuncGenericFunction) - (char **args, - npy_intp *dimensions, - npy_intp *strides, - void *innerloopdata); - -/* - * The most generic one-dimensional inner loop for - * a standard element-wise ufunc. This typedef is also - * more consistent with the other NumPy function pointer typedefs - * than PyUFuncGenericFunction. - */ -typedef void (PyUFunc_StridedInnerLoopFunc)( - char **dataptrs, npy_intp *strides, - npy_intp count, - NpyAuxData *innerloopdata); - -/* - * The most generic one-dimensional inner loop for - * a masked standard element-wise ufunc. "Masked" here means that it skips - * doing calculations on any items for which the maskptr array has a true - * value. - */ -typedef void (PyUFunc_MaskedStridedInnerLoopFunc)( - char **dataptrs, npy_intp *strides, - char *maskptr, npy_intp mask_stride, - npy_intp count, - NpyAuxData *innerloopdata); - -/* Forward declaration for the type resolver and loop selector typedefs */ -struct _tagPyUFuncObject; - -/* - * Given the operands for calling a ufunc, should determine the - * calculation input and output data types and return an inner loop function. - * This function should validate that the casting rule is being followed, - * and fail if it is not. - * - * For backwards compatibility, the regular type resolution function does not - * support auxiliary data with object semantics. The type resolution call - * which returns a masked generic function returns a standard NpyAuxData - * object, for which the NPY_AUXDATA_FREE and NPY_AUXDATA_CLONE macros - * work. - * - * ufunc: The ufunc object. - * casting: The 'casting' parameter provided to the ufunc. - * operands: An array of length (ufunc->nin + ufunc->nout), - * with the output parameters possibly NULL. - * type_tup: Either NULL, or the type_tup passed to the ufunc. - * out_dtypes: An array which should be populated with new - * references to (ufunc->nin + ufunc->nout) new - * dtypes, one for each input and output. These - * dtypes should all be in native-endian format. - * - * Should return 0 on success, -1 on failure (with exception set), - * or -2 if Py_NotImplemented should be returned. - */ -typedef int (PyUFunc_TypeResolutionFunc)( - struct _tagPyUFuncObject *ufunc, - NPY_CASTING casting, - PyArrayObject **operands, - PyObject *type_tup, - PyArray_Descr **out_dtypes); - -/* - * Given an array of DTypes as returned by the PyUFunc_TypeResolutionFunc, - * and an array of fixed strides (the array will contain NPY_MAX_INTP for - * strides which are not necessarily fixed), returns an inner loop - * with associated auxiliary data. - * - * For backwards compatibility, there is a variant of the inner loop - * selection which returns an inner loop irrespective of the strides, - * and with a void* static auxiliary data instead of an NpyAuxData * - * dynamically allocatable auxiliary data. - * - * ufunc: The ufunc object. - * dtypes: An array which has been populated with dtypes, - * in most cases by the type resolution funciton - * for the same ufunc. - * fixed_strides: For each input/output, either the stride that - * will be used every time the function is called - * or NPY_MAX_INTP if the stride might change or - * is not known ahead of time. The loop selection - * function may use this stride to pick inner loops - * which are optimized for contiguous or 0-stride - * cases. - * out_innerloop: Should be populated with the correct ufunc inner - * loop for the given type. - * out_innerloopdata: Should be populated with the void* data to - * be passed into the out_innerloop function. - * out_needs_api: If the inner loop needs to use the Python API, - * should set the to 1, otherwise should leave - * this untouched. - */ -typedef int (PyUFunc_LegacyInnerLoopSelectionFunc)( - struct _tagPyUFuncObject *ufunc, - PyArray_Descr **dtypes, - PyUFuncGenericFunction *out_innerloop, - void **out_innerloopdata, - int *out_needs_api); -typedef int (PyUFunc_InnerLoopSelectionFunc)( - struct _tagPyUFuncObject *ufunc, - PyArray_Descr **dtypes, - npy_intp *fixed_strides, - PyUFunc_StridedInnerLoopFunc **out_innerloop, - NpyAuxData **out_innerloopdata, - int *out_needs_api); -typedef int (PyUFunc_MaskedInnerLoopSelectionFunc)( - struct _tagPyUFuncObject *ufunc, - PyArray_Descr **dtypes, - PyArray_Descr *mask_dtype, - npy_intp *fixed_strides, - npy_intp fixed_mask_stride, - PyUFunc_MaskedStridedInnerLoopFunc **out_innerloop, - NpyAuxData **out_innerloopdata, - int *out_needs_api); - -typedef struct _tagPyUFuncObject { - PyObject_HEAD - /* - * nin: Number of inputs - * nout: Number of outputs - * nargs: Always nin + nout (Why is it stored?) - */ - int nin, nout, nargs; - - /* Identity for reduction, either PyUFunc_One or PyUFunc_Zero */ - int identity; - - /* Array of one-dimensional core loops */ - PyUFuncGenericFunction *functions; - /* Array of funcdata that gets passed into the functions */ - void **data; - /* The number of elements in 'functions' and 'data' */ - int ntypes; - - /* Does not appear to be used */ - int check_return; - - /* The name of the ufunc */ - char *name; - - /* Array of type numbers, of size ('nargs' * 'ntypes') */ - char *types; - - /* Documentation string */ - char *doc; - - void *ptr; - PyObject *obj; - PyObject *userloops; - - /* generalized ufunc parameters */ - - /* 0 for scalar ufunc; 1 for generalized ufunc */ - int core_enabled; - /* number of distinct dimension names in signature */ - int core_num_dim_ix; - - /* - * dimension indices of input/output argument k are stored in - * core_dim_ixs[core_offsets[k]..core_offsets[k]+core_num_dims[k]-1] - */ - - /* numbers of core dimensions of each argument */ - int *core_num_dims; - /* - * dimension indices in a flatted form; indices - * are in the range of [0,core_num_dim_ix) - */ - int *core_dim_ixs; - /* - * positions of 1st core dimensions of each - * argument in core_dim_ixs - */ - int *core_offsets; - /* signature string for printing purpose */ - char *core_signature; - - /* - * A function which resolves the types and fills an array - * with the dtypes for the inputs and outputs. - */ - PyUFunc_TypeResolutionFunc *type_resolver; - /* - * A function which returns an inner loop written for - * NumPy 1.6 and earlier ufuncs. This is for backwards - * compatibility, and may be NULL if inner_loop_selector - * is specified. - */ - PyUFunc_LegacyInnerLoopSelectionFunc *legacy_inner_loop_selector; - /* - * A function which returns an inner loop for the new mechanism - * in NumPy 1.7 and later. If provided, this is used, otherwise - * if NULL the legacy_inner_loop_selector is used instead. - */ - PyUFunc_InnerLoopSelectionFunc *inner_loop_selector; - /* - * A function which returns a masked inner loop for the ufunc. - */ - PyUFunc_MaskedInnerLoopSelectionFunc *masked_inner_loop_selector; - - /* - * List of flags for each operand when ufunc is called by nditer object. - * These flags will be used in addition to the default flags for each - * operand set by nditer object. - */ - npy_uint32 *op_flags; - - /* - * List of global flags used when ufunc is called by nditer object. - * These flags will be used in addition to the default global flags - * set by nditer object. - */ - npy_uint32 iter_flags; -} PyUFuncObject; - -#include "arrayobject.h" - -#define UFUNC_ERR_IGNORE 0 -#define UFUNC_ERR_WARN 1 -#define UFUNC_ERR_RAISE 2 -#define UFUNC_ERR_CALL 3 -#define UFUNC_ERR_PRINT 4 -#define UFUNC_ERR_LOG 5 - - /* Python side integer mask */ - -#define UFUNC_MASK_DIVIDEBYZERO 0x07 -#define UFUNC_MASK_OVERFLOW 0x3f -#define UFUNC_MASK_UNDERFLOW 0x1ff -#define UFUNC_MASK_INVALID 0xfff - -#define UFUNC_SHIFT_DIVIDEBYZERO 0 -#define UFUNC_SHIFT_OVERFLOW 3 -#define UFUNC_SHIFT_UNDERFLOW 6 -#define UFUNC_SHIFT_INVALID 9 - - -/* platform-dependent code translates floating point - status to an integer sum of these values -*/ -#define UFUNC_FPE_DIVIDEBYZERO 1 -#define UFUNC_FPE_OVERFLOW 2 -#define UFUNC_FPE_UNDERFLOW 4 -#define UFUNC_FPE_INVALID 8 - -/* Error mode that avoids look-up (no checking) */ -#define UFUNC_ERR_DEFAULT 0 - -#define UFUNC_OBJ_ISOBJECT 1 -#define UFUNC_OBJ_NEEDS_API 2 - - /* Default user error mode */ -#define UFUNC_ERR_DEFAULT2 \ - (UFUNC_ERR_WARN << UFUNC_SHIFT_DIVIDEBYZERO) + \ - (UFUNC_ERR_WARN << UFUNC_SHIFT_OVERFLOW) + \ - (UFUNC_ERR_WARN << UFUNC_SHIFT_INVALID) - -#if NPY_ALLOW_THREADS -#define NPY_LOOP_BEGIN_THREADS do {if (!(loop->obj & UFUNC_OBJ_NEEDS_API)) _save = PyEval_SaveThread();} while (0); -#define NPY_LOOP_END_THREADS do {if (!(loop->obj & UFUNC_OBJ_NEEDS_API)) PyEval_RestoreThread(_save);} while (0); -#else -#define NPY_LOOP_BEGIN_THREADS -#define NPY_LOOP_END_THREADS -#endif - -/* - * UFunc has unit of 1, and the order of operations can be reordered - * This case allows reduction with multiple axes at once. - */ -#define PyUFunc_One 1 -/* - * UFunc has unit of 0, and the order of operations can be reordered - * This case allows reduction with multiple axes at once. - */ -#define PyUFunc_Zero 0 -/* - * UFunc has no unit, and the order of operations cannot be reordered. - * This case does not allow reduction with multiple axes at once. - */ -#define PyUFunc_None -1 -/* - * UFunc has no unit, and the order of operations can be reordered - * This case allows reduction with multiple axes at once. - */ -#define PyUFunc_ReorderableNone -2 - -#define UFUNC_REDUCE 0 -#define UFUNC_ACCUMULATE 1 -#define UFUNC_REDUCEAT 2 -#define UFUNC_OUTER 3 - - -typedef struct { - int nin; - int nout; - PyObject *callable; -} PyUFunc_PyFuncData; - -/* A linked-list of function information for - user-defined 1-d loops. - */ -typedef struct _loop1d_info { - PyUFuncGenericFunction func; - void *data; - int *arg_types; - struct _loop1d_info *next; - int nargs; - PyArray_Descr **arg_dtypes; -} PyUFunc_Loop1d; - - -#include "__ufunc_api.h" - -#define UFUNC_PYVALS_NAME "UFUNC_PYVALS" - -#define UFUNC_CHECK_ERROR(arg) \ - do {if ((((arg)->obj & UFUNC_OBJ_NEEDS_API) && PyErr_Occurred()) || \ - ((arg)->errormask && \ - PyUFunc_checkfperr((arg)->errormask, \ - (arg)->errobj, \ - &(arg)->first))) \ - goto fail;} while (0) - -/* This code checks the IEEE status flags in a platform-dependent way */ -/* Adapted from Numarray */ - -#if (defined(__unix__) || defined(unix)) && !defined(USG) -#include -#endif - -/* OSF/Alpha (Tru64) ---------------------------------------------*/ -#if defined(__osf__) && defined(__alpha) - -#include - -#define UFUNC_CHECK_STATUS(ret) { \ - unsigned long fpstatus; \ - \ - fpstatus = ieee_get_fp_control(); \ - /* clear status bits as well as disable exception mode if on */ \ - ieee_set_fp_control( 0 ); \ - ret = ((IEEE_STATUS_DZE & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ - | ((IEEE_STATUS_OVF & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ - | ((IEEE_STATUS_UNF & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ - | ((IEEE_STATUS_INV & fpstatus) ? UFUNC_FPE_INVALID : 0); \ - } - -/* MS Windows -----------------------------------------------------*/ -#elif defined(_MSC_VER) - -#include - -/* Clear the floating point exception default of Borland C++ */ -#if defined(__BORLANDC__) -#define UFUNC_NOFPE _control87(MCW_EM, MCW_EM); -#endif - -#if defined(_WIN64) -#define UFUNC_CHECK_STATUS(ret) { \ - int fpstatus = (int) _clearfp(); \ - \ - ret = ((SW_ZERODIVIDE & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ - | ((SW_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ - | ((SW_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ - | ((SW_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ - } -#else -/* windows enables sse on 32 bit, so check both flags */ -#define UFUNC_CHECK_STATUS(ret) { \ - int fpstatus, fpstatus2; \ - _statusfp2(&fpstatus, &fpstatus2); \ - _clearfp(); \ - fpstatus |= fpstatus2; \ - \ - ret = ((SW_ZERODIVIDE & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ - | ((SW_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ - | ((SW_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ - | ((SW_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ - } -#endif - -/* Solaris --------------------------------------------------------*/ -/* --------ignoring SunOS ieee_flags approach, someone else can -** deal with that! */ -#elif defined(sun) || defined(__BSD__) || defined(__OpenBSD__) || \ - (defined(__FreeBSD__) && (__FreeBSD_version < 502114)) || \ - defined(__NetBSD__) -#include - -#define UFUNC_CHECK_STATUS(ret) { \ - int fpstatus; \ - \ - fpstatus = (int) fpgetsticky(); \ - ret = ((FP_X_DZ & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ - | ((FP_X_OFL & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ - | ((FP_X_UFL & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ - | ((FP_X_INV & fpstatus) ? UFUNC_FPE_INVALID : 0); \ - (void) fpsetsticky(0); \ - } - -#elif defined(__GLIBC__) || defined(__APPLE__) || \ - defined(__CYGWIN__) || defined(__MINGW32__) || \ - (defined(__FreeBSD__) && (__FreeBSD_version >= 502114)) - -#if defined(__GLIBC__) || defined(__APPLE__) || \ - defined(__MINGW32__) || defined(__FreeBSD__) -#include -#elif defined(__CYGWIN__) -#include "numpy/fenv/fenv.h" -#endif - -#define UFUNC_CHECK_STATUS(ret) { \ - int fpstatus = (int) fetestexcept(FE_DIVBYZERO | FE_OVERFLOW | \ - FE_UNDERFLOW | FE_INVALID); \ - ret = ((FE_DIVBYZERO & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ - | ((FE_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ - | ((FE_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ - | ((FE_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ - (void) feclearexcept(FE_DIVBYZERO | FE_OVERFLOW | \ - FE_UNDERFLOW | FE_INVALID); \ -} - -#elif defined(_AIX) - -#include -#include - -#define UFUNC_CHECK_STATUS(ret) { \ - fpflag_t fpstatus; \ - \ - fpstatus = fp_read_flag(); \ - ret = ((FP_DIV_BY_ZERO & fpstatus) ? UFUNC_FPE_DIVIDEBYZERO : 0) \ - | ((FP_OVERFLOW & fpstatus) ? UFUNC_FPE_OVERFLOW : 0) \ - | ((FP_UNDERFLOW & fpstatus) ? UFUNC_FPE_UNDERFLOW : 0) \ - | ((FP_INVALID & fpstatus) ? UFUNC_FPE_INVALID : 0); \ - fp_swap_flag(0); \ -} - -#else - -#define NO_FLOATING_POINT_SUPPORT -#define UFUNC_CHECK_STATUS(ret) { \ - ret = 0; \ - } - -#endif - -/* - * THESE MACROS ARE DEPRECATED. - * Use npy_set_floatstatus_* in the npymath library. - */ -#define generate_divbyzero_error() npy_set_floatstatus_divbyzero() -#define generate_overflow_error() npy_set_floatstatus_overflow() - - /* Make sure it gets defined if it isn't already */ -#ifndef UFUNC_NOFPE -#define UFUNC_NOFPE -#endif - - -#ifdef __cplusplus -} -#endif -#endif /* !Py_UFUNCOBJECT_H */ diff --git a/gtsam/3rdparty/numpy_c_api/include/numpy/utils.h b/gtsam/3rdparty/numpy_c_api/include/numpy/utils.h deleted file mode 100644 index cc968a354..000000000 --- a/gtsam/3rdparty/numpy_c_api/include/numpy/utils.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef __NUMPY_UTILS_HEADER__ -#define __NUMPY_UTILS_HEADER__ - -#ifndef __COMP_NPY_UNUSED - #if defined(__GNUC__) - #define __COMP_NPY_UNUSED __attribute__ ((__unused__)) - # elif defined(__ICC) - #define __COMP_NPY_UNUSED __attribute__ ((__unused__)) - #else - #define __COMP_NPY_UNUSED - #endif -#endif - -/* Use this to tag a variable as not used. It will remove unused variable - * warning on support platforms (see __COM_NPY_UNUSED) and mangle the variable - * to avoid accidental use */ -#define NPY_UNUSED(x) (__NPY_UNUSED_TAGGED ## x) __COMP_NPY_UNUSED - -#endif From 31888d653c1c586d2e582c8131a6a881cbf6d794 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Tue, 19 Jan 2016 14:45:34 -0500 Subject: [PATCH 072/105] Remove CMake option to use 3rdparty numpy C-API --- python/CMakeLists.txt | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 85d7c6765..9ea873259 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,4 +1,3 @@ -option(GTSAM_USE_SYSTEM_NUMPY_C_API "Find and use system-installed NumPy C-API. If 'off', use the one bundled with GTSAM" OFF) # Guard to avoid breaking this code in ccmake if by accident GTSAM_PYTHON_VERSION is set to an empty string if(GTSAM_PYTHON_VERSION STREQUAL "") @@ -30,12 +29,10 @@ else() set(BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE "") endif() -# Find NumPy C-API -if(GTSAM_USE_SYSTEM_NUMPY_C_API) - find_package(NumPy) - include_directories(${NUMPY_INCLUDE_DIRS}) -else() - include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_c_api/include/) +# Find NumPy C-API -- this is part of the numpy package +find_package(NumPy) +if(NumPy_FOUND) + include_directories(${NUMPY_INCLUDE_DIRS}) endif() # Find Python @@ -54,7 +51,7 @@ endif() find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_SUFFIX}) # Build python module library and setup the module inside build -if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND) +if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND AND NumPy_FOUND) include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) @@ -83,6 +80,10 @@ else() endif() # Print warnings (useful for ccmake) +if(NOT NumPy_FOUND) + message(WARNING "Numpy not found -- Python module cannot be built.") +endif() + if(NOT PYTHONLIBS_FOUND) if(GTSAM_PYTHON_VERSION STREQUAL "Default") message(WARNING "Default PythonLibs was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") From c77997fbb1941c4e2c1b6e41d1f15135f5767581 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 19 Jan 2016 23:18:39 -0800 Subject: [PATCH 073/105] Fixed typo --- python/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 9ea873259..4d3d0237d 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -31,7 +31,7 @@ endif() # Find NumPy C-API -- this is part of the numpy package find_package(NumPy) -if(NumPy_FOUND) +if(NUMPY_FOUND) include_directories(${NUMPY_INCLUDE_DIRS}) endif() @@ -51,7 +51,7 @@ endif() find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_SUFFIX}) # Build python module library and setup the module inside build -if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND AND NumPy_FOUND) +if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND AND NUMPY_FOUND) include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) @@ -80,7 +80,7 @@ else() endif() # Print warnings (useful for ccmake) -if(NOT NumPy_FOUND) +if(NOT NUMPY_FOUND) message(WARNING "Numpy not found -- Python module cannot be built.") endif() From eb5d026a4a1fdba69944c1b5e2416387c93b07d2 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 20 Jan 2016 09:28:30 -0800 Subject: [PATCH 074/105] Synced with commit https://github.com/ethz-asl/Schweizer-Messer/commit/b30d90bf704fdde38f95796bf1f9cea7ba60bfb5#diff-43bc6d5065b2331de9923fd47b8c5d56 --- .../numpy_eigen/NumpyEigenConverter.hpp | 56 ++++++++++++------- .../include/numpy_eigen/copy_routines.hpp | 41 +++++++------- .../include/numpy_eigen/type_traits.hpp | 35 ++++++++---- 3 files changed, 82 insertions(+), 50 deletions(-) diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp index 67b04537c..4cf16a974 100755 --- a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp @@ -12,8 +12,17 @@ #ifndef NUMPY_EIGEN_CONVERTER_HPP #define NUMPY_EIGEN_CONVERTER_HPP -#include "boost_python_headers.hpp" -#include +#include +//#include + +#include "numpy/numpyconfig.h" +#ifdef NPY_1_7_API_VERSION +#define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION +#define NPE_PY_ARRAY_OBJECT PyArrayObject +#else +//TODO Remove this as soon as support for Numpy version before 1.7 is dropped +#define NPE_PY_ARRAY_OBJECT PyObject +#endif #define PY_ARRAY_UNIQUE_SYMBOL NP_Eigen_AS #include @@ -92,8 +101,8 @@ struct NumpyEigenConverter // Create a 1D array npy_intp dimensions[1]; dimensions[0] = M.size(); - P = PyArray_SimpleNew(1, dimensions, TypeToNumPy::NpyType); - numpyTypeDemuxer< CopyEigenToNumpyVector >(&M,P); + P = PyArray_SimpleNew(1, dimensions, TypeToNumPy::NpyType); + numpyTypeDemuxer< CopyEigenToNumpyVector >(&M, reinterpret_cast(P)); } else { @@ -102,7 +111,7 @@ struct NumpyEigenConverter dimensions[0] = M.rows(); dimensions[1] = M.cols(); P = PyArray_SimpleNew(2, dimensions, TypeToNumPy::NpyType); - numpyTypeDemuxer< CopyEigenToNumpyMatrix >(&M,P); + numpyTypeDemuxer< CopyEigenToNumpyMatrix >(&M, reinterpret_cast(P)); } // incrementing the reference seems to cause a memory leak. @@ -131,7 +140,7 @@ struct NumpyEigenConverter return valid; } - static void checkMatrixSizes(PyObject * obj_ptr) + static void checkMatrixSizes(NPE_PY_ARRAY_OBJECT * obj_ptr) { int rows = PyArray_DIM(obj_ptr, 0); int cols = PyArray_DIM(obj_ptr, 1); @@ -145,7 +154,7 @@ struct NumpyEigenConverter } } - static void checkRowVectorSizes(PyObject * obj_ptr, int cols) + static void checkRowVectorSizes(NPE_PY_ARRAY_OBJECT * obj_ptr, int cols) { if(!isDimensionValid(cols, ColsAtCompileTime, MaxColsAtCompileTime)) { @@ -154,7 +163,7 @@ struct NumpyEigenConverter } } - static void checkColumnVectorSizes(PyObject * obj_ptr, int rows) + static void checkColumnVectorSizes(NPE_PY_ARRAY_OBJECT * obj_ptr, int rows) { // Check if the type can accomidate one column. if(ColsAtCompileTime == Eigen::Dynamic || ColsAtCompileTime == 1) @@ -173,7 +182,7 @@ struct NumpyEigenConverter } - static void checkVectorSizes(PyObject * obj_ptr) + static void checkVectorSizes(NPE_PY_ARRAY_OBJECT * obj_ptr) { int size = PyArray_DIM(obj_ptr, 0); @@ -206,8 +215,10 @@ struct NumpyEigenConverter return 0; } + NPE_PY_ARRAY_OBJECT * array_ptr = reinterpret_cast(obj_ptr); + // Check the type of the array. - int npyType = PyArray_ObjectType(obj_ptr, 0); + int npyType = getNpyType(array_ptr); if(!TypeToNumPy::canConvert(npyType)) { @@ -219,7 +230,7 @@ struct NumpyEigenConverter // Check the array dimensions. - int nd = PyArray_NDIM(obj_ptr); + int nd = PyArray_NDIM(array_ptr); if(nd != 1 && nd != 2) { @@ -228,12 +239,12 @@ struct NumpyEigenConverter if(nd == 1) { - checkVectorSizes(obj_ptr); + checkVectorSizes(array_ptr); } else { // Two-dimensional matrix type. - checkMatrixSizes(obj_ptr); + checkMatrixSizes(array_ptr); } @@ -265,10 +276,17 @@ struct NumpyEigenConverter matrix_t & M = *Mp; - int nd = PyArray_NDIM(obj_ptr); + if (!PyArray_Check(obj_ptr)) + { + THROW_TYPE_ERROR("construct is only defined for numpy array and matrix types"); + } + + NPE_PY_ARRAY_OBJECT * array_ptr = reinterpret_cast(obj_ptr); + + int nd = PyArray_NDIM(array_ptr); if(nd == 1) { - int size = PyArray_DIM(obj_ptr, 0); + int size = PyArray_DIM(array_ptr, 0); // This is a vector type if(RowsAtCompileTime == 1) { @@ -280,15 +298,15 @@ struct NumpyEigenConverter // Column Vector M.resize(size,1); } - numpyTypeDemuxer< CopyNumpyToEigenVector >(&M,obj_ptr); + numpyTypeDemuxer< CopyNumpyToEigenVector >(&M, array_ptr); } else { - int rows = PyArray_DIM(obj_ptr, 0); - int cols = PyArray_DIM(obj_ptr, 1); + int rows = PyArray_DIM(array_ptr, 0); + int cols = PyArray_DIM(array_ptr, 1); M.resize(rows,cols); - numpyTypeDemuxer< CopyNumpyToEigenMatrix >(&M,obj_ptr); + numpyTypeDemuxer< CopyNumpyToEigenMatrix >(&M, array_ptr); } diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp index 8ac94e8b7..b112a7426 100755 --- a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp @@ -9,16 +9,16 @@ struct CopyNumpyToEigenMatrix typedef typename matrix_t::Scalar scalar_t; template - void exec(EIGEN_T * M_, PyObject * P_) + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) { // Assumes M is already initialized. for(int r = 0; r < M_->rows(); r++) { - for(int c = 0; c < M_->cols(); c++) - { - T * p = static_cast(PyArray_GETPTR2(P_, r, c)); - (*M_)(r,c) = static_cast(*p); - } + for(int c = 0; c < M_->cols(); c++) + { + T * p = static_cast(PyArray_GETPTR2(P_, r, c)); + (*M_)(r,c) = static_cast(*p); + } } } @@ -31,16 +31,16 @@ struct CopyEigenToNumpyMatrix typedef typename matrix_t::Scalar scalar_t; template - void exec(EIGEN_T * M_, PyObject * P_) + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) { // Assumes M is already initialized. for(int r = 0; r < M_->rows(); r++) { - for(int c = 0; c < M_->cols(); c++) - { - T * p = static_cast(PyArray_GETPTR2(P_, r, c)); - *p = static_cast((*M_)(r,c)); - } + for(int c = 0; c < M_->cols(); c++) + { + T * p = static_cast(PyArray_GETPTR2(P_, r, c)); + *p = static_cast((*M_)(r,c)); + } } } @@ -53,13 +53,13 @@ struct CopyEigenToNumpyVector typedef typename matrix_t::Scalar scalar_t; template - void exec(EIGEN_T * M_, PyObject * P_) + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) { // Assumes M is already initialized. for(int i = 0; i < M_->size(); i++) { - T * p = static_cast(PyArray_GETPTR1(P_, i)); - *p = static_cast((*M_)(i)); + T * p = static_cast(PyArray_GETPTR1(P_, i)); + *p = static_cast((*M_)(i)); } } @@ -73,13 +73,13 @@ struct CopyNumpyToEigenVector typedef typename matrix_t::Scalar scalar_t; template - void exec(EIGEN_T * M_, PyObject * P_) + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) { // Assumes M is already initialized. for(int i = 0; i < M_->size(); i++) { - T * p = static_cast(PyArray_GETPTR1(P_, i)); - (*M_)(i) = static_cast(*p); + T * p = static_cast(PyArray_GETPTR1(P_, i)); + (*M_)(i) = static_cast(*p); } } @@ -91,10 +91,11 @@ struct CopyNumpyToEigenVector // Crazy syntax in this function was found here: // http://stackoverflow.com/questions/1840253/c-template-member-function-of-template-class-called-from-template-function/1840318#1840318 template< typename FUNCTOR_T> -inline void numpyTypeDemuxer(typename FUNCTOR_T::matrix_t * M, PyObject * P) +inline void numpyTypeDemuxer(typename FUNCTOR_T::matrix_t * M, NPE_PY_ARRAY_OBJECT * P) { FUNCTOR_T f; - int npyType = PyArray_ObjectType(P, 0); + + int npyType = getNpyType(P); switch(npyType) { case NPY_BOOL: diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp index 36fae1a03..97e4bb5a0 100755 --- a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp +++ b/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp @@ -1,12 +1,12 @@ #ifndef NUMPY_EIGEN_TYPE_TRAITS_HPP #define NUMPY_EIGEN_TYPE_TRAITS_HPP -#define THROW_TYPE_ERROR(msg) \ - { \ - std::stringstream type_error_ss; \ - type_error_ss << msg; \ - PyErr_SetString(PyExc_TypeError, type_error_ss.str().c_str()); \ - throw boost::python::error_already_set(); \ +#define THROW_TYPE_ERROR(msg) \ + { \ + std::stringstream type_error_ss; \ + type_error_ss << msg; \ + PyErr_SetString(PyExc_TypeError, type_error_ss.str().c_str()); \ + throw boost::python::error_already_set(); \ } @@ -99,6 +99,19 @@ template<> struct TypeToNumPy }; +inline int getNpyType(PyObject * obj_ptr){ + return PyArray_ObjectType(obj_ptr, 0); +} + +#ifdef NPY_1_7_API_VERSION +inline int getNpyType(PyArrayObject * obj_ptr){ + PyArray_Descr * descr = PyArray_MinScalarType(obj_ptr); + if (descr == NULL){ + THROW_TYPE_ERROR("Unsupported type: PyArray_MinScalarType returned null!"); + } + return descr->type_num; +} +#endif inline const char * npyTypeToString(int npyType) { @@ -157,18 +170,18 @@ inline const char * npyTypeToString(int npyType) } } -inline std::string npyArrayTypeString(PyObject * obj_ptr) +inline std::string npyArrayTypeString(NPE_PY_ARRAY_OBJECT * obj_ptr) { std::stringstream ss; int nd = PyArray_NDIM(obj_ptr); - ss << "numpy.array<" << npyTypeToString(PyArray_ObjectType(obj_ptr, 0)) << ">["; + ss << "numpy.array<" << npyTypeToString(getNpyType(obj_ptr)) << ">["; if(nd > 0) { ss << PyArray_DIM(obj_ptr, 0); for(int i = 1; i < nd; i++) - { - ss << ", " << PyArray_DIM(obj_ptr, i); - } + { + ss << ", " << PyArray_DIM(obj_ptr, i); + } } ss << "]"; return ss.str(); From 4c44ddc4e67e409a25d20f96e76c2cf7f8e5060a Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Thu, 21 Jan 2016 01:13:22 -0500 Subject: [PATCH 075/105] Print all python-related dependency warnings at the end of cmake output with all the other warnings. Don't automatically toggle GTSAM_BUILD_PYTHON option to OFF - this is more consistent with how other options are handled. --- CMakeLists.txt | 11 ++++++++-- python/CMakeLists.txt | 51 ++++++++++++++++++++++++------------------- 2 files changed, 37 insertions(+), 25 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a886f2702..b7e30253b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -355,7 +355,6 @@ if (GTSAM_BUILD_PYTHON) # comments on the next lines # wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "") - add_subdirectory(python) endif() @@ -478,7 +477,12 @@ print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") message(STATUS "Python module flags ") -print_config_flag(${GTSAM_BUILD_PYTHON} "Build python module ") + +if(GTSAM_PYTHON_WARNINGS) + message(STATUS " Build python module : No - dependencies missing") +else() + print_config_flag(${GTSAM_BUILD_PYTHON} "Build python module ") +endif() if(GTSAM_BUILD_PYTHON) message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") endif() @@ -494,6 +498,9 @@ endif() if(GTSAM_WITH_EIGEN_MKL_OPENMP AND NOT OPENMP_FOUND AND MKL_FOUND) message(WARNING "Your compiler does not support OpenMP - this is ok, but performance may be improved with OpenMP. Set GTSAM_WITH_EIGEN_MKL_OPENMP to 'Off' to avoid this warning.") endif() +if(GTSAM_BUILD_PYTHON AND GTSAM_PYTHON_WARNINGS) + message(WARNING "${GTSAM_PYTHON_WARNINGS}") +endif() # Include CPack *after* all flags include(CPack) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 4d3d0237d..f21bb1a76 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -31,9 +31,6 @@ endif() # Find NumPy C-API -- this is part of the numpy package find_package(NumPy) -if(NUMPY_FOUND) - include_directories(${NUMPY_INCLUDE_DIRS}) -endif() # Find Python # First, be sure that python version can be found by FindPythonLibs.cmake @@ -52,6 +49,9 @@ find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_SUFFIX}) # Build python module library and setup the module inside build if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND AND NUMPY_FOUND) + + include_directories(${NUMPY_INCLUDE_DIRS}) + include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) @@ -74,28 +74,33 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU add_dependencies(gtsam_python copy_${PY_SRC_TARGET_SUFFIX}) endforeach() -# Disable python module if we didn't find required lybraries +# Disable python module if we didn't find required libraries else() - set(GTSAM_BUILD_PYTHON OFF CACHE BOOL "Build Python wrapper statically (increases build time)" FORCE) -endif() -# Print warnings (useful for ccmake) -if(NOT NUMPY_FOUND) - message(WARNING "Numpy not found -- Python module cannot be built.") -endif() - -if(NOT PYTHONLIBS_FOUND) - if(GTSAM_PYTHON_VERSION STREQUAL "Default") - message(WARNING "Default PythonLibs was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") - else() - message(WARNING "PythonLibs version ${GTSAM_PYTHON_VERSION} was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") + # message will print at end of main CMakeLists.txt + SET(GTSAM_PYTHON_WARNINGS "Python dependencies not found - Python module will not be built. Set GTSAM_BUILD_PYTHON to 'Off' to disable this warning. Details:") + + if(NOT PYTHONLIBS_FOUND) + if(GTSAM_PYTHON_VERSION STREQUAL "Default") + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Default PythonLibs not found") + else() + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- PythonLibs version ${GTSAM_PYTHON_VERSION} not found") + endif() endif() -endif() - -if(NOT Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND) - if(GTSAM_PYTHON_VERSION STREQUAL "Default") - message(WARNING "Default Boost python was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") - else() - message(WARNING "Boost Python for python ${GTSAM_PYTHON_VERSION} was not found -- Python module cannot be built. Option GTSAM_BUILD_PYTHON disabled.") + + if(NOT NUMPY_FOUND) + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Numpy not found") endif() + + if(NOT Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND) + if(GTSAM_PYTHON_VERSION STREQUAL "Default") + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Default Boost python not found") + else() + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Boost Python for python ${GTSAM_PYTHON_VERSION} not found") + endif() + endif() + + # make available at top-level + SET(GTSAM_PYTHON_WARNINGS ${GTSAM_PYTHON_WARNINGS} PARENT_SCOPE) + endif() From fb8a62dd1dbb1de6f143c5a680a4d0c4b5edbc11 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 24 Jan 2016 15:28:16 -0800 Subject: [PATCH 076/105] Used python.in to generate setup.py Also fixed cmake stuff to copy library to correct location Minor improvements of cmake Automatic install of python package --- python/CMakeLists.txt | 56 ++++++++++++------------------- python/handwritten/CMakeLists.txt | 7 ++-- python/{setup.py => setup.py.in} | 10 ++---- 3 files changed, 28 insertions(+), 45 deletions(-) rename python/{setup.py => setup.py.in} (64%) mode change 100755 => 100644 diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index f21bb1a76..3bd45eca8 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,4 +1,3 @@ - # Guard to avoid breaking this code in ccmake if by accident GTSAM_PYTHON_VERSION is set to an empty string if(GTSAM_PYTHON_VERSION STREQUAL "") set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "Target python version for GTSAM python module. Use 'Default' to chose the default version" FORCE) @@ -18,6 +17,18 @@ if(NOT (${GTSAM_PYTHON_VERSION} MATCHES ${GTSAM_LAST_PYTHON_VERSION})) set(GTSAM_LAST_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "Updating python version used in the last build" FORCE) endif() +if(GTSAM_PYTHON_VERSION STREQUAL "Default") + # Search the default version. + find_package(PythonInterp) + find_package(PythonLibs) +else() + find_package(PythonInterp ${GTSAM_PYTHON_VERSION}) + find_package(PythonLibs ${GTSAM_PYTHON_VERSION}) +endif() + +# Find NumPy C-API -- this is part of the numpy package +find_package(NumPy) + # Compose strings used to specify the boost python version. They will be empty if we want to use the defaut if(NOT GTSAM_PYTHON_VERSION STREQUAL "Default") string(REPLACE "." "" BOOST_PYTHON_VERSION_SUFFIX ${GTSAM_PYTHON_VERSION}) # Remove '.' from version @@ -29,29 +40,12 @@ else() set(BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE "") endif() -# Find NumPy C-API -- this is part of the numpy package -find_package(NumPy) - -# Find Python -# First, be sure that python version can be found by FindPythonLibs.cmake -# See: http://stackoverflow.com/a/15660652/2220173 -set(Python_ADDITIONAL_VERSIONS ${GTSAM_PYTHON_VERSION}) -# Then look for the the lib. If no version is specified when looking for PythonLibs it searches the default version. -# See: https://cmake.org/cmake/help/v3.1/module/FindPythonInterp.html -if(GTSAM_PYTHON_VERSION STREQUAL "Default") - find_package(PythonLibs) -else() - find_package(PythonLibs ${GTSAM_PYTHON_VERSION}) -endif() - # Find Boost Python find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_SUFFIX}) -# Build python module library and setup the module inside build if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND AND NUMPY_FOUND) - + # Build library include_directories(${NUMPY_INCLUDE_DIRS}) - include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) @@ -59,24 +53,16 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU # Build the python module library add_subdirectory(handwritten) - # Copy all .py files that changes since last build - file(GLOB_RECURSE GTSAM_PY_SRCS RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} "*.py") - foreach(PY_SRC ${GTSAM_PY_SRCS}) - string(REPLACE "/" "_" PY_SRC_TARGET_SUFFIX ${PY_SRC}) # Replace "/" with "_" - add_custom_command( - OUTPUT ${PY_SRC} - DEPENDS ${PY_SRC} - COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/${PY_SRC} ${CMAKE_CURRENT_BINARY_DIR}/${PY_SRC} - COMMENT "Copying python/${PY_SRC}" - ) - add_custom_target(copy_${PY_SRC_TARGET_SUFFIX} DEPENDS ${PY_SRC}) - # Add dependency so the copy is made BEFORE building the python module - add_dependencies(gtsam_python copy_${PY_SRC_TARGET_SUFFIX}) - endforeach() + # Create and invoke setup.py, see https://bloerg.net/2012/11/10/cmake-and-distutils.html + set(SETUP_PY_IN "${CMAKE_CURRENT_SOURCE_DIR}/setup.py.in") + set(SETUP_PY "${CMAKE_CURRENT_BINARY_DIR}/setup.py") -# Disable python module if we didn't find required libraries + configure_file(${SETUP_PY_IN} ${SETUP_PY}) + + # TODO(frank): possibly support a different prefix a la matlab wrapper + install(CODE "execute_process(WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} COMMAND ${PYTHON_EXECUTABLE} setup.py -v install --prefix ${CMAKE_INSTALL_PREFIX})") else() - + # Disable python module if we didn't find required libraries # message will print at end of main CMakeLists.txt SET(GTSAM_PYTHON_WARNINGS "Python dependencies not found - Python module will not be built. Set GTSAM_BUILD_PYTHON to 'Off' to disable this warning. Details:") diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt index 90eb1fc49..9d4f9151a 100644 --- a/python/handwritten/CMakeLists.txt +++ b/python/handwritten/CMakeLists.txt @@ -1,4 +1,3 @@ - # get subdirectories list subdirlist(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}) @@ -16,14 +15,16 @@ set_target_properties(gtsam_python PROPERTIES SKIP_BUILD_RPATH TRUE CLEAN_DIRECT_OUTPUT 1 ) -target_link_libraries(gtsam_python ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} ${PYTHON_LIBRARY} gtsam) +target_link_libraries(gtsam_python + ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} + ${PYTHON_LIBRARY} gtsam) # Cause the library to be output in the correct directory. # TODO: Change below to work on different systems (currently works only with Linux) add_custom_command( OUTPUT ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so DEPENDS gtsam_python - COMMAND ${CMAKE_COMMAND} -E copy $ ${CMAKE_BINARY_DIR}/python/gtsam/_$ + COMMAND ${CMAKE_COMMAND} -E copy $ ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so COMMENT "Copying extension module to python/gtsam/_libgtsam_python.so" ) add_custom_target(copy_gtsam_python_module ALL DEPENDS ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so) \ No newline at end of file diff --git a/python/setup.py b/python/setup.py.in old mode 100755 new mode 100644 similarity index 64% rename from python/setup.py rename to python/setup.py.in index 46bbfaddf..359a5e8c3 --- a/python/setup.py +++ b/python/setup.py.in @@ -1,15 +1,11 @@ -#!/usr/bin/env python - -#http://docs.python.org/2/distutils/setupscript.html#setup-script - from distutils.core import setup setup(name='gtsam', - version='4.0.0', + version='${GTSAM_VERSION_STRING}', description='GTSAM Python wrapper', license = "BSD", - author='Dellaert et. al', - author_email='Andrew.Melim@gatech.edu', + author='Frank Dellaert et. al', + author_email='frank.dellaert@gatech.edu', maintainer_email='gtsam@lists.gatech.edu', url='https://collab.cc.gatech.edu/borg/gtsam', packages=['gtsam', 'gtsam.examples', 'gtsam.utils'], From 0605abfea5a31af33a69907cc509b31ad6aff559 Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 24 Jan 2016 15:50:31 -0800 Subject: [PATCH 077/105] Chaned dir structure a bit --- python/{gtsam/examples => gtsam_examples}/OdometeryExample.py | 0 python/{gtsam/examples => gtsam_examples}/SFMdata.py | 0 python/{gtsam/examples => gtsam_examples}/VisualISAM2Example.py | 0 python/{gtsam/examples => gtsam_examples}/__init__.py | 0 python/{gtsam/utils => gtsam_utils}/__init__.py | 0 python/{gtsam/utils => gtsam_utils}/_plot.py | 0 6 files changed, 0 insertions(+), 0 deletions(-) rename python/{gtsam/examples => gtsam_examples}/OdometeryExample.py (100%) rename python/{gtsam/examples => gtsam_examples}/SFMdata.py (100%) rename python/{gtsam/examples => gtsam_examples}/VisualISAM2Example.py (100%) rename python/{gtsam/examples => gtsam_examples}/__init__.py (100%) rename python/{gtsam/utils => gtsam_utils}/__init__.py (100%) rename python/{gtsam/utils => gtsam_utils}/_plot.py (100%) diff --git a/python/gtsam/examples/OdometeryExample.py b/python/gtsam_examples/OdometeryExample.py similarity index 100% rename from python/gtsam/examples/OdometeryExample.py rename to python/gtsam_examples/OdometeryExample.py diff --git a/python/gtsam/examples/SFMdata.py b/python/gtsam_examples/SFMdata.py similarity index 100% rename from python/gtsam/examples/SFMdata.py rename to python/gtsam_examples/SFMdata.py diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam_examples/VisualISAM2Example.py similarity index 100% rename from python/gtsam/examples/VisualISAM2Example.py rename to python/gtsam_examples/VisualISAM2Example.py diff --git a/python/gtsam/examples/__init__.py b/python/gtsam_examples/__init__.py similarity index 100% rename from python/gtsam/examples/__init__.py rename to python/gtsam_examples/__init__.py diff --git a/python/gtsam/utils/__init__.py b/python/gtsam_utils/__init__.py similarity index 100% rename from python/gtsam/utils/__init__.py rename to python/gtsam_utils/__init__.py diff --git a/python/gtsam/utils/_plot.py b/python/gtsam_utils/_plot.py similarity index 100% rename from python/gtsam/utils/_plot.py rename to python/gtsam_utils/_plot.py From 7b493812e8ec343760a69785590f9e0593c4417c Mon Sep 17 00:00:00 2001 From: dellaert Date: Sun, 24 Jan 2016 15:51:04 -0800 Subject: [PATCH 078/105] Adapt to new dir structure --- python/gtsam/__init__.py | 1 - python/gtsam_examples/VisualISAM2Example.py | 4 ++-- python/setup.py.in | 3 ++- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py index 8e093879c..f9e40517d 100644 --- a/python/gtsam/__init__.py +++ b/python/gtsam/__init__.py @@ -1,2 +1 @@ from ._libgtsam_python import * -from . import utils \ No newline at end of file diff --git a/python/gtsam_examples/VisualISAM2Example.py b/python/gtsam_examples/VisualISAM2Example.py index a8be94719..3ba1d35f7 100644 --- a/python/gtsam_examples/VisualISAM2Example.py +++ b/python/gtsam_examples/VisualISAM2Example.py @@ -1,7 +1,7 @@ from __future__ import print_function import gtsam -from gtsam.examples.SFMdata import * -from gtsam.utils import * +from gtsam_examples.SFMdata import * +from gtsam_utils import * import matplotlib.pyplot as plt from mpl_toolkits.mplot3d import Axes3D import time # for sleep() diff --git a/python/setup.py.in b/python/setup.py.in index 359a5e8c3..d7e108e0a 100644 --- a/python/setup.py.in +++ b/python/setup.py.in @@ -8,6 +8,7 @@ setup(name='gtsam', author_email='frank.dellaert@gatech.edu', maintainer_email='gtsam@lists.gatech.edu', url='https://collab.cc.gatech.edu/borg/gtsam', - packages=['gtsam', 'gtsam.examples', 'gtsam.utils'], + package_dir={ '': '${CMAKE_CURRENT_SOURCE_DIR}' }, + packages=['gtsam', 'gtsam_utils', 'gtsam_examples', 'gtsam_tests'], package_data={'gtsam' : ['_libgtsam_python.so']}, ) From 6b85a8db14e8c538a2b54115da2bb77725307571 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Sun, 24 Jan 2016 20:54:16 -0500 Subject: [PATCH 079/105] typo --- python/gtsam_examples/{OdometeryExample.py => OdometryExample.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename python/gtsam_examples/{OdometeryExample.py => OdometryExample.py} (100%) diff --git a/python/gtsam_examples/OdometeryExample.py b/python/gtsam_examples/OdometryExample.py similarity index 100% rename from python/gtsam_examples/OdometeryExample.py rename to python/gtsam_examples/OdometryExample.py From 8c0f928f11573f70a6464f87c64c602fb6efa848 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Sun, 24 Jan 2016 23:22:40 -0500 Subject: [PATCH 080/105] Another attempt at fixing installation of _libgtsam_python.so. package_data is relative to package_dir, so the previous approach doesn't work when package_dir is in the source tree (and we don't want to copy the lib to source, or all of the source into lib). Using data_files method instead. --- python/CMakeLists.txt | 4 ++++ python/setup.py.in | 3 ++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 3bd45eca8..7f54d32cf 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -57,6 +57,10 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU set(SETUP_PY_IN "${CMAKE_CURRENT_SOURCE_DIR}/setup.py.in") set(SETUP_PY "${CMAKE_CURRENT_BINARY_DIR}/setup.py") + # Hacky way to figure out install folder - valid for Linux & Mac + # default pattern: prefix/lib/pythonX.Y/site-packages from https://docs.python.org/2/install/ + STRING(CONCAT PY_INSTALL_FOLDER ${CMAKE_INSTALL_PREFIX} "/lib/python" ${PYTHON_VERSION_MAJOR} "." ${PYTHON_VERSION_MINOR} "/site-packages") + configure_file(${SETUP_PY_IN} ${SETUP_PY}) # TODO(frank): possibly support a different prefix a la matlab wrapper diff --git a/python/setup.py.in b/python/setup.py.in index d7e108e0a..d3b5fcde4 100644 --- a/python/setup.py.in +++ b/python/setup.py.in @@ -10,5 +10,6 @@ setup(name='gtsam', url='https://collab.cc.gatech.edu/borg/gtsam', package_dir={ '': '${CMAKE_CURRENT_SOURCE_DIR}' }, packages=['gtsam', 'gtsam_utils', 'gtsam_examples', 'gtsam_tests'], - package_data={'gtsam' : ['_libgtsam_python.so']}, + #package_data={'gtsam' : ['_libgtsam_python.so']}, # location of .so file is relative to package_dir + data_files=[('${PY_INSTALL_FOLDER}/gtsam/', ['gtsam/_libgtsam_python.so'])], # location of .so file relative to setup.py ) From 00da6d3f81f095f1093746d7b314c01b2c6f358c Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Sun, 24 Jan 2016 23:29:06 -0500 Subject: [PATCH 081/105] string concat the CMake 2.8-friendly way --- python/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 7f54d32cf..01141973a 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -59,7 +59,7 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU # Hacky way to figure out install folder - valid for Linux & Mac # default pattern: prefix/lib/pythonX.Y/site-packages from https://docs.python.org/2/install/ - STRING(CONCAT PY_INSTALL_FOLDER ${CMAKE_INSTALL_PREFIX} "/lib/python" ${PYTHON_VERSION_MAJOR} "." ${PYTHON_VERSION_MINOR} "/site-packages") + SET(PY_INSTALL_FOLDER "${CMAKE_INSTALL_PREFIX}/lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages") configure_file(${SETUP_PY_IN} ${SETUP_PY}) From fe56fcd747700e9d25b9d66b651731b31c8b8876 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Sun, 24 Jan 2016 23:40:11 -0500 Subject: [PATCH 082/105] Make option text consistent with Matlab text --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b7e30253b..e8da98ffd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,7 +64,7 @@ option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TB option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" ON) option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" ON) option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) -option(GTSAM_BUILD_PYTHON "Build Python wrapper statically (increases build time)" ON) +option(GTSAM_BUILD_PYTHON "Enable/Disable building & installation of Python module" ON) # Options relating to MATLAB wrapper # TODO: Check for matlab mex binary before handling building of binaries From cd0215d9a83b03b136919af6f7ce8a9954862b28 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Sun, 24 Jan 2016 23:47:36 -0500 Subject: [PATCH 083/105] Add back empty __init__.py file for gtsam_tests. Seems required to be able to do "import gtsam_tests", but it can be empty. --- python/gtsam_tests/__init__.py | 1 + 1 file changed, 1 insertion(+) create mode 100644 python/gtsam_tests/__init__.py diff --git a/python/gtsam_tests/__init__.py b/python/gtsam_tests/__init__.py new file mode 100644 index 000000000..8b1378917 --- /dev/null +++ b/python/gtsam_tests/__init__.py @@ -0,0 +1 @@ + From 31923862d6e7cdf0c2fab84c8fd7b9a408ef9c78 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Sun, 24 Jan 2016 23:59:22 -0500 Subject: [PATCH 084/105] Adding Ellon to list of contributors. Very important :-) --- THANKS | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/THANKS b/THANKS index 9c06a5d28..f84cfa185 100644 --- a/THANKS +++ b/THANKS @@ -38,6 +38,10 @@ at Uni Zurich: * Christian Forster +at LAAS-CNRS + +* Ellon Paiva + Many thanks for your hard work!!!! Frank Dellaert From 6ee3e42d27dff96f0d5047d23ab9de89bff8b66d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 25 Jan 2016 00:09:51 -0800 Subject: [PATCH 085/105] Update README --- python/README.md | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/python/README.md b/python/README.md index fc83ff702..f1c218cfb 100644 --- a/python/README.md +++ b/python/README.md @@ -3,16 +3,16 @@ Python Wrapper and Packaging This directory contains the basic setup script and directory structure for the gtsam python module. During the build of gtsam, when GTSAM_BUILD_PYTHON is enabled, the following instructions will run. -* The python files that compose the module are copied from python/gtsam to $BUILD_DIR/python/gtsam -* The handwritten module source files are then compiled and linked with Boost Python, generating a shared library which can then be imported by python -* The shared library is then copied to $BUILD_DIR/python/gtsam and renamed with a "_" prefix -* The user can use the setup.py script inside $BUILD_DIR/python to build and install a python package, allowing easy importing into a python project. Examples (when run from $BUILD_DIR): - * python setup.py sdist ---- Builds a tarball of the python package which can then be distributed - * python setup.py install ---- Installs the package into the python dist-packages folder. Can then be imported from any python file. - * python setup.py install --prefix="your/local/install/path"---- Installs the package into a local instalation folder. Can then be imported from any python file if _prefix_/lib/pythonX.Y/site-packages is present in your $PYTHONPATH -* To run the unit tests, you must first install the package on your path (TODO: Make this easier) +* The handwritten module source files are compiled and linked with Boost Python, generating a shared + library which can then be imported by python +* A setup.py script is configured from setup.py.in +* The gtsam packages 'gtsam', 'gtsam_utils', 'gtsam_examples', and 'gtsam_tests' are installed into + the site-packages folder within the (possibly non-default) installation prefix folder. If + installing to a non-standard prefix, make sure that _prefix_/lib/pythonX.Y/site-packages is + present in your $PYTHONPATH -The target version of Python to create the module can be set by defining GTSAM_PYTHON_VERSION to 'X.Y' (Example: 2.7 or 3.4), or 'Default' if you want to use the default python installed in your system. Note that if you specify a target version of python, you should also have the correspondent Boost Python version installed (Example: libboost_python-py27.so or libboost_python-py34.so on Linux). If you're using the default version, your default Boost Python library (Example: libboost_python.so on Linux) should correspond to the default python version in your system. +The target version of Python to create the module can be set by defining GTSAM_PYTHON_VERSION to 'X.Y' (Example: 2.7 or 3.4), or 'Default' if you want to use the default python installed in your system. Note that if you specify a target version of python, you should also have the correspondening Boost +Python version installed (Example: libboost_python-py27.so or libboost_python-py34.so on Linux). +If you're using the default version, your default Boost Python library (Example: libboost_python.so on Linux) should correspond to the default python version in your system. -TODO: There are many issues with this build system, but these are the basics. From 312b8f5da0f51428a3b380037a146a9d214075ca Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 25 Jan 2016 00:57:35 -0800 Subject: [PATCH 086/105] Cleaned up example --- python/gtsam_examples/VisualISAM2Example.py | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/python/gtsam_examples/VisualISAM2Example.py b/python/gtsam_examples/VisualISAM2Example.py index 3ba1d35f7..4d7889e9b 100644 --- a/python/gtsam_examples/VisualISAM2Example.py +++ b/python/gtsam_examples/VisualISAM2Example.py @@ -1,11 +1,14 @@ from __future__ import print_function -import gtsam -from gtsam_examples.SFMdata import * -from gtsam_utils import * + import matplotlib.pyplot as plt from mpl_toolkits.mplot3d import Axes3D +import numpy as np import time # for sleep() +import gtsam +from gtsam_examples import SFMdata +import gtsam_utils + def visual_ISAM2_plot(poses, points, result): # VisualISAMPlot plots current state of ISAM2 object # Author: Ellon Paiva @@ -22,14 +25,14 @@ def visual_ISAM2_plot(poses, points, result): # Can't use data because current frame might not see all points # marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()); # TODO - this is slow # gtsam.plot3DPoints(result, [], marginals); - plot3DPoints(fignum, result, 'rx'); + gtsam_utils.plot3DPoints(fignum, result, 'rx'); # Plot cameras M = 0; while result.exists(int(gtsam.Symbol('x',M))): ii = int(gtsam.Symbol('x',M)); pose_i = result.pose3_at(ii); - plotPose3(fignum, pose_i, 10); + gtsam_utils.plotPose3(fignum, pose_i, 10); M = M + 1; @@ -49,10 +52,10 @@ def visual_ISAM2_example(): measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v # Create the set of ground-truth landmarks - points = createPoints() # from SFMdata + points = SFMdata.createPoints() # Create the set of ground-truth poses - poses = createPoses() # from SFMdata + poses = SFMdata.createPoses() # Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps to maintain proper linearization # and efficient variable ordering, iSAM2 performs partial relinearization/reordering at each step. A parameter From a6c265fda094a998fed775062de1264cae666784 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 25 Jan 2016 00:58:08 -0800 Subject: [PATCH 087/105] OdometryExample and necessary wrapping --- python/gtsam_examples/OdometryExample.py | 39 ++++++++++++++++--- .../nonlinear/LevenbergMarquardtOptimizer.cpp | 13 ++++++- .../nonlinear/NonlinearFactorGraph.cpp | 4 +- python/handwritten/nonlinear/Values.cpp | 16 +++++++- 4 files changed, 63 insertions(+), 9 deletions(-) diff --git a/python/gtsam_examples/OdometryExample.py b/python/gtsam_examples/OdometryExample.py index 45f729a89..0800bab4e 100644 --- a/python/gtsam_examples/OdometryExample.py +++ b/python/gtsam_examples/OdometryExample.py @@ -1,7 +1,36 @@ #!/usr/bin/env python -from gtsam import * -import numpy_eigen as npe +from __future__ import print_function +import gtsam +import numpy as np -noisemodel = DiagonalNoiseModel.Sigmas([0.1, 0.1, 0.1]) -graph = NonlinearFactorGraph() -initialEstimate = Values() \ No newline at end of file +# Create an empty nonlinear factor graph +graph = gtsam.NonlinearFactorGraph() + +# Add a prior on the first pose, setting it to the origin +# A prior factor consists of a mean and a noise model (covariance matrix) +priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin +priorNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) +graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) + +# Add odometry factors +odometry = gtsam.Pose2(2.0, 0.0, 0.0) +# For simplicity, we will use the same noise model for each odometry factor +odometryNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) +# Create odometry (Between) factors between consecutive poses +graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise)) +graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, odometryNoise)) +graph.print("\nFactor Graph:\n") + +# Create the data structure to hold the initialEstimate estimate to the solution +# For illustrative purposes, these have been deliberately set to incorrect values +initial = gtsam.Values() +initial.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) +initial.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) +initial.insert(3, gtsam.Pose2(4.1, 0.1, 0.1)) +initial.print("\nInitial Estimate:\n") + +# optimize using Levenberg-Marquardt optimization +params = gtsam.LevenbergMarquardtParams() +optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) +result = optimizer.optimize() +result.print("\nFinal Result:\n") diff --git a/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp b/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp index 44b11f00b..7c7cdf3cc 100644 --- a/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -9,8 +9,19 @@ using namespace boost::python; using namespace gtsam; void exportLevenbergMarquardtOptimizer(){ + class_("LevenbergMarquardtParams", init<>()) + .def("setDiagonalDamping", &LevenbergMarquardtParams::setDiagonalDamping) + .def("setlambdaFactor", &LevenbergMarquardtParams::setlambdaFactor) + .def("setlambdaInitial", &LevenbergMarquardtParams::setlambdaInitial) + .def("setlambdaLowerBound", &LevenbergMarquardtParams::setlambdaLowerBound) + .def("setlambdaUpperBound", &LevenbergMarquardtParams::setlambdaUpperBound) + .def("setLogFile", &LevenbergMarquardtParams::setLogFile) + .def("setUseFixedLambdaFactor", &LevenbergMarquardtParams::setUseFixedLambdaFactor) + .def("setVerbosityLM", &LevenbergMarquardtParams::setVerbosityLM) + ; + class_("LevenbergMarquardtOptimizer", init()) .def("optimize", &LevenbergMarquardtOptimizer::optimize, return_value_policy()) ; -} \ No newline at end of file +} diff --git a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp index 4200a150e..f1e14deda 100644 --- a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp +++ b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp @@ -26,6 +26,7 @@ using namespace boost::python; using namespace gtsam; +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, NonlinearFactorGraph::print, 0, 1); void exportNonlinearFactorGraph(){ @@ -40,6 +41,7 @@ void exportNonlinearFactorGraph(){ .def("add", add1) .def("resize", &NonlinearFactorGraph::resize) .def("empty", &NonlinearFactorGraph::empty) + .def("print", &NonlinearFactorGraph::print, print_overloads(args("s"))) ; -} \ No newline at end of file +} diff --git a/python/handwritten/nonlinear/Values.cpp b/python/handwritten/nonlinear/Values.cpp index 0302abbe2..6715fb071 100644 --- a/python/handwritten/nonlinear/Values.cpp +++ b/python/handwritten/nonlinear/Values.cpp @@ -20,6 +20,9 @@ #include #include "gtsam/nonlinear/Values.h" +#include "gtsam/geometry/Point2.h" +#include "gtsam/geometry/Rot2.h" +#include "gtsam/geometry/Pose2.h" #include "gtsam/geometry/Point3.h" #include "gtsam/geometry/Rot3.h" #include "gtsam/geometry/Pose3.h" @@ -69,6 +72,8 @@ using namespace gtsam; // return v.at(j); // } +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Values::print, 0, 1); + void exportValues(){ // NOTE: Apparently the class 'Value'' is deprecated, so the commented lines below @@ -77,10 +82,14 @@ void exportValues(){ // const Value& (Values::*at1)(Key) const = &Values::at; // void (Values::*insert1)(Key, const Value&) = &Values::insert; bool (Values::*exists1)(Key) const = &Values::exists; + void (Values::*insert_point2)(Key, const gtsam::Point2&) = &Values::insert; + void (Values::*insert_rot2) (Key, const gtsam::Rot2&) = &Values::insert; + void (Values::*insert_pose2) (Key, const gtsam::Pose2&) = &Values::insert; void (Values::*insert_point3)(Key, const gtsam::Point3&) = &Values::insert; void (Values::*insert_rot3) (Key, const gtsam::Rot3&) = &Values::insert; void (Values::*insert_pose3) (Key, const gtsam::Pose3&) = &Values::insert; + class_("Values", init<>()) .def(init()) .def("clear", &Values::clear) @@ -89,12 +98,15 @@ void exportValues(){ .def("equals", &Values::equals) .def("erase", &Values::erase) .def("insert_fixed", &Values::insertFixed) - .def("print", &Values::print) + .def("print", &Values::print, print_overloads(args("s"))) .def("size", &Values::size) .def("swap", &Values::swap) // NOTE: Following commented lines add useless methods on Values // .def("insert", insert1) // .def("at", at1, return_value_policy()) + .def("insert", insert_point2) + .def("insert", insert_rot2) + .def("insert", insert_pose2) .def("insert", insert_point3) .def("insert", insert_rot3) .def("insert", insert_pose3) @@ -109,4 +121,4 @@ void exportValues(){ .def("exists", exists1) .def("keys", &Values::keys) ; -} \ No newline at end of file +} From 6fbb8cdff8b8b4420ad1a3277e617a7a42ab1275 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 26 Jan 2016 11:42:43 -0800 Subject: [PATCH 088/105] Added gtsampy.h header to support development of py_wrap branch: the differences between gtsam.h and gtsampy.h highlight the progress of python wrapping. --- gtsampy.h | 2669 +++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 2669 insertions(+) create mode 100644 gtsampy.h diff --git a/gtsampy.h b/gtsampy.h new file mode 100644 index 000000000..ca014ad5d --- /dev/null +++ b/gtsampy.h @@ -0,0 +1,2669 @@ +/** + + * GTSAM Wrap Module Definition + * + * These are the current classes available through the matlab toolbox interface, + * add more functions/classes as they are available. + * + * Requirements: + * Classes must start with an uppercase letter + * - Can wrap a typedef + * Only one Method/Constructor per line, though methods/constructors can extend across multiple lines + * Methods can return + * - Eigen types: Matrix, Vector + * - C/C++ basic types: string, bool, size_t, int, double, char, unsigned char + * - void + * - Any class with which be copied with boost::make_shared() + * - boost::shared_ptr of any object type + * Constructors + * - Overloads are supported + * - A class with no constructors can be returned from other functions but not allocated directly in MATLAB + * Methods + * - Constness has no effect + * - Specify by-value (not reference) return types, even if C++ method returns reference + * - Must start with a letter (upper or lowercase) + * - Overloads are supported + * Static methods + * - Must start with a letter (upper or lowercase) and use the "static" keyword + * - The first letter will be made uppercase in the generated MATLAB interface + * - Overloads are supported + * Arguments to functions any of + * - Eigen types: Matrix, Vector + * - Eigen types and classes as an optionally const reference + * - C/C++ basic types: string, bool, size_t, size_t, double, char, unsigned char + * - Any class with which be copied with boost::make_shared() (except Eigen) + * - boost::shared_ptr of any object type (except Eigen) + * Comments can use either C++ or C style, with multiple lines + * Namespace definitions + * - Names of namespaces must start with a lowercase letter + * - start a namespace with "namespace {" + * - end a namespace with exactly "}" + * - Namespaces can be nested + * Namespace usage + * - Namespaces can be specified for classes in arguments and return values + * - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName" + * Includes in C++ wrappers + * - All includes will be collected and added in a single file + * - All namespaces must have angle brackets: + * - No default includes will be added + * Global/Namespace functions + * - Functions specified outside of a class are global + * - Can be overloaded with different arguments + * - Can have multiple functions of the same name in different namespaces + * Using classes defined in other modules + * - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error + * Virtual inheritance + * - Specify fully-qualified base classes, i.e. "virtual class Derived : ns::Base {" where "ns" is the namespace + * - Mark with 'virtual' keyword, e.g. "virtual class Base {", and also "virtual class Derived : ns::Base {" + * - Forward declarations must also be marked virtual, e.g. "virtual class ns::Base;" and + * also "virtual class ns::Derived;" + * - Pure virtual (abstract) classes should list no constructors in this interface file + * - Virtual classes must have a clone() function in C++ (though it does not have to be included + * in the MATLAB interface). clone() will be called whenever an object copy is needed, instead + * of using the copy constructor (which is used for non-virtual objects). + * - Signature of clone function - will be called virtually, so must appear at least at the top of the inheritance tree + * virtual boost::shared_ptr clone() const; + * Class Templates + * - Basic templates are supported either with an explicit list of types to instantiate, + * e.g. template class Class1 { ... }; + * or with typedefs, e.g. + * template class Class2 { ... }; + * typedef Class2 MyInstantiatedClass; + * - In the class definition, appearances of the template argument(s) will be replaced with their + * instantiated types, e.g. 'void setValue(const T& value);'. + * - To refer to the instantiation of the template class itself, use 'This', i.e. 'static This Create();' + * - To create new instantiations in other modules, you must copy-and-paste the whole class definition + * into the new module, but use only your new instantiation types. + * - When forward-declaring template instantiations, use the generated/typedefed name, e.g. + * class gtsam::Class1Pose2; + * class gtsam::MyInstantiatedClass; + * Boost.serialization within Matlab: + * - you need to mark classes as being serializable in the markup file (see this file for an example). + * - There are two options currently, depending on the class. To "mark" a class as serializable, + * add a function with a particular signature so that wrap will catch it. + * - Add "void serialize()" to a class to create serialization functions for a class. + * Adding this flag subsumes the serializable() flag below. Requirements: + * - A default constructor must be publicly accessible + * - Must not be an abstract base class + * - The class must have an actual boost.serialization serialize() function. + * - 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. + */ + +/** + * Status: + * - TODO: default values for arguments + * - WORKAROUND: make multiple versions of the same function for different configurations of default arguments + * - TODO: Handle gtsam::Rot3M conversions to quaternions + * - TODO: Parse return of const ref arguments + * - TODO: Parse std::string variants and convert directly to special string + * - TODO: Add enum support + * - TODO: Add generalized serialization support via boost.serialization with hooks to matlab save/load + */ + +namespace std { + #include + template + 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 + template + class list + { + + + }; + +} + +namespace gtsam { + +//************************************************************************* +// base +//************************************************************************* + +/** gtsam namespace functions */ +bool linear_independent(Matrix A, Matrix B, double tol); + +virtual class Value { + // No constructors because this is an abstract class + + // Testable + void print(string s) const; + + // Manifold + size_t dim() const; +}; + +#include +class LieScalar { + // Standard constructors + LieScalar(); + LieScalar(double d); + + // Standard interface + double value() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieScalar& expected, double tol) const; + + // Group + static gtsam::LieScalar identity(); + gtsam::LieScalar inverse() const; + gtsam::LieScalar compose(const gtsam::LieScalar& p) const; + gtsam::LieScalar between(const gtsam::LieScalar& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieScalar retract(Vector v) const; + Vector localCoordinates(const gtsam::LieScalar& t2) const; + + // Lie group + static gtsam::LieScalar Expmap(Vector v); + static Vector Logmap(const gtsam::LieScalar& p); +}; + +#include +class LieVector { + // Standard constructors + LieVector(); + LieVector(Vector v); + + // Standard interface + Vector vector() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieVector& expected, double tol) const; + + // Group + static gtsam::LieVector identity(); + gtsam::LieVector inverse() const; + gtsam::LieVector compose(const gtsam::LieVector& p) const; + gtsam::LieVector between(const gtsam::LieVector& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieVector retract(Vector v) const; + Vector localCoordinates(const gtsam::LieVector& t2) const; + + // Lie group + static gtsam::LieVector Expmap(Vector v); + static Vector Logmap(const gtsam::LieVector& p); + + // enabling serialization functionality + void serialize() const; +}; + +#include +class LieMatrix { + // Standard constructors + LieMatrix(); + LieMatrix(Matrix v); + + // Standard interface + Matrix matrix() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieMatrix& expected, double tol) const; + + // Group + static gtsam::LieMatrix identity(); + gtsam::LieMatrix inverse() const; + gtsam::LieMatrix compose(const gtsam::LieMatrix& p) const; + gtsam::LieMatrix between(const gtsam::LieMatrix& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieMatrix retract(Vector v) const; + Vector localCoordinates(const gtsam::LieMatrix & t2) const; + + // Lie group + static gtsam::LieMatrix Expmap(Vector v); + static Vector Logmap(const gtsam::LieMatrix& p); + + // enabling serialization functionality + void serialize() const; +}; + +//************************************************************************* +// geometry +//************************************************************************* + +class Point2 { + // Standard Constructors + Point2(); + Point2(double x, double y); + Point2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Point2& pose, double tol) const; + + // Group + static gtsam::Point2 identity(); + gtsam::Point2 inverse() const; + gtsam::Point2 compose(const gtsam::Point2& p2) const; + gtsam::Point2 between(const gtsam::Point2& p2) const; + + // Manifold + gtsam::Point2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Point2& p) const; + + // Lie Group + static gtsam::Point2 Expmap(Vector v); + static Vector Logmap(const gtsam::Point2& p); + + // Standard Interface + double x() const; + double y() const; + Vector vector() const; + double dist(const gtsam::Point2& p2) const; + double norm() const; + + // enabling serialization functionality + void serialize() const; +}; + +// std::vector +class Point2Vector +{ + // Constructors + Point2Vector(); + Point2Vector(const gtsam::Point2Vector& v); + + //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 + gtsam::Point2 at(size_t n) const; + gtsam::Point2 front() const; + gtsam::Point2 back() const; + + //Modifiers + void assign(size_t n, const gtsam::Point2& u); + void push_back(const gtsam::Point2& x); + void pop_back(); +}; + +class StereoPoint2 { + // Standard Constructors + StereoPoint2(); + StereoPoint2(double uL, double uR, double v); + + // Testable + void print(string s) const; + bool equals(const gtsam::StereoPoint2& point, double tol) const; + + // Group + static gtsam::StereoPoint2 identity(); + gtsam::StereoPoint2 inverse() const; + gtsam::StereoPoint2 compose(const gtsam::StereoPoint2& p2) const; + gtsam::StereoPoint2 between(const gtsam::StereoPoint2& p2) const; + + // Manifold + gtsam::StereoPoint2 retract(Vector v) const; + Vector localCoordinates(const gtsam::StereoPoint2& p) const; + + // Lie Group + static gtsam::StereoPoint2 Expmap(Vector v); + static Vector Logmap(const gtsam::StereoPoint2& p); + + // Standard Interface + Vector vector() const; + double uL() const; + double uR() const; + double v() const; + + // enabling serialization functionality + void serialize() const; +}; + +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(); + gtsam::Point3 inverse() const; + gtsam::Point3 compose(const gtsam::Point3& p2) const; + gtsam::Point3 between(const gtsam::Point3& p2) const; + + // Manifold + gtsam::Point3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Point3& p) const; + + // Lie Group + static gtsam::Point3 Expmap(Vector v); + static Vector Logmap(const gtsam::Point3& p); + + // Standard Interface + Vector vector() const; + double x() const; + double y() const; + double z() const; + + // enabling serialization functionality + void serialize() const; +}; + +class Rot2 { + // Standard Constructors and Named Constructors + Rot2(); + Rot2(double theta); + static gtsam::Rot2 fromAngle(double theta); + static gtsam::Rot2 fromDegrees(double theta); + static gtsam::Rot2 fromCosSin(double c, double s); + + // Testable + void print(string s) const; + bool equals(const gtsam::Rot2& rot, double tol) const; + + // Group + static gtsam::Rot2 identity(); + gtsam::Rot2 inverse(); + gtsam::Rot2 compose(const gtsam::Rot2& p2) const; + gtsam::Rot2 between(const gtsam::Rot2& p2) const; + + // Manifold + gtsam::Rot2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Rot2& p) const; + + // Lie Group + static gtsam::Rot2 Expmap(Vector v); + static Vector Logmap(const gtsam::Rot2& p); + + // Group Action on Point2 + gtsam::Point2 rotate(const gtsam::Point2& point) const; + gtsam::Point2 unrotate(const gtsam::Point2& point) const; + + // Standard Interface + static gtsam::Rot2 relativeBearing(const gtsam::Point2& d); // Ignoring derivative + static gtsam::Rot2 atan2(double y, double x); + double theta() const; + double degrees() const; + double c() const; + double s() const; + Matrix matrix() const; + + // enabling serialization functionality + void serialize() const; +}; + +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; +}; + +class Pose2 { + // Standard Constructor + Pose2(); + 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); + Pose2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Pose2& pose, double tol) const; + + // Group + static gtsam::Pose2 identity(); + gtsam::Pose2 inverse() const; + gtsam::Pose2 compose(const gtsam::Pose2& p2) const; + gtsam::Pose2 between(const gtsam::Pose2& p2) const; + + // Manifold + gtsam::Pose2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Pose2& p) const; + + // Lie Group + static gtsam::Pose2 Expmap(Vector v); + static Vector Logmap(const gtsam::Pose2& p); + Matrix AdjointMap() const; + Vector Adjoint(const Vector& xi) const; + static Matrix wedge(double vx, double vy, double w); + + // Group Actions on Point2 + gtsam::Point2 transform_from(const gtsam::Point2& p) const; + gtsam::Point2 transform_to(const gtsam::Point2& p) const; + + // Standard Interface + double x() const; + double y() const; + double theta() const; + gtsam::Rot2 bearing(const gtsam::Point2& point) const; + double range(const gtsam::Point2& point) const; + gtsam::Point2 translation() const; + gtsam::Rot2 rotation() const; + Matrix matrix() const; + + // enabling serialization functionality + void serialize() const; +}; + +class Pose3 { + // Standard Constructors + Pose3(); + 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); + + // Testable + void print(string s) const; + bool equals(const gtsam::Pose3& pose, double tol) const; + + // Group + static gtsam::Pose3 identity(); + gtsam::Pose3 inverse() const; + gtsam::Pose3 compose(const gtsam::Pose3& p2) const; + gtsam::Pose3 between(const gtsam::Pose3& p2) const; + + // Manifold + gtsam::Pose3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Pose3& T2) const; + + // Lie Group + static gtsam::Pose3 Expmap(Vector v); + static Vector Logmap(const gtsam::Pose3& p); + Matrix AdjointMap() const; + Vector Adjoint(Vector xi) const; + static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz); + + // Group Action on Point3 + gtsam::Point3 transform_from(const gtsam::Point3& p) const; + gtsam::Point3 transform_to(const gtsam::Point3& p) const; + + // Standard Interface + gtsam::Rot3 rotation() const; + gtsam::Point3 translation() const; + double x() const; + double y() const; + double z() const; + Matrix matrix() const; + gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to() + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& pose); + + // enabling serialization functionality + void serialize() const; +}; + +// std::vector +class Pose3Vector +{ + Pose3Vector(); + size_t size() const; + bool empty() const; + gtsam::Pose3 at(size_t n) const; + void push_back(const gtsam::Pose3& x); +}; + +#include +class Unit3 { + // Standard Constructors + Unit3(); + Unit3(const gtsam::Point3& pose); + + // Testable + void print(string s) const; + bool equals(const gtsam::Unit3& pose, double tol) const; + + // Other functionality + Matrix basis() const; + Matrix skew() const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Unit3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Unit3& s) const; +}; + +#include +class EssentialMatrix { + // Standard Constructors + EssentialMatrix(const gtsam::Rot3& aRb, const gtsam::Unit3& aTb); + + // Testable + void print(string s) const; + bool equals(const gtsam::EssentialMatrix& pose, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::EssentialMatrix retract(Vector v) const; + Vector localCoordinates(const gtsam::EssentialMatrix& s) const; + + // Other methods: + gtsam::Rot3 rotation() const; + gtsam::Unit3 direction() const; + Matrix matrix() const; + double error(Vector vA, Vector vB); +}; + +class Cal3_S2 { + // Standard Constructors + Cal3_S2(); + Cal3_S2(double fx, double fy, double s, double u0, double v0); + Cal3_S2(Vector v); + Cal3_S2(double fov, int w, int h); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3_S2& rhs, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Cal3_S2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3_S2& c) const; + + // Action on Point2 + gtsam::Point2 calibrate(const gtsam::Point2& p) const; + gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + gtsam::Point2 principalPoint() const; + Vector vector() const; + Matrix matrix() const; + Matrix matrix_inverse() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class Cal3DS2_Base { + // Standard Constructors + Cal3DS2_Base(); + + // Testable + void print(string s) const; + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + double k1() const; + double k2() const; + + // 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; +}; + +#include +virtual class Cal3DS2 : gtsam::Cal3DS2_Base { + // Standard Constructors + Cal3DS2(); + Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2); + Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2); + Cal3DS2(Vector v); + + // Testable + bool equals(const gtsam::Cal3DS2& rhs, double tol) const; + + // Manifold + size_t dim() const; + static size_t Dim(); + gtsam::Cal3DS2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3DS2& c) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class Cal3Unified : gtsam::Cal3DS2_Base { + // Standard Constructors + Cal3Unified(); + Cal3Unified(double fx, double fy, double s, double u0, double v0, double k1, double k2); + Cal3Unified(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2, double xi); + Cal3Unified(Vector v); + + // Testable + bool equals(const gtsam::Cal3Unified& rhs, double tol) const; + + // Standard Interface + double xi() const; + gtsam::Point2 spaceToNPlane(const gtsam::Point2& p) const; + gtsam::Point2 nPlaneToSpace(const gtsam::Point2& p) const; + + // Manifold + size_t dim() const; + static size_t Dim(); + gtsam::Cal3Unified retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3Unified& c) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +class Cal3_S2Stereo { + // Standard Constructors + Cal3_S2Stereo(); + Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b); + Cal3_S2Stereo(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3_S2Stereo& K, double tol) const; + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + gtsam::Point2 principalPoint() const; + double baseline() const; +}; + +#include +class Cal3Bundler { + // Standard Constructors + Cal3Bundler(); + Cal3Bundler(double fx, double k1, double k2, double u0, double v0); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3Bundler& rhs, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Cal3Bundler retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3Bundler& c) const; + + // 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 + double fx() const; + double fy() const; + double k1() const; + double k2() const; + double u0() const; + double v0() const; + Vector vector() const; + Vector k() const; + //Matrix K() const; //FIXME: Uppercase + + // enabling serialization functionality + void serialize() const; +}; + +class CalibratedCamera { + // Standard Constructors and Named Constructors + CalibratedCamera(); + CalibratedCamera(const gtsam::Pose3& pose); + CalibratedCamera(const Vector& v); + static gtsam::CalibratedCamera Level(const gtsam::Pose2& pose2, double height); + + // Testable + void print(string s) const; + bool equals(const gtsam::CalibratedCamera& camera, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::CalibratedCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + + // Action on Point3 + gtsam::Point2 project(const gtsam::Point3& point) const; + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); + + // Standard Interface + gtsam::Pose3 pose() const; + double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods + + // enabling serialization functionality + void serialize() const; +}; + +template +class PinholeCamera { + // Standard Constructors and Named Constructors + PinholeCamera(); + PinholeCamera(const gtsam::Pose3& pose); + PinholeCamera(const gtsam::Pose3& pose, const CALIBRATION& K); + static This Level(const CALIBRATION& K, const gtsam::Pose2& pose, double height); + static This Level(const gtsam::Pose2& pose, double height); + static This Lookat(const gtsam::Point3& eye, const gtsam::Point3& target, + const gtsam::Point3& upVector, const CALIBRATION& K); + + // Testable + void print(string s) const; + bool equals(const This& camera, double tol) const; + + // Standard Interface + gtsam::Pose3 pose() const; + CALIBRATION calibration() const; + + // Manifold + This retract(const Vector& d) const; + Vector localCoordinates(const This& T2) const; + size_t dim() const; + static size_t Dim(); + + // Transformations and measurement functions + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); + pair projectSafe(const gtsam::Point3& pw) const; + gtsam::Point2 project(const gtsam::Point3& point); + gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& point); + + // enabling serialization functionality + void serialize() const; +}; + +virtual class SimpleCamera { + // Standard Constructors and Named Constructors + SimpleCamera(); + SimpleCamera(const gtsam::Pose3& pose); + SimpleCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2& K); + static gtsam::SimpleCamera Level(const gtsam::Cal3_S2& K, const gtsam::Pose2& pose, double height); + static gtsam::SimpleCamera Level(const gtsam::Pose2& pose, double height); + static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, const gtsam::Point3& target, + const gtsam::Point3& upVector, const gtsam::Cal3_S2& K); + + // Testable + void print(string s) const; + bool equals(const gtsam::SimpleCamera& camera, double tol) const; + + // Standard Interface + gtsam::Pose3 pose() const; + gtsam::Cal3_S2 calibration() const; + + // Manifold + gtsam::SimpleCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::SimpleCamera& T2) const; + size_t dim() const; + static size_t Dim(); + + // Transformations and measurement functions + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); + pair projectSafe(const gtsam::Point3& pw) const; + gtsam::Point2 project(const gtsam::Point3& point); + gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& point); + + // enabling serialization functionality + void serialize() const; + +}; + +// Some typedefs for common camera types +// PinholeCameraCal3_S2 is the same as SimpleCamera above +typedef gtsam::PinholeCamera PinholeCameraCal3_S2; +typedef gtsam::PinholeCamera PinholeCameraCal3DS2; +typedef gtsam::PinholeCamera PinholeCameraCal3Unified; +typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; + +class StereoCamera { + // Standard Constructors and Named Constructors + StereoCamera(); + StereoCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2Stereo* K); + + // Testable + void print(string s) const; + bool equals(const gtsam::StereoCamera& camera, double tol) const; + + // Standard Interface + gtsam::Pose3 pose() const; + double baseline() const; + gtsam::Cal3_S2Stereo calibration() const; + + // Manifold + gtsam::StereoCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::StereoCamera& T2) const; + size_t dim() const; + static size_t Dim(); + + // Transformations and measurement functions + gtsam::StereoPoint2 project(const gtsam::Point3& point); + gtsam::Point3 backproject(const gtsam::StereoPoint2& p) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include + +// Templates appear not yet supported for free functions +gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses, + gtsam::Cal3_S2* sharedCal, const gtsam::Point2Vector& measurements, + double rank_tol, bool optimize); +gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses, + gtsam::Cal3Bundler* sharedCal, const gtsam::Point2Vector& measurements, + double rank_tol, bool optimize); + +//************************************************************************* +// Symbolic +//************************************************************************* + +#include +virtual class SymbolicFactor { + // Standard Constructors and Named Constructors + SymbolicFactor(const gtsam::SymbolicFactor& f); + SymbolicFactor(); + SymbolicFactor(size_t j); + SymbolicFactor(size_t j1, size_t j2); + SymbolicFactor(size_t j1, size_t j2, size_t j3); + SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4); + SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5); + SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5, size_t j6); + static gtsam::SymbolicFactor FromKeys(const gtsam::KeyVector& js); + + // From Factor + size_t size() const; + void print(string s) const; + bool equals(const gtsam::SymbolicFactor& other, double tol) const; + gtsam::KeyVector keys(); +}; + +#include +virtual class SymbolicFactorGraph { + SymbolicFactorGraph(); + SymbolicFactorGraph(const gtsam::SymbolicBayesNet& bayesNet); + SymbolicFactorGraph(const gtsam::SymbolicBayesTree& bayesTree); + + // From FactorGraph + void push_back(gtsam::SymbolicFactor* factor); + void print(string s) const; + bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const; + size_t size() const; + bool exists(size_t idx) const; + + // 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); + + //Advanced Interface + void push_factor(size_t key); + void push_factor(size_t key1, size_t key2); + void push_factor(size_t key1, size_t key2, size_t key3); + void push_factor(size_t key1, size_t key2, size_t key3, size_t key4); + + gtsam::SymbolicBayesNet* eliminateSequential(); + gtsam::SymbolicBayesNet* eliminateSequential(const gtsam::Ordering& ordering); + gtsam::SymbolicBayesTree* eliminateMultifrontal(); + gtsam::SymbolicBayesTree* eliminateMultifrontal(const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::KeyVector& keys); + pair eliminatePartialMultifrontal( + const gtsam::Ordering& ordering); + pair eliminatePartialMultifrontal( + const gtsam::KeyVector& keys); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::SymbolicFactorGraph* marginal(const gtsam::KeyVector& variables); +}; + +#include +virtual class SymbolicConditional : gtsam::SymbolicFactor { + // Standard Constructors and Named Constructors + SymbolicConditional(); + SymbolicConditional(const gtsam::SymbolicConditional& other); + SymbolicConditional(size_t key); + SymbolicConditional(size_t key, size_t parent); + SymbolicConditional(size_t key, size_t parent1, size_t parent2); + SymbolicConditional(size_t key, size_t parent1, size_t parent2, size_t parent3); + static gtsam::SymbolicConditional FromKeys(const gtsam::KeyVector& keys, size_t nrFrontals); + + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicConditional& other, double tol) const; + + // Standard interface + size_t nrFrontals() const; + size_t nrParents() const; +}; + +#include +class SymbolicBayesNet { + SymbolicBayesNet(); + SymbolicBayesNet(const gtsam::SymbolicBayesNet& other); + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicBayesNet& other, double tol) const; + + // Standard interface + size_t size() const; + void saveGraph(string s) const; + gtsam::SymbolicConditional* at(size_t idx) const; + gtsam::SymbolicConditional* front() const; + gtsam::SymbolicConditional* back() const; + void push_back(gtsam::SymbolicConditional* conditional); + void push_back(const gtsam::SymbolicBayesNet& bayesNet); +}; + +#include +class SymbolicBayesTree { + + //Constructors + SymbolicBayesTree(); + 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 size(); + void saveGraph(string s) const; + void clear(); + void deleteCachedShortcuts(); + size_t numCachedSeparatorMarginals() const; + + gtsam::SymbolicConditional* marginalFactor(size_t key) const; + gtsam::SymbolicFactorGraph* joint(size_t key1, size_t key2) const; + gtsam::SymbolicBayesNet* jointBayesNet(size_t key1, size_t key2) const; +}; + +// class SymbolicBayesTreeClique { +// BayesTreeClique(); +// BayesTreeClique(CONDITIONAL* conditional); +// // BayesTreeClique(const std::pair& result) : Base(result) {} +// +// bool equals(const This& other, double tol) const; +// void print(string s) const; +// void printTree() const; // Default indent of "" +// void printTree(string indent) const; +// size_t numCachedSeparatorMarginals() const; +// +// CONDITIONAL* conditional() const; +// bool isRoot() const; +// size_t treeSize() const; +// // const std::list& children() const { return children_; } +// // derived_ptr parent() const { return parent_.lock(); } +// +// // FIXME: need wrapped versions graphs, BayesNet +// // BayesNet shortcut(derived_ptr root, Eliminate function) const; +// // FactorGraph marginal(derived_ptr root, Eliminate function) const; +// // FactorGraph joint(derived_ptr C2, derived_ptr root, Eliminate function) const; +// +// void deleteCachedShortcuts(); +// }; + +#include +class VariableIndex { + // Standard Constructors and Named Constructors + VariableIndex(); + // TODO: Templetize constructor when wrap supports it + //template + //VariableIndex(const T& factorGraph, size_t nVariables); + //VariableIndex(const T& factorGraph); + VariableIndex(const gtsam::SymbolicFactorGraph& factorGraph); + VariableIndex(const gtsam::GaussianFactorGraph& factorGraph); + VariableIndex(const gtsam::NonlinearFactorGraph& factorGraph); + VariableIndex(const gtsam::VariableIndex& other); + + // Testable + bool equals(const gtsam::VariableIndex& other, double tol) const; + void print(string s) const; + + // Standard interface + size_t size() const; + size_t nFactors() const; + size_t nEntries() const; +}; + +//************************************************************************* +// linear +//************************************************************************* + +namespace noiseModel { +#include +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; +}; + +virtual class Constrained : gtsam::noiseModel::Diagonal { + static gtsam::noiseModel::Constrained* MixedSigmas(const Vector& mu, const Vector& sigmas); + static gtsam::noiseModel::Constrained* MixedSigmas(double m, const Vector& sigmas); + static gtsam::noiseModel::Constrained* MixedVariances(const Vector& mu, const Vector& variances); + static gtsam::noiseModel::Constrained* MixedVariances(const Vector& variances); + static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& mu, const Vector& precisions); + static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& precisions); + + static gtsam::noiseModel::Constrained* All(size_t dim); + static gtsam::noiseModel::Constrained* All(size_t dim, double mu); + + gtsam::noiseModel::Constrained* unit() const; + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Isotropic : gtsam::noiseModel::Diagonal { + 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; + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Unit : gtsam::noiseModel::Isotropic { + static gtsam::noiseModel::Unit* Create(size_t dim); + 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; +}; + +virtual class Tukey: gtsam::noiseModel::mEstimator::Base { + Tukey(double k); + void print(string s) const; + static gtsam::noiseModel::mEstimator::Tukey* 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 +class Sampler { + //Constructors + Sampler(gtsam::noiseModel::Diagonal* model, int seed); + Sampler(Vector sigmas, int seed); + Sampler(int seed); + + //Standard Interface + size_t dim() const; + Vector sigmas() const; + gtsam::noiseModel::Diagonal* model() const; + Vector sample(); + Vector sampleNewModel(gtsam::noiseModel::Diagonal* model); +}; + +#include +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; +}; + +#include +virtual class GaussianFactor { + gtsam::KeyVector keys() const; + void print(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + double error(const gtsam::VectorValues& c) const; + gtsam::GaussianFactor* clone() const; + gtsam::GaussianFactor* negate() const; + Matrix augmentedInformation() const; + Matrix information() const; + Matrix augmentedJacobian() const; + pair jacobian() const; + size_t size() const; + bool empty() const; +}; + +#include +virtual class JacobianFactor : gtsam::GaussianFactor { + //Constructors + JacobianFactor(); + JacobianFactor(const gtsam::GaussianFactor& factor); + JacobianFactor(Vector b_in); + JacobianFactor(size_t i1, Matrix A1, Vector b, + const gtsam::noiseModel::Diagonal* model); + JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, Vector b, + const gtsam::noiseModel::Diagonal* model); + 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); + + //Testable + void print(string s) const; + void printKeys(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + size_t size() const; + Vector unweighted_error(const gtsam::VectorValues& c) const; + Vector error_vector(const gtsam::VectorValues& c) const; + double error(const gtsam::VectorValues& c) const; + + //Standard Interface + Matrix getA() const; + Vector getb() const; + size_t rows() const; + size_t cols() const; + bool isConstrained() const; + pair jacobianUnweighted() const; + Matrix augmentedJacobianUnweighted() const; + + void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const; + gtsam::JacobianFactor whiten() const; + + pair eliminate(const gtsam::Ordering& keys) const; + + void setModel(bool anyConstrained, const Vector& sigmas); + + gtsam::noiseModel::Diagonal* get_model() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class HessianFactor : gtsam::GaussianFactor { + //Constructors + HessianFactor(); + HessianFactor(const gtsam::GaussianFactor& factor); + HessianFactor(size_t j, Matrix G, Vector g, double f); + HessianFactor(size_t j, Vector mu, Matrix Sigma); + HessianFactor(size_t j1, size_t j2, Matrix G11, Matrix G12, Vector g1, Matrix G22, + Vector g2, double f); + HessianFactor(size_t j1, size_t j2, size_t j3, Matrix G11, Matrix G12, Matrix G13, + Vector g1, Matrix G22, Matrix G23, Vector g2, Matrix G33, Vector g3, + double f); + HessianFactor(const gtsam::GaussianFactorGraph& factors); + + //Testable + size_t size() const; + void print(string s) const; + void printKeys(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + double error(const gtsam::VectorValues& c) const; + + //Standard Interface + size_t rows() const; + Matrix info() const; + double constantTerm() const; + Vector linearTerm() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +class GaussianFactorGraph { + GaussianFactorGraph(); + GaussianFactorGraph(const gtsam::GaussianBayesNet& bayesNet); + GaussianFactorGraph(const gtsam::GaussianBayesTree& bayesTree); + + // From FactorGraph + void print(string s) const; + bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const; + size_t size() const; + gtsam::GaussianFactor* at(size_t idx) const; + gtsam::KeySet keys() const; + bool exists(size_t idx) const; + + // Building the graph + void push_back(const gtsam::GaussianFactor* factor); + void push_back(const gtsam::GaussianConditional* factor); + void push_back(const gtsam::GaussianFactorGraph& graph); + void push_back(const gtsam::GaussianBayesNet& bayesNet); + void push_back(const gtsam::GaussianBayesTree& bayesTree); + void add(const gtsam::GaussianFactor& factor); + void add(Vector b); + void add(size_t key1, Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, Vector b, + const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, size_t key3, Matrix A3, + Vector b, const gtsam::noiseModel::Diagonal* model); + + // error and probability + double error(const gtsam::VectorValues& c) const; + double probPrime(const gtsam::VectorValues& c) const; + + gtsam::GaussianFactorGraph clone() const; + gtsam::GaussianFactorGraph negate() const; + + // Optimizing and linear algebra + gtsam::VectorValues optimize() const; + gtsam::VectorValues optimize(const gtsam::Ordering& ordering) const; + gtsam::VectorValues optimizeGradientSearch() const; + gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; + gtsam::VectorValues gradientAtZero() const; + + // Elimination and marginals + gtsam::GaussianBayesNet* eliminateSequential(); + gtsam::GaussianBayesNet* eliminateSequential(const gtsam::Ordering& ordering); + gtsam::GaussianBayesTree* eliminateMultifrontal(); + gtsam::GaussianBayesTree* eliminateMultifrontal(const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::KeyVector& keys); + pair eliminatePartialMultifrontal( + const gtsam::Ordering& ordering); + pair eliminatePartialMultifrontal( + const gtsam::KeyVector& keys); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::GaussianFactorGraph* marginal(const gtsam::KeyVector& variables); + + // Conversion to matrices + Matrix sparseJacobian_() const; + Matrix augmentedJacobian() const; + Matrix augmentedJacobian(const gtsam::Ordering& ordering) const; + pair jacobian() const; + pair jacobian(const gtsam::Ordering& ordering) const; + Matrix augmentedHessian() const; + Matrix augmentedHessian(const gtsam::Ordering& ordering) const; + pair hessian() const; + pair hessian(const gtsam::Ordering& ordering) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class GaussianConditional : gtsam::GaussianFactor { + //Constructors + GaussianConditional(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + const gtsam::noiseModel::Diagonal* sigmas); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + size_t name2, Matrix T, const gtsam::noiseModel::Diagonal* sigmas); + + //Constructors with no noise model + GaussianConditional(size_t key, Vector d, Matrix R); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + size_t name2, Matrix T); + + //Standard Interface + void print(string s) const; + bool equals(const gtsam::GaussianConditional &cg, double tol) const; + + //Advanced Interface + gtsam::VectorValues solve(const gtsam::VectorValues& parents) const; + gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents, const gtsam::VectorValues& rhs) const; + void solveTransposeInPlace(gtsam::VectorValues& gy) const; + void scaleFrontalsBySigma(gtsam::VectorValues& gy) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class GaussianDensity : gtsam::GaussianConditional { + //Constructors + GaussianDensity(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); + + //Standard Interface + void print(string s) const; + bool equals(const gtsam::GaussianDensity &cg, double tol) const; + Vector mean() const; + Matrix covariance() const; +}; + +#include +virtual class GaussianBayesNet { + //Constructors + GaussianBayesNet(); + GaussianBayesNet(const gtsam::GaussianConditional* conditional); + + // Testable + void print(string s) const; + bool equals(const gtsam::GaussianBayesNet& other, double tol) const; + size_t size() const; + + // FactorGraph derived interface + size_t size() const; + gtsam::GaussianConditional* at(size_t idx) const; + gtsam::KeySet keys() const; + bool exists(size_t idx) const; + + gtsam::GaussianConditional* front() const; + gtsam::GaussianConditional* back() const; + void push_back(gtsam::GaussianConditional* conditional); + void push_back(const gtsam::GaussianBayesNet& bayesNet); + + gtsam::VectorValues optimize() const; + gtsam::VectorValues optimize(gtsam::VectorValues& solutionForMissing) const; + gtsam::VectorValues optimizeGradientSearch() const; + gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; + gtsam::VectorValues gradientAtZero() const; + double error(const gtsam::VectorValues& x) const; + double determinant() const; + double logDeterminant() const; + gtsam::VectorValues backSubstitute(const gtsam::VectorValues& gx) const; + gtsam::VectorValues backSubstituteTranspose(const gtsam::VectorValues& gx) const; +}; + +#include +virtual class GaussianBayesTree { + // Standard Constructors and Named Constructors + GaussianBayesTree(); + GaussianBayesTree(const gtsam::GaussianBayesTree& other); + bool equals(const gtsam::GaussianBayesTree& other, double tol) const; + void print(string s); + size_t size() const; + bool empty() const; + size_t numCachedSeparatorMarginals() const; + void saveGraph(string s) const; + + gtsam::VectorValues optimize() const; + gtsam::VectorValues optimizeGradientSearch() const; + gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; + gtsam::VectorValues gradientAtZero() const; + double error(const gtsam::VectorValues& x) const; + double determinant() const; + double logDeterminant() const; + Matrix marginalCovariance(size_t key) const; + gtsam::GaussianConditional* marginalFactor(size_t key) const; + gtsam::GaussianFactorGraph* joint(size_t key1, size_t key2) const; + gtsam::GaussianBayesNet* jointBayesNet(size_t key1, size_t key2) const; +}; + +class Errors { + //Constructors + Errors(); + Errors(const gtsam::VectorValues& V); + + //Testable + void print(string s); + bool equals(const gtsam::Errors& expected, double tol) const; +}; + +class GaussianISAM { + //Constructor + GaussianISAM(); + + //Standard Interface + void update(const gtsam::GaussianFactorGraph& newFactors); + void saveGraph(string s) const; + void clear(); +}; + +#include +virtual class IterativeOptimizationParameters { + string getVerbosity() const; + void setVerbosity(string s) ; + void print() const; +}; + +//virtual class IterativeSolver { +// IterativeSolver(); +// gtsam::VectorValues optimize (); +//}; + +#include +virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParameters { + ConjugateGradientParameters(); + int getMinIterations() const ; + int getMaxIterations() const ; + int getReset() const; + double getEpsilon_rel() const; + double getEpsilon_abs() const; + + void setMinIterations(int value); + void setMaxIterations(int value); + void setReset(int value); + void setEpsilon_rel(double value); + void setEpsilon_abs(double value); + void print(); +}; + +#include +virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters { + SubgraphSolverParameters(); + void print() const; +}; + +virtual class SubgraphSolver { + SubgraphSolver(const gtsam::GaussianFactorGraph &A, const gtsam::SubgraphSolverParameters ¶meters, const gtsam::Ordering& ordering); + SubgraphSolver(const gtsam::GaussianFactorGraph &Ab1, const gtsam::GaussianFactorGraph &Ab2, const gtsam::SubgraphSolverParameters ¶meters, const gtsam::Ordering& ordering); + gtsam::VectorValues optimize() const; +}; + +#include +class KalmanFilter { + KalmanFilter(size_t n); + // gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0); + gtsam::GaussianDensity* init(Vector x0, Matrix P0); + void print(string s) const; + static size_t step(gtsam::GaussianDensity* p); + gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F, + Matrix B, Vector u, const gtsam::noiseModel::Diagonal* modelQ); + gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, Matrix F, + Matrix B, Vector u, Matrix Q); + gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, Matrix A0, + Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); + gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H, + Vector z, const gtsam::noiseModel::Diagonal* model); + gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H, + Vector z, Matrix Q); +}; + +//************************************************************************* +// nonlinear +//************************************************************************* + +#include +size_t symbol(char chr, size_t index); +char symbolChr(size_t key); +size_t symbolIndex(size_t key); + +// Default keyformatter +void PrintKeyList (const gtsam::KeyList& keys); +void PrintKeyList (const gtsam::KeyList& keys, string s); +void PrintKeyVector(const gtsam::KeyVector& keys); +void PrintKeyVector(const gtsam::KeyVector& keys, string s); +void PrintKeySet (const gtsam::KeySet& keys); +void PrintKeySet (const gtsam::KeySet& keys, string s); + +#include +class LabeledSymbol { + LabeledSymbol(size_t full_key); + LabeledSymbol(const gtsam::LabeledSymbol& key); + LabeledSymbol(unsigned char valType, unsigned char label, size_t j); + + size_t key() const; + unsigned char label() const; + unsigned char chr() const; + size_t index() const; + + gtsam::LabeledSymbol upper() const; + gtsam::LabeledSymbol lower() const; + gtsam::LabeledSymbol newChr(unsigned char c) const; + gtsam::LabeledSymbol newLabel(unsigned char label) const; + + void print(string s) const; +}; + +size_t mrsymbol(unsigned char c, unsigned char label, size_t j); +unsigned char mrsymbolChr(size_t key); +unsigned char mrsymbolLabel(size_t key); +size_t mrsymbolIndex(size_t key); + +#include +class Ordering { + // Standard Constructors and Named Constructors + Ordering(); + Ordering(const gtsam::Ordering& other); + + // Testable + void print(string s) const; + bool equals(const gtsam::Ordering& ord, double tol) const; + + // Standard interface + size_t size() const; + size_t at(size_t key) const; + void push_back(size_t key); + + // enabling serialization functionality + void serialize() const; +}; + +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& constraints) const; + gtsam::GaussianFactorGraph* linearize(const gtsam::Values& values) const; + gtsam::NonlinearFactorGraph clone() const; + + // enabling serialization functionality + void serialize() const; +}; + +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 +}; + +virtual class NoiseModelFactor: gtsam::NonlinearFactor { + void equals(const gtsam::NoiseModelFactor& other, double tol) const; + gtsam::noiseModel::Base* get_noiseModel() const; + Vector unwhitenedError(const gtsam::Values& x) const; + Vector whitenedError(const gtsam::Values& x) const; +}; + +#include +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; + + void insert(size_t j, const gtsam::Point2& t); + void insert(size_t j, const gtsam::Point3& t); + void insert(size_t j, const gtsam::Rot2& t); + void insert(size_t j, const gtsam::Pose2& t); + void insert(size_t j, const gtsam::Rot3& t); + void insert(size_t j, const gtsam::Pose3& t); + void insert(size_t j, const gtsam::Cal3_S2& t); + void insert(size_t j, const gtsam::Cal3DS2& t); + void insert(size_t j, const gtsam::Cal3Bundler& t); + void insert(size_t j, const gtsam::EssentialMatrix& t); + void insert(size_t j, const gtsam::SimpleCamera& t); + void insert(size_t j, const gtsam::imuBias::ConstantBias& t); + void insert(size_t j, Vector t); + void insert(size_t j, Matrix t); + + // Fixed size version + void insertFixed(size_t j, Vector t, size_t n); + + void update(size_t j, const gtsam::Point2& t); + void update(size_t j, const gtsam::Point3& t); + void update(size_t j, const gtsam::Rot2& t); + void update(size_t j, const gtsam::Pose2& t); + void update(size_t j, const gtsam::Rot3& t); + void update(size_t j, const gtsam::Pose3& t); + void update(size_t j, const gtsam::Cal3_S2& t); + void update(size_t j, const gtsam::Cal3DS2& t); + void update(size_t j, const gtsam::Cal3Bundler& t); + void update(size_t j, const gtsam::EssentialMatrix& t); + void update(size_t j, const gtsam::imuBias::ConstantBias& t); + void update(size_t j, Vector t); + void update(size_t j, Matrix t); + + template + T at(size_t j); + + /// Fixed size versions, for n in 1..9 + void insertFixed(size_t j, Vector t, size_t n); + + /// Fixed size versions, for n in 1..9 + Vector atFixed(size_t j, size_t n); + + /// version for double + void insertDouble(size_t j, double c); + double atDouble(size_t j) const; +}; + +// Actually a FastList +#include +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 +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 +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 +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 +class Marginals { + Marginals(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& solution); + + void print(string s) const; + Matrix marginalCovariance(size_t variable) const; + Matrix marginalInformation(size_t variable) const; + gtsam::JointMarginal jointMarginalCovariance(const gtsam::KeyVector& variables) const; + gtsam::JointMarginal jointMarginalInformation(const gtsam::KeyVector& variables) const; +}; + +class JointMarginal { + Matrix at(size_t iVariable, size_t jVariable) const; + Matrix fullMatrix() const; + void print(string s) const; + void print() const; +}; + +#include +virtual class LinearContainerFactor : gtsam::NonlinearFactor { + + LinearContainerFactor(gtsam::GaussianFactor* factor, const gtsam::Values& linearizationPoint); + LinearContainerFactor(gtsam::GaussianFactor* factor); + + gtsam::GaussianFactor* factor() const; +// const boost::optional& linearizationPoint() const; + + bool isJacobian() const; + gtsam::JacobianFactor* toJacobian() const; + gtsam::HessianFactor* toHessian() const; + + static gtsam::NonlinearFactorGraph convertLinearGraph(const gtsam::GaussianFactorGraph& linear_graph, + const gtsam::Values& linearizationPoint); + + static gtsam::NonlinearFactorGraph convertLinearGraph(const gtsam::GaussianFactorGraph& linear_graph); + + // enabling serialization functionality + void serializable() const; +}; // \class LinearContainerFactor + +// Summarization functionality +//#include +// +//// Uses partial QR approach by default +//gtsam::GaussianFactorGraph summarize( +// const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values, +// const gtsam::KeySet& saved_keys); +// +//gtsam::NonlinearFactorGraph summarizeAsNonlinearContainer( +// const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values, +// const gtsam::KeySet& saved_keys); + +//************************************************************************* +// Nonlinear optimizers +//************************************************************************* + +#include +#include +virtual class NonlinearOptimizerParams { + NonlinearOptimizerParams(); + void print(string s) const; + + int getMaxIterations() const; + double getRelativeErrorTol() const; + double getAbsoluteErrorTol() const; + double getErrorTol() const; + string getVerbosity() const; + + void setMaxIterations(int value); + void setRelativeErrorTol(double value); + void setAbsoluteErrorTol(double value); + void setErrorTol(double value); + void setVerbosity(string s); + + string getLinearSolverType() const; + + void setLinearSolverType(string solver); + void setOrdering(const gtsam::Ordering& ordering); + void setIterativeParams(gtsam::IterativeOptimizationParameters* params); + + bool isMultifrontal() const; + bool isSequential() const; + bool isCholmod() const; + bool isIterative() const; +}; + +bool checkConvergence(double relativeErrorTreshold, + double absoluteErrorTreshold, double errorThreshold, + double currentError, double newError); + +#include +virtual class GaussNewtonParams : gtsam::NonlinearOptimizerParams { + GaussNewtonParams(); +}; + +#include +virtual class LevenbergMarquardtParams : gtsam::NonlinearOptimizerParams { + LevenbergMarquardtParams(); + + double getlambdaInitial() const; + double getlambdaFactor() const; + double getlambdaUpperBound() const; + string getVerbosityLM() const; + + void setlambdaInitial(double value); + void setlambdaFactor(double value); + void setlambdaUpperBound(double value); + void setVerbosityLM(string s); +}; + +#include +virtual class DoglegParams : gtsam::NonlinearOptimizerParams { + DoglegParams(); + + double getDeltaInitial() const; + string getVerbosityDL() const; + + void setDeltaInitial(double deltaInitial) const; + void setVerbosityDL(string verbosityDL) const; +}; + +virtual class NonlinearOptimizer { + gtsam::Values optimize(); + gtsam::Values optimizeSafely(); + double error() const; + int iterations() const; + gtsam::Values values() const; + void iterate() const; +}; + +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); +}; + +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; +}; + +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); + double lambda() const; + void print(string str) const; +}; + +#include +class ISAM2GaussNewtonParams { + ISAM2GaussNewtonParams(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + double getWildfireThreshold() const; + void setWildfireThreshold(double wildfireThreshold); +}; + +class ISAM2DoglegParams { + ISAM2DoglegParams(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + double getWildfireThreshold() const; + void setWildfireThreshold(double wildfireThreshold); + double getInitialDelta() const; + void setInitialDelta(double initialDelta); + string getAdaptationMode() const; + void setAdaptationMode(string adaptationMode); + bool isVerbose() const; + void setVerbose(bool verbose); +}; + +class ISAM2ThresholdMapValue { + ISAM2ThresholdMapValue(char c, Vector thresholds); + ISAM2ThresholdMapValue(const gtsam::ISAM2ThresholdMapValue& other); +}; + +class ISAM2ThresholdMap { + ISAM2ThresholdMap(); + ISAM2ThresholdMap(const gtsam::ISAM2ThresholdMap& other); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + void insert(const gtsam::ISAM2ThresholdMapValue& value) const; +}; + +class ISAM2Params { + ISAM2Params(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& params); + void setOptimizationParams(const gtsam::ISAM2DoglegParams& params); + void setRelinearizeThreshold(double relinearizeThreshold); + void setRelinearizeThreshold(const gtsam::ISAM2ThresholdMap& relinearizeThreshold); + int getRelinearizeSkip() const; + void setRelinearizeSkip(int relinearizeSkip); + bool isEnableRelinearization() const; + void setEnableRelinearization(bool enableRelinearization); + bool isEvaluateNonlinearError() const; + void setEvaluateNonlinearError(bool evaluateNonlinearError); + string getFactorization() const; + void setFactorization(string factorization); + bool isCacheLinearizedFactors() const; + void setCacheLinearizedFactors(bool cacheLinearizedFactors); + bool isEnableDetailedResults() const; + void setEnableDetailedResults(bool enableDetailedResults); + bool isEnablePartialRelinearizationCheck() const; + void setEnablePartialRelinearizationCheck(bool enablePartialRelinearizationCheck); +}; + +class ISAM2Clique { + + //Constructors + ISAM2Clique(); + + //Standard Interface + Vector gradientContribution() const; + void print(string s); +}; + +class ISAM2Result { + ISAM2Result(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + size_t getVariablesRelinearized() const; + size_t getVariablesReeliminated() const; + size_t getCliques() const; +}; + +class ISAM2 { + ISAM2(); + ISAM2(const gtsam::ISAM2Params& params); + ISAM2(const gtsam::ISAM2& other); + + bool equals(const gtsam::ISAM2& other, double tol) const; + void print(string s) const; + void printStats() const; + void saveGraph(string s) const; + + gtsam::ISAM2Result update(); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, const gtsam::KeyGroupMap& constrainedKeys); + // TODO: wrap the full version of update + //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys); + //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys, bool force_relinearize); + + gtsam::Values getLinearizationPoint() const; + gtsam::Values calculateEstimate() const; + gtsam::Value calculateEstimate(size_t key) const; + gtsam::Values calculateBestEstimate() const; + Matrix marginalCovariance(size_t key) const; + gtsam::VectorValues getDelta() const; + gtsam::NonlinearFactorGraph getFactorsUnsafe() const; + gtsam::VariableIndex getVariableIndex() const; + gtsam::ISAM2Params params() const; +}; + +#include +class NonlinearISAM { + NonlinearISAM(); + NonlinearISAM(int reorderInterval); + void print(string s) const; + void printStats() const; + void saveGraph(string s) const; + gtsam::Values estimate() const; + Matrix marginalCovariance(size_t key) const; + int reorderInterval() const; + int reorderCounter() const; + void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& initialValues); + void reorder_relinearize(); + + // These might be expensive as instead of a reference the wrapper will make a copy + gtsam::GaussianISAM bayesTree() const; + gtsam::Values getLinearizationPoint() const; + gtsam::NonlinearFactorGraph getFactorsUnsafe() const; +}; + +//************************************************************************* +// Nonlinear factor types +//************************************************************************* +#include +#include +#include + +#include +template +virtual class PriorFactor : gtsam::NoiseModelFactor { + PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); + T prior() const; + + // enabling serialization functionality + void serialize() const; +}; + + +#include +template +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; +}; + + + +#include +template +virtual class NonlinearEquality : gtsam::NoiseModelFactor { + // Constructor - forces exact evaluation + NonlinearEquality(size_t j, const T& feasible); + // Constructor - allows inexact evaluation + NonlinearEquality(size_t j, const T& feasible, double error_gain); + + // enabling serialization functionality + void serialize() const; +}; + + +#include +template +virtual class RangeFactor : gtsam::NoiseModelFactor { + RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::RangeFactor RangeFactorPosePoint2; +typedef gtsam::RangeFactor RangeFactorPosePoint3; +typedef gtsam::RangeFactor RangeFactorPose2; +typedef gtsam::RangeFactor RangeFactorPose3; +typedef gtsam::RangeFactor RangeFactorCalibratedCameraPoint; +typedef gtsam::RangeFactor RangeFactorSimpleCameraPoint; +typedef gtsam::RangeFactor RangeFactorCalibratedCamera; +typedef gtsam::RangeFactor RangeFactorSimpleCamera; + + +#include +template +virtual class BearingFactor : gtsam::NoiseModelFactor { + BearingFactor(size_t key1, size_t key2, const BEARING& measured, const gtsam::noiseModel::Base* noiseModel); + + // enabling serialization functionality + void serialize() const; +}; + +typedef gtsam::BearingFactor BearingFactor2D; + +#include +template +virtual class BearingRangeFactor : gtsam::NoiseModelFactor { + BearingRangeFactor(size_t poseKey, size_t pointKey, + const BEARING& measuredBearing, const RANGE& measuredRange, + const gtsam::noiseModel::Base* noiseModel); + + // enabling serialization functionality + void serialize() const; +}; + +typedef gtsam::BearingRangeFactor BearingRangeFactor2D; + + +#include +template +virtual class GenericProjectionFactor : gtsam::NoiseModelFactor { + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k); + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k, const POSE& body_P_sensor); + + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality); + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality, + const POSE& body_P_sensor); + + gtsam::Point2 measured() const; + CALIBRATION* calibration() const; + bool verboseCheirality() const; + bool throwCheirality() const; + + // enabling serialization functionality + void serialize() const; +}; +typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3_S2; +typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3DS2; + + +#include +template +virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { + GeneralSFMFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t cameraKey, size_t landmarkKey); + gtsam::Point2 measured() const; +}; +typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; +typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; + +template +virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { + GeneralSFMFactor2(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t poseKey, size_t landmarkKey, size_t calibKey); + gtsam::Point2 measured() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +class SmartProjectionParams { + SmartProjectionParams(); + // TODO(frank): make these work: + // void setLinearizationMode(LinearizationMode linMode); + // void setDegeneracyMode(DegeneracyMode degMode); + void setRankTolerance(double rankTol); + void setEnableEPI(bool enableEPI); + void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold); + void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold); +}; + +#include +template +virtual class SmartProjectionPoseFactor: gtsam::NonlinearFactor { + + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor, + const gtsam::SmartProjectionParams& params); + + void add(const gtsam::Point2& measured_i, size_t poseKey_i); + + // enabling serialization functionality + //void serialize() const; +}; + +typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor; + + +#include +template +virtual class GenericStereoFactor : gtsam::NoiseModelFactor { + GenericStereoFactor(const gtsam::StereoPoint2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t landmarkKey, const gtsam::Cal3_S2Stereo* K); + gtsam::StereoPoint2 measured() const; + gtsam::Cal3_S2Stereo* calibration() const; + + // enabling serialization functionality + void serialize() const; +}; +typedef gtsam::GenericStereoFactor GenericStereoFactor3D; + +#include +template +virtual class PoseTranslationPrior : gtsam::NoiseModelFactor { + PoseTranslationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::PoseTranslationPrior PoseTranslationPrior2D; +typedef gtsam::PoseTranslationPrior PoseTranslationPrior3D; + +#include +template +virtual class PoseRotationPrior : gtsam::NoiseModelFactor { + PoseRotationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::PoseRotationPrior PoseRotationPrior2D; +typedef gtsam::PoseRotationPrior PoseRotationPrior3D; + +#include +virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor { + EssentialMatrixFactor(size_t key, const gtsam::Point2& pA, const gtsam::Point2& pB, + const gtsam::noiseModel::Base* noiseModel); +}; + +#include +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model); +pair load2D(string filename); +pair load2D_robust(string filename, + gtsam::noiseModel::Base* model); +void save2D(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& config, gtsam::noiseModel::Diagonal* model, + string filename); + +pair readG2o(string filename); +void writeG2o(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& estimate, string filename); + +//************************************************************************* +// Navigation +//************************************************************************* +namespace imuBias { +#include + +class ConstantBias { + // Standard Constructor + ConstantBias(); + ConstantBias(Vector biasAcc, Vector biasGyro); + + // Testable + void print(string s) const; + bool equals(const gtsam::imuBias::ConstantBias& expected, double tol) const; + + // Group + static gtsam::imuBias::ConstantBias identity(); + gtsam::imuBias::ConstantBias inverse() const; + gtsam::imuBias::ConstantBias compose(const gtsam::imuBias::ConstantBias& b) const; + gtsam::imuBias::ConstantBias between(const gtsam::imuBias::ConstantBias& b) const; + + // Manifold + gtsam::imuBias::ConstantBias retract(Vector v) const; + Vector localCoordinates(const gtsam::imuBias::ConstantBias& b) const; + + // Lie Group + static gtsam::imuBias::ConstantBias Expmap(Vector v); + static Vector Logmap(const gtsam::imuBias::ConstantBias& b); + + // Standard Interface + Vector vector() const; + Vector accelerometer() const; + Vector gyroscope() const; + Vector correctAccelerometer(Vector measurement) const; + Vector correctGyroscope(Vector measurement) const; +}; + +}///\namespace imuBias + +#include +class PoseVelocityBias{ + PoseVelocityBias(const gtsam::Pose3& pose, Vector velocity, const gtsam::imuBias::ConstantBias& bias); + }; +class PreintegratedImuMeasurements { + // Standard Constructor + PreintegratedImuMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance, bool use2ndOrderIntegration); + PreintegratedImuMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance); + // PreintegratedImuMeasurements(const gtsam::PreintegratedImuMeasurements& rhs); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegratedImuMeasurements& expected, double tol); + + double deltaTij() const; + gtsam::Rot3 deltaRij() const; + Vector deltaPij() const; + Vector deltaVij() const; + Vector biasHatVector() const; + Matrix delPdelBiasAcc() const; + Matrix delPdelBiasOmega() const; + Matrix delVdelBiasAcc() const; + Matrix delVdelBiasOmega() const; + Matrix delRdelBiasOmega() const; + Matrix preintMeasCov() const; + + // Standard Interface + void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); + gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, + Vector gravity, Vector omegaCoriolis) const; +}; + +virtual class ImuFactor : gtsam::NonlinearFactor { + ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, + const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis); + ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, + const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis, + const gtsam::Pose3& body_P_sensor); + // Standard Interface + gtsam::PreintegratedImuMeasurements preintegratedMeasurements() const; +}; + +#include +class PreintegratedCombinedMeasurements { + // Standard Constructor + PreintegratedCombinedMeasurements( + const gtsam::imuBias::ConstantBias& bias, + Matrix measuredAccCovariance, + Matrix measuredOmegaCovariance, + Matrix integrationErrorCovariance, + Matrix biasAccCovariance, + Matrix biasOmegaCovariance, + Matrix biasAccOmegaInit); + PreintegratedCombinedMeasurements( + const gtsam::imuBias::ConstantBias& bias, + Matrix measuredAccCovariance, + Matrix measuredOmegaCovariance, + Matrix integrationErrorCovariance, + Matrix biasAccCovariance, + Matrix biasOmegaCovariance, + Matrix biasAccOmegaInit, + bool use2ndOrderIntegration); + // PreintegratedCombinedMeasurements(const gtsam::PreintegratedCombinedMeasurements& rhs); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegratedCombinedMeasurements& expected, double tol); + + double deltaTij() const; + gtsam::Rot3 deltaRij() const; + Vector deltaPij() const; + Vector deltaVij() const; + Vector biasHatVector() const; + Matrix delPdelBiasAcc() const; + Matrix delPdelBiasOmega() const; + Matrix delVdelBiasAcc() const; + Matrix delVdelBiasOmega() const; + Matrix delRdelBiasOmega() const; + Matrix preintMeasCov() const; + + // Standard Interface + void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); + gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, + Vector gravity, Vector omegaCoriolis) const; +}; + +virtual class CombinedImuFactor : gtsam::NonlinearFactor { + CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias_i, size_t bias_j, + const gtsam::PreintegratedCombinedMeasurements& CombinedPreintegratedMeasurements, Vector gravity, Vector omegaCoriolis); + // Standard Interface + gtsam::PreintegratedCombinedMeasurements preintegratedMeasurements() const; +}; + +#include +class PreintegratedAhrsMeasurements { + // Standard Constructor + PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance); + PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance); + PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegratedAhrsMeasurements& expected, double tol); + + // get Data + gtsam::Rot3 deltaRij() const; + double deltaTij() const; + Vector biasHat() const; + + // Standard Interface + void integrateMeasurement(Vector measuredOmega, double deltaT); + void resetIntegration() ; +}; + +virtual class AHRSFactor : gtsam::NonlinearFactor { + AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis); + AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis, + const gtsam::Pose3& body_P_sensor); + + // Standard Interface + gtsam::PreintegratedAhrsMeasurements preintegratedMeasurements() const; + Vector evaluateError(const gtsam::Rot3& rot_i, const gtsam::Rot3& rot_j, + Vector bias) const; + gtsam::Rot3 predict(const gtsam::Rot3& rot_i, Vector bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, + Vector omegaCoriolis) const; +}; + +#include +//virtual class AttitudeFactor : gtsam::NonlinearFactor { +// AttitudeFactor(const Unit3& nZ, const Unit3& bRef); +// AttitudeFactor(); +//}; +virtual class Rot3AttitudeFactor : gtsam::NonlinearFactor{ + Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model, + const gtsam::Unit3& bRef); + Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model); + Rot3AttitudeFactor(); + void print(string s) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol) const; + gtsam::Unit3 nZ() const; + gtsam::Unit3 bRef() const; +}; + +virtual class Pose3AttitudeFactor : gtsam::NonlinearFactor{ + Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model, + const gtsam::Unit3& bRef); + Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model); + Pose3AttitudeFactor(); + void print(string s) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol) const; + gtsam::Unit3 nZ() const; + gtsam::Unit3 bRef() const; +}; + +//************************************************************************* +// Utilities +//************************************************************************* + +namespace utilities { + + #include + gtsam::KeyList createKeyList(Vector I); + gtsam::KeyList createKeyList(string s, Vector I); + gtsam::KeyVector createKeyVector(Vector I); + gtsam::KeyVector createKeyVector(string s, Vector I); + gtsam::KeySet createKeySet(Vector I); + gtsam::KeySet createKeySet(string s, Vector I); + Matrix extractPoint2(const gtsam::Values& values); + Matrix extractPoint3(const gtsam::Values& values); + Matrix extractPose2(const gtsam::Values& values); + gtsam::Values allPose3s(gtsam::Values& values); + Matrix extractPose3(const gtsam::Values& values); + void perturbPoint2(gtsam::Values& values, double sigma, int seed); + void perturbPose2 (gtsam::Values& values, double sigmaT, double sigmaR, int seed); + void perturbPoint3(gtsam::Values& values, double sigma, int seed); + void insertBackprojections(gtsam::Values& values, const gtsam::SimpleCamera& c, Vector J, Matrix Z, double depth); + void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K); + void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K, const gtsam::Pose3& body_P_sensor); + Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values); + gtsam::Values localToWorld(const gtsam::Values& local, const gtsam::Pose2& base); + gtsam::Values localToWorld(const gtsam::Values& local, const gtsam::Pose2& base, const gtsam::KeyVector& keys); + +} //\namespace utilities + +} From 4d93a33f610334068b6ea71458d2a7d788ef4c2a Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 26 Jan 2016 23:09:58 -0800 Subject: [PATCH 089/105] Static methods should be uppercase. --- .gitignore | 1 + examples/CreateSFMExampleData.cpp | 6 +- gtsam/geometry/Rot3.h | 19 ++++-- gtsam/geometry/tests/testCalibratedCamera.cpp | 4 +- gtsam/geometry/tests/testEssentialMatrix.cpp | 10 +-- gtsam/geometry/tests/testOrientedPlane3.cpp | 2 +- gtsam/geometry/tests/testPinholeCamera.cpp | 2 +- gtsam/geometry/tests/testPinholePose.cpp | 2 +- gtsam/geometry/tests/testPose3.cpp | 16 ++--- gtsam/geometry/tests/testRot3.cpp | 22 +++--- gtsam/geometry/tests/testTriangulation.cpp | 10 +-- gtsam/geometry/tests/testUnit3.cpp | 4 +- gtsam/navigation/GPSFactor.cpp | 4 +- gtsam/navigation/MagFactor.h | 2 +- gtsam/navigation/tests/testAHRSFactor.cpp | 2 +- .../tests/testCombinedImuFactor.cpp | 4 +- gtsam/navigation/tests/testGPSFactor.cpp | 2 +- gtsam/navigation/tests/testImuFactor.cpp | 10 +-- gtsam/navigation/tests/testMagFactor.cpp | 2 +- gtsam/slam/dataset.cpp | 4 +- gtsam/slam/tests/smartFactorScenarios.h | 4 +- gtsam/slam/tests/testDataset.cpp | 2 +- gtsam/slam/tests/testOrientedPlane3Factor.cpp | 4 +- gtsam/slam/tests/testPoseRotationPrior.cpp | 2 +- gtsam/slam/tests/testPoseTranslationPrior.cpp | 2 +- .../tests/testSmartProjectionCameraFactor.cpp | 4 +- .../tests/testSmartProjectionPoseFactor.cpp | 56 +++++++-------- gtsam/slam/tests/testTriangulationFactor.cpp | 2 +- gtsam_unstable/dynamics/PoseRTV.cpp | 2 +- .../dynamics/tests/testIMUSystem.cpp | 12 ++-- gtsam_unstable/dynamics/tests/testPoseRTV.cpp | 8 +-- .../dynamics/tests/testSimpleHelicopter.cpp | 2 +- gtsam_unstable/geometry/Pose3Upright.cpp | 2 +- .../geometry/tests/testInvDepthCamera3.cpp | 4 +- .../geometry/tests/testPose3Upright.cpp | 4 +- .../geometry/tests/testSimilarity3.cpp | 36 +++++----- gtsam_unstable/slam/Mechanization_bRn2.cpp | 2 +- .../slam/tests/testInvDepthFactor3.cpp | 2 +- .../slam/tests/testInvDepthFactorVariant1.cpp | 4 +- .../slam/tests/testInvDepthFactorVariant2.cpp | 4 +- .../slam/tests/testInvDepthFactorVariant3.cpp | 4 +- .../tests/testRelativeElevationFactor.cpp | 2 +- .../testSmartStereoProjectionPoseFactor.cpp | 68 +++++++++---------- 43 files changed, 184 insertions(+), 176 deletions(-) diff --git a/.gitignore b/.gitignore index d46bddd10..7850df41b 100644 --- a/.gitignore +++ b/.gitignore @@ -6,3 +6,4 @@ /examples/Data/pose3example-rewritten.txt *.txt.user *.txt.user.6d59f0c +/python-build/ diff --git a/examples/CreateSFMExampleData.cpp b/examples/CreateSFMExampleData.cpp index bcc0b6320..010f474bf 100644 --- a/examples/CreateSFMExampleData.cpp +++ b/examples/CreateSFMExampleData.cpp @@ -35,7 +35,7 @@ void createExampleBALFile(const string& filename, const vector& P, SfM_data data; // Create two cameras - Rot3 aRb = Rot3::yaw(M_PI_2); + Rot3 aRb = Rot3::Yaw(M_PI_2); Point3 aTb(0.1, 0, 0); Pose3 identity, aPb(aRb, aTb); data.cameras.push_back(SfM_Camera(pose1, K)); @@ -66,7 +66,7 @@ void createExampleBALFile(const string& filename, const vector& P, void create5PointExample1() { // Create two cameras poses - Rot3 aRb = Rot3::yaw(M_PI_2); + Rot3 aRb = Rot3::Yaw(M_PI_2); Point3 aTb(0.1, 0, 0); Pose3 pose1, pose2(aRb, aTb); @@ -85,7 +85,7 @@ void create5PointExample1() { void create5PointExample2() { // Create two cameras poses - Rot3 aRb = Rot3::yaw(M_PI_2); + Rot3 aRb = Rot3::Yaw(M_PI_2); Point3 aTb(10, 0, 0); Pose3 pose1, pose2(aRb, aTb); diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index d8b8a4682..4dd582a77 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -146,13 +146,13 @@ namespace gtsam { } /// Positive yaw is to right (as in aircraft heading). See ypr - static Rot3 yaw (double t) { return Rz(t); } + static Rot3 Yaw (double t) { return Rz(t); } /// Positive pitch is up (increasing aircraft altitude).See ypr - static Rot3 pitch(double t) { return Ry(t); } + static Rot3 Pitch(double t) { return Ry(t); } //// Positive roll is to right (increasing yaw in aircraft). - static Rot3 roll (double t) { return Rx(t); } + static Rot3 Roll (double t) { return Rx(t); } /** * Returns rotation nRb from body to nav frame. @@ -163,7 +163,7 @@ namespace gtsam { * as described in http://www.sedris.org/wg8home/Documents/WG80462.pdf. * Assumes vehicle coordinate frame X forward, Y right, Z down. */ - static Rot3 ypr(double y, double p, double r) { return RzRyRx(r,p,y);} + static Rot3 Ypr(double y, double p, double r) { return RzRyRx(r,p,y);} /** Create from Quaternion coefficients */ static Rot3 quaternion(double w, double x, double y, double z) { @@ -419,13 +419,13 @@ namespace gtsam { /** * Use RQ to calculate yaw-pitch-roll angle representation - * @return a vector containing ypr s.t. R = Rot3::ypr(y,p,r) + * @return a vector containing ypr s.t. R = Rot3::Ypr(y,p,r) */ Vector3 ypr() const; /** * Use RQ to calculate roll-pitch-yaw angle representation - * @return a vector containing ypr s.t. R = Rot3::ypr(y,p,r) + * @return a vector containing ypr s.t. R = Rot3::Ypr(y,p,r) */ Vector3 rpy() const; @@ -488,6 +488,13 @@ namespace gtsam { static Rot3 rodriguez(double wx, double wy, double wz) { return Rodrigues(wx, wy, wz); } /// @} +#ifdef ALLOW_DEPRECATED_IN_GTSAM4 + static Rot3 yaw (double t) { return Yaw(t); } + static Rot3 pitch(double t) { return Pitch(t); } + static Rot3 roll (double t) { return Roll(t); } + static Rot3 ypr(double y, double p, double r) { return Ypr(r,p,y);} +#endif + private: /** Serialization function */ diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index 3b0906b44..5bc645a58 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -135,7 +135,7 @@ TEST( CalibratedCamera, Dproject_point_pose) // Add a test with more arbitrary rotation TEST( CalibratedCamera, Dproject_point_pose2) { - static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); static const CalibratedCamera camera(pose1); Matrix Dpose, Dpoint; camera.project(point1, Dpose, Dpoint); @@ -165,7 +165,7 @@ TEST( CalibratedCamera, Dproject_point_pose_infinity) // Add a test with more arbitrary rotation TEST( CalibratedCamera, Dproject_point_pose2_infinity) { - static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); static const CalibratedCamera camera(pose1); Matrix Dpose, Dpoint; camera.project2(pointAtInfinity, Dpose, Dpoint); diff --git a/gtsam/geometry/tests/testEssentialMatrix.cpp b/gtsam/geometry/tests/testEssentialMatrix.cpp index fe27b2911..bfff0a182 100644 --- a/gtsam/geometry/tests/testEssentialMatrix.cpp +++ b/gtsam/geometry/tests/testEssentialMatrix.cpp @@ -20,7 +20,7 @@ GTSAM_CONCEPT_MANIFOLD_INST(EssentialMatrix) //************************************************************************* // Create two cameras and corresponding essential matrix E -Rot3 c1Rc2 = Rot3::yaw(M_PI_2); +Rot3 c1Rc2 = Rot3::Yaw(M_PI_2); Point3 c1Tc2(0.1, 0, 0); EssentialMatrix trueE(c1Rc2, Unit3(c1Tc2)); @@ -98,8 +98,8 @@ Point3 transform_to_(const EssentialMatrix& E, const Point3& point) { } TEST (EssentialMatrix, transform_to) { // test with a more complicated EssentialMatrix - Rot3 aRb2 = Rot3::yaw(M_PI / 3.0) * Rot3::pitch(M_PI_4) - * Rot3::roll(M_PI / 6.0); + Rot3 aRb2 = Rot3::Yaw(M_PI / 3.0) * Rot3::Pitch(M_PI_4) + * Rot3::Roll(M_PI / 6.0); Point3 aTb2(19.2, 3.7, 5.9); EssentialMatrix E(aRb2, Unit3(aTb2)); //EssentialMatrix E(aRb, Unit3(aTb).retract(Vector2(0.1, 0))); @@ -159,7 +159,7 @@ TEST (EssentialMatrix, FromPose3_a) { //************************************************************************* TEST (EssentialMatrix, FromPose3_b) { Matrix actualH; - Rot3 c1Rc2 = Rot3::ypr(0.1, -0.2, 0.3); + Rot3 c1Rc2 = Rot3::Ypr(0.1, -0.2, 0.3); Point3 c1Tc2(0.4, 0.5, 0.6); EssentialMatrix E(c1Rc2, Unit3(c1Tc2)); Pose3 pose(c1Rc2, c1Tc2); // Pose between two cameras @@ -181,7 +181,7 @@ TEST (EssentialMatrix, streaming) { //************************************************************************* TEST (EssentialMatrix, epipoles) { // Create an E - Rot3 c1Rc2 = Rot3::ypr(0.1, -0.2, 0.3); + Rot3 c1Rc2 = Rot3::Ypr(0.1, -0.2, 0.3); Point3 c1Tc2(0.4, 0.5, 0.6); EssentialMatrix E(c1Rc2, Unit3(c1Tc2)); diff --git a/gtsam/geometry/tests/testOrientedPlane3.cpp b/gtsam/geometry/tests/testOrientedPlane3.cpp index 11931449f..180abb0d6 100644 --- a/gtsam/geometry/tests/testOrientedPlane3.cpp +++ b/gtsam/geometry/tests/testOrientedPlane3.cpp @@ -59,7 +59,7 @@ OrientedPlane3 transform_(const OrientedPlane3& plane, const Pose3& xr) { } TEST (OrientedPlane3, transform) { - gtsam::Pose3 pose(gtsam::Rot3::ypr(-M_PI / 4.0, 0.0, 0.0), + gtsam::Pose3 pose(gtsam::Rot3::Ypr(-M_PI / 4.0, 0.0, 0.0), gtsam::Point3(2.0, 3.0, 4.0)); OrientedPlane3 plane(-1, 0, 0, 5); OrientedPlane3 expectedPlane(-sqrt(2.0) / 2.0, -sqrt(2.0) / 2.0, 0.0, 3); diff --git a/gtsam/geometry/tests/testPinholeCamera.cpp b/gtsam/geometry/tests/testPinholeCamera.cpp index 74bc4ca2a..7293d4235 100644 --- a/gtsam/geometry/tests/testPinholeCamera.cpp +++ b/gtsam/geometry/tests/testPinholeCamera.cpp @@ -242,7 +242,7 @@ TEST( PinholeCamera, Dproject2) // Add a test with more arbitrary rotation TEST( PinholeCamera, Dproject3) { - static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); static const Camera camera(pose1); Matrix Dpose, Dpoint; camera.project2(point1, Dpose, Dpoint); diff --git a/gtsam/geometry/tests/testPinholePose.cpp b/gtsam/geometry/tests/testPinholePose.cpp index dc294899f..8f3eadc51 100644 --- a/gtsam/geometry/tests/testPinholePose.cpp +++ b/gtsam/geometry/tests/testPinholePose.cpp @@ -172,7 +172,7 @@ TEST( PinholePose, Dproject2) // Add a test with more arbitrary rotation TEST( CalibratedCamera, Dproject3) { - static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); static const Camera camera(pose1); Matrix Dpose, Dpoint; camera.project2(point1, Dpose, Dpoint); diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 9007ce1bd..fb3907df3 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -556,12 +556,12 @@ TEST( Pose3, between ) /* ************************************************************************* */ // some shared test values - pulled from equivalent test in Pose2 Point3 l1(1, 0, 0), l2(1, 1, 0), l3(2, 2, 0), l4(1, 4,-4); -Pose3 x1, x2(Rot3::ypr(0.0, 0.0, 0.0), l2), x3(Rot3::ypr(M_PI/4.0, 0.0, 0.0), l2); +Pose3 x1, x2(Rot3::Ypr(0.0, 0.0, 0.0), l2), x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2); Pose3 - xl1(Rot3::ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)), - xl2(Rot3::ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)), - xl3(Rot3::ypr(1.0, 0.0, 0.0), Point3(2, 2, 0)), - xl4(Rot3::ypr(0.0, 0.0, 1.0), Point3(1, 4,-4)); + xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)), + xl2(Rot3::Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)), + xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0)), + xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4)); /* ************************************************************************* */ double range_proxy(const Pose3& pose, const Point3& point) { @@ -654,9 +654,9 @@ TEST( Pose3, unicycle ) { // velocity in X should be X in inertial frame, rather than global frame Vector x_step = delta(6,3,1.0); - EXPECT(assert_equal(Pose3(Rot3::ypr(0,0,0), l1), expmap_default(x1, x_step), tol)); - EXPECT(assert_equal(Pose3(Rot3::ypr(0,0,0), Point3(2,1,0)), expmap_default(x2, x_step), tol)); - EXPECT(assert_equal(Pose3(Rot3::ypr(M_PI/4.0,0,0), Point3(2,2,0)), expmap_default(x3, sqrt(2.0) * x_step), tol)); + EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), l1), expmap_default(x1, x_step), tol)); + EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), Point3(2,1,0)), expmap_default(x2, x_step), tol)); + EXPECT(assert_equal(Pose3(Rot3::Ypr(M_PI/4.0,0,0), Point3(2,2,0)), expmap_default(x3, sqrt(2.0) * x_step), tol)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index a61467b82..296bd2b7c 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -501,17 +501,17 @@ TEST( Rot3, yaw_pitch_roll ) double t = 0.1; // yaw is around z axis - CHECK(assert_equal(Rot3::Rz(t),Rot3::yaw(t))); + CHECK(assert_equal(Rot3::Rz(t),Rot3::Yaw(t))); // pitch is around y axis - CHECK(assert_equal(Rot3::Ry(t),Rot3::pitch(t))); + CHECK(assert_equal(Rot3::Ry(t),Rot3::Pitch(t))); // roll is around x axis - CHECK(assert_equal(Rot3::Rx(t),Rot3::roll(t))); + CHECK(assert_equal(Rot3::Rx(t),Rot3::Roll(t))); // Check compound rotation - Rot3 expected = Rot3::yaw(0.1) * Rot3::pitch(0.2) * Rot3::roll(0.3); - CHECK(assert_equal(expected,Rot3::ypr(0.1,0.2,0.3))); + Rot3 expected = Rot3::Yaw(0.1) * Rot3::Pitch(0.2) * Rot3::Roll(0.3); + CHECK(assert_equal(expected,Rot3::Ypr(0.1,0.2,0.3))); CHECK(assert_equal((Vector)Vector3(0.1, 0.2, 0.3),expected.ypr())); } @@ -531,14 +531,14 @@ TEST( Rot3, RQ) CHECK(assert_equal(expected,R.xyz(),1e-6)); CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::RzRyRx(0.1,0.2,0.3).xyz())); - // Try using ypr call, asserting that Rot3::ypr(y,p,r).ypr()==[y;p;r] - CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::ypr(0.1,0.2,0.3).ypr())); - CHECK(assert_equal((Vector)Vector3(0.3,0.2,0.1),Rot3::ypr(0.1,0.2,0.3).rpy())); + // Try using ypr call, asserting that Rot3::Ypr(y,p,r).ypr()==[y;p;r] + CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::Ypr(0.1,0.2,0.3).ypr())); + CHECK(assert_equal((Vector)Vector3(0.3,0.2,0.1),Rot3::Ypr(0.1,0.2,0.3).rpy())); // Try ypr for pure yaw-pitch-roll matrices - CHECK(assert_equal((Vector)Vector3(0.1,0.0,0.0),Rot3::yaw (0.1).ypr())); - CHECK(assert_equal((Vector)Vector3(0.0,0.1,0.0),Rot3::pitch(0.1).ypr())); - CHECK(assert_equal((Vector)Vector3(0.0,0.0,0.1),Rot3::roll (0.1).ypr())); + CHECK(assert_equal((Vector)Vector3(0.1,0.0,0.0),Rot3::Yaw (0.1).ypr())); + CHECK(assert_equal((Vector)Vector3(0.0,0.1,0.0),Rot3::Pitch(0.1).ypr())); + CHECK(assert_equal((Vector)Vector3(0.0,0.0,0.1),Rot3::Roll (0.1).ypr())); // Try RQ to recover calibration from 3*3 sub-block of projection matrix Matrix K = (Matrix(3, 3) << 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0).finished(); diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index bd18143cb..c3df95abc 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -40,7 +40,7 @@ static const boost::shared_ptr sharedCal = // boost::make_shared(1500, 1200, 0, 640, 480); // Looking along X-axis, 1 meter above ground plane (x-y) -static const Rot3 upright = Rot3::ypr(-M_PI / 2, 0., -M_PI / 2); +static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2); static const Pose3 pose1 = Pose3(upright, gtsam::Point3(0, 0, 1)); PinholeCamera camera1(pose1, *sharedCal); @@ -150,7 +150,7 @@ TEST( triangulation, fourPoses) { EXPECT(assert_equal(landmark, *actual2, 1e-2)); // 3. Add a slightly rotated third camera above, again with measurement noise - Pose3 pose3 = pose1 * Pose3(Rot3::ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); + Pose3 pose3 = pose1 * Pose3(Rot3::Ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); SimpleCamera camera3(pose3, *sharedCal); Point2 z3 = camera3.project(landmark); @@ -167,7 +167,7 @@ TEST( triangulation, fourPoses) { EXPECT(assert_equal(landmark, *triangulated_3cameras_opt, 1e-2)); // 4. Test failure: Add a 4th camera facing the wrong way - Pose3 pose4 = Pose3(Rot3::ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose4 = Pose3(Rot3::Ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); SimpleCamera camera4(pose4, *sharedCal); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION @@ -214,7 +214,7 @@ TEST( triangulation, fourPoses_distinct_Ks) { EXPECT(assert_equal(landmark, *actual2, 1e-2)); // 3. Add a slightly rotated third camera above, again with measurement noise - Pose3 pose3 = pose1 * Pose3(Rot3::ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); + Pose3 pose3 = pose1 * Pose3(Rot3::Ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); Cal3_S2 K3(700, 500, 0, 640, 480); SimpleCamera camera3(pose3, K3); Point2 z3 = camera3.project(landmark); @@ -232,7 +232,7 @@ TEST( triangulation, fourPoses_distinct_Ks) { EXPECT(assert_equal(landmark, *triangulated_3cameras_opt, 1e-2)); // 4. Test failure: Add a 4th camera facing the wrong way - Pose3 pose4 = Pose3(Rot3::ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose4 = Pose3(Rot3::Ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); Cal3_S2 K4(700, 500, 0, 640, 480); SimpleCamera camera4(pose4, K4); diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 3cfffa0da..dbe315807 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -70,7 +70,7 @@ static Unit3 rotate_(const Rot3& R, const Unit3& p) { } TEST(Unit3, rotate) { - Rot3 R = Rot3::yaw(0.5); + Rot3 R = Rot3::Yaw(0.5); Unit3 p(1, 0, 0); Unit3 expected = Unit3(R.column(1)); Unit3 actual = R * p; @@ -95,7 +95,7 @@ static Unit3 unrotate_(const Rot3& R, const Unit3& p) { } TEST(Unit3, unrotate) { - Rot3 R = Rot3::yaw(-M_PI / 4.0); + Rot3 R = Rot3::Yaw(-M_PI / 4.0); Unit3 p(1, 0, 0); Unit3 expected = Unit3(1, 1, 0); Unit3 actual = R.unrotate(p); diff --git a/gtsam/navigation/GPSFactor.cpp b/gtsam/navigation/GPSFactor.cpp index bfd3ebb52..87913cda6 100644 --- a/gtsam/navigation/GPSFactor.cpp +++ b/gtsam/navigation/GPSFactor.cpp @@ -58,10 +58,10 @@ pair GPSFactor::EstimateState(double t1, const Point3& NED1, // Estimate Rotation double yaw = atan2(nV.y(), nV.x()); - Rot3 nRy = Rot3::yaw(yaw); // yaw frame + Rot3 nRy = Rot3::Yaw(yaw); // yaw frame Point3 yV = nRy.inverse() * nV; // velocity in yaw frame double pitch = -atan2(yV.z(), yV.x()), roll = 0; - Rot3 nRb = Rot3::ypr(yaw, pitch, roll); + Rot3 nRb = Rot3::Ypr(yaw, pitch, roll); // Construct initial pose Pose3 nTb(nRb, nT); // nTb diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index f70bec8c6..fc1e69190 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -60,7 +60,7 @@ public: static Point3 unrotate(const Rot2& R, const Point3& p, boost::optional HR = boost::none) { - Point3 q = Rot3::yaw(R.theta()).unrotate(p, HR, boost::none); + Point3 q = Rot3::Yaw(R.theta()).unrotate(p, HR, boost::none); if (HR) { // assign to temporary first to avoid error in Win-Debug mode Matrix H = HR->col(2); diff --git a/gtsam/navigation/tests/testAHRSFactor.cpp b/gtsam/navigation/tests/testAHRSFactor.cpp index 2121eda35..02911acb1 100644 --- a/gtsam/navigation/tests/testAHRSFactor.cpp +++ b/gtsam/navigation/tests/testAHRSFactor.cpp @@ -423,7 +423,7 @@ TEST (AHRSFactor, predictTest) { // Predict Rot3 x; - Rot3 expectedRot = Rot3().ypr(20*M_PI, 0, 0); + Rot3 expectedRot = Rot3::Ypr(20*M_PI, 0, 0); Rot3 actualRot = factor.predict(x, bias, pim, kZeroOmegaCoriolis); EXPECT(assert_equal(expectedRot, actualRot, 1e-6)); diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index d473207da..e3d366d55 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -293,10 +293,10 @@ TEST(CombinedImuFactor, PredictRotation) { gravity, omegaCoriolis); // Predict - Pose3 x(Rot3().ypr(0, 0, 0), Point3(0, 0, 0)), x2; + Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; Vector3 v(0, 0, 0), v2; CombinedImuFactor::Predict(x, v, x2, v2, bias, pim, gravity, omegaCoriolis); - Pose3 expectedPose(Rot3().ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); + Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); EXPECT(assert_equal(expectedPose, x2, tol)); } diff --git a/gtsam/navigation/tests/testGPSFactor.cpp b/gtsam/navigation/tests/testGPSFactor.cpp index 8c93020c9..6149c1651 100644 --- a/gtsam/navigation/tests/testGPSFactor.cpp +++ b/gtsam/navigation/tests/testGPSFactor.cpp @@ -89,7 +89,7 @@ TEST(GPSData, init) { // Check values values EXPECT(assert_equal((Vector )Vector3(29.9575, -29.0564, -1.95993), nV, 1e-4)); - EXPECT( assert_equal(Rot3::ypr(-0.770131, 0.046928, 0), T.rotation(), 1e-5)); + EXPECT( assert_equal(Rot3::Ypr(-0.770131, 0.046928, 0), T.rotation(), 1e-5)); Point3 expectedT(2.38461, -2.31289, -0.156011); EXPECT(assert_equal(expectedT, T.translation(), 1e-5)); } diff --git a/gtsam/navigation/tests/testImuFactor.cpp b/gtsam/navigation/tests/testImuFactor.cpp index 25a6e732c..b7893281d 100644 --- a/gtsam/navigation/tests/testImuFactor.cpp +++ b/gtsam/navigation/tests/testImuFactor.cpp @@ -813,7 +813,7 @@ TEST(ImuFactor, PredictRotation) { Vector3 v2; ImuFactor::Predict(x1, v1, x2, v2, bias, pim, kGravityAlongNavZDown, kZeroOmegaCoriolis); - Pose3 expectedPose(Rot3().ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); + Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); Vector3 expectedVelocity; expectedVelocity << 0, 0, 0; EXPECT(assert_equal(expectedPose, x2)); @@ -891,7 +891,7 @@ TEST(ImuFactor, bodyPSensorNoBias) { double dt = 0.001; // Rotate sensor (z-down) to body (same as navigation) i.e. z-up - Pose3 body_P_sensor(Rot3::ypr(0, 0, M_PI), Point3(0, 0, 0)); + Pose3 body_P_sensor(Rot3::Ypr(0, 0, M_PI), Point3(0, 0, 0)); ImuFactor::PreintegratedMeasurements pim(bias, Z_3x3, Z_3x3, Z_3x3, true); @@ -907,7 +907,7 @@ TEST(ImuFactor, bodyPSensorNoBias) { PoseVelocityBias poseVelocity = pim.predict(x1, v1, bias, n_gravity, omegaCoriolis); - Pose3 expectedPose(Rot3().ypr(-M_PI / 10, 0, 0), Point3(0, 0, 0)); + Pose3 expectedPose(Rot3::Ypr(-M_PI / 10, 0, 0), Point3(0, 0, 0)); EXPECT(assert_equal(expectedPose, poseVelocity.pose)); Vector3 expectedVelocity(0, 0, 0); @@ -942,7 +942,7 @@ TEST(ImuFactor, bodyPSensorWithBias) { // table exerts an equal and opposite force w.r.t gravity Vector3 measuredAcc(0, 0, -9.81); - Pose3 body_P_sensor(Rot3::ypr(0, 0, M_PI), Point3()); + Pose3 body_P_sensor(Rot3::Ypr(0, 0, M_PI), Point3()); Matrix3 accCov = 1e-7 * I_3x3; Matrix3 gyroCov = 1e-8 * I_3x3; @@ -1025,7 +1025,7 @@ TEST(ImuFactor, serialization) { using namespace gtsam::serializationTestHelpers; Vector3 n_gravity(0, 0, -9.81); - Pose3 body_P_sensor(Rot3::ypr(0, 0, M_PI), Point3()); + Pose3 body_P_sensor(Rot3::Ypr(0, 0, M_PI), Point3()); Matrix3 accCov = 1e-7 * I_3x3; Matrix3 gyroCov = 1e-8 * I_3x3; Matrix3 integrationCov = 1e-9 * I_3x3; diff --git a/gtsam/navigation/tests/testMagFactor.cpp b/gtsam/navigation/tests/testMagFactor.cpp index 950c6ce63..38aecfcbc 100644 --- a/gtsam/navigation/tests/testMagFactor.cpp +++ b/gtsam/navigation/tests/testMagFactor.cpp @@ -40,7 +40,7 @@ Point3 nM(22653.29982, -1956.83010, 44202.47862); // Let's assume scale factor, double scale = 255.0 / 50000.0; // ...ground truth orientation, -Rot3 nRb = Rot3::yaw(-0.1); +Rot3 nRb = Rot3::Yaw(-0.1); Rot2 theta = nRb.yaw(); // ...and bias Point3 bias(10, -10, 50); diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 68c27e76b..9e71e3753 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -510,7 +510,7 @@ GraphAndValues load3D(const string& filename) { Key id; double x, y, z, roll, pitch, yaw; ls >> id >> x >> y >> z >> roll >> pitch >> yaw; - Rot3 R = Rot3::ypr(yaw,pitch,roll); + Rot3 R = Rot3::Ypr(yaw,pitch,roll); Point3 t = Point3(x, y, z); initial->insert(id, Pose3(R,t)); } @@ -537,7 +537,7 @@ GraphAndValues load3D(const string& filename) { Key id1, id2; double x, y, z, roll, pitch, yaw; ls >> id1 >> id2 >> x >> y >> z >> roll >> pitch >> yaw; - Rot3 R = Rot3::ypr(yaw,pitch,roll); + Rot3 R = Rot3::Ypr(yaw,pitch,roll); Point3 t = Point3(x, y, z); Matrix m = eye(6); for (int i = 0; i < 6; i++) diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index 8e83ec503..ccad83f01 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -34,7 +34,7 @@ Point3 landmark4(10, 0.5, 1.2); Point3 landmark5(10, -0.5, 1.2); // First camera pose, looking along X-axis, 1 meter above ground plane (x-y) -Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); +Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); // Second camera 1 meter to the right of first camera Pose3 pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); // Third camera 1 meter above the first camera @@ -123,7 +123,7 @@ Camera cam3(pose_above, sharedBundlerK); template CAMERA perturbCameraPose(const CAMERA& camera) { - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Pose3 cameraPose = camera.pose(); Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 0406c3d27..26a00360e 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -452,7 +452,7 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ SfM_data readData; readBAL(filenameToRead, readData); - Pose3 poseChange = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3)); + Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3)); Values value; for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera diff --git a/gtsam/slam/tests/testOrientedPlane3Factor.cpp b/gtsam/slam/tests/testOrientedPlane3Factor.cpp index 4a7b4c3fe..f1e830d03 100644 --- a/gtsam/slam/tests/testOrientedPlane3Factor.cpp +++ b/gtsam/slam/tests/testOrientedPlane3Factor.cpp @@ -47,7 +47,7 @@ TEST (OrientedPlane3Factor, lm_translation_error) { // Init pose and prior. Pose Prior is needed since a single plane measurement does not fully constrain the pose Symbol init_sym('x', 0); - Pose3 init_pose(Rot3::ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); + Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); Vector sigmas(6); sigmas << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001; PriorFactor pose_prior(init_sym, init_pose, @@ -94,7 +94,7 @@ TEST (OrientedPlane3Factor, lm_rotation_error) { // Init pose and prior. Pose Prior is needed since a single plane measurement does not fully constrain the pose Symbol init_sym('x', 0); - Pose3 init_pose(Rot3::ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); + Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); PriorFactor pose_prior(init_sym, init_pose, noiseModel::Diagonal::Sigmas( (Vector(6) << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001).finished())); diff --git a/gtsam/slam/tests/testPoseRotationPrior.cpp b/gtsam/slam/tests/testPoseRotationPrior.cpp index db04a74eb..3c7d5f2b2 100644 --- a/gtsam/slam/tests/testPoseRotationPrior.cpp +++ b/gtsam/slam/tests/testPoseRotationPrior.cpp @@ -30,7 +30,7 @@ const gtsam::Key poseKey = 1; // Pose3 examples const Point3 point3A(1.0, 2.0, 3.0), point3B(4.0, 6.0, 8.0); -const Rot3 rot3A, rot3B = Rot3::pitch(-M_PI_2), rot3C = Rot3::Expmap(Vector3(0.1, 0.2, 0.3)); +const Rot3 rot3A, rot3B = Rot3::Pitch(-M_PI_2), rot3C = Rot3::Expmap(Vector3(0.1, 0.2, 0.3)); // Pose2 examples const Point2 point2A(1.0, 2.0), point2B(4.0, 6.0); diff --git a/gtsam/slam/tests/testPoseTranslationPrior.cpp b/gtsam/slam/tests/testPoseTranslationPrior.cpp index 2f39701f7..2fd471c9c 100644 --- a/gtsam/slam/tests/testPoseTranslationPrior.cpp +++ b/gtsam/slam/tests/testPoseTranslationPrior.cpp @@ -27,7 +27,7 @@ const gtsam::Key poseKey = 1; // Pose3 examples const Point3 point3A(1.0, 2.0, 3.0), point3B(4.0, 6.0, 8.0); -const Rot3 rot3A, rot3B = Rot3::pitch(-M_PI_2), rot3C = Rot3::RzRyRx(0.1, 0.2, 0.3); +const Rot3 rot3A, rot3B = Rot3::Pitch(-M_PI_2), rot3C = Rot3::RzRyRx(0.1, 0.2, 0.3); // Pose2 examples const Point2 point2A(1.0, 2.0), point2B(4.0, 6.0); diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 54bbd6c22..467aefe91 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -47,7 +47,7 @@ template PinholeCamera perturbCameraPoseAndCalibration( const PinholeCamera& camera) { GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Pose3 cameraPose = camera.pose(); Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); @@ -61,7 +61,7 @@ PinholeCamera perturbCameraPoseAndCalibration( /* ************************************************************************* */ TEST( SmartProjectionCameraFactor, perturbCameraPose) { using namespace vanilla; - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Pose3 perturbed_level_pose = level_pose.compose(noise_pose); Camera actualCamera(perturbed_level_pose, K2); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 0e2429840..1c1bc3c03 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -163,7 +163,7 @@ TEST( SmartProjectionPoseFactor, noisy ) { Values values; values.insert(x1, cam1.pose()); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); values.insert(x2, pose_right.compose(noise_pose)); @@ -196,7 +196,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ Cal3_S2::shared_ptr K(new Cal3_S2(fov,w,h)); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 cameraPose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); // body poses + Pose3 cameraPose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); // body poses Pose3 cameraPose2 = cameraPose1 * Pose3(Rot3(), Point3(1,0,0)); Pose3 cameraPose3 = cameraPose1 * Pose3(Rot3(), Point3(0,-1,0)); @@ -205,7 +205,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ SimpleCamera cam3(cameraPose3, *K); // create arbitrary body_Pose_sensor (transforms from sensor to body) - Pose3 sensor_to_body = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(1, 1, 1)); // Pose3(); // + Pose3 sensor_to_body = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(1, 1, 1)); // Pose3(); // // These are the poses we want to estimate, from camera measurements Pose3 bodyPose1 = cameraPose1.compose(sensor_to_body.inverse()); @@ -263,7 +263,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ double expectedError = 0.0; DOUBLES_EQUAL(expectedError, actualError, 1e-7) - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); Values values; values.insert(x1, bodyPose1); values.insert(x2, bodyPose2); @@ -317,8 +317,8 @@ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { groundTruth.insert(x3, cam3.pose()); DOUBLES_EQUAL(0, graph.error(groundTruth), 1e-9); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -539,8 +539,8 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -606,8 +606,8 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -667,8 +667,8 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -792,7 +792,7 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -844,7 +844,7 @@ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { graph.push_back(PriorFactor(x1, level_pose, noisePrior)); graph.push_back(PriorFactor(x2, pose_right, noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; values.insert(x1, level_pose); @@ -908,8 +908,8 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { graph.push_back(smartFactor2); graph.push_back(smartFactor3); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -995,7 +995,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac graph.push_back( PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -1063,8 +1063,8 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) graph.push_back( PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -1108,7 +1108,7 @@ TEST( SmartProjectionPoseFactor, Hessian ) { SmartFactor::shared_ptr smartFactor1(new SmartFactor(model, sharedK2)); smartFactor1->add(measurements_cam1, views); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; values.insert(x1, cam1.pose()); @@ -1148,7 +1148,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { boost::shared_ptr factor = smartFactorInstance->linearize( values); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(level_pose)); @@ -1161,7 +1161,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { // Hessian is invariant to rotations in the nondegenerate case EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-7)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; @@ -1203,7 +1203,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { boost::shared_ptr factor = smartFactor->linearize(values); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(level_pose)); @@ -1216,7 +1216,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { // Hessian is invariant to rotations in the nondegenerate case EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-7)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; @@ -1278,8 +1278,8 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); @@ -1357,8 +1357,8 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { graph.push_back( PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, cam1.pose()); diff --git a/gtsam/slam/tests/testTriangulationFactor.cpp b/gtsam/slam/tests/testTriangulationFactor.cpp index 5ac92b4a9..1d2baefee 100644 --- a/gtsam/slam/tests/testTriangulationFactor.cpp +++ b/gtsam/slam/tests/testTriangulationFactor.cpp @@ -37,7 +37,7 @@ static const boost::shared_ptr sharedCal = // boost::make_shared(1500, 1200, 0, 640, 480); // Looking along X-axis, 1 meter above ground plane (x-y) -static const Rot3 upright = Rot3::ypr(-M_PI / 2, 0., -M_PI / 2); +static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2); static const Pose3 pose1 = Pose3(upright, gtsam::Point3(0, 0, 1)); SimpleCamera camera1(pose1, *sharedCal); diff --git a/gtsam_unstable/dynamics/PoseRTV.cpp b/gtsam_unstable/dynamics/PoseRTV.cpp index 51737285a..1a7fdf3de 100644 --- a/gtsam_unstable/dynamics/PoseRTV.cpp +++ b/gtsam_unstable/dynamics/PoseRTV.cpp @@ -100,7 +100,7 @@ PoseRTV PoseRTV::flyingDynamics( double pitch2 = r2.pitch(); double forward_accel = -thrust * sin(pitch2); // r2, pitch (in global frame?) controls forward force double loss_lift = lift*fabs(sin(pitch2)); - Rot3 yaw_correction_bn = Rot3::yaw(yaw2); + Rot3 yaw_correction_bn = Rot3::Yaw(yaw2); Point3 forward(forward_accel, 0.0, 0.0); Vector Acc_n = yaw_correction_bn.rotate(forward).vector() // applies locally forward force in the global frame diff --git a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp index 3fff06de1..3fc6a0197 100644 --- a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp +++ b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp @@ -56,9 +56,9 @@ TEST( testIMUSystem, optimize_chain ) { // create a simple chain of poses to generate IMU measurements const double dt = 1.0; PoseRTV pose1, - pose2(Point3(1.0, 1.0, 0.0), Rot3::ypr(0.1, 0.0, 0.0), Velocity3(2.0, 2.0, 0.0)), - pose3(Point3(2.0, 2.0, 0.0), Rot3::ypr(0.2, 0.0, 0.0), Velocity3(0.0, 0.0, 0.0)), - pose4(Point3(3.0, 3.0, 0.0), Rot3::ypr(0.3, 0.0, 0.0), Velocity3(2.0, 2.0, 0.0)); + pose2(Point3(1.0, 1.0, 0.0), Rot3::Ypr(0.1, 0.0, 0.0), Velocity3(2.0, 2.0, 0.0)), + pose3(Point3(2.0, 2.0, 0.0), Rot3::Ypr(0.2, 0.0, 0.0), Velocity3(0.0, 0.0, 0.0)), + pose4(Point3(3.0, 3.0, 0.0), Rot3::Ypr(0.3, 0.0, 0.0), Velocity3(2.0, 2.0, 0.0)); // create measurements SharedDiagonal model = noiseModel::Unit::Create(6); @@ -102,9 +102,9 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) { // create a simple chain of poses to generate IMU measurements const double dt = 1.0; PoseRTV pose1, - pose2(Point3(1.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)), - pose3(Point3(2.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)), - pose4(Point3(3.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)); + pose2(Point3(1.0, 0.0, 0.0), Rot3::Ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)), + pose3(Point3(2.0, 0.0, 0.0), Rot3::Ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)), + pose4(Point3(3.0, 0.0, 0.0), Rot3::Ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)); // create measurements SharedDiagonal model = noiseModel::Isotropic::Sigma(9, 1.0); diff --git a/gtsam_unstable/dynamics/tests/testPoseRTV.cpp b/gtsam_unstable/dynamics/tests/testPoseRTV.cpp index 0386d8bcd..db2f8f7f8 100644 --- a/gtsam_unstable/dynamics/tests/testPoseRTV.cpp +++ b/gtsam_unstable/dynamics/tests/testPoseRTV.cpp @@ -193,7 +193,7 @@ TEST( testPoseRTV, transformed_from_1 ) { Point3 T(1.0, 2.0, 3.0); Velocity3 V(2.0, 3.0, 4.0); PoseRTV start(R, T, V); - Pose3 transform(Rot3::yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); + Pose3 transform(Rot3::Yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); Matrix actDTrans, actDGlobal; PoseRTV actual = start.transformed_from(transform, actDGlobal, actDTrans); @@ -212,7 +212,7 @@ TEST( testPoseRTV, transformed_from_2 ) { Point3 T(1.0, 2.0, 3.0); Velocity3 V(2.0, 3.0, 4.0); PoseRTV start(R, T, V); - Pose3 transform(Rot3::yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); + Pose3 transform(Rot3::Yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); Matrix actDTrans, actDGlobal; PoseRTV actual = start.transformed_from(transform, actDGlobal, actDTrans); @@ -229,14 +229,14 @@ TEST( testPoseRTV, transformed_from_2 ) { TEST(testPoseRTV, RRTMbn) { EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(kZero3))); EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(Rot3()))); - EXPECT(assert_equal(PoseRTV::RRTMbn(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMbn(Rot3::ypr(0.1, 0.2, 0.3)))); + EXPECT(assert_equal(PoseRTV::RRTMbn(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMbn(Rot3::Ypr(0.1, 0.2, 0.3)))); } /* ************************************************************************* */ TEST(testPoseRTV, RRTMnb) { EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(kZero3))); EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(Rot3()))); - EXPECT(assert_equal(PoseRTV::RRTMnb(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMnb(Rot3::ypr(0.1, 0.2, 0.3)))); + EXPECT(assert_equal(PoseRTV::RRTMnb(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMnb(Rot3::Ypr(0.1, 0.2, 0.3)))); } /* ************************************************************************* */ diff --git a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp index a0d969c4d..1fb2cf39e 100644 --- a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp +++ b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp @@ -16,7 +16,7 @@ const double tol=1e-5; const double h = 0.01; //const double deg2rad = M_PI/180.0; -//Pose3 g1(Rot3::ypr(deg2rad*10.0, deg2rad*20.0, deg2rad*30.0), Point3(100.0, 200.0, 300.0)); +//Pose3 g1(Rot3::Ypr(deg2rad*10.0, deg2rad*20.0, deg2rad*30.0), Point3(100.0, 200.0, 300.0)); Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0)); //Vector6 v1((Vector(6) << 0.1, 0.05, 0.02, 10.0, 20.0, 30.0).finished()); Vector6 V1_w((Vector(6) << 0.0, 0.0, M_PI/3, 0.0, 0.0, 30.0).finished()); diff --git a/gtsam_unstable/geometry/Pose3Upright.cpp b/gtsam_unstable/geometry/Pose3Upright.cpp index 2ab3a6a9e..f83cb19fb 100644 --- a/gtsam_unstable/geometry/Pose3Upright.cpp +++ b/gtsam_unstable/geometry/Pose3Upright.cpp @@ -64,7 +64,7 @@ Rot2 Pose3Upright::rotation2() const { /* ************************************************************************* */ Rot3 Pose3Upright::rotation() const { - return Rot3::yaw(theta()); + return Rot3::Yaw(theta()); } /* ************************************************************************* */ diff --git a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp index 2f3c763dd..6ac3389ed 100644 --- a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp +++ b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp @@ -17,7 +17,7 @@ using namespace std; using namespace gtsam; static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); -Pose3 level_pose = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); +Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); SimpleCamera level_camera(level_pose, *K); /* ************************************************************************* */ @@ -142,7 +142,7 @@ TEST(InvDepthFactor, backproject2) // backwards facing camera Vector expected((Vector(5) << -5.,-5.,2., 3., -0.1).finished()); double inv_depth(1./10); - InvDepthCamera3 inv_camera(Pose3(Rot3::ypr(1.5,0.1, -1.5), Point3(-5, -5, 2)),K); + InvDepthCamera3 inv_camera(Pose3(Rot3::Ypr(1.5,0.1, -1.5), Point3(-5, -5, 2)),K); Point2 z = inv_camera.project(expected, inv_depth); Vector5 actual_vec; diff --git a/gtsam_unstable/geometry/tests/testPose3Upright.cpp b/gtsam_unstable/geometry/tests/testPose3Upright.cpp index 0929035b6..cd54a8813 100644 --- a/gtsam_unstable/geometry/tests/testPose3Upright.cpp +++ b/gtsam_unstable/geometry/tests/testPose3Upright.cpp @@ -58,9 +58,9 @@ TEST( testPose3Upright, conversions ) { EXPECT(assert_equal(Point3(1.0, 2.0, 3.0), pose.translation(), tol)); EXPECT(assert_equal(Point2(1.0, 2.0), pose.translation2(), tol)); EXPECT(assert_equal(Rot2::fromAngle(0.1), pose.rotation2(), tol)); - EXPECT(assert_equal(Rot3::yaw(0.1), pose.rotation(), tol)); + EXPECT(assert_equal(Rot3::Yaw(0.1), pose.rotation(), tol)); EXPECT(assert_equal(Pose2(1.0, 2.0, 0.1), pose.pose2(), tol)); - EXPECT(assert_equal(Pose3(Rot3::yaw(0.1), Point3(1.0, 2.0, 3.0)), pose.pose(), tol)); + EXPECT(assert_equal(Pose3(Rot3::Yaw(0.1), Point3(1.0, 2.0, 3.0)), pose.pose(), tol)); } /* ************************************************************************* */ diff --git a/gtsam_unstable/geometry/tests/testSimilarity3.cpp b/gtsam_unstable/geometry/tests/testSimilarity3.cpp index 14dfb8f1a..849206a7d 100644 --- a/gtsam_unstable/geometry/tests/testSimilarity3.cpp +++ b/gtsam_unstable/geometry/tests/testSimilarity3.cpp @@ -56,14 +56,14 @@ TEST(Similarity3, Getters) { //****************************************************************************** TEST(Similarity3, Getters2) { - Similarity3 test(Rot3::ypr(1, 2, 3), Point3(4, 5, 6), 7); - EXPECT(assert_equal(Rot3::ypr(1, 2, 3), test.rotation())); + Similarity3 test(Rot3::Ypr(1, 2, 3), Point3(4, 5, 6), 7); + EXPECT(assert_equal(Rot3::Ypr(1, 2, 3), test.rotation())); EXPECT(assert_equal(Point3(4, 5, 6), test.translation())); EXPECT_DOUBLES_EQUAL(7.0, test.scale(), 1e-9); } TEST(Similarity3, AdjointMap) { - Similarity3 test(Rot3::ypr(1,2,3).inverse(), Point3(4,5,6), 7); + Similarity3 test(Rot3::Ypr(1,2,3).inverse(), Point3(4,5,6), 7); Matrix7 result; result << -1.5739, -2.4512, -6.3651, -50.7671, -11.2503, 16.8859, -28.0000, 6.3167, -2.9884, -0.4111, 0.8502, 8.6373, -49.7260, -35.0000, @@ -76,7 +76,7 @@ TEST(Similarity3, AdjointMap) { } TEST(Similarity3, inverse) { - Similarity3 test(Rot3::ypr(1,2,3).inverse(), Point3(4,5,6), 7); + Similarity3 test(Rot3::Ypr(1,2,3).inverse(), Point3(4,5,6), 7); Matrix3 Re; Re << -0.2248, 0.9024, -0.3676, -0.3502, -0.4269, -0.8337, @@ -87,8 +87,8 @@ TEST(Similarity3, inverse) { } TEST(Similarity3, multiplication) { - Similarity3 test1(Rot3::ypr(1,2,3).inverse(), Point3(4,5,6), 7); - Similarity3 test2(Rot3::ypr(1,2,3).inverse(), Point3(8,9,10), 11); + Similarity3 test1(Rot3::Ypr(1,2,3).inverse(), Point3(4,5,6), 7); + Similarity3 test2(Rot3::Ypr(1,2,3).inverse(), Point3(8,9,10), 11); Matrix3 re; re << 0.0688, 0.9863, -0.1496, -0.5665, -0.0848, -0.8197, @@ -117,14 +117,14 @@ TEST(Similarity3, Manifold) { v3 << 0, 0, 0, 1, 2, 3, 0; EXPECT(assert_equal(v3, sim2.localCoordinates(sim3))); -// Similarity3 other = Similarity3(Rot3::ypr(0.01, 0.02, 0.03), Point3(0.4, 0.5, 0.6), 1); - Similarity3 other = Similarity3(Rot3::ypr(0.1, 0.2, 0.3),Point3(4,5,6),1); +// Similarity3 other = Similarity3(Rot3::Ypr(0.01, 0.02, 0.03), Point3(0.4, 0.5, 0.6), 1); + Similarity3 other = Similarity3(Rot3::Ypr(0.1, 0.2, 0.3),Point3(4,5,6),1); Vector vlocal = sim.localCoordinates(other); EXPECT(assert_equal(sim.retract(vlocal), other, 1e-2)); - Similarity3 other2 = Similarity3(Rot3::ypr(0.3, 0, 0),Point3(4,5,6),1); + Similarity3 other2 = Similarity3(Rot3::Ypr(0.3, 0, 0),Point3(4,5,6),1); Rot3 R = Rot3::Rodrigues(0.3,0,0); Vector vlocal2 = sim.localCoordinates(other2); @@ -167,7 +167,7 @@ TEST(Similarity3, manifold_first_order) } TEST(Similarity3, Optimization) { - Similarity3 prior = Similarity3(Rot3::ypr(0.1, 0.2, 0.3), Point3(1, 2, 3), 4); + Similarity3 prior = Similarity3(Rot3::Ypr(0.1, 0.2, 0.3), Point3(1, 2, 3), 4); noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(7, 1); Symbol key('x',1); PriorFactor factor(key, prior, model); @@ -187,10 +187,10 @@ TEST(Similarity3, Optimization) { TEST(Similarity3, Optimization2) { Similarity3 prior = Similarity3(); - Similarity3 m1 = Similarity3(Rot3::ypr(M_PI/4.0, 0, 0), Point3(2.0, 0, 0), 1.0); - Similarity3 m2 = Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(sqrt(8)*0.9, 0, 0), 1.0); - Similarity3 m3 = Similarity3(Rot3::ypr(3*M_PI/4.0, 0, 0), Point3(sqrt(32)*0.8, 0, 0), 1.0); - Similarity3 m4 = Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(6*0.7, 0, 0), 1.0); + Similarity3 m1 = Similarity3(Rot3::Ypr(M_PI/4.0, 0, 0), Point3(2.0, 0, 0), 1.0); + Similarity3 m2 = Similarity3(Rot3::Ypr(M_PI/2.0, 0, 0), Point3(sqrt(8)*0.9, 0, 0), 1.0); + Similarity3 m3 = Similarity3(Rot3::Ypr(3*M_PI/4.0, 0, 0), Point3(sqrt(32)*0.8, 0, 0), 1.0); + Similarity3 m4 = Similarity3(Rot3::Ypr(M_PI/2.0, 0, 0), Point3(6*0.7, 0, 0), 1.0); Similarity3 loop = Similarity3(1.42); //prior.print("Goal Transform"); @@ -220,10 +220,10 @@ TEST(Similarity3, Optimization2) { Values initial; initial.insert(X(1), Similarity3()); - initial.insert(X(2), Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(1, 0, 0), 1.1)); - initial.insert(X(3), Similarity3(Rot3::ypr(2.0*M_PI/2.0, 0, 0), Point3(0.9, 1.1, 0), 1.2)); - initial.insert(X(4), Similarity3(Rot3::ypr(3.0*M_PI/2.0, 0, 0), Point3(0, 1, 0), 1.3)); - initial.insert(X(5), Similarity3(Rot3::ypr(4.0*M_PI/2.0, 0, 0), Point3(0, 0, 0), 1.0)); + initial.insert(X(2), Similarity3(Rot3::Ypr(M_PI/2.0, 0, 0), Point3(1, 0, 0), 1.1)); + initial.insert(X(3), Similarity3(Rot3::Ypr(2.0*M_PI/2.0, 0, 0), Point3(0.9, 1.1, 0), 1.2)); + initial.insert(X(4), Similarity3(Rot3::Ypr(3.0*M_PI/2.0, 0, 0), Point3(0, 1, 0), 1.3)); + initial.insert(X(5), Similarity3(Rot3::Ypr(4.0*M_PI/2.0, 0, 0), Point3(0, 0, 0), 1.0)); //initial.print("Initial Estimate\n"); diff --git a/gtsam_unstable/slam/Mechanization_bRn2.cpp b/gtsam_unstable/slam/Mechanization_bRn2.cpp index f6f1c4a5c..20ffbdd4f 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.cpp +++ b/gtsam_unstable/slam/Mechanization_bRn2.cpp @@ -60,7 +60,7 @@ Mechanization_bRn2 Mechanization_bRn2::initialize(const Matrix& U, double pitch = atan2(-g1, sqrt(g2 * g2 + g3 * g3)); double yaw = 0; // This returns body-to-nav nRb - Rot3 bRn = Rot3::ypr(yaw, pitch, roll).inverse(); + Rot3 bRn = Rot3::Ypr(yaw, pitch, roll).inverse(); return Mechanization_bRn2(bRn, x_g, x_a); } diff --git a/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp index 407c9a345..99f494ad9 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp @@ -22,7 +22,7 @@ static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); static SharedNoiseModel sigma(noiseModel::Unit::Create(2)); // camera pose at (0,0,1) looking straight along the x-axis. -Pose3 level_pose = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); +Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); SimpleCamera level_camera(level_pose, *K); typedef InvDepthFactor3 InverseDepthFactor; diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp index 99a4f90a4..3aa758701 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp @@ -24,8 +24,8 @@ using namespace gtsam; TEST( InvDepthFactorVariant1, optimize) { // Create two poses looking in the x-direction - Pose3 pose1(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.0)); - Pose3 pose2(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.5)); + Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.0)); + Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.5)); // Create a landmark 5 meters in front of pose1 (camera center at (0,0,1)) Point3 landmark(5, 0, 1); diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp index 2c85b3dad..d20fc000c 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp @@ -24,8 +24,8 @@ using namespace gtsam; TEST( InvDepthFactorVariant2, optimize) { // Create two poses looking in the x-direction - Pose3 pose1(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); - Pose3 pose2(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); + Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); + Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); // Create a landmark 5 meters in front of pose1 (camera center at (0,0,1)) Point3 landmark(5, 0, 1); diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp index ec9aa90c3..a6eed54d5 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp @@ -24,8 +24,8 @@ using namespace gtsam; TEST( InvDepthFactorVariant3, optimize) { // Create two poses looking in the x-direction - Pose3 pose1(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); - Pose3 pose2(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); + Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); + Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); // Create a landmark 5 meters in front of pose1 (camera center at (0,0,1)) Point3 landmark(5, 0, 1); diff --git a/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp index c6ad9a38b..a06c39182 100644 --- a/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp +++ b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp @@ -18,7 +18,7 @@ SharedNoiseModel model1 = noiseModel::Unit::Create(1); const double tol = 1e-5; const Pose3 pose1(Rot3(), Point3(2.0, 3.0, 4.0)); -const Pose3 pose2(Rot3::pitch(-M_PI_2), Point3(2.0, 3.0, 4.0)); +const Pose3 pose2(Rot3::Pitch(-M_PI_2), Point3(2.0, 3.0, 4.0)); const Pose3 pose3(Rot3::RzRyRx(0.1, 0.2, 0.3), Point3(2.0, 3.0, 4.0)); const Point3 point1(3.0, 4.0, 2.0); const gtsam::Key poseKey = 1, pointKey = 2; diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index 2981f675d..5bad0e171 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -115,7 +115,7 @@ TEST( SmartStereoProjectionPoseFactor, Equals ) { /* *************************************************************************/ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), + Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera level_camera(level_pose, K2); @@ -154,7 +154,7 @@ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, noisy ) { // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), + Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera level_camera(level_pose, K2); @@ -172,7 +172,7 @@ TEST( SmartStereoProjectionPoseFactor, noisy ) { Values values; values.insert(x1, level_pose); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); values.insert(x2, level_pose_right.compose(noise_pose)); @@ -206,7 +206,7 @@ TEST( SmartStereoProjectionPoseFactor, noisy ) { TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K2); // create second camera 1 meter to the right of first camera @@ -257,8 +257,8 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); @@ -354,7 +354,7 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); @@ -397,8 +397,8 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); @@ -422,7 +422,7 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); @@ -466,8 +466,8 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); @@ -490,7 +490,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); @@ -548,7 +548,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); @@ -587,7 +587,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K); // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); @@ -626,8 +626,8 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PriorFactor(x2, pose2, noisePrior)); // -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise +// // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); @@ -648,7 +648,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera @@ -684,7 +684,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PriorFactor(x2, pose2, noisePrior)); // -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); @@ -708,7 +708,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera @@ -754,7 +754,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { values.insert(x1, pose1); values.insert(x2, pose2); // initialize third pose with some noise, we expect it to move back to original pose3 - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise values.insert(x3, pose3 * noise_pose); @@ -796,7 +796,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera @@ -835,7 +835,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); // graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.1,0.1,0.1)); // smaller noise +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2*noise_pose); @@ -862,7 +862,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K); // // // create second camera 1 meter to the right of first camera @@ -908,8 +908,8 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); // graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise +// // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); @@ -935,7 +935,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // views.push_back(x2); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera @@ -955,7 +955,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor()); // smartFactor1->add(measurements_cam1,views, model, K2); // -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); @@ -977,7 +977,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera @@ -1005,7 +1005,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { smartFactorInstance->linearize(values); // hessianFactor->print("Hessian factor \n"); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(pose1)); @@ -1021,7 +1021,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-7)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; @@ -1047,7 +1047,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K2); // Second and third cameras in same place, which is a degenerate configuration @@ -1072,7 +1072,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { boost::shared_ptr hessianFactor = smartFactor->linearize( values); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(pose1)); @@ -1087,7 +1087,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-6)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; From 6eece9cc603cf20ad9a40a777819ba5d172f3940 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 26 Jan 2016 23:57:34 -0800 Subject: [PATCH 090/105] Quaternion now also uppercase --- gtsam/geometry/Rot3.cpp | 2 +- gtsam/geometry/Rot3.h | 21 +++++++++------- gtsam/geometry/Rot3M.cpp | 6 ++--- gtsam/geometry/Rot3Q.cpp | 18 ++++++------- gtsam/geometry/tests/testRot3.cpp | 4 +-- gtsam/nonlinear/tests/testAdaptAutoDiff.cpp | 2 +- gtsam/slam/dataset.cpp | 4 +-- gtsam/slam/tests/testDataset.cpp | 28 ++++++++++----------- python/handwritten/geometry/Rot3.cpp | 6 ++--- 9 files changed, 47 insertions(+), 44 deletions(-) diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index 6b28f5125..ef384c3ef 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -123,7 +123,7 @@ Vector3 Rot3::rpy() const { /* ************************************************************************* */ Vector Rot3::quaternion() const { - Quaternion q = toQuaternion(); + gtsam::Quaternion q = toQuaternion(); Vector v(4); v(0) = q.w(); v(1) = q.x(); diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 4dd582a77..5b7acb4be 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -59,7 +59,7 @@ namespace gtsam { #ifdef GTSAM_USE_QUATERNIONS /** Internal Eigen Quaternion */ - Quaternion quaternion_; + gtsam::Quaternion quaternion_; #else Matrix3 rot_; #endif @@ -166,8 +166,8 @@ namespace gtsam { static Rot3 Ypr(double y, double p, double r) { return RzRyRx(r,p,y);} /** Create from Quaternion coefficients */ - static Rot3 quaternion(double w, double x, double y, double z) { - Quaternion q(w, x, y, z); + static Rot3 Quaternion(double w, double x, double y, double z) { + gtsam::Quaternion q(w, x, y, z); return Rot3(q); } @@ -179,7 +179,7 @@ namespace gtsam { */ static Rot3 AxisAngle(const Vector3& axis, double angle) { #ifdef GTSAM_USE_QUATERNIONS - return Quaternion(Eigen::AngleAxis(angle, axis)); + return gtsam::Quaternion(Eigen::AngleAxis(angle, axis)); #else return SO3::AxisAngle(axis,angle); #endif @@ -313,7 +313,7 @@ namespace gtsam { static Rot3 Expmap(const Vector3& v, OptionalJacobian<3,3> H = boost::none) { if(H) *H = Rot3::ExpmapDerivative(v); #ifdef GTSAM_USE_QUATERNIONS - return traits::Expmap(v); + return traits::Expmap(v); #else return traits::Expmap(v); #endif @@ -460,7 +460,7 @@ namespace gtsam { /** Compute the quaternion representation of this rotation. * @return The quaternion */ - Quaternion toQuaternion() const; + gtsam::Quaternion toQuaternion() const; /** * Converts to a generic matrix to allow for use with matlab @@ -479,6 +479,8 @@ namespace gtsam { GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Rot3& p); /// @} + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// @name Deprecated /// @{ static Rot3 rodriguez(const Vector3& axis, double angle) { return AxisAngle(axis, angle); } @@ -486,13 +488,14 @@ namespace gtsam { static Rot3 rodriguez(const Unit3& axis, double angle) { return AxisAngle(axis, angle); } static Rot3 rodriguez(const Vector3& w) { return Rodrigues(w); } static Rot3 rodriguez(double wx, double wy, double wz) { return Rodrigues(wx, wy, wz); } - /// @} - -#ifdef ALLOW_DEPRECATED_IN_GTSAM4 static Rot3 yaw (double t) { return Yaw(t); } static Rot3 pitch(double t) { return Pitch(t); } static Rot3 roll (double t) { return Roll(t); } static Rot3 ypr(double y, double p, double r) { return Ypr(r,p,y);} + static Rot3 quaternion(double w, double x, double y, double z) { + return Rot3::Quaternion q(w, x, y, z); + } + /// @} #endif private: diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index a7b654070..c3636000b 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -51,7 +51,7 @@ Rot3::Rot3(double R11, double R12, double R13, } /* ************************************************************************* */ -Rot3::Rot3(const Quaternion& q) : rot_(q.toRotationMatrix()) { +Rot3::Rot3(const gtsam::Quaternion& q) : rot_(q.toRotationMatrix()) { } /* ************************************************************************* */ @@ -191,8 +191,8 @@ Point3 Rot3::r2() const { return Point3(rot_.col(1)); } Point3 Rot3::r3() const { return Point3(rot_.col(2)); } /* ************************************************************************* */ -Quaternion Rot3::toQuaternion() const { - return Quaternion(rot_); +gtsam::Quaternion Rot3::toQuaternion() const { + return gtsam::Quaternion(rot_); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Rot3Q.cpp b/gtsam/geometry/Rot3Q.cpp index 2497f6806..f8a01141b 100644 --- a/gtsam/geometry/Rot3Q.cpp +++ b/gtsam/geometry/Rot3Q.cpp @@ -47,30 +47,30 @@ namespace gtsam { R31, R32, R33).finished()) {} /* ************************************************************************* */ - Rot3::Rot3(const Quaternion& q) : + Rot3::Rot3(const gtsam::Quaternion& q) : quaternion_(q) { } /* ************************************************************************* */ Rot3 Rot3::Rx(double t) { - return Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitX())); + return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitX())); } /* ************************************************************************* */ Rot3 Rot3::Ry(double t) { - return Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitY())); + return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitY())); } /* ************************************************************************* */ Rot3 Rot3::Rz(double t) { - return Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitZ())); + return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitZ())); } /* ************************************************************************* */ Rot3 Rot3::RzRyRx(double x, double y, double z) { return Rot3( - Quaternion(Eigen::AngleAxisd(z, Eigen::Vector3d::UnitZ())) * - Quaternion(Eigen::AngleAxisd(y, Eigen::Vector3d::UnitY())) * - Quaternion(Eigen::AngleAxisd(x, Eigen::Vector3d::UnitX()))); + gtsam::Quaternion(Eigen::AngleAxisd(z, Eigen::Vector3d::UnitZ())) * + gtsam::Quaternion(Eigen::AngleAxisd(y, Eigen::Vector3d::UnitY())) * + gtsam::Quaternion(Eigen::AngleAxisd(x, Eigen::Vector3d::UnitX()))); } /* ************************************************************************* */ @@ -98,7 +98,7 @@ namespace gtsam { /* ************************************************************************* */ Vector3 Rot3::Logmap(const Rot3& R, OptionalJacobian<3, 3> H) { - return traits::Logmap(R.quaternion_, H); + return traits::Logmap(R.quaternion_, H); } /* ************************************************************************* */ @@ -128,7 +128,7 @@ namespace gtsam { Point3 Rot3::r3() const { return Point3(quaternion_.toRotationMatrix().col(2)); } /* ************************************************************************* */ - Quaternion Rot3::toQuaternion() const { return quaternion_; } + gtsam::Quaternion Rot3::toQuaternion() const { return quaternion_; } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 296bd2b7c..3cf3f9387 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -594,9 +594,9 @@ TEST(Rot3, quaternion) { // Check creating Rot3 from quaternion EXPECT(assert_equal(R1, Rot3(q1))); - EXPECT(assert_equal(R1, Rot3::quaternion(q1.w(), q1.x(), q1.y(), q1.z()))); + EXPECT(assert_equal(R1, Rot3::Quaternion(q1.w(), q1.x(), q1.y(), q1.z()))); EXPECT(assert_equal(R2, Rot3(q2))); - EXPECT(assert_equal(R2, Rot3::quaternion(q2.w(), q2.x(), q2.y(), q2.z()))); + EXPECT(assert_equal(R2, Rot3::Quaternion(q2.w(), q2.x(), q2.y(), q2.z()))); // Check converting Rot3 to quaterion EXPECT(assert_equal(Vector(R1.toQuaternion().coeffs()), Vector(q1.coeffs()))); diff --git a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp index 377d6cd34..16117845e 100644 --- a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp +++ b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp @@ -62,7 +62,7 @@ using namespace gtsam; // Check that ceres rotation convention is the same TEST(AdaptAutoDiff, Rotation) { Vector3 axisAngle(0.1, 0.2, 0.3); - Matrix3 expected = Rot3::rodriguez(axisAngle).matrix(); + Matrix3 expected = Rot3::Rodrigues(axisAngle).matrix(); Matrix3 actual; ceres::AngleAxisToRotationMatrix(axisAngle.data(), actual.data()); EXPECT(assert_equal(expected, actual)); diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 9e71e3753..50516afe4 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -518,7 +518,7 @@ GraphAndValues load3D(const string& filename) { Key id; double x, y, z, qx, qy, qz, qw; ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw; - Rot3 R = Rot3::quaternion(qw, qx, qy, qz); + Rot3 R = Rot3::Quaternion(qw, qx, qy, qz); Point3 t = Point3(x, y, z); initial->insert(id, Pose3(R,t)); } @@ -553,7 +553,7 @@ GraphAndValues load3D(const string& filename) { Key id1, id2; double x, y, z, qx, qy, qz, qw; ls >> id1 >> id2 >> x >> y >> z >> qx >> qy >> qz >> qw; - Rot3 R = Rot3::quaternion(qw, qx, qy, qz); + Rot3 R = Rot3::Quaternion(qw, qx, qy, qz); Point3 t = Point3(x, y, z); for (int i = 0; i < 6; i++){ for (int j = i; j < 6; j++){ diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 26a00360e..4e8e3dbf3 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -137,23 +137,23 @@ TEST( dataSet, readG2o3D) boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D); Values expectedValues; - Rot3 R0 = Rot3::quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); + Rot3 R0 = Rot3::Quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); Point3 p0 = Point3(0.000000, 0.000000, 0.000000); expectedValues.insert(0, Pose3(R0, p0)); - Rot3 R1 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R1 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); Point3 p1 = Point3(1.001367, 0.015390, 0.004948); expectedValues.insert(1, Pose3(R1, p1)); - Rot3 R2 = Rot3::quaternion(0.421446, -0.351729, -0.597838, 0.584174 ); + Rot3 R2 = Rot3::Quaternion(0.421446, -0.351729, -0.597838, 0.584174 ); Point3 p2 = Point3(1.993500, 0.023275, 0.003793); expectedValues.insert(2, Pose3(R2, p2)); - Rot3 R3 = Rot3::quaternion(0.067024, 0.331798, -0.200659, 0.919323); + Rot3 R3 = Rot3::Quaternion(0.067024, 0.331798, -0.200659, 0.919323); Point3 p3 = Point3(2.004291, 1.024305, 0.018047); expectedValues.insert(3, Pose3(R3, p3)); - Rot3 R4 = Rot3::quaternion(0.765488, -0.035697, -0.462490, 0.445933); + Rot3 R4 = Rot3::Quaternion(0.765488, -0.035697, -0.462490, 0.445933); Point3 p4 = Point3(0.999908, 1.055073, 0.020212); expectedValues.insert(4, Pose3(R4, p4)); @@ -163,27 +163,27 @@ TEST( dataSet, readG2o3D) NonlinearFactorGraph expectedGraph; Point3 p01 = Point3(1.001367, 0.015390, 0.004948); - Rot3 R01 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R01 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); expectedGraph.add(BetweenFactor(0, 1, Pose3(R01,p01), model)); Point3 p12 = Point3(0.523923, 0.776654, 0.326659); - Rot3 R12 = Rot3::quaternion(0.105373 , 0.311512, 0.656877, -0.678505 ); + Rot3 R12 = Rot3::Quaternion(0.105373 , 0.311512, 0.656877, -0.678505 ); expectedGraph.add(BetweenFactor(1, 2, Pose3(R12,p12), model)); Point3 p23 = Point3(0.910927, 0.055169, -0.411761); - Rot3 R23 = Rot3::quaternion(0.568551 , 0.595795, -0.561677, 0.079353 ); + Rot3 R23 = Rot3::Quaternion(0.568551 , 0.595795, -0.561677, 0.079353 ); expectedGraph.add(BetweenFactor(2, 3, Pose3(R23,p23), model)); Point3 p34 = Point3(0.775288, 0.228798, -0.596923); - Rot3 R34 = Rot3::quaternion(0.542221 , -0.592077, 0.303380, -0.513226 ); + Rot3 R34 = Rot3::Quaternion(0.542221 , -0.592077, 0.303380, -0.513226 ); expectedGraph.add(BetweenFactor(3, 4, Pose3(R34,p34), model)); Point3 p14 = Point3(-0.577841, 0.628016, -0.543592); - Rot3 R14 = Rot3::quaternion(0.327419 , -0.125250, -0.534379, 0.769122 ); + Rot3 R14 = Rot3::Quaternion(0.327419 , -0.125250, -0.534379, 0.769122 ); expectedGraph.add(BetweenFactor(1, 4, Pose3(R14,p14), model)); Point3 p30 = Point3(-0.623267, 0.086928, 0.773222); - Rot3 R30 = Rot3::quaternion(0.083672 , 0.104639, 0.627755, 0.766795 ); + Rot3 R30 = Rot3::Quaternion(0.083672 , 0.104639, 0.627755, 0.766795 ); expectedGraph.add(BetweenFactor(3, 0, Pose3(R30,p30), model)); EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); @@ -199,11 +199,11 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D); Values expectedValues; - Rot3 R0 = Rot3::quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); + Rot3 R0 = Rot3::Quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); Point3 p0 = Point3(0.000000, 0.000000, 0.000000); expectedValues.insert(0, Pose3(R0, p0)); - Rot3 R1 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R1 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); Point3 p1 = Point3(1.001367, 0.015390, 0.004948); expectedValues.insert(1, Pose3(R1, p1)); @@ -223,7 +223,7 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) noiseModel::Gaussian::shared_ptr model = noiseModel::Gaussian::Covariance(Info.inverse()); NonlinearFactorGraph expectedGraph; Point3 p01 = Point3(1.001367, 0.015390, 0.004948); - Rot3 R01 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R01 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); expectedGraph.add(BetweenFactor(0, 1, Pose3(R01,p01), model)); EXPECT(assert_equal(expectedGraph,*actualGraph,1e-2)); diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp index b4551ca5c..68643fe2c 100644 --- a/python/handwritten/geometry/Rot3.cpp +++ b/python/handwritten/geometry/Rot3.cpp @@ -27,12 +27,12 @@ using namespace gtsam; static Rot3 Quaternion_0(const Vector4& q) { - return Rot3::quaternion(q[0],q[1],q[2],q[3]); + return Rot3::Quaternion(q[0],q[1],q[2],q[3]); } static Rot3 Quaternion_1(double w, double x, double y, double z) { - return Rot3::quaternion(w,x,y,z); + return Rot3::Quaternion(w,x,y,z); } // Prototypes used to perform overloading @@ -108,4 +108,4 @@ void exportRot3(){ .def(repr(self)) // __repr__ ; -} \ No newline at end of file +} From f078741ed402322393870ab6c9a82ff9fa7658f1 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 26 Jan 2016 23:57:44 -0800 Subject: [PATCH 091/105] New GTSAM option --- CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index e8da98ffd..71f2dd939 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -65,6 +65,7 @@ option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" ON) option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) option(GTSAM_BUILD_PYTHON "Enable/Disable building & installation of Python module" ON) +option(GTSAM_ALLOW_DEPRECATED_SINCE_V4 "Allow use of methods/functions deprecated in GTSAM 4" ON) # Options relating to MATLAB wrapper # TODO: Check for matlab mex binary before handling building of binaries @@ -471,6 +472,7 @@ print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default R print_config_flag(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") print_config_flag(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") print_config_flag(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") +print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V4} "Deprecated in GTSAM 4 allowed ") message(STATUS "MATLAB toolbox flags ") print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") From 88fad4caffeceeccd13455a1aab62ad1e4db6aad Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 27 Jan 2016 09:24:49 -0800 Subject: [PATCH 092/105] Fix small bugs with MATLAB wrapping --- gtsam.h | 10 +++++----- gtsam/geometry/triangulation.h | 1 + gtsam/sam/RangeFactor.h | 3 +-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam.h b/gtsam.h index ca014ad5d..57a1e09be 100644 --- a/gtsam.h +++ b/gtsam.h @@ -434,11 +434,11 @@ class Rot3 { 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 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 diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index bec901830..c6e613b14 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -19,6 +19,7 @@ #pragma once #include +#include #include #include #include diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index 1ad27865d..a5bcac822 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -31,8 +31,7 @@ struct Range; * Works for any two types A1,A2 for which the functor Range() is defined * @addtogroup SAM */ -template ::result_type> +template class RangeFactor : public ExpressionFactor2 { private: typedef RangeFactor This; From 540772819b2e58189c1d00db1fd024c31952cbe9 Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 27 Jan 2016 22:07:46 -0800 Subject: [PATCH 093/105] Added definition --- CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 71f2dd939..9d543b87b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -318,6 +318,10 @@ if(GTSAM_ENABLE_CONSISTENCY_CHECKS) add_definitions(-DGTSAM_EXTRA_CONSISTENCY_CHECKS) endif() +if(GTSAM_ENABLE_CONSISTENCY_CHECKS) + add_definitions(-DGTSAM_ALLOW_DEPRECATED_SINCE_V4) +endif() + ############################################################################### # Add components From 73f9b9d3fb75386997d2b08953efea7d6a50ec08 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:26:43 -0800 Subject: [PATCH 094/105] Better behaved numerics --- gtsam/geometry/SO3.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/geometry/SO3.cpp b/gtsam/geometry/SO3.cpp index a417164e4..ca80167f4 100644 --- a/gtsam/geometry/SO3.cpp +++ b/gtsam/geometry/SO3.cpp @@ -47,7 +47,7 @@ SO3 SO3::AxisAngle(const Vector3& axis, double theta) { // get components of axis \omega, where is a unit vector const double& wx = axis.x(), wy = axis.y(), wz = axis.z(); - const double costheta = cos(theta), sintheta = sin(theta), c_1 = 1 - costheta; + const double costheta = cos(theta), sintheta = sin(theta), s2 = sin(theta/2.0), c_1 = 2.0*s2*s2; const double wx_sintheta = wx * sintheta, wy_sintheta = wy * sintheta, wz_sintheta = wz * sintheta; @@ -130,7 +130,6 @@ Vector3 SO3::Logmap(const SO3& R, ChartJacobian H) { /* ************************************************************************* */ Matrix3 SO3::ExpmapDerivative(const Vector3& omega) { - using std::cos; using std::sin; const double theta2 = omega.dot(omega); From 27405fc1852acb1754b8d30a645c6cbf25117bc2 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:26:57 -0800 Subject: [PATCH 095/105] renaming variables --- gtsam/geometry/Pose3.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index f373e5ad4..9954240fd 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -120,9 +120,9 @@ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { Rot3 R = Rot3::Expmap(omega.vector()); double theta2 = omega.dot(omega); if (theta2 > std::numeric_limits::epsilon()) { - double omega_v = omega.dot(v); // translation parallel to axis - Point3 omega_cross_v = omega.cross(v); // points towards axis - Point3 t = (omega_cross_v - R * omega_cross_v + omega_v * omega) / theta2; + Point3 t_parallel = omega * omega.dot(v); // translation parallel to axis + Point3 omega_cross_v = omega.cross(v); // points towards axis + Point3 t = (omega_cross_v - R * omega_cross_v + t_parallel) / theta2; return Pose3(R, t); } else { return Pose3(R, v); From e66fcf8612fcc9a6a20eff1339a4b44a374276b6 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:27:18 -0800 Subject: [PATCH 096/105] New tests --- gtsam/geometry/tests/testPoint3.cpp | 11 ++++ gtsam/geometry/tests/testPose3.cpp | 37 ++++++++++- gtsam/geometry/tests/testRot3.cpp | 99 +++++++++++++++++++++++------ 3 files changed, 125 insertions(+), 22 deletions(-) diff --git a/gtsam/geometry/tests/testPoint3.cpp b/gtsam/geometry/tests/testPoint3.cpp index 6811ed122..246d23c9a 100644 --- a/gtsam/geometry/tests/testPoint3.cpp +++ b/gtsam/geometry/tests/testPoint3.cpp @@ -133,6 +133,17 @@ TEST (Point3, distance) { EXPECT(assert_equal(numH2, H2, 1e-8)); } +/* ************************************************************************* */ +TEST(Point3, cross) { + Matrix aH1, aH2; + boost::function f = + boost::bind(&Point3::cross, _1, _2, boost::none, boost::none); + const Point3 omega(0, 1, 0), theta(4, 6, 8); + omega.cross(theta, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(f, omega, theta), aH1)); + EXPECT(assert_equal(numericalDerivative22(f, omega, theta), aH2)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index fb3907df3..56e1e022c 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -715,7 +715,42 @@ TEST( Pose3, ExpmapDerivative1) { } /* ************************************************************************* */ -TEST( Pose3, LogmapDerivative1) { +TEST(Pose3, ExpmapDerivative2) { + // Iserles05an (Lie-group Methods) says: + // scalar is easy: d exp(a(t)) / dt = exp(a(t)) a'(t) + // matrix is hard: d exp(A(t)) / dt = exp(A(t)) dexp[-A(t)] A'(t) + // where A(t): T -> se(3) is a trajectory in the tangent space of SE(3) + // and dexp[A] is a linear map from 4*4 to 4*4 derivatives of se(3) + // Hence, the above matrix equation is typed: 4*4 = SE(3) * linear_map(4*4) + + // In GTSAM, we don't work with the Lie-algebra elements A directly, but with 6-vectors. + // xi is easy: d Expmap(xi(t)) / dt = ExmapDerivative[xi(t)] * xi'(t) + + // Let's verify the above formula. + + auto xi = [](double t) { + Vector6 v; + v << 2 * t, sin(t), 4 * t * t, 2 * t, sin(t), 4 * t * t; + return v; + }; + auto xi_dot = [](double t) { + Vector6 v; + v << 2, cos(t), 8 * t, 2, cos(t), 8 * t; + return v; + }; + + // We define a function T + auto T = [xi](double t) { return Pose3::Expmap(xi(t)); }; + + for (double t = -2.0; t < 2.0; t += 0.3) { + const Matrix expected = numericalDerivative11(T, t); + const Matrix actual = Pose3::ExpmapDerivative(xi(t)) * xi_dot(t); + CHECK(assert_equal(expected, actual, 1e-7)); + } +} + +/* ************************************************************************* */ +TEST( Pose3, LogmapDerivative) { Matrix6 actualH; Vector6 w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0; Pose3 p = Pose3::Expmap(w); diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 3cf3f9387..25ddd16ce 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -244,44 +244,99 @@ TEST(Rot3, retract_localCoordinates2) EXPECT(assert_equal(t1, t2.retract(d21))); } /* ************************************************************************* */ -Vector w = Vector3(0.1, 0.27, -0.2); - -// Left trivialization Derivative of exp(w) wrpt w: +namespace exmap_derivative { +static const Vector3 w(0.1, 0.27, -0.2); +} +// Left trivialized Derivative of exp(w) wrpt w: // How does exp(w) change when w changes? // We find a y such that: exp(w) exp(y) = exp(w + dw) for dw --> 0 // => y = log (exp(-w) * exp(w+dw)) Vector3 testDexpL(const Vector3& dw) { + using exmap_derivative::w; return Rot3::Logmap(Rot3::Expmap(-w) * Rot3::Expmap(w + dw)); } TEST( Rot3, ExpmapDerivative) { - Matrix actualDexpL = Rot3::ExpmapDerivative(w); - Matrix expectedDexpL = numericalDerivative11(testDexpL, + using exmap_derivative::w; + const Matrix actualDexpL = Rot3::ExpmapDerivative(w); + const Matrix expectedDexpL = numericalDerivative11(testDexpL, Vector3::Zero(), 1e-2); EXPECT(assert_equal(expectedDexpL, actualDexpL,1e-7)); - Matrix actualDexpInvL = Rot3::LogmapDerivative(w); + const Matrix actualDexpInvL = Rot3::LogmapDerivative(w); EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL,1e-7)); + } + +/* ************************************************************************* */ +TEST( Rot3, ExpmapDerivative2) +{ + const Vector3 theta(0.1, 0, 0.1); + const Matrix Jexpected = numericalDerivative11( + boost::bind(&Rot3::Expmap, _1, boost::none), theta); + + CHECK(assert_equal(Jexpected, Rot3::ExpmapDerivative(theta))); + CHECK(assert_equal(Matrix3(Jexpected.transpose()), Rot3::ExpmapDerivative(-theta))); } /* ************************************************************************* */ -Vector3 thetahat(0.1, 0, 0.1); -TEST( Rot3, ExpmapDerivative2) +TEST( Rot3, ExpmapDerivative3) { - Matrix Jexpected = numericalDerivative11( - boost::bind(&Rot3::Expmap, _1, boost::none), thetahat); + const Vector3 theta(10, 20, 30); + const Matrix Jexpected = numericalDerivative11( + boost::bind(&Rot3::Expmap, _1, boost::none), theta); - Matrix Jactual = Rot3::ExpmapDerivative(thetahat); - CHECK(assert_equal(Jexpected, Jactual)); + CHECK(assert_equal(Jexpected, Rot3::ExpmapDerivative(theta))); + CHECK(assert_equal(Matrix3(Jexpected.transpose()), Rot3::ExpmapDerivative(-theta))); +} - Matrix Jactual2 = Rot3::ExpmapDerivative(thetahat); - CHECK(assert_equal(Jexpected, Jactual2)); +/* ************************************************************************* */ +TEST(Rot3, ExpmapDerivative4) { + // Iserles05an (Lie-group Methods) says: + // scalar is easy: d exp(a(t)) / dt = exp(a(t)) a'(t) + // matrix is hard: d exp(A(t)) / dt = exp(A(t)) dexp[-A(t)] A'(t) + // where A(t): R -> so(3) is a trajectory in the tangent space of SO(3) + // and dexp[A] is a linear map from 3*3 to 3*3 derivatives of se(3) + // Hence, the above matrix equation is typed: 3*3 = SO(3) * linear_map(3*3) + + // In GTSAM, we don't work with the skew-symmetric matrices A directly, but with 3-vectors. + // omega is easy: d Expmap(w(t)) / dt = ExmapDerivative[w(t)] * w'(t) + + // Let's verify the above formula. + + auto w = [](double t) { return Vector3(2 * t, sin(t), 4 * t * t); }; + auto w_dot = [](double t) { return Vector3(2, cos(t), 8 * t); }; + + // We define a function R + auto R = [w](double t) { return Rot3::Expmap(w(t)); }; + + for (double t = -2.0; t < 2.0; t += 0.3) { + const Matrix expected = numericalDerivative11(R, t); + const Matrix actual = Rot3::ExpmapDerivative(w(t)) * w_dot(t); + CHECK(assert_equal(expected, actual, 1e-7)); + } +} + +/* ************************************************************************* */ +TEST(Rot3, ExpmapDerivative5) { + auto w = [](double t) { return Vector3(2 * t, sin(t), 4 * t * t); }; + auto w_dot = [](double t) { return Vector3(2, cos(t), 8 * t); }; + + // Same as above, but define R as mapping local coordinates to neighborhood aroud R0. + const Rot3 R0 = Rot3::Rodrigues(0.1, 0.4, 0.2); + auto R = [R0, w](double t) { return R0.expmap(w(t)); }; + + for (double t = -2.0; t < 2.0; t += 0.3) { + const Matrix expected = numericalDerivative11(R, t); + const Matrix actual = Rot3::ExpmapDerivative(w(t)) * w_dot(t); + CHECK(assert_equal(expected, actual, 1e-7)); + } } /* ************************************************************************* */ TEST( Rot3, jacobianExpmap ) { - Matrix Jexpected = numericalDerivative11(boost::bind( + const Vector3 thetahat(0.1, 0, 0.1); + const Matrix Jexpected = numericalDerivative11(boost::bind( &Rot3::Expmap, _1, boost::none), thetahat); Matrix3 Jactual; const Rot3 R = Rot3::Expmap(thetahat, Jactual); @@ -291,18 +346,20 @@ TEST( Rot3, jacobianExpmap ) /* ************************************************************************* */ TEST( Rot3, LogmapDerivative ) { - Rot3 R = Rot3::Expmap(thetahat); // some rotation - Matrix Jexpected = numericalDerivative11(boost::bind( + const Vector3 thetahat(0.1, 0, 0.1); + const Rot3 R = Rot3::Expmap(thetahat); // some rotation + const Matrix Jexpected = numericalDerivative11(boost::bind( &Rot3::Logmap, _1, boost::none), R); - Matrix3 Jactual = Rot3::LogmapDerivative(thetahat); + const Matrix3 Jactual = Rot3::LogmapDerivative(thetahat); EXPECT(assert_equal(Jexpected, Jactual)); } /* ************************************************************************* */ -TEST( Rot3, jacobianLogmap ) +TEST( Rot3, JacobianLogmap ) { - Rot3 R = Rot3::Expmap(thetahat); // some rotation - Matrix Jexpected = numericalDerivative11(boost::bind( + const Vector3 thetahat(0.1, 0, 0.1); + const Rot3 R = Rot3::Expmap(thetahat); // some rotation + const Matrix Jexpected = numericalDerivative11(boost::bind( &Rot3::Logmap, _1, boost::none), R); Matrix3 Jactual; Rot3::Logmap(R, Jactual); From a1b23b24bc6a6da5757da1f97e7a98d0e2f62722 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:27:33 -0800 Subject: [PATCH 097/105] Take ordering into account --- gtsam/linear/GaussianBayesNet.cpp | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/GaussianBayesNet.cpp b/gtsam/linear/GaussianBayesNet.cpp index b3b8b9a41..6db13adb6 100644 --- a/gtsam/linear/GaussianBayesNet.cpp +++ b/gtsam/linear/GaussianBayesNet.cpp @@ -141,7 +141,20 @@ namespace gtsam { /* ************************************************************************* */ pair GaussianBayesNet::matrix() const { - return GaussianFactorGraph(*this).jacobian(); + GaussianFactorGraph factorGraph(*this); + KeySet keys = factorGraph.keys(); + // add frontal keys in order + Ordering ordering; + BOOST_FOREACH (const sharedConditional& cg, *this) + BOOST_FOREACH (Key key, cg->frontals()) { + ordering.push_back(key); + keys.erase(key); + } + // add remaining keys in case Bayes net is incomplete + BOOST_FOREACH (Key key, keys) + ordering.push_back(key); + // return matrix and RHS + return factorGraph.jacobian(ordering); } ///* ************************************************************************* */ From 361101fdd9bb96c6ff225a7f489287d27e164e83 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:31:05 -0800 Subject: [PATCH 098/105] Improved/refactored example --- python/gtsam_examples/VisualISAM2Example.py | 72 +++++++++++---------- 1 file changed, 37 insertions(+), 35 deletions(-) diff --git a/python/gtsam_examples/VisualISAM2Example.py b/python/gtsam_examples/VisualISAM2Example.py index 4d7889e9b..9dafa13e7 100644 --- a/python/gtsam_examples/VisualISAM2Example.py +++ b/python/gtsam_examples/VisualISAM2Example.py @@ -3,19 +3,23 @@ from __future__ import print_function import matplotlib.pyplot as plt from mpl_toolkits.mplot3d import Axes3D import numpy as np -import time # for sleep() +import time # for sleep() import gtsam from gtsam_examples import SFMdata import gtsam_utils +# shorthand symbols: +X = lambda i: int(gtsam.Symbol('x', i)) +L = lambda j: int(gtsam.Symbol('l', j)) + def visual_ISAM2_plot(poses, points, result): # VisualISAMPlot plots current state of ISAM2 object # Author: Ellon Paiva # Based on MATLAB version by: Duy Nguyen Ta and Frank Dellaert # Declare an id for the figure - fignum = 0; + fignum = 0 fig = plt.figure(fignum) ax = fig.gca(projection='3d') @@ -23,33 +27,31 @@ def visual_ISAM2_plot(poses, points, result): # Plot points # Can't use data because current frame might not see all points - # marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()); # TODO - this is slow - # gtsam.plot3DPoints(result, [], marginals); - gtsam_utils.plot3DPoints(fignum, result, 'rx'); + # marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()) # TODO - this is slow + # gtsam.plot3DPoints(result, [], marginals) + gtsam_utils.plot3DPoints(fignum, result, 'rx') # Plot cameras - M = 0; - while result.exists(int(gtsam.Symbol('x',M))): - ii = int(gtsam.Symbol('x',M)); - pose_i = result.pose3_at(ii); - gtsam_utils.plotPose3(fignum, pose_i, 10); - - M = M + 1; + i = 0 + while result.exists(X(i)): + pose_i = result.atPose3(X(i)) + gtsam_utils.plotPose3(fignum, pose_i, 10) + i += 1 # draw ax.set_xlim3d(-40, 40) ax.set_ylim3d(-40, 40) ax.set_zlim3d(-40, 40) - plt.ion() - plt.show() - plt.draw() + plt.pause(1) def visual_ISAM2_example(): + plt.ion() + # Define the camera calibration parameters K = gtsam.Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) # Define the camera observation noise model - measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v + measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v # Create the set of ground-truth landmarks points = SFMdata.createPoints() @@ -78,29 +80,29 @@ def visual_ISAM2_example(): for j, point in enumerate(points): camera = gtsam.PinholeCameraCal3_S2(pose, K) measurement = camera.project(point) - graph.push_back(gtsam.GenericProjectionFactorCal3_S2(measurement, measurementNoise, int(gtsam.Symbol('x', i)), int(gtsam.Symbol('l', j)), K)) + graph.push_back(gtsam.GenericProjectionFactorCal3_S2(measurement, measurementNoise, X(i), L(j), K)) # Add an initial guess for the current pose # Intentionally initialize the variables off from the ground truth - initialEstimate.insert(int(gtsam.Symbol('x', i)), pose.compose(gtsam.Pose3(gtsam.Rot3.Rodrigues(-0.1, 0.2, 0.25), gtsam.Point3(0.05, -0.10, 0.20)))) + initialEstimate.insert(X(i), pose.compose(gtsam.Pose3(gtsam.Rot3.Rodrigues(-0.1, 0.2, 0.25), gtsam.Point3(0.05, -0.10, 0.20)))) # If this is the first iteration, add a prior on the first pose to set the coordinate frame # and a prior on the first landmark to set the scale # Also, as iSAM solves incrementally, we must wait until each is observed at least twice before # adding it to iSAM. - if( i == 0): + if(i == 0): # Add a prior on pose x0 - poseNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw - graph.push_back(gtsam.PriorFactorPose3(int(gtsam.Symbol('x', 0)), poses[0], poseNoise)) + poseNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.push_back(gtsam.PriorFactorPose3(X(0), poses[0], poseNoise)) # Add a prior on landmark l0 pointNoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) - graph.push_back(gtsam.PriorFactorPoint3(int(gtsam.Symbol('l', 0)), points[0], pointNoise)) # add directly to graph + graph.push_back(gtsam.PriorFactorPoint3(L(0), points[0], pointNoise)) # add directly to graph # Add initial guesses to all observed landmarks # Intentionally initialize the variables off from the ground truth for j, point in enumerate(points): - initialEstimate.insert(int(gtsam.Symbol('l', j)), point + gtsam.Point3(-0.25, 0.20, 0.15)); + initialEstimate.insert(L(j), point + gtsam.Point3(-0.25, 0.20, 0.15)) else: # Update iSAM with the new factors isam.update(graph, initialEstimate) @@ -108,23 +110,23 @@ def visual_ISAM2_example(): # If accuracy is desired at the expense of time, update(*) can be called additional times # to perform multiple optimizer iterations every step. isam.update() - currentEstimate = isam.calculate_estimate(); - print( "****************************************************" ) - print( "Frame", i, ":" ) - for j in range(i+1): - print( gtsam.Symbol('x',j) ) - print( currentEstimate.pose3_at(int(gtsam.Symbol('x',j))) ) + currentEstimate = isam.calculate_estimate() + print("****************************************************") + print("Frame", i, ":") + for j in range(i + 1): + print(X(j), ":", currentEstimate.atPose3(X(j))) for j in range(len(points)): - print( gtsam.Symbol('l',j) ) - print( currentEstimate.point3_at(int(gtsam.Symbol('l',j))) ) + print(L(j), ":", currentEstimate.atPoint3(L(j))) - visual_ISAM2_plot(poses, points, currentEstimate); - time.sleep(1) + visual_ISAM2_plot(poses, points, currentEstimate) # Clear the factor graph and values for the next iteration - graph.resize(0); - initialEstimate.clear(); + graph.resize(0) + initialEstimate.clear() + + plt.ioff() + plt.show() if __name__ == '__main__': visual_ISAM2_example() From 1b9b90803abc4807765c63ffab1a7dfb0713e12f Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:31:44 -0800 Subject: [PATCH 099/105] Committed to MATLAB atT methods --- python/handwritten/nonlinear/Values.cpp | 76 ++++++------------------- 1 file changed, 16 insertions(+), 60 deletions(-) diff --git a/python/handwritten/nonlinear/Values.cpp b/python/handwritten/nonlinear/Values.cpp index 6715fb071..84e82f376 100644 --- a/python/handwritten/nonlinear/Values.cpp +++ b/python/handwritten/nonlinear/Values.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -26,61 +26,17 @@ #include "gtsam/geometry/Point3.h" #include "gtsam/geometry/Rot3.h" #include "gtsam/geometry/Pose3.h" +#include "gtsam/navigation/ImuBias.h" using namespace boost::python; using namespace gtsam; -/** 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_MEMBER_FUNCTION_OVERLOADS(print_overloads, Values::print, 0, 1); void exportValues(){ - // NOTE: Apparently the class 'Value'' is deprecated, so the commented lines below - // will compile, but are useless in the python wrapper. We need to use specific - // 'at' and 'insert' methods for each type. - // const Value& (Values::*at1)(Key) const = &Values::at; - // void (Values::*insert1)(Key, const Value&) = &Values::insert; + typedef imuBias::ConstantBias Bias; + bool (Values::*exists1)(Key) const = &Values::exists; void (Values::*insert_point2)(Key, const gtsam::Point2&) = &Values::insert; void (Values::*insert_rot2) (Key, const gtsam::Rot2&) = &Values::insert; @@ -88,7 +44,8 @@ void exportValues(){ void (Values::*insert_point3)(Key, const gtsam::Point3&) = &Values::insert; void (Values::*insert_rot3) (Key, const gtsam::Rot3&) = &Values::insert; void (Values::*insert_pose3) (Key, const gtsam::Pose3&) = &Values::insert; - + void (Values::*insert_bias) (Key, const Bias&) = &Values::insert; + void (Values::*insert_vector3) (Key, const gtsam::Vector3&) = &Values::insert; class_("Values", init<>()) .def(init()) @@ -101,23 +58,22 @@ void exportValues(){ .def("print", &Values::print, print_overloads(args("s"))) .def("size", &Values::size) .def("swap", &Values::swap) - // NOTE: Following commented lines add useless methods on Values - // .def("insert", insert1) - // .def("at", at1, return_value_policy()) .def("insert", insert_point2) .def("insert", insert_rot2) .def("insert", insert_pose2) .def("insert", insert_point3) .def("insert", insert_rot3) .def("insert", insert_pose3) - // NOTE: The following commented lines are another way of specializing the return type. - // See long comment above. - // .def("at", &ValuesAt, return_internal_reference<>()) - // .def("at", &ValuesAt, return_internal_reference<>()) - // .def("at", &ValuesAt, return_internal_reference<>()) - .def("point3_at", &Values::at, return_value_policy()) - .def("rot3_at", &Values::at, return_value_policy()) - .def("pose3_at", &Values::at, return_value_policy()) + .def("insert", insert_bias) + .def("insert", insert_vector3) + .def("atPoint2", &Values::at, return_value_policy()) + .def("atRot2", &Values::at, return_value_policy()) + .def("atPose2", &Values::at, return_value_policy()) + .def("atPoint3", &Values::at, return_value_policy()) + .def("atRot3", &Values::at, return_value_policy()) + .def("atPose3", &Values::at, return_value_policy()) + .def("atConstantBias", &Values::at, return_value_policy()) + .def("atVector3", &Values::at, return_value_policy()) .def("exists", exists1) .def("keys", &Values::keys) ; From 659caa58c1d838bf092052b379ee336991169984 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:32:02 -0800 Subject: [PATCH 100/105] getNonlinearFactor --- .../nonlinear/NonlinearFactorGraph.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp index f1e14deda..4ba4ba008 100644 --- a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp +++ b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -11,7 +11,7 @@ /** * @brief exports NonlinearFactorGraph class to python - * @author Andrew Melim + * @author Andrew Melim * @author Ellon Paiva Mendes (LAAS-CNRS) **/ @@ -28,6 +28,13 @@ using namespace gtsam; BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, NonlinearFactorGraph::print, 0, 1); +boost::shared_ptr getNonlinearFactor( + const NonlinearFactorGraph& graph, size_t idx) { + auto p = boost::dynamic_pointer_cast(graph.at(idx)); + if (!p) throw std::runtime_error("No NonlinearFactor at requested index"); + return p; +}; + void exportNonlinearFactorGraph(){ typedef NonlinearFactorGraph::sharedFactor sharedFactor; @@ -36,7 +43,7 @@ void exportNonlinearFactorGraph(){ void (NonlinearFactorGraph::*add1)(const sharedFactor&) = &NonlinearFactorGraph::add; class_("NonlinearFactorGraph", init<>()) - .def("size",&NonlinearFactorGraph::size) + .def("size",&NonlinearFactorGraph::size) .def("push_back", push_back1) .def("add", add1) .def("resize", &NonlinearFactorGraph::resize) @@ -44,4 +51,6 @@ void exportNonlinearFactorGraph(){ .def("print", &NonlinearFactorGraph::print, print_overloads(args("s"))) ; + def("getNonlinearFactor", getNonlinearFactor); + } From c4494ba9691a6c132d0d1be9ee72f550e606f626 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:32:20 -0800 Subject: [PATCH 101/105] Small changes --- python/handwritten/slam/BetweenFactor.cpp | 18 +++++++++--------- python/handwritten/slam/PriorFactor.cpp | 7 ++++--- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/python/handwritten/slam/BetweenFactor.cpp b/python/handwritten/slam/BetweenFactor.cpp index b6fc552a0..0e0949fb5 100644 --- a/python/handwritten/slam/BetweenFactor.cpp +++ b/python/handwritten/slam/BetweenFactor.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -11,7 +11,7 @@ /** * @brief wraps BetweenFactor for several values to python - * @author Andrew Melim + * @author Andrew Melim * @author Ellon Paiva Mendes (LAAS-CNRS) **/ @@ -33,17 +33,17 @@ using namespace gtsam; using namespace std; -// template +// template // void exportBetweenFactor(const std::string& name){ -// class_(name, init<>()) -// .def(init()) +// class_(name, init<>()) +// .def(init()) // ; // } -#define BETWEENFACTOR(VALUE) \ - class_< BetweenFactor, bases, boost::shared_ptr< BetweenFactor > >("BetweenFactor"#VALUE) \ - .def(init()) \ - .def("measured", &BetweenFactor::measured, return_internal_reference<>()) \ +#define BETWEENFACTOR(T) \ + class_< BetweenFactor, bases, boost::shared_ptr< BetweenFactor > >("BetweenFactor"#T) \ + .def(init()) \ + .def("measured", &BetweenFactor::measured, return_internal_reference<>()) \ ; void exportBetweenFactors() diff --git a/python/handwritten/slam/PriorFactor.cpp b/python/handwritten/slam/PriorFactor.cpp index dcb9de8ea..3ada91f43 100644 --- a/python/handwritten/slam/PriorFactor.cpp +++ b/python/handwritten/slam/PriorFactor.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -11,7 +11,7 @@ /** * @brief wraps PriorFactor for several values to python - * @author Andrew Melim + * @author Andrew Melim * @author Ellon Paiva Mendes (LAAS-CNRS) **/ @@ -54,4 +54,5 @@ void exportPriorFactors() PRIORFACTOR(Point3) PRIORFACTOR(Rot3) PRIORFACTOR(Pose3) -} \ No newline at end of file + PRIORFACTOR(Vector3) +} From 1d62faa5a5a055e32ea34a96ffad0c2056fdf4c1 Mon Sep 17 00:00:00 2001 From: dellaert Date: Thu, 28 Jan 2016 01:32:36 -0800 Subject: [PATCH 102/105] Refactored plot without underscores --- python/gtsam_utils/__init__.py | 2 +- python/gtsam_utils/plot.py | 59 ++++++++++++++++++++++++++++++++++ 2 files changed, 60 insertions(+), 1 deletion(-) create mode 100644 python/gtsam_utils/plot.py diff --git a/python/gtsam_utils/__init__.py b/python/gtsam_utils/__init__.py index 0ef2dfcd3..56c55aa94 100644 --- a/python/gtsam_utils/__init__.py +++ b/python/gtsam_utils/__init__.py @@ -1 +1 @@ -from ._plot import * +from .plot import * diff --git a/python/gtsam_utils/plot.py b/python/gtsam_utils/plot.py new file mode 100644 index 000000000..84a388bbb --- /dev/null +++ b/python/gtsam_utils/plot.py @@ -0,0 +1,59 @@ +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D as _Axes3D + +def plotPoint3(fignum, point, linespec): + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + ax.plot([point.x()], [point.y()], [point.z()], linespec) + + +def plot3DPoints(fignum, values, linespec, marginals=None): + # PLOT3DPOINTS Plots the Point3's in a values, with optional covariances + # Finds all the Point3 objects in the given Values object and plots them. + # If a Marginals object is given, this function will also plot marginal + # covariance ellipses for each point. + + keys = values.keys() + + # Plot points and covariance matrices + for key in keys: + try: + p = values.atPoint3(key); + # if haveMarginals + # P = marginals.marginalCovariance(key); + # gtsam.plotPoint3(p, linespec, P); + # else + plotPoint3(fignum, p, linespec); + except RuntimeError: + continue + # I guess it's not a Point3 + +def plotPose3(fignum, pose, axisLength=0.1): + # get figure object + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + + # get rotation and translation (center) + gRp = pose.rotation().matrix() # rotation from pose to global + C = pose.translation().vector() + + # draw the camera axes + xAxis = C + gRp[:, 0] * axisLength + L = np.append(C[np.newaxis], xAxis[np.newaxis], axis=0) + ax.plot(L[:, 0], L[:, 1], L[:, 2], 'r-') + + yAxis = C + gRp[:, 1] * axisLength + L = np.append(C[np.newaxis], yAxis[np.newaxis], axis=0) + ax.plot(L[:, 0], L[:, 1], L[:, 2], 'g-') + + zAxis = C + gRp[:, 2] * axisLength + L = np.append(C[np.newaxis], zAxis[np.newaxis], axis=0) + ax.plot(L[:, 0], L[:, 1], L[:, 2], 'b-') + + # # plot the covariance + # if (nargin>2) && (~isempty(P)) + # pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame + # gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame + # gtsam.covarianceEllipse3D(C,gPp); + # end From 4eeedd31fcaa6d83235ebac0238112bde5374767 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Thu, 28 Jan 2016 12:00:39 -0500 Subject: [PATCH 103/105] Fix GTSAM_ALLOW_DEPRECATED_SINCE_V4 flag typo --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9d543b87b..9bfa9a758 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -318,7 +318,7 @@ if(GTSAM_ENABLE_CONSISTENCY_CHECKS) add_definitions(-DGTSAM_EXTRA_CONSISTENCY_CHECKS) endif() -if(GTSAM_ENABLE_CONSISTENCY_CHECKS) +if(GTSAM_ALLOW_DEPRECATED_SINCE_V4) add_definitions(-DGTSAM_ALLOW_DEPRECATED_SINCE_V4) endif() From 56992899af64b385808ad11ea46fcaed1e9afe22 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Thu, 28 Jan 2016 12:35:57 -0500 Subject: [PATCH 104/105] fix trivial compiler error --- gtsam/geometry/Rot3.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 5b7acb4be..264be1537 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -493,7 +493,7 @@ namespace gtsam { static Rot3 roll (double t) { return Roll(t); } static Rot3 ypr(double y, double p, double r) { return Ypr(r,p,y);} static Rot3 quaternion(double w, double x, double y, double z) { - return Rot3::Quaternion q(w, x, y, z); + return Rot3::Quaternion(w, x, y, z); } /// @} #endif From 52f3432988f46c884d641a94a0ad6f9dffbf952e Mon Sep 17 00:00:00 2001 From: Frank Date: Thu, 28 Jan 2016 16:47:12 -0800 Subject: [PATCH 105/105] Moved numpy_eigen headers to a more logical place --- .gitignore | 1 + python/CMakeLists.txt | 2 +- python/handwritten/slam/BearingFactor.cpp | 11 +++++------ .../include/numpy_eigen/NumpyEigenConverter.hpp | 0 .../3rdparty => python/include}/numpy_eigen/README.md | 0 .../include/numpy_eigen/boost_python_headers.hpp | 0 .../include/numpy_eigen/copy_routines.hpp | 0 .../include/numpy_eigen/type_traits.hpp | 0 8 files changed, 7 insertions(+), 7 deletions(-) rename {gtsam/3rdparty/numpy_eigen => python}/include/numpy_eigen/NumpyEigenConverter.hpp (100%) rename {gtsam/3rdparty => python/include}/numpy_eigen/README.md (100%) rename {gtsam/3rdparty/numpy_eigen => python}/include/numpy_eigen/boost_python_headers.hpp (100%) rename {gtsam/3rdparty/numpy_eigen => python}/include/numpy_eigen/copy_routines.hpp (100%) rename {gtsam/3rdparty/numpy_eigen => python}/include/numpy_eigen/type_traits.hpp (100%) diff --git a/.gitignore b/.gitignore index 7850df41b..04e8e76d1 100644 --- a/.gitignore +++ b/.gitignore @@ -7,3 +7,4 @@ *.txt.user *.txt.user.6d59f0c /python-build/ +*.pydevproject diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 01141973a..f7ceb62b3 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -48,7 +48,7 @@ if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOU include_directories(${NUMPY_INCLUDE_DIRS}) include_directories(${PYTHON_INCLUDE_DIRS}) include_directories(${Boost_INCLUDE_DIRS}) - include_directories(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/numpy_eigen/include/) + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/include/) # Build the python module library add_subdirectory(handwritten) diff --git a/python/handwritten/slam/BearingFactor.cpp b/python/handwritten/slam/BearingFactor.cpp index 84c67d522..2d4688bde 100644 --- a/python/handwritten/slam/BearingFactor.cpp +++ b/python/handwritten/slam/BearingFactor.cpp @@ -3,15 +3,14 @@ #define NO_IMPORT_ARRAY #include -#include +#include using namespace boost::python; using namespace gtsam; using namespace std; -template -void exportBearingFactor(const std::string& name){ - class_(name, init<>()) - ; -} \ No newline at end of file +template +void exportBearingFactor(const std::string& name) { + class_(name, init<>()); +} diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp b/python/include/numpy_eigen/NumpyEigenConverter.hpp similarity index 100% rename from gtsam/3rdparty/numpy_eigen/include/numpy_eigen/NumpyEigenConverter.hpp rename to python/include/numpy_eigen/NumpyEigenConverter.hpp diff --git a/gtsam/3rdparty/numpy_eigen/README.md b/python/include/numpy_eigen/README.md similarity index 100% rename from gtsam/3rdparty/numpy_eigen/README.md rename to python/include/numpy_eigen/README.md diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/boost_python_headers.hpp b/python/include/numpy_eigen/boost_python_headers.hpp similarity index 100% rename from gtsam/3rdparty/numpy_eigen/include/numpy_eigen/boost_python_headers.hpp rename to python/include/numpy_eigen/boost_python_headers.hpp diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp b/python/include/numpy_eigen/copy_routines.hpp similarity index 100% rename from gtsam/3rdparty/numpy_eigen/include/numpy_eigen/copy_routines.hpp rename to python/include/numpy_eigen/copy_routines.hpp diff --git a/gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp b/python/include/numpy_eigen/type_traits.hpp similarity index 100% rename from gtsam/3rdparty/numpy_eigen/include/numpy_eigen/type_traits.hpp rename to python/include/numpy_eigen/type_traits.hpp