Namespaces | Classes | Functions
eigenpy Namespace Reference

Namespaces

 detail
 
 details
 
 internal
 

Classes

struct  aligned_instance
 
struct  aligned_storage
 
class  AngleAxisVisitor
 
struct  BFGSPreconditionerBaseVisitor
 
struct  call
 Allows a template specialization. More...
 
struct  call< Eigen::AngleAxis< Scalar > >
 
struct  call< Eigen::Quaternion< Scalar, Options > >
 
struct  call_destructor
 
struct  cast
 Default cast algo to cast a From to To. Can be specialized for any types. More...
 
struct  ConjugateGradientVisitor
 
struct  CopyableVisitor
 Add the Python method copy to allow a copy of this by calling the copy constructor. More...
 
struct  DiagonalPreconditionerVisitor
 
struct  eigen_allocator_impl
 
struct  eigen_allocator_impl< const MatType, const Eigen::MatrixBase< MatType > >
 
struct  eigen_allocator_impl< MatType, Eigen::MatrixBase< MatType > >
 
struct  eigen_allocator_impl_matrix
 
struct  eigen_from_py_converter_impl
 
struct  eigen_from_py_converter_impl< MatType, Eigen::MatrixBase< MatType > >
 
struct  eigen_from_py_converter_impl< TensorType, Eigen::TensorBase< TensorType > >
 
struct  eigen_from_py_impl
 
struct  eigen_from_py_impl< MatType, Eigen::MatrixBase< MatType > >
 
struct  eigen_from_py_impl< TensorType, Eigen::TensorBase< TensorType > >
 
struct  eigen_to_py_impl
 
struct  eigen_to_py_impl< const MatType &, const Eigen::MatrixBase< MatType > >
 
struct  eigen_to_py_impl< const MatType, const Eigen::MatrixBase< MatType > >
 
struct  eigen_to_py_impl< MatType &, Eigen::MatrixBase< MatType > >
 
struct  eigen_to_py_impl< MatType, Eigen::MatrixBase< MatType > >
 
struct  eigen_to_py_impl_matrix
 
struct  EigenAllocator
 
struct  EigenFromPy
 
struct  EigenFromPy< const Eigen::TensorRef< const TensorType > >
 
struct  EigenFromPy< Eigen::EigenBase< MatType >, typename MatType::Scalar >
 
struct  EigenFromPy< Eigen::MatrixBase< MatType > >
 
struct  EigenFromPy< Eigen::PlainObjectBase< MatType > >
 
struct  EigenFromPy< Eigen::TensorBase< TensorType > >
 
struct  EigenFromPy< Eigen::TensorRef< TensorType > >
 
struct  EigenFromPyConverter
 
struct  EigenSolverVisitor
 
struct  EigenToPy
 
struct  EigenToPyConverter
 
struct  EmptyPythonVisitor
 
struct  EulerAnglesConvertor
 
class  Exception
 
class  ExceptionIndex
 
struct  expected_pytype_for_arg
 
struct  expected_pytype_for_arg< MatType, Eigen::MatrixBase< MatType > >
 
struct  expected_pytype_for_arg< TensorType, Eigen::TensorBase< TensorType > >
 
struct  expose_eigen_type_impl
 
struct  expose_eigen_type_impl< MatType, Eigen::MatrixBase< MatType >, Scalar >
 
struct  FromTypeToType
 
struct  FromTypeToType< double, long double >
 
struct  FromTypeToType< double, std::complex< double > >
 
struct  FromTypeToType< double, std::complex< long double > >
 
struct  FromTypeToType< float, double >
 
struct  FromTypeToType< float, long double >
 
struct  FromTypeToType< float, std::complex< double > >
 
struct  FromTypeToType< float, std::complex< float > >
 
struct  FromTypeToType< float, std::complex< long double > >
 
struct  FromTypeToType< int, double >
 
struct  FromTypeToType< int, float >
 
struct  FromTypeToType< int, long >
 
struct  FromTypeToType< int, long double >
 
struct  FromTypeToType< int, std::complex< double > >
 
struct  FromTypeToType< int, std::complex< float > >
 
struct  FromTypeToType< int, std::complex< long double > >
 
struct  FromTypeToType< long, double >
 
struct  FromTypeToType< long, float >
 
struct  FromTypeToType< long, long double >
 
struct  FromTypeToType< long, std::complex< double > >
 
struct  FromTypeToType< long, std::complex< float > >
 
struct  FromTypeToType< long, std::complex< long double > >
 
struct  FromTypeToType< SCALAR, SCALAR >
 
struct  get_eigen_base_type
 
struct  get_eigen_ref_plain_type
 
struct  get_eigen_ref_plain_type< Eigen::Ref< MatType, Options, Stride > >
 
struct  IdentityPreconditionerVisitor
 
struct  IterativeSolverBaseVisitor
 
struct  IterativeSolverVisitor
 
struct  LDLTSolverVisitor
 
struct  LeastSquaresConjugateGradientVisitor
 
struct  LimitedBFGSPreconditionerBaseVisitor
 
struct  LLTSolverVisitor
 
struct  MINRESSolverVisitor
 
struct  numpy_allocator_impl
 
struct  numpy_allocator_impl< const MatType &, const Eigen::MatrixBase< MatType > >
 
struct  numpy_allocator_impl< const MatType, const Eigen::MatrixBase< typename remove_const_reference< MatType >::type > >
 
struct  numpy_allocator_impl< MatType, Eigen::MatrixBase< typename remove_const_reference< MatType >::type > >
 
struct  numpy_allocator_impl_matrix
 
struct  numpy_allocator_impl_matrix< const MatType & >
 
struct  numpy_allocator_impl_matrix< MatType & >
 
struct  numpy_map_impl
 
struct  numpy_map_impl< const MatType, InputScalar, AlignmentValue, Stride, const Eigen::MatrixBase< MatType > >
 
struct  numpy_map_impl< MatType, InputScalar, AlignmentValue, Stride, Eigen::MatrixBase< MatType > >
 
struct  numpy_map_impl_matrix
 
struct  numpy_map_impl_matrix< MatType, InputScalar, AlignmentValue, Stride, false >
 
struct  numpy_map_impl_matrix< MatType, InputScalar, AlignmentValue, Stride, true >
 
struct  NumpyAllocator
 
struct  NumpyEquivalentType
 
struct  NumpyEquivalentType< bool >
 
struct  NumpyEquivalentType< double >
 
struct  NumpyEquivalentType< float >
 
struct  NumpyEquivalentType< int >
 
struct  NumpyEquivalentType< long >
 
struct  NumpyEquivalentType< long double >
 
struct  NumpyEquivalentType< long long >
 
struct  NumpyEquivalentType< std::complex< double > >
 
struct  NumpyEquivalentType< std::complex< float > >
 
struct  NumpyEquivalentType< std::complex< long double > >
 
struct  NumpyEquivalentType< unsigned int >
 
struct  NumpyEquivalentType< unsigned long >
 
struct  NumpyMap
 
struct  NumpyType
 
struct  OptionalConverter
 
struct  PickleVector
 Create a pickle interface for the std::vector. More...
 
struct  PreconditionerBaseVisitor
 
struct  PySwigObject
 
class  QuaternionVisitor
 
struct  Register
 Structure collecting all the types registers in Numpy via EigenPy. More...
 
struct  remove_const_reference
 
struct  rvalue_from_python_data
 
struct  scalar_name
 
struct  scalar_name< double >
 
struct  scalar_name< float >
 
struct  scalar_name< long double >
 
struct  scalar_name< std::complex< Scalar > >
 
struct  SelfAdjointEigenSolverVisitor
 
struct  SolversScope
 
struct  SparseSolverVisitor
 
struct  StdContainerFromPythonList
 Register the conversion from a Python list to a std::vector. More...
 
struct  StdVectorPythonVisitor
 Expose an std::vector from a type given as template argument. More...
 
struct  stride_type
 
struct  stride_type< const MatrixType, InnerStride, OuterStride, const Eigen::MatrixBase< MatrixType > >
 
struct  stride_type< MatrixType, InnerStride, OuterStride, Eigen::MatrixBase< MatrixType > >
 
struct  stride_type_matrix
 
struct  stride_type_matrix< MatType, InnerStride, OuterStride, true >
 
struct  StrideType
 

Functions

void * aligned_malloc (std::size_t size, std::size_t alignment=EIGENPY_DEFAULT_ALIGN_BYTES)
 
bool call_PyArray_Check (PyObject *py_obj)
 
PyArray_Descr * call_PyArray_DescrFromType (int typenum)
 
void call_PyArray_InitArrFuncs (PyArray_ArrFuncs *funcs)
 
PyArray_Descr * call_PyArray_MinScalarType (PyArrayObject *arr)
 
PyObject * call_PyArray_New (PyTypeObject *py_type_ptr, int nd, npy_intp *shape, int np_type, void *data_ptr, int options)
 
PyObject * call_PyArray_New (PyTypeObject *py_type_ptr, int nd, npy_intp *shape, int np_type, npy_intp *strides, void *data_ptr, int options)
 
int call_PyArray_ObjectType (PyObject *obj, int val)
 
int call_PyArray_RegisterCanCast (PyArray_Descr *descr, int totype, NPY_SCALARKIND scalar)
 
int call_PyArray_RegisterCastFunc (PyArray_Descr *descr, int totype, PyArray_VectorUnaryFunc *castfunc)
 
int call_PyArray_RegisterDataType (PyArray_Descr *dtype)
 
PyObject * call_PyArray_SimpleNew (int nd, npy_intp *shape, int np_type)
 
template<typename T >
bool check_registration ()
 Check at runtime the registration of the type T inside the boost python registry. More...
 
bool EIGENPY_DLLAPI checkVersionAtLeast (unsigned int major_version, unsigned int minor_version, unsigned int patch_version)
 Checks if the current version of EigenPy is at least the version provided by the input arguments. More...
 
template<typename MatOrRefType >
void eigen_from_py_construct (PyObject *pyObj, bp::converter::rvalue_from_python_stage1_data *memory)
 
void EIGENPY_DLLAPI enableEigenPy ()
 
template<typename MatType >
void enableEigenPySpecific ()
 
template<typename T >
void expose ()
 Call the expose function of a given type T. More...
 
void EIGENPY_DLLAPI exposeAngleAxis ()
 
void exposeComputationInfo ()
 
void EIGENPY_DLLAPI exposeDecompositions ()
 
void EIGENPY_DLLAPI exposeGeometryConversion ()
 
void exposeMatrixBool ()
 
void exposeMatrixComplexDouble ()
 
void exposeMatrixComplexFloat ()
 
void exposeMatrixComplexLongDouble ()
 
void exposeMatrixDouble ()
 
void exposeMatrixFloat ()
 
void exposeMatrixInt ()
 
void exposeMatrixLong ()
 
void exposeMatrixLongDouble ()
 
void exposeNoneType ()
 
void EIGENPY_DLLAPI exposePreconditioners ()
 
void EIGENPY_DLLAPI exposeQuaternion ()
 
void EIGENPY_DLLAPI exposeSolvers ()
 
void EIGENPY_DLLAPI exposeStdVector ()
 
template<typename MatType >
void exposeStdVectorEigenSpecificType (const char *name)
 
template<typename Scalar , int Options>
EIGEN_DONT_INLINE void exposeType ()
 
template<typename Scalar >
EIGEN_DONT_INLINE void exposeType ()
 
PySwigObjectget_PySwigObject (PyObject *pyObj)
 
template<typename T >
boost::python::object getInstanceClass ()
 Get the class object for a wrapped type that has been exposed through Boost.Python. More...
 
PyTypeObject * getPyArrayType ()
 
void EIGENPY_DLLAPI import_numpy ()
 
bool is_aligned (const void *ptr, std::size_t alignment)
 
template<typename MatrixType1 , typename MatrixType2 >
EIGEN_DONT_INLINE bool is_approx (const Eigen::MatrixBase< MatrixType1 > &mat1, const Eigen::MatrixBase< MatrixType2 > &mat2, const typename MatrixType1::Scalar &prec)
 
template<typename MatrixType1 , typename MatrixType2 >
EIGEN_DONT_INLINE bool is_approx (const Eigen::MatrixBase< MatrixType1 > &mat1, const Eigen::MatrixBase< MatrixType2 > &mat2)
 
template<typename Scalar >
bool isNumpyNativeType ()
 
template<typename Scalar >
bool np_type_is_convertible_into_scalar (const int np_type)
 
std::string EIGENPY_DLLAPI printEigenVersion (const std::string &delimiter=".")
 Returns the current version of Eigen3 as a string using the following standard: EIGEN_MINOR_VERSION.EIGEN_MINOR_VERSION.EIGEN_PATCH_VERSION. More...
 
std::string EIGENPY_DLLAPI printVersion (const std::string &delimiter=".")
 Returns the current version of EigenPy as a string using the following standard: EIGENPY_MINOR_VERSION.EIGENPY_MINOR_VERSION.EIGENPY_PATCH_VERSION. More...
 
int EIGENPY_DLLAPI PyArray_TypeNum (PyTypeObject *type)
 
template<typename T >
bool register_symbolic_link_to_registered_type ()
 Symlink to the current scope the already registered class T. More...
 
template<typename From , typename To >
bool registerCast (const bool safe)
 
template<typename Scalar >
void registerCommonUfunc ()
 
template<typename Scalar >
int registerNewType (PyTypeObject *py_type_ptr=NULL)
 
void seed (unsigned int seed_value)
 

Detailed Description

Copyright (c) 2016-2022 CNRS INRIA This file was taken from Pinocchio (header <pinocchio/bindings/python/utils/std-vector.hpp>)

Copyright 2023 CNRS, INRIA

Function Documentation

◆ aligned_malloc()

void* eigenpy::aligned_malloc ( std::size_t  size,
std::size_t  alignment = EIGENPY_DEFAULT_ALIGN_BYTES 
)
inline

Definition at line 33 of file alignment.hpp.

◆ call_PyArray_Check()

bool eigenpy::call_PyArray_Check ( PyObject *  py_obj)
inline

Definition at line 136 of file numpy.hpp.

◆ call_PyArray_DescrFromType()

PyArray_Descr* eigenpy::call_PyArray_DescrFromType ( int  typenum)
inline

Definition at line 165 of file numpy.hpp.

◆ call_PyArray_InitArrFuncs()

void eigenpy::call_PyArray_InitArrFuncs ( PyArray_ArrFuncs *  funcs)
inline

Definition at line 169 of file numpy.hpp.

◆ call_PyArray_MinScalarType()

PyArray_Descr* eigenpy::call_PyArray_MinScalarType ( PyArrayObject *  arr)
inline

Definition at line 177 of file numpy.hpp.

◆ call_PyArray_New() [1/2]

PyObject* eigenpy::call_PyArray_New ( PyTypeObject *  py_type_ptr,
int  nd,
npy_intp *  shape,
int  np_type,
void *  data_ptr,
int  options 
)
inline

Definition at line 144 of file numpy.hpp.

◆ call_PyArray_New() [2/2]

PyObject* eigenpy::call_PyArray_New ( PyTypeObject *  py_type_ptr,
int  nd,
npy_intp *  shape,
int  np_type,
npy_intp *  strides,
void *  data_ptr,
int  options 
)
inline

Definition at line 151 of file numpy.hpp.

◆ call_PyArray_ObjectType()

int eigenpy::call_PyArray_ObjectType ( PyObject *  obj,
int  val 
)
inline

Definition at line 159 of file numpy.hpp.

◆ call_PyArray_RegisterCanCast()

int eigenpy::call_PyArray_RegisterCanCast ( PyArray_Descr *  descr,
int  totype,
NPY_SCALARKIND  scalar 
)
inline

Definition at line 181 of file numpy.hpp.

◆ call_PyArray_RegisterCastFunc()

int eigenpy::call_PyArray_RegisterCastFunc ( PyArray_Descr *  descr,
int  totype,
PyArray_VectorUnaryFunc *  castfunc 
)
inline

Definition at line 186 of file numpy.hpp.

◆ call_PyArray_RegisterDataType()

int eigenpy::call_PyArray_RegisterDataType ( PyArray_Descr *  dtype)
inline

Definition at line 173 of file numpy.hpp.

◆ call_PyArray_SimpleNew()

PyObject* eigenpy::call_PyArray_SimpleNew ( int  nd,
npy_intp *  shape,
int  np_type 
)
inline

Definition at line 140 of file numpy.hpp.

◆ check_registration()

template<typename T >
bool eigenpy::check_registration ( )
inline

Check at runtime the registration of the type T inside the boost python registry.

Template Parameters
TThe type to check the registration.
Returns
true if the type T is already registered.

Definition at line 22 of file registration.hpp.

◆ checkVersionAtLeast()

bool eigenpy::checkVersionAtLeast ( unsigned int  major_version,
unsigned int  minor_version,
unsigned int  patch_version 
)

Checks if the current version of EigenPy is at least the version provided by the input arguments.

Parameters
[in]major_versionMajor version to check.
[in]minor_versionMinor version to check.
[in]patch_versionPatch version to check.
Returns
true if the current version of EigenPy is greater than the version provided by the input arguments.

Definition at line 27 of file version.cpp.

◆ eigen_from_py_construct()

template<typename MatOrRefType >
void eigenpy::eigen_from_py_construct ( PyObject *  pyObj,
bp::converter::rvalue_from_python_stage1_data *  memory 
)

Definition at line 248 of file eigen-from-python.hpp.

◆ enableEigenPy()

void eigenpy::enableEigenPy ( )

Definition at line 29 of file eigenpy.cpp.

◆ enableEigenPySpecific()

template<typename MatType >
void eigenpy::enableEigenPySpecific ( )

Definition at line 63 of file details.hpp.

◆ expose()

template<typename T >
void eigenpy::expose ( )
inline

Call the expose function of a given type T.

Definition at line 23 of file expose.hpp.

◆ exposeAngleAxis()

void eigenpy::exposeAngleAxis ( )

Definition at line 10 of file angle-axis.cpp.

◆ exposeComputationInfo()

void eigenpy::exposeComputationInfo ( )
inline

Definition at line 11 of file computation-info.hpp.

◆ exposeDecompositions()

void eigenpy::exposeDecompositions ( )

Definition at line 15 of file decompositions.cpp.

◆ exposeGeometryConversion()

void eigenpy::exposeGeometryConversion ( )

Definition at line 10 of file geometry-conversion.cpp.

◆ exposeMatrixBool()

void eigenpy::exposeMatrixBool ( )

Definition at line 8 of file matrix-bool.cpp.

◆ exposeMatrixComplexDouble()

void eigenpy::exposeMatrixComplexDouble ( )

Definition at line 8 of file matrix-complex-double.cpp.

◆ exposeMatrixComplexFloat()

void eigenpy::exposeMatrixComplexFloat ( )

Definition at line 8 of file matrix-complex-float.cpp.

◆ exposeMatrixComplexLongDouble()

void eigenpy::exposeMatrixComplexLongDouble ( )

Definition at line 8 of file matrix-complex-long-double.cpp.

◆ exposeMatrixDouble()

void eigenpy::exposeMatrixDouble ( )

Definition at line 8 of file matrix-double.cpp.

◆ exposeMatrixFloat()

void eigenpy::exposeMatrixFloat ( )

Definition at line 8 of file matrix-float.cpp.

◆ exposeMatrixInt()

void eigenpy::exposeMatrixInt ( )

Definition at line 8 of file matrix-int.cpp.

◆ exposeMatrixLong()

void eigenpy::exposeMatrixLong ( )

Definition at line 8 of file matrix-long.cpp.

◆ exposeMatrixLongDouble()

void eigenpy::exposeMatrixLongDouble ( )

Definition at line 8 of file matrix-long-double.cpp.

◆ exposeNoneType()

void eigenpy::exposeNoneType ( )

Definition at line 8 of file optional.cpp.

◆ exposePreconditioners()

void EIGENPY_DLLAPI eigenpy::exposePreconditioners ( )

◆ exposeQuaternion()

void eigenpy::exposeQuaternion ( )

Definition at line 12 of file quaternion.cpp.

◆ exposeSolvers()

void EIGENPY_DLLAPI eigenpy::exposeSolvers ( )

◆ exposeStdVector()

void eigenpy::exposeStdVector ( )

Expose std::vector for given matrix or vector sizes.

Definition at line 10 of file std-vector.cpp.

◆ exposeStdVectorEigenSpecificType()

template<typename MatType >
void eigenpy::exposeStdVectorEigenSpecificType ( const char *  name)

Definition at line 435 of file std-vector.hpp.

◆ exposeType() [1/2]

template<typename Scalar , int Options>
EIGEN_DONT_INLINE void eigenpy::exposeType ( )

Definition at line 27 of file eigenpy.hpp.

◆ exposeType() [2/2]

template<typename Scalar >
EIGEN_DONT_INLINE void eigenpy::exposeType ( )

Definition at line 58 of file eigenpy.hpp.

◆ get_PySwigObject()

PySwigObject* eigenpy::get_PySwigObject ( PyObject *  pyObj)
inline

Definition at line 16 of file swig.hpp.

◆ getInstanceClass()

template<typename T >
boost::python::object eigenpy::getInstanceClass ( )

Get the class object for a wrapped type that has been exposed through Boost.Python.

Definition at line 287 of file user-type.hpp.

◆ getPyArrayType()

PyTypeObject* eigenpy::getPyArrayType ( )
inline

Definition at line 163 of file numpy.hpp.

◆ import_numpy()

void eigenpy::import_numpy ( )

Definition at line 8 of file numpy.cpp.

◆ is_aligned()

bool eigenpy::is_aligned ( const void *  ptr,
std::size_t  alignment 
)
inline

Definition at line 9 of file is-aligned.hpp.

◆ is_approx() [1/2]

template<typename MatrixType1 , typename MatrixType2 >
EIGEN_DONT_INLINE bool eigenpy::is_approx ( const Eigen::MatrixBase< MatrixType1 > &  mat1,
const Eigen::MatrixBase< MatrixType2 > &  mat2,
const typename MatrixType1::Scalar &  prec 
)
inline

Definition at line 12 of file is-approx.hpp.

◆ is_approx() [2/2]

template<typename MatrixType1 , typename MatrixType2 >
EIGEN_DONT_INLINE bool eigenpy::is_approx ( const Eigen::MatrixBase< MatrixType1 > &  mat1,
const Eigen::MatrixBase< MatrixType2 > &  mat2 
)
inline

Definition at line 20 of file is-approx.hpp.

◆ isNumpyNativeType()

template<typename Scalar >
bool eigenpy::isNumpyNativeType ( )

Definition at line 94 of file numpy.hpp.

◆ np_type_is_convertible_into_scalar()

template<typename Scalar >
bool eigenpy::np_type_is_convertible_into_scalar ( const int  np_type)

Definition at line 19 of file numpy-type.hpp.

◆ printEigenVersion()

std::string eigenpy::printEigenVersion ( const std::string &  delimiter = ".")

Returns the current version of Eigen3 as a string using the following standard: EIGEN_MINOR_VERSION.EIGEN_MINOR_VERSION.EIGEN_PATCH_VERSION.

Definition at line 20 of file version.cpp.

◆ printVersion()

std::string eigenpy::printVersion ( const std::string &  delimiter = ".")

Returns the current version of EigenPy as a string using the following standard: EIGENPY_MINOR_VERSION.EIGENPY_MINOR_VERSION.EIGENPY_PATCH_VERSION.

Definition at line 13 of file version.cpp.

◆ PyArray_TypeNum()

int eigenpy::PyArray_TypeNum ( PyTypeObject *  type)

Definition at line 16 of file numpy.cpp.

◆ register_symbolic_link_to_registered_type()

template<typename T >
bool eigenpy::register_symbolic_link_to_registered_type ( )
inline

Symlink to the current scope the already registered class T.

 

Returns
true if the type T is effectively symlinked.
Template Parameters
TThe type to symlink.

Definition at line 41 of file registration.hpp.

◆ registerCast()

template<typename From , typename To >
bool eigenpy::registerCast ( const bool  safe)

Definition at line 243 of file user-type.hpp.

◆ registerCommonUfunc()

template<typename Scalar >
void eigenpy::registerCommonUfunc ( )

Definition at line 206 of file ufunc.hpp.

◆ registerNewType()

template<typename Scalar >
int eigenpy::registerNewType ( PyTypeObject *  py_type_ptr = NULL)

Definition at line 305 of file user-type.hpp.

◆ seed()

void eigenpy::seed ( unsigned int  seed_value)

Definition at line 12 of file eigenpy.cpp.



eigenpy
Author(s): Justin Carpentier, Nicolas Mansard
autogenerated on Fri Jun 2 2023 02:10:27