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.release/4.3a0
parent
c140a784fe
commit
05f6237f71
|
@ -18,6 +18,8 @@
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
#include <boost/cstdint.hpp>
|
#include <boost/cstdint.hpp>
|
||||||
|
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include <gtsam/base/Matrix.h>
|
#include <gtsam/base/Matrix.h>
|
||||||
#include <gtsam/base/Vector.h>
|
#include <gtsam/base/Vector.h>
|
||||||
|
|
||||||
|
@ -55,6 +57,8 @@ void registerNumpyEigenConversions();
|
||||||
BOOST_PYTHON_MODULE(libgtsam_python){
|
BOOST_PYTHON_MODULE(libgtsam_python){
|
||||||
|
|
||||||
// Should be the first thing to be done
|
// Should be the first thing to be done
|
||||||
|
import_array();
|
||||||
|
|
||||||
registerNumpyEigenConversions();
|
registerNumpyEigenConversions();
|
||||||
|
|
||||||
exportPoint2();
|
exportPoint2();
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/geometry/Point2.h"
|
#include "gtsam/geometry/Point2.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/geometry/Point3.h"
|
#include "gtsam/geometry/Point3.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/geometry/Pose2.h"
|
#include "gtsam/geometry/Pose2.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/geometry/Pose3.h"
|
#include "gtsam/geometry/Pose3.h"
|
||||||
|
|
||||||
#include "gtsam/geometry/Pose2.h"
|
#include "gtsam/geometry/Pose2.h"
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/geometry/Rot2.h"
|
#include "gtsam/geometry/Rot2.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/geometry/Rot3.h"
|
#include "gtsam/geometry/Rot3.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -23,6 +23,9 @@
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/linear/NoiseModel.h"
|
#include "gtsam/linear/NoiseModel.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -15,6 +15,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/nonlinear/ISAM2.h"
|
#include "gtsam/nonlinear/ISAM2.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -1,4 +1,8 @@
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -15,6 +15,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/nonlinear/NonlinearFactor.h"
|
#include "gtsam/nonlinear/NonlinearFactor.h"
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/nonlinear/NonlinearFactorGraph.h"
|
#include "gtsam/nonlinear/NonlinearFactorGraph.h"
|
||||||
#include "gtsam/nonlinear/NonlinearFactor.h"
|
#include "gtsam/nonlinear/NonlinearFactor.h"
|
||||||
|
|
||||||
|
|
|
@ -15,6 +15,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/nonlinear/Values.h"
|
#include "gtsam/nonlinear/Values.h"
|
||||||
#include "gtsam/geometry/Point3.h"
|
#include "gtsam/geometry/Point3.h"
|
||||||
#include "gtsam/geometry/Rot3.h"
|
#include "gtsam/geometry/Rot3.h"
|
||||||
|
|
|
@ -1,4 +1,8 @@
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include <gtsam/slam/BearingFactor.h>
|
#include <gtsam/slam/BearingFactor.h>
|
||||||
|
|
||||||
using namespace boost::python;
|
using namespace boost::python;
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/slam/BetweenFactor.h"
|
#include "gtsam/slam/BetweenFactor.h"
|
||||||
#include "gtsam/geometry/Point2.h"
|
#include "gtsam/geometry/Point2.h"
|
||||||
#include "gtsam/geometry/Rot2.h"
|
#include "gtsam/geometry/Rot2.h"
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/slam/PriorFactor.h"
|
#include "gtsam/slam/PriorFactor.h"
|
||||||
#include "gtsam/geometry/Point2.h"
|
#include "gtsam/geometry/Point2.h"
|
||||||
#include "gtsam/geometry/Rot2.h"
|
#include "gtsam/geometry/Rot2.h"
|
||||||
|
|
|
@ -14,8 +14,9 @@
|
||||||
* @author Ellon Paiva Mendes (LAAS-CNRS)
|
* @author Ellon Paiva Mendes (LAAS-CNRS)
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <boost/python.hpp>
|
#include <boost/python.hpp>
|
||||||
|
|
||||||
|
#define NO_IMPORT_ARRAY
|
||||||
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
#include <numpy_eigen/NumpyEigenConverter.hpp>
|
||||||
|
|
||||||
#include "gtsam/base/Matrix.h"
|
#include "gtsam/base/Matrix.h"
|
||||||
|
@ -26,7 +27,8 @@ using namespace gtsam;
|
||||||
|
|
||||||
void registerNumpyEigenConversions()
|
void registerNumpyEigenConversions()
|
||||||
{
|
{
|
||||||
import_array();
|
// NOTE: import array should be called only in the cpp defining the module
|
||||||
|
// import_array();
|
||||||
NumpyEigenConverter<Vector>::register_converter();
|
NumpyEigenConverter<Vector>::register_converter();
|
||||||
NumpyEigenConverter<Vector1>::register_converter();
|
NumpyEigenConverter<Vector1>::register_converter();
|
||||||
NumpyEigenConverter<Vector2>::register_converter();
|
NumpyEigenConverter<Vector2>::register_converter();
|
||||||
|
|
Loading…
Reference in New Issue