5 #ifndef __eigenpy_eigen_allocator_hpp__ 6 #define __eigenpy_eigen_allocator_hpp__ 17 template <
typename MatType,
18 bool IsVectorAtCompileTime = MatType::IsVectorAtCompileTime>
22 return new (storage) MatType(rows, cols);
24 return new MatType(rows, cols);
27 static MatType *
run(PyArrayObject *pyArray,
void *storage = NULL) {
28 assert(PyArray_NDIM(pyArray) == 1 || PyArray_NDIM(pyArray) == 2);
31 const int ndim = PyArray_NDIM(pyArray);
33 rows = (int)PyArray_DIMS(pyArray)[0];
34 cols = (int)PyArray_DIMS(pyArray)[1];
35 }
else if (ndim == 1) {
36 rows = (int)PyArray_DIMS(pyArray)[0];
40 return run(rows,
cols, storage);
44 template <
typename MatType>
48 return new (storage) MatType(rows, cols);
50 return new MatType(rows, cols);
53 static MatType *
run(
int size,
void *storage) {
55 return new (storage) MatType(size);
57 return new MatType(size);
60 static MatType *
run(PyArrayObject *pyArray,
void *storage = NULL) {
61 const int ndim = PyArray_NDIM(pyArray);
63 const int size = (int)PyArray_DIMS(pyArray)[0];
64 return run(size, storage);
66 const int rows = (int)PyArray_DIMS(pyArray)[0];
67 const int cols = (int)PyArray_DIMS(pyArray)[1];
68 return run(rows, cols, storage);
73 #ifdef EIGENPY_WITH_TENSOR_SUPPORT 74 template <
typename Tensor>
76 static Tensor *
run(PyArrayObject *pyArray,
void *storage = NULL) {
77 enum { Rank = Tensor::NumDimensions };
78 assert(PyArray_NDIM(pyArray) == Rank);
79 typedef typename Tensor::Index Index;
81 Eigen::array<Index, Rank> dimensions;
82 for (
int k = 0; k < PyArray_NDIM(pyArray); ++k)
83 dimensions[k] = PyArray_DIMS(pyArray)[k];
86 return new (storage) Tensor(dimensions);
88 return new Tensor(dimensions);
93 template <
typename MatType>
96 template <
typename EigenType,
100 template <
typename MatType>
104 template <
typename MatType>
106 static bool run(PyArrayObject *pyArray,
107 const Eigen::MatrixBase<MatType> &
mat) {
108 if (PyArray_NDIM(pyArray) == 0)
return false;
109 if (mat.rows() == PyArray_DIMS(pyArray)[0])
116 template <
typename EigenType>
121 #ifdef EIGENPY_WITH_TENSOR_SUPPORT 122 template <
typename TensorType>
123 struct check_swap_impl_tensor {
124 static bool run(PyArrayObject * ,
const TensorType & ) {
129 template <
typename TensorType>
131 : check_swap_impl_tensor<TensorType> {};
155 template <
typename Scalar,
typename NewScalar,
156 template <
typename D>
class EigenBase = Eigen::MatrixBase,
159 template <
typename MatrixIn,
typename MatrixOut>
160 static void run(
const Eigen::MatrixBase<MatrixIn> &input,
161 const Eigen::MatrixBase<MatrixOut> &dest) {
166 #ifdef EIGENPY_WITH_TENSOR_SUPPORT 167 template <
typename Scalar,
typename NewScalar>
168 struct cast<Scalar, NewScalar, Eigen::TensorRef, true> {
169 template <
typename TensorIn,
typename TensorOut>
170 static void run(
const TensorIn &input, TensorOut &dest) {
176 template <
typename Scalar,
typename NewScalar,
177 template <
typename D>
class EigenBase>
178 struct cast<Scalar, NewScalar, EigenBase, false> {
179 template <
typename MatrixIn,
typename MatrixOut>
180 static void run(
const MatrixIn ,
const MatrixOut ) {
182 assert(
false &&
"Must never happened");
188 #define EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_MATRIX(MatType, Scalar, NewScalar, \ 190 details::cast<Scalar, NewScalar>::run( \ 191 NumpyMap<MatType, Scalar>::map(pyArray, \ 192 details::check_swap(pyArray, mat)), \ 195 #define EIGENPY_CAST_FROM_EIGEN_MATRIX_TO_PYARRAY(MatType, Scalar, NewScalar, \ 197 details::cast<Scalar, NewScalar>::run( \ 198 mat, NumpyMap<MatType, NewScalar>::map( \ 199 pyArray, details::check_swap(pyArray, mat))) 201 template <
typename EigenType>
204 template <
typename EigenType,
208 template <
typename MatType>
211 template <
typename MatType>
215 template <
typename MatType>
219 template <
typename MatType>
225 PyArrayObject *pyArray,
226 boost::python::converter::rvalue_from_python_storage<MatType> *storage) {
227 void *raw_ptr = storage->storage.bytes;
229 "The pointer is not aligned.");
232 Type &
mat = *mat_ptr;
238 template <
typename MatrixDerived>
239 static void copy(PyArrayObject *pyArray,
240 const Eigen::MatrixBase<MatrixDerived> &mat_) {
241 MatrixDerived &
mat = mat_.const_cast_derived();
243 const int Scalar_type_code = Register::getTypeCode<Scalar>();
245 if (pyArray_type_code == Scalar_type_code) {
251 switch (pyArray_type_code) {
266 Scalar, pyArray, mat);
274 Scalar, pyArray, mat);
280 case NPY_CLONGDOUBLE:
282 MatType, std::complex<long double>, Scalar, pyArray, mat);
285 throw Exception(
"You asked for a conversion which is not implemented.");
290 template <
typename MatrixDerived>
291 static void copy(
const Eigen::MatrixBase<MatrixDerived> &mat_,
292 PyArrayObject *pyArray) {
293 const MatrixDerived &
mat =
294 const_cast<const MatrixDerived &
>(mat_.derived());
296 const int Scalar_type_code = Register::getTypeCode<Scalar>();
298 if (pyArray_type_code == Scalar_type_code)
305 switch (pyArray_type_code) {
320 MatType, Scalar, std::complex<float>, mat, pyArray);
328 MatType, Scalar, std::complex<double>, mat, pyArray);
334 case NPY_CLONGDOUBLE:
336 MatType, Scalar, std::complex<long double>, mat, pyArray);
339 throw Exception(
"You asked for a conversion which is not implemented.");
344 #ifdef EIGENPY_WITH_TENSOR_SUPPORT 345 template <
typename TensorType>
346 struct eigen_allocator_impl_tensor;
348 template <
typename TensorType>
350 : eigen_allocator_impl_tensor<TensorType> {};
352 template <
typename TensorType>
354 const Eigen::TensorBase<TensorType> >
355 : eigen_allocator_impl_tensor<const TensorType> {};
357 template <
typename TensorType>
358 struct eigen_allocator_impl_tensor {
359 typedef typename TensorType::Scalar
Scalar;
360 static void allocate(
361 PyArrayObject *pyArray,
362 boost::python::converter::rvalue_from_python_storage<TensorType>
364 void *raw_ptr = storage->storage.bytes;
366 "The pointer is not aligned.");
368 TensorType *tensor_ptr =
370 TensorType &tensor = *tensor_ptr;
372 copy(pyArray, tensor);
375 #define EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(TensorType, Scalar, \ 376 NewScalar, pyArray, tensor) \ 378 typename NumpyMap<TensorType, Scalar>::EigenMap pyArray_map = \ 379 NumpyMap<TensorType, Scalar>::map( \ 380 pyArray, details::check_swap(pyArray, tensor)); \ 381 details::cast<Scalar, NewScalar, Eigen::TensorRef>::run(pyArray_map, \ 386 template <
typename TensorDerived>
387 static void copy(PyArrayObject *pyArray, TensorDerived &tensor) {
389 const int Scalar_type_code = Register::getTypeCode<Scalar>();
391 if (pyArray_type_code == Scalar_type_code) {
397 switch (pyArray_type_code) {
399 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(TensorType,
int, Scalar,
403 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(TensorType,
long, Scalar,
407 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(TensorType,
float, Scalar,
411 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(
412 TensorType, std::complex<float>, Scalar, pyArray, tensor);
415 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(TensorType,
double, Scalar,
419 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(
420 TensorType, std::complex<double>, Scalar, pyArray, tensor);
423 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(TensorType,
long double,
424 Scalar, pyArray, tensor);
426 case NPY_CLONGDOUBLE:
427 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(
428 TensorType, std::complex<long double>, Scalar, pyArray, tensor);
431 throw Exception(
"You asked for a conversion which is not implemented.");
435 #define EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(TensorType, Scalar, \ 436 NewScalar, tensor, pyArray) \ 438 typename NumpyMap<TensorType, NewScalar>::EigenMap pyArray_map = \ 439 NumpyMap<TensorType, NewScalar>::map( \ 440 pyArray, details::check_swap(pyArray, tensor)); \ 441 details::cast<Scalar, NewScalar, Eigen::TensorRef>::run(tensor, \ 446 static void copy(
const TensorType &tensor, PyArrayObject *pyArray) {
448 const int Scalar_type_code = Register::getTypeCode<Scalar>();
450 if (pyArray_type_code == Scalar_type_code)
457 switch (pyArray_type_code) {
459 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(TensorType, Scalar,
int,
463 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(TensorType, Scalar,
long,
467 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(TensorType, Scalar,
float,
471 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(
472 TensorType, Scalar, std::complex<float>, tensor, pyArray);
475 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(TensorType, Scalar,
double,
479 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(
480 TensorType, Scalar, std::complex<double>, tensor, pyArray);
483 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(TensorType, Scalar,
484 long double, tensor, pyArray);
486 case NPY_CLONGDOUBLE:
487 EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(
488 TensorType, Scalar, std::complex<long double>, tensor, pyArray);
491 throw Exception(
"You asked for a conversion which is not implemented.");
497 #if EIGEN_VERSION_AT_LEAST(3, 2, 0) 498 template <
typename MatType>
506 inline bool is_arr_layout_compatible_with_mat_type(PyArrayObject *pyArray) {
507 bool is_array_C_cont = PyArray_IS_C_CONTIGUOUS(pyArray);
508 bool is_array_F_cont = PyArray_IS_F_CONTIGUOUS(pyArray);
509 return (MatType::IsRowMajor && is_array_C_cont) ||
510 (!MatType::IsRowMajor && is_array_F_cont) ||
511 (MatType::IsVectorAtCompileTime &&
512 (is_array_C_cont || is_array_F_cont));
515 template <
typename MatType,
int Options,
typename Str
ide>
517 typedef Eigen::Ref<MatType, Options, Stride> RefType;
518 typedef typename MatType::Scalar
Scalar;
521 typename ::boost::python::detail::referent_storage<RefType &>::StorageType
524 static void allocate(
525 PyArrayObject *pyArray,
526 ::boost::python::converter::rvalue_from_python_storage<RefType>
530 Eigen::internal::traits<RefType>::StrideType::InnerStrideAtCompileTime,
531 Eigen::internal::traits<RefType>::StrideType::
532 OuterStrideAtCompileTime>::type NumpyMapStride;
534 bool need_to_allocate =
false;
536 const int Scalar_type_code = Register::getTypeCode<Scalar>();
537 if (pyArray_type_code != Scalar_type_code) need_to_allocate |=
true;
538 bool incompatible_layout =
539 !is_arr_layout_compatible_with_mat_type<MatType>(pyArray);
540 need_to_allocate |= incompatible_layout;
545 void *data_ptr = PyArray_DATA(pyArray);
546 if (!PyArray_ISONESEGMENT(pyArray) || !
is_aligned(data_ptr, Options))
547 need_to_allocate |=
true;
550 void *raw_ptr = storage->storage.bytes;
551 if (need_to_allocate) {
554 RefType mat_ref(*mat_ptr);
556 new (raw_ptr) StorageType(mat_ref, pyArray, mat_ptr);
558 RefType &
mat = *
reinterpret_cast<RefType *
>(raw_ptr);
561 assert(pyArray_type_code == Scalar_type_code);
565 RefType mat_ref(numpyMap);
566 new (raw_ptr) StorageType(mat_ref, pyArray);
570 static void copy(RefType
const &
ref, PyArrayObject *pyArray) {
575 template <
typename MatType,
int Options,
typename Str
ide>
577 const Eigen::Ref<const MatType, Options, Stride> > {
578 typedef const Eigen::Ref<const MatType, Options, Stride> RefType;
579 typedef typename MatType::Scalar
Scalar;
582 typename ::boost::python::detail::referent_storage<RefType &>::StorageType
585 static void allocate(
586 PyArrayObject *pyArray,
587 ::boost::python::converter::rvalue_from_python_storage<RefType>
591 Eigen::internal::traits<RefType>::StrideType::InnerStrideAtCompileTime,
592 Eigen::internal::traits<RefType>::StrideType::
593 OuterStrideAtCompileTime>::type NumpyMapStride;
595 bool need_to_allocate =
false;
597 const int Scalar_type_code = Register::getTypeCode<Scalar>();
599 if (pyArray_type_code != Scalar_type_code) need_to_allocate |=
true;
600 bool incompatible_layout =
601 !is_arr_layout_compatible_with_mat_type<MatType>(pyArray);
602 need_to_allocate |= incompatible_layout;
607 void *data_ptr = PyArray_DATA(pyArray);
608 if (!PyArray_ISONESEGMENT(pyArray) || !
is_aligned(data_ptr, Options))
609 need_to_allocate |=
true;
612 void *raw_ptr = storage->storage.bytes;
613 if (need_to_allocate) {
616 RefType mat_ref(*mat_ptr);
618 new (raw_ptr) StorageType(mat_ref, pyArray, mat_ptr);
620 MatType &
mat = *mat_ptr;
623 assert(pyArray_type_code == Scalar_type_code);
627 RefType mat_ref(numpyMap);
628 new (raw_ptr) StorageType(mat_ref, pyArray);
632 static void copy(RefType
const &
ref, PyArrayObject *pyArray) {
638 #ifdef EIGENPY_WITH_TENSOR_SUPPORT 640 template <
typename TensorType,
typename TensorRef>
641 struct eigen_allocator_impl_tensor_ref;
643 template <
typename TensorType>
644 struct eigen_allocator_impl_tensor<Eigen::TensorRef<TensorType> >
645 : eigen_allocator_impl_tensor_ref<TensorType,
646 Eigen::TensorRef<TensorType> > {};
648 template <
typename TensorType>
649 struct eigen_allocator_impl_tensor<const Eigen::TensorRef<const TensorType> >
650 : eigen_allocator_impl_tensor_ref<
651 const TensorType, const Eigen::TensorRef<const TensorType> > {};
653 template <
typename TensorType,
typename RefType>
654 struct eigen_allocator_impl_tensor_ref {
655 typedef typename TensorType::Scalar
Scalar;
658 typename ::boost::python::detail::referent_storage<RefType &>::StorageType
661 static void allocate(
662 PyArrayObject *pyArray,
663 ::boost::python::converter::rvalue_from_python_storage<RefType>
671 static const int Options = Eigen::internal::traits<TensorType>::Options;
673 bool need_to_allocate =
false;
675 const int Scalar_type_code = Register::getTypeCode<Scalar>();
676 if (pyArray_type_code != Scalar_type_code) need_to_allocate |=
true;
691 void *raw_ptr = storage->storage.bytes;
692 if (need_to_allocate) {
693 typedef typename boost::remove_const<TensorType>::type TensorTypeNonConst;
694 TensorTypeNonConst *tensor_ptr;
696 RefType tensor_ref(*tensor_ptr);
698 new (raw_ptr) StorageType(tensor_ref, pyArray, tensor_ptr);
700 TensorTypeNonConst &tensor = *tensor_ptr;
703 assert(pyArray_type_code == Scalar_type_code);
706 RefType tensor_ref(numpyMap);
707 new (raw_ptr) StorageType(tensor_ref, pyArray);
711 static void copy(RefType
const &
ref, PyArrayObject *pyArray) {
718 template <
typename EigenType>
723 #endif // __eigenpy_eigen_allocator_hpp__ ReturnMatrix copy(const Eigen::MatrixBase< Matrix > &mat)
#define EIGENPY_CAST_FROM_EIGEN_MATRIX_TO_PYARRAY(MatType, Scalar, NewScalar, mat, pyArray)
static MatType * run(int rows, int cols, void *storage)
#define EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_MATRIX(MatType, Scalar, NewScalar, pyArray, mat)
static void copy(PyArrayObject *pyArray, const Eigen::MatrixBase< MatrixDerived > &mat_)
Copy Python array into the input matrix mat.
static void run(const Eigen::MatrixBase< MatrixIn > &input, const Eigen::MatrixBase< MatrixOut > &dest)
static MatType * run(PyArrayObject *pyArray, void *storage=NULL)
static MatType * run(PyArrayObject *pyArray, void *storage=NULL)
static void allocate(PyArrayObject *pyArray, boost::python::converter::rvalue_from_python_storage< MatType > *storage)
static void copy(const Eigen::MatrixBase< MatrixDerived > &mat_, PyArrayObject *pyArray)
Copy mat into the Python array using Eigen::Map.
static MatType * run(int size, void *storage)
static MatType * run(int rows, int cols, void *storage)
#define EIGENPY_DEFAULT_ALIGN_BYTES
static bool run(PyArrayObject *pyArray, const Eigen::MatrixBase< MatType > &mat)
#define EIGENPY_GET_PY_ARRAY_TYPE(array)
bool is_aligned(const void *ptr, std::size_t alignment)
Eigen::TensorRef< Tensor > ref(Eigen::TensorRef< Tensor > tensor)
static void run(const MatrixIn, const MatrixOut)
bool check_swap(PyArrayObject *pyArray, const EigenType &mat)
boost::mpl::if_< boost::is_const< typename boost::remove_reference< EigenType >::type >, const _type, _type >::type type