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);
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];
44 template <
typename MatType>
48 return new (storage) 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];
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>
130 struct check_swap_impl<TensorType,
Eigen::TensorBase<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)))
202 #if defined _WIN32 || defined __CYGWIN__
205 #define EIGENPY_CAST_FROM_NUMPY_TO_EIGEN_SWITCH_OS_SPECIFIC( \
206 MatType, Scalar, pyArray, mat, CAST_MACRO) \
208 CAST_MACRO(MatType, int32_t, Scalar, pyArray, mat); \
211 CAST_MACRO(MatType, uint32_t, Scalar, pyArray, mat); \
213 #elif defined __APPLE__
218 #define EIGENPY_CAST_FROM_NUMPY_TO_EIGEN_SWITCH_OS_SPECIFIC( \
219 MatType, Scalar, pyArray, mat, CAST_MACRO) \
221 CAST_MACRO(MatType, int64_t, Scalar, pyArray, mat); \
223 case NPY_ULONGLONG: \
224 CAST_MACRO(MatType, uint64_t, Scalar, pyArray, mat); \
227 #define EIGENPY_CAST_FROM_NUMPY_TO_EIGEN_SWITCH_OS_SPECIFIC( \
228 MatType, Scalar, pyArray, mat, CAST_MACRO)
232 #define EIGENPY_CAST_FROM_NUMPY_TO_EIGEN_SWITCH( \
233 pyArray_type_code, MatType, Scalar, pyArray, mat, CAST_MACRO) \
234 switch (pyArray_type_code) { \
236 CAST_MACRO(MatType, bool, Scalar, pyArray, mat); \
239 CAST_MACRO(MatType, int8_t, Scalar, pyArray, mat); \
242 CAST_MACRO(MatType, int16_t, Scalar, pyArray, mat); \
245 CAST_MACRO(MatType, int32_t, Scalar, pyArray, mat); \
248 CAST_MACRO(MatType, int64_t, Scalar, pyArray, mat); \
251 CAST_MACRO(MatType, uint8_t, Scalar, pyArray, mat); \
254 CAST_MACRO(MatType, uint16_t, Scalar, pyArray, mat); \
257 CAST_MACRO(MatType, uint32_t, Scalar, pyArray, mat); \
260 CAST_MACRO(MatType, uint64_t, Scalar, pyArray, mat); \
263 CAST_MACRO(MatType, float, Scalar, pyArray, mat); \
266 CAST_MACRO(MatType, std::complex<float>, Scalar, pyArray, mat); \
269 CAST_MACRO(MatType, double, Scalar, pyArray, mat); \
272 CAST_MACRO(MatType, std::complex<double>, Scalar, pyArray, mat); \
274 case NPY_LONGDOUBLE: \
275 CAST_MACRO(MatType, long double, Scalar, pyArray, mat); \
277 case NPY_CLONGDOUBLE: \
278 CAST_MACRO(MatType, std::complex<long double>, Scalar, pyArray, mat); \
280 EIGENPY_CAST_FROM_NUMPY_TO_EIGEN_SWITCH_OS_SPECIFIC( \
281 MatType, Scalar, pyArray, mat, CAST_MACRO) \
283 throw Exception("You asked for a conversion which is not implemented."); \
286 template <
typename EigenType>
289 template <
typename EigenType,
293 template <
typename MatType>
296 template <
typename MatType>
300 template <
typename MatType>
304 template <
typename MatType>
310 PyArrayObject *pyArray,
311 boost::python::converter::rvalue_from_python_storage<MatType> *storage) {
312 void *raw_ptr = storage->storage.bytes;
314 "The pointer is not aligned.");
323 template <
typename MatrixDerived>
324 static void copy(PyArrayObject *pyArray,
325 const Eigen::MatrixBase<MatrixDerived> &mat_) {
326 MatrixDerived &
mat = mat_.const_cast_derived();
328 const int Scalar_type_code = Register::getTypeCode<Scalar>();
330 if (pyArray_type_code == Scalar_type_code) {
336 pyArray_type_code, MatType,
Scalar, pyArray,
mat,
341 template <
typename MatrixDerived>
342 static void copy(
const Eigen::MatrixBase<MatrixDerived> &mat_,
343 PyArrayObject *pyArray) {
344 const MatrixDerived &
mat =
345 const_cast<const MatrixDerived &
>(mat_.derived());
347 const int Scalar_type_code = Register::getTypeCode<Scalar>();
349 if (pyArray_type_code == Scalar_type_code)
356 "Scalar conversion from Eigen to Numpy is not implemented.");
360 #ifdef EIGENPY_WITH_TENSOR_SUPPORT
361 template <
typename TensorType>
362 struct eigen_allocator_impl_tensor;
364 template <
typename TensorType>
365 struct eigen_allocator_impl<TensorType,
Eigen::TensorBase<TensorType> >
366 : eigen_allocator_impl_tensor<TensorType> {};
368 template <
typename TensorType>
369 struct eigen_allocator_impl<const TensorType,
370 const
Eigen::TensorBase<TensorType> >
371 : eigen_allocator_impl_tensor<const TensorType> {};
373 template <
typename TensorType>
374 struct eigen_allocator_impl_tensor {
375 typedef typename TensorType::Scalar Scalar;
376 static void allocate(
377 PyArrayObject *pyArray,
378 boost::python::converter::rvalue_from_python_storage<TensorType>
380 void *raw_ptr = storage->storage.bytes;
382 "The pointer is not aligned.");
384 TensorType *tensor_ptr =
386 TensorType &tensor = *tensor_ptr;
388 copy(pyArray, tensor);
391 #define EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR(TensorType, Scalar, \
392 NewScalar, pyArray, tensor) \
394 typename NumpyMap<TensorType, Scalar>::EigenMap pyArray_map = \
395 NumpyMap<TensorType, Scalar>::map( \
396 pyArray, details::check_swap(pyArray, tensor)); \
397 details::cast<Scalar, NewScalar, Eigen::TensorRef>::run(pyArray_map, \
402 template <
typename TensorDerived>
403 static void copy(PyArrayObject *pyArray, TensorDerived &tensor) {
405 const int Scalar_type_code = Register::getTypeCode<Scalar>();
407 if (pyArray_type_code == Scalar_type_code) {
408 tensor = NumpyMap<TensorType, Scalar>::map(
414 pyArray_type_code, TensorType, Scalar, pyArray, tensor,
415 EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_TENSOR);
418 #define EIGENPY_CAST_FROM_EIGEN_TENSOR_TO_PYARRAY(TensorType, Scalar, \
419 NewScalar, tensor, pyArray) \
421 typename NumpyMap<TensorType, NewScalar>::EigenMap pyArray_map = \
422 NumpyMap<TensorType, NewScalar>::map( \
423 pyArray, details::check_swap(pyArray, tensor)); \
424 details::cast<Scalar, NewScalar, Eigen::TensorRef>::run(tensor, \
429 static void copy(
const TensorType &tensor, PyArrayObject *pyArray) {
431 const int Scalar_type_code = Register::getTypeCode<Scalar>();
433 if (pyArray_type_code == Scalar_type_code)
435 NumpyMap<TensorType, Scalar>::map(
441 "Scalar conversion from Eigen to Numpy is not implemented.");
446 #if EIGEN_VERSION_AT_LEAST(3, 2, 0)
447 template <
typename MatType>
455 inline bool is_arr_layout_compatible_with_mat_type(PyArrayObject *pyArray) {
456 bool is_array_C_cont = PyArray_IS_C_CONTIGUOUS(pyArray);
457 bool is_array_F_cont = PyArray_IS_F_CONTIGUOUS(pyArray);
458 return (MatType::IsRowMajor && is_array_C_cont) ||
459 (!MatType::IsRowMajor && is_array_F_cont) ||
460 (MatType::IsVectorAtCompileTime &&
461 (is_array_C_cont || is_array_F_cont));
464 template <
typename MatType,
int Options,
typename Str
ide>
465 struct eigen_allocator_impl_matrix<
Eigen::Ref<MatType, Options, Stride> > {
466 typedef Eigen::Ref<MatType, Options, Stride> RefType;
467 typedef typename MatType::Scalar
Scalar;
470 typename ::boost::python::detail::referent_storage<RefType &>::StorageType
474 PyArrayObject *pyArray,
475 ::boost::python::converter::rvalue_from_python_storage<RefType>
477 typedef typename StrideType<
479 Eigen::internal::traits<RefType>::StrideType::InnerStrideAtCompileTime,
480 Eigen::internal::traits<RefType>::StrideType::
481 OuterStrideAtCompileTime>::type NumpyMapStride;
483 bool need_to_allocate =
false;
485 const int Scalar_type_code = Register::getTypeCode<Scalar>();
486 if (pyArray_type_code != Scalar_type_code) need_to_allocate |=
true;
487 bool incompatible_layout =
488 !is_arr_layout_compatible_with_mat_type<MatType>(pyArray);
489 need_to_allocate |= incompatible_layout;
494 void *data_ptr = PyArray_DATA(pyArray);
495 if (!PyArray_ISONESEGMENT(pyArray) || !
is_aligned(data_ptr, Options))
496 need_to_allocate |=
true;
499 void *raw_ptr = storage->storage.bytes;
500 if (need_to_allocate) {
503 RefType mat_ref(*mat_ptr);
505 new (raw_ptr) StorageType(mat_ref, pyArray, mat_ptr);
507 RefType &
mat = *
reinterpret_cast<RefType *
>(raw_ptr);
510 assert(pyArray_type_code == Scalar_type_code);
511 typename NumpyMap<MatType, Scalar, Options, NumpyMapStride>::EigenMap
513 NumpyMap<MatType, Scalar, Options, NumpyMapStride>::map(pyArray);
514 RefType mat_ref(numpyMap);
515 new (raw_ptr) StorageType(mat_ref, pyArray);
519 static void copy(RefType
const &
ref, PyArrayObject *pyArray) {
524 template <
typename MatType,
int Options,
typename Str
ide>
525 struct eigen_allocator_impl_matrix<
526 const
Eigen::Ref<const MatType, Options, Stride> > {
527 typedef const Eigen::Ref<const MatType, Options, Stride> RefType;
528 typedef typename MatType::Scalar
Scalar;
531 typename ::boost::python::detail::referent_storage<RefType &>::StorageType
535 PyArrayObject *pyArray,
536 ::boost::python::converter::rvalue_from_python_storage<RefType>
538 typedef typename StrideType<
540 Eigen::internal::traits<RefType>::StrideType::InnerStrideAtCompileTime,
541 Eigen::internal::traits<RefType>::StrideType::
542 OuterStrideAtCompileTime>::type NumpyMapStride;
544 bool need_to_allocate =
false;
546 const int Scalar_type_code = Register::getTypeCode<Scalar>();
548 if (pyArray_type_code != Scalar_type_code) need_to_allocate |=
true;
549 bool incompatible_layout =
550 !is_arr_layout_compatible_with_mat_type<MatType>(pyArray);
551 need_to_allocate |= incompatible_layout;
556 void *data_ptr = PyArray_DATA(pyArray);
557 if (!PyArray_ISONESEGMENT(pyArray) || !
is_aligned(data_ptr, Options))
558 need_to_allocate |=
true;
561 void *raw_ptr = storage->storage.bytes;
562 if (need_to_allocate) {
565 RefType mat_ref(*mat_ptr);
567 new (raw_ptr) StorageType(mat_ref, pyArray, mat_ptr);
569 MatType &
mat = *mat_ptr;
572 assert(pyArray_type_code == Scalar_type_code);
573 typename NumpyMap<MatType, Scalar, Options, NumpyMapStride>::EigenMap
575 NumpyMap<MatType, Scalar, Options, NumpyMapStride>::map(pyArray);
576 RefType mat_ref(numpyMap);
577 new (raw_ptr) StorageType(mat_ref, pyArray);
581 static void copy(RefType
const &
ref, PyArrayObject *pyArray) {
587 #ifdef EIGENPY_WITH_TENSOR_SUPPORT
589 template <
typename TensorType,
typename TensorRef>
590 struct eigen_allocator_impl_tensor_ref;
592 template <
typename TensorType>
593 struct eigen_allocator_impl_tensor<
Eigen::TensorRef<TensorType> >
594 : eigen_allocator_impl_tensor_ref<TensorType,
595 Eigen::TensorRef<TensorType> > {};
597 template <
typename TensorType>
598 struct eigen_allocator_impl_tensor<const
Eigen::TensorRef<const TensorType> >
599 : eigen_allocator_impl_tensor_ref<
600 const TensorType, const Eigen::TensorRef<const TensorType> > {};
602 template <
typename TensorType,
typename RefType>
603 struct eigen_allocator_impl_tensor_ref {
604 typedef typename TensorType::Scalar Scalar;
607 typename ::boost::python::detail::referent_storage<RefType &>::StorageType
610 static void allocate(
611 PyArrayObject *pyArray,
612 ::boost::python::converter::rvalue_from_python_storage<RefType>
620 static const int Options = Eigen::internal::traits<TensorType>::Options;
622 bool need_to_allocate =
false;
624 const int Scalar_type_code = Register::getTypeCode<Scalar>();
625 if (pyArray_type_code != Scalar_type_code) need_to_allocate |=
true;
640 void *raw_ptr = storage->storage.bytes;
641 if (need_to_allocate) {
642 typedef typename boost::remove_const<TensorType>::type TensorTypeNonConst;
643 TensorTypeNonConst *tensor_ptr;
645 RefType tensor_ref(*tensor_ptr);
647 new (raw_ptr) StorageType(tensor_ref, pyArray, tensor_ptr);
649 TensorTypeNonConst &tensor = *tensor_ptr;
652 assert(pyArray_type_code == Scalar_type_code);
653 typename NumpyMap<TensorType, Scalar, Options>::EigenMap numpyMap =
654 NumpyMap<TensorType, Scalar, Options>::map(pyArray);
655 RefType tensor_ref(numpyMap);
656 new (raw_ptr) StorageType(tensor_ref, pyArray);
660 static void copy(RefType
const &
ref, PyArrayObject *pyArray) {
667 template <
typename EigenType>
668 struct EigenAllocator : eigen_allocator_impl<EigenType> {};
672 #endif // __eigenpy_eigen_allocator_hpp__