eigenpy: Jazzy
Links
Rosindex
Website
Repository
C++ API
Full C++ API
Namespaces
Namespace boost
Namespace boost::mpl
Namespace boost::mpl::if_c
Namespace boost::python
Namespace boost::python::converter
Namespace boost::python::detail
Namespace boost::python::objects
Namespace converter
Namespace eigenpy
Namespace eigenpy::detail
Namespace eigenpy::details
Namespace eigenpy::internal
Namespace eigenpy::literals
Namespace eigenpy::python
Namespace internal
Namespace internal::has_operator_equal_impl
Namespace std
Classes and Structs
Template Struct expected_pytype_for_arg< boost::optional< T > >
Template Struct expected_pytype_for_arg< Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols > >
Template Struct expected_pytype_for_arg< Eigen::SparseMatrix< Scalar, Options, StorageIndex > >
Template Struct expected_pytype_for_arg< Eigen::Tensor< Scalar, Rank, Options, IndexType > >
Template Struct implicit< Quaternion, Eigen::QuaternionBase< Quaternion > >
Template Struct reference_arg_from_python< std::vector< Type, Allocator >, & >
Template Struct rvalue_from_python_data< const Eigen::Ref< const MatType, Options, Stride >, & >
Template Struct rvalue_from_python_data< Eigen::EigenBase< Derived >, const & >
Template Struct rvalue_from_python_data< Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols >, const & >
Template Struct rvalue_from_python_data< Eigen::MatrixBase< Derived >, const & >
Template Struct rvalue_from_python_data< Eigen::PlainObjectBase< Derived >, const & >
Template Struct rvalue_from_python_data< Eigen::QuaternionBase< Quaternion >, const & >
Template Struct rvalue_from_python_data< Eigen::Ref< MatType, Options, Stride >, & >
Template Struct rvalue_from_python_data< Eigen::SparseMatrix< Scalar, Options, StorageIndex >, const & >
Template Struct rvalue_from_python_data< Eigen::SparseMatrixBase< Derived >, const & >
Template Struct rvalue_from_python_data< Eigen::Tensor< Scalar, Rank, Options, IndexType >, const & >
Template Struct rvalue_from_python_data< Eigen::TensorBase< Derived >, const & >
Template Struct referent_storage< const Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols >, & >
Template Struct referent_storage< const Eigen::Quaternion< Scalar, Options >, & >
Template Struct referent_storage< const Eigen::TensorRef< const TensorType >, & >
Template Struct referent_storage< Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols >, & >
Template Struct referent_storage< Eigen::Quaternion< Scalar, Options >, & >
Template Struct referent_storage< Eigen::TensorRef< TensorType >, & >
Template Struct extract< Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols >, & >
Template Struct extract< Eigen::MatrixBase< Derived >, & >
Template Struct extract< Eigen::RefBase< Derived >, & >
Template Struct extract_to_eigen_ref
Template Struct instance< value_holder< Derived > >
Template Struct to_python_indirect< const Eigen::Matrix< Scalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime >, &, MakeHolder >
Template Struct to_python_indirect< Eigen::Matrix< Scalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime >, &, MakeHolder >
Template Struct to_python_indirect_eigen
Template Struct to_python_value< const std::unique_ptr< T >, & >
Template Struct AccelerateImplVisitor
Template Struct aligned_instance
Template Struct aligned_storage
Template Struct BDCSVDVisitor
Template Struct BFGSPreconditionerBaseVisitor
Template Struct BiCGSTABVisitor
Template Struct call
Template Struct call< Eigen::AngleAxis< Scalar > >
Template Struct call< Eigen::Quaternion< Scalar, Options > >
Template Struct call_destructor
Template Struct cast
Template Struct CholmodBaseVisitor
Template Struct CholmodDecompositionVisitor
Template Struct CholmodSimplicialLDLTVisitor
Template Struct CholmodSimplicialLLTVisitor
Template Struct CholmodSupernodalLLTVisitor
Template Struct ColPivHouseholderQRSolverVisitor
Template Struct CompleteOrthogonalDecompositionSolverVisitor
Template Struct ComplexEigenSolverVisitor
Template Struct ComplexSchurVisitor
Template Struct ConjugateGradientVisitor
Template Struct CopyableVisitor
Template Struct deprecated_function
Template Struct deprecated_member
Template Struct deprecation_warning_policy
Template Struct NoneToPython
Template Struct nullopt_helper
Template Struct nullopt_helper< boost::optional >
Template Struct OptionalFromPython
Template Struct OptionalToPython
Template Struct build_list
Template Struct build_list< vector_type, true >
Template Struct cast
Template Struct cast< Scalar, NewScalar, EigenBase, false >
Template Struct check_swap_impl
Template Struct check_swap_impl< MatType, Eigen::MatrixBase< MatType > >
Template Struct check_swap_impl_matrix
Template Struct container_traits
Template Struct container_traits< std::array< _Tp, Size > >
Template Struct copy_if_non_const
Template Struct copy_if_non_const< const MatType, true >
Template Struct empty_variant
Template Struct empty_variant< boost::variant< Alternatives… > >
Template Struct EmptyConvertible
Template Struct init_matrix_or_array
Template Struct init_matrix_or_array< MatType, true >
Struct InternalStdUniquePtrConverter
Template Struct InternalStdUniquePtrConverter::apply
Struct apply::type
Template Struct is_class_or_union
Template Struct is_empty_variant
Template Struct is_empty_variant< boost::blank >
Template Struct is_python_complex
Template Struct is_python_complex< std::complex< double > >
Template Struct is_python_complex< std::complex< float > >
Template Struct is_python_complex< std::complex< long double > >
Template Struct is_python_primitive_type
Template Struct is_python_primitive_type_helper
Template Struct NumericConvertible
Template Struct NumericConvertibleImpl
Template Struct NumericConvertibleImpl< T, typename std::enable_if< std::is_floating_point< T >::value >::type >
Template Struct NumericConvertibleImpl< T, typename std::enable_if< std::is_same< T, bool >::value >::type >
Template Struct NumericConvertibleImpl< T, typename std::enable_if< !std::is_same< T, bool >::value &&std::is_integral< T >::value >::type >
Template Struct overload_base_get_item_for_std_vector
Template Struct remove_cvref
Struct StdUniquePtrResultConverter
Template Struct StdUniquePtrResultConverter::apply
Struct apply::type
Template Struct VariantAlternatives
Template Struct VariantAlternatives< boost::variant< Alternatives… > >
Template Struct VariantConverter
Template Struct VariantConverter::apply
Struct apply::type
Template Struct VariantConvertible
Template Struct VariantRefToObject
Template Struct VariantValueToObject
Template Struct VariantVisitorType
Template Struct VariantVisitorType< ResultType, boost::variant< Alternatives… > >
Template Struct DiagonalPreconditionerVisitor
Template Struct dict_to_map
Template Struct eigen_allocator_impl
Template Struct eigen_allocator_impl< const MatType, const Eigen::MatrixBase< MatType > >
Template Struct eigen_allocator_impl< MatType, Eigen::MatrixBase< MatType > >
Template Struct eigen_allocator_impl_matrix
Template Struct eigen_from_py_converter_impl
Template Struct eigen_from_py_converter_impl< MatType, Eigen::MatrixBase< MatType > >
Template Struct eigen_from_py_converter_impl< SparseMatrixType, Eigen::SparseMatrixBase< SparseMatrixType > >
Template Struct eigen_from_py_converter_impl< TensorType, Eigen::TensorBase< TensorType > >
Template Struct eigen_from_py_impl
Template Struct eigen_from_py_impl< MatType, Eigen::MatrixBase< MatType > >
Template Struct eigen_from_py_impl< SparseMatrixType, Eigen::SparseMatrixBase< SparseMatrixType > >
Template Struct eigen_from_py_impl< TensorType, Eigen::TensorBase< TensorType > >
Template Struct eigen_to_py_impl
Template Struct eigen_to_py_impl< const MatType &, const Eigen::MatrixBase< MatType > >
Template Struct eigen_to_py_impl< const MatType &, const Eigen::SparseMatrixBase< MatType > >
Template Struct eigen_to_py_impl< const MatType, const Eigen::MatrixBase< MatType > >
Template Struct eigen_to_py_impl< const MatType, const Eigen::SparseMatrixBase< MatType > >
Template Struct eigen_to_py_impl< MatType &, Eigen::MatrixBase< MatType > >
Template Struct eigen_to_py_impl< MatType &, Eigen::SparseMatrixBase< MatType > >
Template Struct eigen_to_py_impl< MatType, Eigen::MatrixBase< MatType > >
Template Struct eigen_to_py_impl< MatType, Eigen::SparseMatrixBase< MatType > >
Template Struct eigen_to_py_impl_matrix
Template Struct eigen_to_py_impl_sparse_matrix
Template Struct EigenAllocator
Template Struct EigenBaseVisitor
Template Struct EigenFromPy
Template Struct EigenFromPy< const Eigen::TensorRef< const TensorType > >
Template Struct EigenFromPy< Eigen::EigenBase< MatType >, typename MatType::Scalar >
Template Struct EigenFromPy< Eigen::MatrixBase< MatType > >
Template Struct EigenFromPy< Eigen::PlainObjectBase< MatType > >
Template Struct EigenFromPy< Eigen::SparseMatrixBase< SparseMatrixType > >
Template Struct EigenFromPy< Eigen::TensorBase< TensorType > >
Template Struct EigenFromPy< Eigen::TensorRef< TensorType > >
Template Struct EigenFromPyConverter
Template Struct EigenSolverVisitor
Template Struct EigenToPy
Template Struct EigenToPyConverter
Template Struct emplace_set_derived_policies
Struct EmptyPythonVisitor
Template Struct EulerAnglesConvertor
Template Struct expected_pytype_for_arg
Template Struct expected_pytype_for_arg< MatType, Eigen::MatrixBase< MatType > >
Template Struct expected_pytype_for_arg< SparseMatrixType, Eigen::SparseMatrixBase< SparseMatrixType > >
Template Struct expected_pytype_for_arg< TensorType, Eigen::TensorBase< TensorType > >
Template Struct expose_eigen_type_impl
Template Struct expose_eigen_type_impl< MatType, Eigen::MatrixBase< MatType >, Scalar >
Template Struct expose_eigen_type_impl< MatType, Eigen::SparseMatrixBase< MatType >, Scalar >
Template Struct FromTypeToType
Template Struct FromTypeToType< std::complex< ScalarSource >, std::complex< ScalarTarget > >
Template Struct FullPivHouseholderQRSolverVisitor
Template Struct FullPivLUSolverVisitor
Template Struct GeneralizedEigenSolverVisitor
Template Struct GeneralizedSelfAdjointEigenSolverVisitor
Template Struct GenericMapVisitor
Template Struct get_eigen_base_type
Template Struct get_eigen_plain_type
Template Struct get_eigen_plain_type< Eigen::Ref< MatType, Options, Stride > >
Template Struct has_operator_equal
Template Struct HessenbergDecompositionVisitor
Template Struct HouseholderQRSolverVisitor
Struct IdentityPreconditionerVisitor
Template Struct IdVisitor
Template Struct IncompleteCholeskyVisitor
Template Struct IncompleteLUTVisitor
Template Struct contains_algo
Template Struct contains_algo< T, false >
Template Struct contains_algo< T, true >
Template Struct contains_vector_derived_policies
Template Struct def_pickle_std_vector
Template Struct def_pickle_std_vector< vector_type, true >
Template Struct ExposeStdMethodToStdVector
Template Struct getitem
Template Struct has_operator_equal_impl
Template Struct OffsetOf
Struct OffsetOf::Data
Template Struct SpecialMethods
Template Struct SpecialMethods< T, NPY_USERDEF >
Template Struct IterativeSolverBaseVisitor
Template Struct IterativeSolverVisitor
Template Struct JacobiSVDVisitor
Template Struct LDLTSolverVisitor
Template Struct LeastSquaresConjugateGradientVisitor
Template Struct LimitedBFGSPreconditionerBaseVisitor
Template Struct LLTSolverVisitor
Template Struct MINRESSolverVisitor
Template Struct numpy_allocator_impl
Template Struct numpy_allocator_impl< const MatType &, const Eigen::MatrixBase< MatType > >
Template Struct numpy_allocator_impl< const MatType, const Eigen::MatrixBase< typename remove_const_reference< MatType >::type > >
Template Struct numpy_allocator_impl< MatType, Eigen::MatrixBase< typename remove_const_reference< MatType >::type > >
Template Struct numpy_allocator_impl_matrix
Template Struct numpy_allocator_impl_matrix< const MatType & >
Template Struct numpy_allocator_impl_matrix< MatType & >
Template Struct numpy_map_impl
Template Struct numpy_map_impl< const MatType, InputScalar, AlignmentValue, Stride, const Eigen::MatrixBase< MatType > >
Template Struct numpy_map_impl< MatType, InputScalar, AlignmentValue, Stride, Eigen::MatrixBase< MatType > >
Template Struct numpy_map_impl_matrix
Template Struct numpy_map_impl_matrix< MatType, InputScalar, AlignmentValue, Stride, false >
Template Struct numpy_map_impl_matrix< MatType, InputScalar, AlignmentValue, Stride, true >
Template Struct NumpyAllocator
Template Struct NumpyEquivalentType
Template Struct NumpyEquivalentType< bool >
Template Struct NumpyEquivalentType< char >
Template Struct NumpyEquivalentType< double >
Template Struct NumpyEquivalentType< float >
Template Struct NumpyEquivalentType< int16_t >
Template Struct NumpyEquivalentType< int32_t >
Template Struct NumpyEquivalentType< int64_t >
Template Struct NumpyEquivalentType< int8_t >
Template Struct NumpyEquivalentType< long double >
Template Struct NumpyEquivalentType< std::complex< double > >
Template Struct NumpyEquivalentType< std::complex< float > >
Template Struct NumpyEquivalentType< std::complex< long double > >
Template Struct NumpyEquivalentType< uint16_t >
Template Struct NumpyEquivalentType< uint32_t >
Template Struct NumpyEquivalentType< uint64_t >
Template Struct NumpyEquivalentType< unsigned char >
Template Struct NumpyMap
Struct NumpyType
Template Struct OptionalConverter
Template Struct overload_base_get_item_for_map
Template Struct PartialPivLUSolverVisitor
Template Struct PermutationMatrixVisitor
Template Struct PickleMap
Template Struct PickleVector
Template Struct PreconditionerBaseVisitor
Struct PySwigObject
Template Struct RealQZVisitor
Template Struct RealSchurVisitor
Struct Register
Struct Register::Compare_PyTypeObject
Struct Register::Compare_TypeInfo
Template Struct remove_const_reference
Struct ReturnInternalStdUniquePtr
Template Struct ReturnInternalVariant
Template Struct rvalue_from_python_data
Template Struct scalar_name
Template Struct scalar_name< double >
Template Struct scalar_name< float >
Template Struct scalar_name< long double >
Template Struct scalar_name< std::complex< Scalar > >
Template Struct scipy_allocator_impl
Template Struct scipy_allocator_impl< const MatType &, const Eigen::SparseMatrixBase< MatType > >
Template Struct scipy_allocator_impl< const MatType, const Eigen::SparseMatrixBase< typename remove_const_reference< MatType >::type > >
Template Struct scipy_allocator_impl< MatType, Eigen::SparseMatrixBase< typename remove_const_reference< MatType >::type > >
Template Struct scipy_allocator_impl_sparse_matrix
Template Struct ScipyAllocator
Struct ScipyType
Template Struct SelfAdjointEigenSolverVisitor
Template Struct SimplicialCholeskyVisitor
Template Struct SimplicialLDLTVisitor
Template Struct SimplicialLLTVisitor
Struct SolversScope
Template Struct SparseLUMatrixLReturnTypeVisitor
Template Struct SparseLUMatrixUReturnTypeVisitor
Template Struct SparseLUVisitor
Template Struct SparseQRMatrixQReturnTypeVisitor
Template Struct SparseQRMatrixQTransposeReturnTypeVisitor
Template Struct SparseQRVisitor
Template Struct SparseSolverBaseVisitor
Template Struct SparseSolverVisitor
Template Struct StdArrayPythonVisitor
Template Struct StdContainerFromPythonList
Template Struct StdMapPythonVisitor
Template Struct StdPairConverter
Struct StdUniquePtrCallPolicies
Template Struct StdVectorPythonVisitor
Template Struct stride_type
Template Struct stride_type< const MatrixType, InnerStride, OuterStride, const Eigen::MatrixBase< MatrixType > >
Template Struct stride_type< MatrixType, InnerStride, OuterStride, Eigen::MatrixBase< MatrixType > >
Template Struct stride_type_matrix
Template Struct stride_type_matrix< MatType, InnerStride, OuterStride, true >
Template Struct StrideType
Template Struct SVDBaseVisitor
Template Struct TridiagonalizationVisitor
Template Struct TypeInfoVisitor
Template Struct VariantConverter
Struct StdContainerFromPythonList
Template Class AngleAxisVisitor
Template Class array_indexing_suite
Template Class final_array_derived_policies
Class Exception
Class ExceptionIndex
Template Class QuaternionVisitor
Template Class registration_class
Enums
Enum DeprecationType
Unions
Union aligned_storage::type
Functions
Function _Py_SET_TYPE
Function eigenpy::aligned_malloc
Function eigenpy::call_PyArray_Check
Function eigenpy::call_PyArray_DescrFromType
Function eigenpy::call_PyArray_InitArrFuncs
Function eigenpy::call_PyArray_MinScalarType
Function eigenpy::call_PyArray_New(PyTypeObject *, int, npy_intp *, int, void *, int)
Function eigenpy::call_PyArray_New(PyTypeObject *, int, npy_intp *, int, npy_intp *, void *, int)
Function eigenpy::call_PyArray_ObjectType
Function eigenpy::call_PyArray_RegisterCanCast
Function eigenpy::call_PyArray_RegisterCastFunc
Function eigenpy::call_PyArray_RegisterDataType
Function eigenpy::call_PyArray_SimpleNew
Template Function eigenpy::check_registration
Function eigenpy::checkVersionAtLeast
Function eigenpy::detail::deprecationTypeToPyObj
Template Function eigenpy::details::check_swap
Template Function eigenpy::details::from_python_list
Template Function eigenpy::details::internal_unique_ptr_to_python(std::unique_ptr<T>&)
Template Function eigenpy::details::internal_unique_ptr_to_python(std::unique_ptr<T>&)
Template Function eigenpy::details::unique_ptr_to_python(std::unique_ptr<T>&&)
Template Function eigenpy::details::unique_ptr_to_python(std::unique_ptr<T>&&)
Template Function eigenpy::eigen_from_py_construct
Template Function eigenpy::eigen_sparse_matrix_from_py_construct
Function eigenpy::enableEigenPy
Template Function eigenpy::enableEigenPySpecific
Template Function eigenpy::expose
Template Function eigenpy::expose_boost_type_info
Template Function eigenpy::expose_std_type_info
Function eigenpy::exposeAngleAxis
Function eigenpy::exposeComputationInfo
Function eigenpy::exposeDecompositions
Function eigenpy::exposeGeometryConversion
Function eigenpy::exposePreconditioners
Function eigenpy::exposeQuaternion
Function eigenpy::exposeSolvers
Template Function eigenpy::exposeStdArrayEigenSpecificType
Function eigenpy::exposeStdVector
Template Function eigenpy::exposeStdVectorEigenSpecificType
Template Function eigenpy::exposeType()
Template Function eigenpy::exposeType()
Function eigenpy::get_PySwigObject
Template Function eigenpy::getInstanceClass
Function eigenpy::getPyArrayType
Function eigenpy::import_numpy
Template Function eigenpy::internal::cast
Template Function eigenpy::internal::createExposeStdMethodToStdVector
Template Function eigenpy::internal::gufunc_matrix_multiply
Template Function eigenpy::internal::matrix_multiply
Function eigenpy::is_aligned
Template Function eigenpy::is_approx(const Eigen::MatrixBase<MatrixType1>&, const Eigen::MatrixBase<MatrixType2>&, const typename MatrixType1::RealScalar&)
Template Function eigenpy::is_approx(const Eigen::MatrixBase<MatrixType1>&, const Eigen::MatrixBase<MatrixType2>&)
Template Function eigenpy::is_approx(const Eigen::SparseMatrixBase<MatrixType1>&, const Eigen::SparseMatrixBase<MatrixType2>&, const typename MatrixType1::RealScalar&)
Template Function eigenpy::is_approx(const Eigen::SparseMatrixBase<MatrixType1>&, const Eigen::SparseMatrixBase<MatrixType2>&)
Template Function eigenpy::isNumpyNativeType
Function eigenpy::literals::operator””_a
Template Function eigenpy::np_type_is_convertible_into_scalar
Function eigenpy::printEigenVersion
Function eigenpy::printVersion
Function eigenpy::PyArray_TypeNum
Template Function eigenpy::register_symbolic_link_to_registered_type()
Template Function eigenpy::register_symbolic_link_to_registered_type(const Visitor&)
Template Function eigenpy::registerCast
Template Function eigenpy::registerCommonUfunc
Template Function eigenpy::registerNewType
Template Function eigenpy::type_info
Function eigenpy::withTensorSupport
Function PyDataType_GetArrFuncs
Defines
Define __eigenpy_memory_hpp__
Define _EIGENPY_PPCAT
Define BOOST_BIND_GLOBAL_PLACEHOLDERS
Define EIGENPY_CAST_FROM_EIGEN_MATRIX_TO_PYARRAY
Define EIGENPY_CAST_FROM_NUMPY_TO_EIGEN_SWITCH
Define EIGENPY_CAST_FROM_NUMPY_TO_EIGEN_SWITCH_OS_SPECIFIC
Define EIGENPY_CAST_FROM_PYARRAY_TO_EIGEN_MATRIX
Define EIGENPY_DEFAULT_ALIGN_BYTES
Define EIGENPY_DEFAULT_ALIGNMENT_VALUE
Define EIGENPY_DEFAULT_OPTIONAL
Define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION
Define EIGENPY_DEPRECATED_FILE
Define EIGENPY_DEPRECATED_MACRO
Define EIGENPY_DOCUMENTATION_START_IGNORE
Define EIGENPY_GET_PY_ARRAY_TYPE
Define EIGENPY_MAKE_FIXED_TYPEDEFS
Define EIGENPY_MAKE_TYPEDEFS
Define EIGENPY_MAKE_TYPEDEFS_ALL_SIZES
Define EIGENPY_NO_ALIGNMENT_VALUE
Define EIGENPY_NPY_CONST_UFUNC_ARG
Define EIGENPY_PPCAT
Define EIGENPY_REGISTER_BINARY_OPERATOR
Define EIGENPY_REGISTER_BINARY_UFUNC
Define EIGENPY_REGISTER_UNARY_OPERATOR
Define EIGENPY_REGISTER_UNARY_UFUNC
Define EIGENPY_RVALUE_FROM_PYTHON_DATA_INIT
Define EIGENPY_SHARED_PTR_HOLDER_TYPE
Define EIGENPY_STRING_LITERAL
Define EIGENPY_STRINGCAT
Define EIGENPY_STRINGIZE
Define EIGENPY_UNUSED_TYPE
Define EIGENPY_UNUSED_VARIABLE
Define EIGENPY_USED_VARIABLE_ONLY_IN_DEBUG_MODE
Define ENABLE_SPECIFIC_MATRIX_TYPE
Define NO_IMPORT_ARRAY
Define NPY_API_SYMBOL_ATTRIBUTE
Define PY_ARRAY_UNIQUE_SYMBOL
Define Py_SET_TYPE
Define PyArray_DescrProto
Define PyStr_Check
Define PyStr_FromString
Typedefs
Typedef eigenpy::instead
Directories
Directory include
Directory eigenpy
Directory decompositions
Directory sparse
Directory accelerate
Directory cholmod
Directory eigen
Directory solvers
Directory sparse
Directory tensor
Directory utils
Files
File Accelerate.hpp
File accelerate.hpp
File alignment.hpp
File angle-axis.hpp
File BasicPreconditioners.hpp
File BDCSVD.hpp
File BFGSPreconditioners.hpp
File BiCGSTAB.hpp
File CholmodBase.hpp
File CholmodDecomposition.hpp
File CholmodSimplicialLDLT.hpp
File CholmodSimplicialLLT.hpp
File CholmodSupernodalLLT.hpp
File ColPivHouseholderQR.hpp
File CompleteOrthogonalDecomposition.hpp
File ComplexEigenSolver.hpp
File ComplexSchur.hpp
File computation-info.hpp
File ConjugateGradient.hpp
File copyable.hpp
File decompositions.hpp
File deprecation-policy.hpp
File details.hpp
File eigen-allocator.hpp
File eigen-from-python.hpp
File eigen-from-python.hpp
File eigen-from-python.hpp
File eigen-to-python.hpp
File eigen-typedef.hpp
File EigenBase.hpp
File eigenpy.hpp
File EigenSolver.hpp
File empty-visitor.hpp
File exception.hpp
File expose.hpp
File FullPivHouseholderQR.hpp
File FullPivLU.hpp
File fwd.hpp
File GeneralizedEigenSolver.hpp
File GeneralizedSelfAdjointEigenSolver.hpp
File geometry-conversion.hpp
File geometry.hpp
File HessenbergDecomposition.hpp
File HouseholderQR.hpp
File id.hpp
File IncompleteCholesky.hpp
File IncompleteLUT.hpp
File is-aligned.hpp
File is-approx.hpp
File IterativeSolverBase.hpp
File JacobiSVD.hpp
File LDLT.hpp
File LDLT.hpp
File LeastSquaresConjugateGradient.hpp
File LLT.hpp
File LLT.hpp
File map.hpp
File memory.hpp
File minres.hpp
File MINRES.hpp
File numpy-allocator.hpp
File numpy-map.hpp
File numpy-type.hpp
File numpy.hpp
File optional.hpp
File PartialPivLU.hpp
File PermutationMatrix.hpp
File pickle-vector.hpp
File preconditioners.hpp
File python-compat.hpp
File QR.hpp
File quaternion.hpp
File RealQZ.hpp
File RealSchur.hpp
File register.hpp
File registration.hpp
File registration_class.hpp
File scalar-conversion.hpp
File scalar-name.hpp
File scipy-allocator.hpp
File scipy-type.hpp
File SelfAdjointEigenSolver.hpp
File SimplicialCholesky.hpp
File SimplicialLDLT.hpp
File SimplicialLLT.hpp
File solvers.hpp
File SparseLU.hpp
File SparseQR.hpp
File SparseSolverBase.hpp
File SparseSolverBase.hpp
File std-array.hpp
File std-map.hpp
File std-pair.hpp
File std-unique-ptr.hpp
File std-vector.hpp
File stride.hpp
File SVDBase.hpp
File swig.hpp
File traits.hpp
File Tridiagonalization.hpp
File type_info.hpp
File ufunc.hpp
File user-type.hpp
File variant.hpp
File version.hpp
Standard Documents
CHANGELOG
Changelog
Unreleased
3.12.0 - 2025-08-12
3.11.0 - 2025-04-25
3.10.3 - 2025-02-11
3.10.2 - 2025-01-13
3.10.1 - 2024-10-30
3.10.0 - 2024-09-26
3.9.1 - 2024-09-19
3.9.0 - 2024-08-31
3.8.2 - 2024-08-26
3.8.1 - 2024-08-25
3.8.0 - 2024-08-14
3.7.0 - 2024-06-11
3.6.0 - 2024-06-05
3.5.1 - 2024-04-25
3.5.0 - 2024-04-14
3.4.0 - 2024-02-26
3.3.0 - 2024-01-23
3.2.0 - 2023-12-12
3.1.4 - 2023-11-27
3.1.3 - 2023-11-09
3.1.2 - 2023-11-09
3.1.1 - 2023-07-31
3.1.0 - 2023-06-01
3.0.0 - 2023-04-22
2.9.2 - 2023-02-01
2.9.1 - 2023-01-31
2.9.0 - 2023-01-09
2.8.1 - 2022-12-07
2.8.0 - 2022-12-05
2.7.14 - 2022-09-11
2.7.13 - 2022-09-08
2.7.12 - 2022-08-24
2.7.11 - 2022-08-11
2.7.10 - 2022-07-27
2.7.9 - 2022-07-27
2.7.8 - 2022-07-24
2.7.7 - 2022-07-19
2.7.6 - 2022-05-22
2.7.5 - 2022-05-20
2.7.4 - 2022-05-06
2.7.3 - 2022-05-02
2.7.2 - 2022-04-22
2.7.1 - 2022-04-09
2.7.0 - 2022-04-02
2.6.11 - 2022-02-25
2.6.10 - 2022-02-02
2.6.9 - 2021-10-29
2.6.8 - 2021-09-05
2.6.7 - 2021-08-19
2.6.6 - 2021-08-13
2.6.5 - 2021-07-30
2.6.4 - 2021-05-25
2.6.3 - 2021-04-16
2.6.2 - 2021-03-28
2.6.1 - 2021-01-20
2.6.0 - 2021-01-04
2.5.0 - 2020-08-25
2.4.4 - 2020-08-18
2.4.3 - 2020-07-20
2.4.2 - 2020-07-17
2.4.1 - 2020-06-09
2.4.0 - 2020-05-25
2.3.2 - 2020-04-23
2.3.1 - 2020-04-08
2.3.0 - 2020-04-03
2.2.2 - 2020-03-30
2.2.1 - 2020-03-27
2.2.0 - 2020-03-18
2.1.2 - 2020-02-28
2.1.1 - 2020-02-27
2.1.0 - 2020-02-25
2.0.3 - 2020-02-20
2.0.2 - 2020-02-06
2.0.1 - 2020-01-31
2.0.0 - 2020-01-30
1.6.13 - 2020-01-10
1.6.12 - 2019-12-10
1.6.11 - 2019-12-09
1.6.10 - 2019-12-09
1.6.9 - 2019-11-25
1.6.8 - 2019-11-25
1.6.7 - 2019-11-15
1.6.6 - 2019-11-13
1.6.5 - 2019-11-08
1.6.4 - 2019-11-07
1.6.3 - 2019-10-29
1.6.2 - 2019-10-24
1.6.1 - 2019-10-16
1.6.0 - 2019-09-19
1.5.8 - 2019-09-09
1.5.7 - 2019-07-19
1.5.6 - 2019-07-16
1.5.5 - 2019-07-15
1.5.4 - 2019-07-13
1.5.3 - 2019-06-28
1.5.2 - 2019-06-26
1.5.1 - 2019-04-16
1.5.0 - 2018-10-29
1.4.5 - 2018-08-29
1.4.4 - 2018-07-19
1.4.3 - 2018-05-12
1.4.2 - 2018-05-02
1.4.1 - 2018-02-26
1.4.0 - 2018-01-14
1.3.3 - 2017-06-09
1.3.2 - 2016-11-21
1.3.1 - 2016-09-23
1.3.0 - 2016-02-03
1.2.0 - 2014-11-13
1.1.0 - 2014-09-16
1.0.1 - 2014-07-18
1.0.0 - 2014-07-18
README
EigenPy — Versatile and efficient Python bindings between Numpy and Eigen
Installation
Build
Credits
Acknowledgments
PACKAGE
LICENSE
Index
eigenpy: Jazzy
C++ API
Template Struct init_matrix_or_array< MatType, true >
View page source
Template Struct init_matrix_or_array< MatType, true >
Defined in
File eigen-allocator.hpp
Struct Documentation
template
<
typename
MatType
>
struct
init_matrix_or_array
<
MatType
,
true
>
Public Static Functions
static
inline
MatType
*
run
(
int
rows
,
int
cols
,
void
*
storage
)
static
inline
MatType
*
run
(
int
size
,
void
*
storage
)
static
inline
MatType
*
run
(
PyArrayObject
*
pyArray
,
void
*
storage
=
NULL
)