|
OpenKalman
|
The root namespace for OpenKalman. More...
Namespaces | |
| collections | |
| Namespace for collections. | |
| coordinates | |
| The namespace for features relating to coordinates::pattern object. | |
| detail | |
| T is an acceptable noise perturbation input to a tests. | |
| values | |
| Definition for values::abs. | |
Classes | |
| struct | constant_adapter |
| A tensor or other matrix in which all elements are a constant value. More... | |
| struct | constant_value_of |
| The static constant value of an indexible object, if it exists. More... | |
| struct | constant_value_of< T, std::enable_if_t< values::fixed< decltype(constant_value(std::declval< T >()))> > > |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| struct | ContinuousPropertyParticleDistribution |
| struct | Covariance |
| A self-adjoint Covariance matrix. More... | |
| struct | CubaturePoints |
| Implementation of a cubature points transform. More... | |
| struct | diagonal_adapter |
| An adapter for creating a diagonal matrix or tensor. More... | |
| struct | DistributionTraits< GaussianDistribution< Coeffs, NestedMean, NestedCovariance, re > > |
| struct | dynamic_index_count |
| Counts the number of indices of T in which the dimensions are dynamic. More... | |
| struct | dynamic_index_count< T, std::enable_if_t< indexible< T > > > |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| struct | element_type_of |
| The element type (e.g., std::float, std::double, std::complex<double>) of an indexible object. More... | |
| struct | element_type_of< T, std::enable_if_t< indexible< T > > > |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| struct | EuclideanMean |
| Similar to a Mean, but the coefficients are transformed into Euclidean space, based on their type. More... | |
| struct | FiniteDifferenceLinearization |
| A tests which calculates the first and second Taylor derivatives using finite differences. More... | |
| struct | FromEuclideanExpr |
| An expression that transforms angular or other modular vector space descriptors back from Euclidean space. More... | |
| struct | GaussianDistribution |
| A Gaussian distribution, defined in terms of a Mean and a Covariance. More... | |
| struct | hermitian_adapter_type_of |
| The triangle_type associated with the storage triangle of one or more matrices. More... | |
| struct | HermitianAdapter |
| A hermitian matrix wrapper. More... | |
| struct | IdentityTransform |
| An identity transform from one statistical distribution to another. More... | |
| struct | IdentityTransformation |
| struct | index_count |
| The minimum number of indices needed to access all the components of an object (i.e., the rank or order). More... | |
| struct | index_count< T, std::enable_if_t< values::fixed< decltype(count_indices(std::declval< const T & >()))> > > |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| struct | index_dimension_of |
| The dimension of an index for a matrix, expression, or array. More... | |
| struct | index_dimension_of< T, N, std::enable_if_t< indexible< T > > > |
| struct | KalmanFilter |
| A Kalman filter, using one or more statistical transforms. More... | |
| struct | KalmanFilter< ProcessTransform, MeasurementTransform > |
| A Kalman filter, using a different statistical transform for the process and the measurement. More... | |
| struct | KalmanFilter< Transform > |
| A Kalman filter, using the same transform for the process and the measurement. More... | |
| struct | layout_of |
| The layout_mapping_policy of an indexible object. More... | |
| struct | layout_of< T, std::enable_if_t< indexible< T > > > |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| class | LinearizedTransform |
| A linearized transform, using a 1st or 2nd order Taylor approximation of a linear tests. More... | |
| class | LinearTransform |
| A linear tests from one statistical distribution to another. More... | |
| struct | LinearTransformation |
| A linear tests from one single-column vector to another. More... | |
| struct | Matrix |
| A matrix with typed rows and columns. More... | |
| struct | max_tensor_order |
| The maximum number of indices of structure T of size other than 1 (including any dynamic indices). More... | |
| struct | max_tensor_order< T, std::enable_if_t< index_count< T >::value !=stdex::dynamic_extent > > |
| struct | Mean |
| A set of one or more column vectors, each representing a statistical mean. More... | |
| struct | MixtureOfContinuousDistributions |
| Weighted mixture of continuous (e.g., Gaussian) distributions. More... | |
| struct | MonteCarloTransform |
| A Monte Carlo transform from one Gaussian distribution to another. More... | |
| struct | nested_object_of |
| A wrapper type's nested object type, if it exists. More... | |
| struct | nested_object_of< T, std::enable_if_t< has_nested_object< T > > > |
| struct | ParticleDistribution |
| Distribution of particles. More... | |
| struct | ParticleFilter |
| struct | pattern_adapter |
| An adapter that attaches a pattern_collection to an indexible object. More... | |
| struct | RecursiveLeastSquaresTransform |
| Propagates a recursive least squares error distribution of parameters, with a forgetting factor λ. More... | |
| struct | SamplePointsTransform |
| Scaled points transform. More... | |
| struct | SphericalSimplex |
| Spherical simplex sigma points, as implemented in, e.g., Simon J. More... | |
| struct | SphericalSimplexParameters |
| struct | SquareRootCovariance |
| The upper or lower triangle Cholesky factor (square root) of a covariance matrix. More... | |
| struct | ToEuclideanExpr |
| An expression that transforms vector space descriptors into Euclidean space for application of directional statistics. More... | |
| struct | Transformation |
| A tests from one single-column vector to another. More... | |
| struct | Transformation< Function > |
| struct | Transformation< Function, JacobianFunction > |
| struct | Transformation< Function, JacobianFunction, HessianFunction > |
| struct | triangle_type_of |
| The triangle_type associated with an indexible object. More... | |
| struct | TriangularAdapter |
| A triangular_adapter, where components above or below the diagonal (or both) are zero. More... | |
| struct | Unscented |
| Scaled symmetric sigma points. More... | |
| struct | UnscentedParametersParameterEstimation |
| Unscented parameters for use in parameter estimation. More... | |
| struct | UnscentedParametersStateEstimation |
| Unscented parameters for use in state estimation (the default). More... | |
| struct | WeightedParticleDistribution |
Typedefs | |
| template<typename Shape , typename N = element_type_of_t<Shape>> | |
| using | zero_adapter = constant_adapter< values::fixed_value< N, 0 >, Shape > |
| A constant_adapter in which all elements are 0. More... | |
| template<typename T , data_layout layout = data_layout::none, typename S = scalar_type_of_t<T>, typename D = decltype(all_vector_space_descriptors(std::declval<T>())), std::enable_if_t< indexible< T > and values::number< S > and pattern_collection< D >, int > = 0> | |
| using | dense_writable_matrix_t = std::decay_t< decltype(make_dense_object< T, layout, S >(std::declval< D >()))> |
| An alias for a dense, writable matrix, patterned on parameter T. More... | |
| template<typename T > | |
| using | element_type_of_t = typename element_type_of< T >::type |
| helper template for element_type_of. | |
| template<typename T > | |
| using | layout_of_t = typename layout_of< T >::type |
| helper template for layout_of. | |
| template<typename T > | |
| using | nested_object_of_t = typename nested_object_of< T >::type |
| Helper type for nested_object_of. More... | |
| using | SphericalSimplexSigmaPoints = SphericalSimplex< SphericalSimplexParameters > |
| using | UnscentedSigmaPointsStateEstimation = Unscented< UnscentedParametersStateEstimation > |
| using | UnscentedSigmaPointsParameterEstimation = Unscented< UnscentedParametersParameterEstimation > |
| using | UnscentedSigmaPoints = Unscented< UnscentedParametersStateEstimation > |
| Same as UnscentedSigmaPointsStateEstimation. | |
| using | CubatureTransform = SamplePointsTransform< CubaturePoints > |
| using | UnscentedTransform = SamplePointsTransform< UnscentedSigmaPoints > |
| using | UnscentedTransformParameterEstimation = SamplePointsTransform< UnscentedSigmaPointsParameterEstimation > |
Enumerations | |
| enum | triangle_type : int { triangle_type::none, triangle_type::any, triangle_type::lower, triangle_type::upper, triangle_type::diagonal } |
| The type of a triangular matrix. More... | |
| enum | HermitianAdapterType : int { HermitianAdapterType::none = static_cast<int>(triangle_type::none), HermitianAdapterType::any = static_cast<int>(triangle_type::diagonal), HermitianAdapterType::lower = static_cast<int>(triangle_type::lower), HermitianAdapterType::upper = static_cast<int>(triangle_type::upper) } |
| The type of a hermitian adapter, indicating which triangle of the nested matrix is used. More... | |
| enum | applicability : int { applicability::guaranteed, applicability::permitted } |
| The applicability of a concept, trait, or restraint. More... | |
Functions | |
| constexpr std::size_t | operator""_uz (unsigned long long x) |
| template<typename M , typename C , std::enable_if_t< typed_matrix< M > and self_adjoint_covariance< C >, int > = 0> | |
| GaussianDistribution (M &&, C &&) -> GaussianDistribution< vector_space_descriptor_of_t< M, 0 >, nested_object_of_t< passable_t< M >>, nested_object_of_t< passable_t< C >>> | |
| template<typename D , std::enable_if_t< gaussian_distribution< D >, int > = 0> | |
| auto | make_GaussianDistribution (D &&dist) |
| Make a Gaussian distribution. More... | |
| template<typename re = std::mt19937, typename M , typename Cov > | |
| auto | make_GaussianDistribution (M &&mean, Cov &&cov) |
| Make a Gaussian distribution. More... | |
| template<typename re = std::mt19937, typename M , typename Cov , std::enable_if_t<(not fixed_pattern< re >) and typed_matrix< M > and vector< M > and has_untyped_index< M, 1 > and square_shaped< Cov > and(covariance_nestable< Cov > or typed_matrix_nestable< Cov >) and(index_dimension_of< M, 0 >::value==index_dimension_of< Cov, 0 >::value), int > = 0> | |
| auto | make_GaussianDistribution (M &&mean, Cov &&cov) |
| Make a Gaussian distribution. More... | |
| template<typename StaticDescriptor , typename re = std::mt19937, typename M , typename Cov , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< M > and vector< M > and(covariance_nestable< Cov > or typed_matrix_nestable< Cov >), int > = 0> | |
| auto | make_GaussianDistribution (M &&mean, Cov &&cov) |
| Make a Gaussian distribution. More... | |
| template<typename M , typename Cov , typename re = std::mt19937, std::enable_if_t< typed_matrix< M > and vector< M > and has_untyped_index< M, 1 > and covariance< Cov > and compares_with< vector_space_descriptor_of_t< M, 0 >, vector_space_descriptor_of_t< Cov, 0 >>, int > = 0> | |
| auto | make_GaussianDistribution () |
| Make a default Gaussian distribution. More... | |
| template<typename StaticDescriptor , typename M , typename Cov , typename re = std::mt19937, std::enable_if_t< typed_matrix_nestable< M > and vector< M > and covariance_nestable< Cov > and(index_dimension_of< M, 0 >::value==index_dimension_of< Cov, 0 >::value), int > = 0> | |
| auto | make_GaussianDistribution () |
| Make a default Gaussian distribution. More... | |
| template<typename Arg , std::enable_if_t< gaussian_distribution< Arg >, int > = 0> | |
| decltype(auto) constexpr | mean_of (Arg &&arg) |
| template<typename Arg , std::enable_if_t< gaussian_distribution< Arg >, int > = 0> | |
| decltype(auto) constexpr | covariance_of (Arg &&arg) |
| template<typename T , std::size_t dimension = index_dimension_of<T, 0>::value, typename Scalar = typename scalar_type_of<T>::type, typename... runtime_dimensions, std::enable_if_t< gaussian_distribution< T > and(sizeof...(runtime_dimensions)==(dimension==stdex::dynamic_extent ? 1 :0)) and(stdex::convertible_to< runtime_dimensions, std::size_t > and ...), int > = 0> | |
| constexpr auto | make_zero_distribution_like (runtime_dimensions...e) |
| template<typename T , std::size_t dimension = index_dimension_of<T, 0>::value, typename Scalar = typename scalar_type_of<T>::type, typename... runtime_dimensions, std::enable_if_t< gaussian_distribution< T > and(sizeof...(runtime_dimensions)==(dimension==stdex::dynamic_extent ? 1 :0)) and(stdex::convertible_to< runtime_dimensions, std::size_t > and ...), int > = 0> | |
| constexpr auto | make_normal_distribution_like (runtime_dimensions...e) |
| template<typename D , typename ... Ds, std::enable_if_t<(gaussian_distribution< D > and ... and gaussian_distribution< Ds >), int > = 0> | |
| auto | concatenate (D &&d, Ds &&... ds) |
| template<typename ... Cs, typename D , std::enable_if_t<(fixed_pattern< Cs > and ...) and gaussian_distribution< D > and coordinates::compares_with< static_concatenate_t< Cs... >, typename DistributionTraits< D >::StaticDescriptor, less_equal<>>, int > = 0> | |
| auto | split (D &&d) |
| Split distribution. | |
| template<typename Dist , std::enable_if_t< gaussian_distribution< Dist >, int > = 0> | |
| std::ostream & | operator<< (std::ostream &os, const Dist &d) |
| template<typename Dist1 , typename Dist2 , std::enable_if_t< gaussian_distribution< Dist1 > and gaussian_distribution< Dist2 > and coordinates::compares_with< typename DistributionTraits< Dist1 >::StaticDescriptor, typename DistributionTraits< Dist2 >::StaticDescriptor >, int > = 0> | |
| auto | operator+ (Dist1 &&d1, Dist2 &&d2) |
| template<typename Dist1 , typename Dist2 , std::enable_if_t< gaussian_distribution< Dist1 > and gaussian_distribution< Dist2 > and coordinates::compares_with< typename DistributionTraits< Dist1 >::StaticDescriptor, typename DistributionTraits< Dist2 >::StaticDescriptor >, int > = 0> | |
| auto | operator- (Dist1 &&d1, Dist2 &&d2) |
| template<typename A , typename D , std::enable_if_t< typed_matrix< A > and gaussian_distribution< D > and(not euclidean_transformed< A >) and(compares_with< vector_space_descriptor_of_t< A, 1 >, typename DistributionTraits< D >::StaticDescriptor >), int > = 0> | |
| auto | operator* (A &&a, D &&d) |
| template<typename Dist , typename S , std::enable_if_t< gaussian_distribution< Dist > and stdex::convertible_to< S, const typename DistributionTraits< Dist >::Scalar >, int > = 0> | |
| auto | operator* (Dist &&d, S s) |
| template<typename Dist , typename S , std::enable_if_t< gaussian_distribution< Dist > and stdex::convertible_to< S, const typename DistributionTraits< Dist >::Scalar >, int > = 0> | |
| auto | operator* (S s, Dist &&d) |
| template<typename Dist , typename S , std::enable_if_t< gaussian_distribution< Dist > and std::is_convertible_v< S, const typename DistributionTraits< Dist >::Scalar >, int > = 0> | |
| auto | operator/ (Dist &&d, S s) |
| template<typename P > | |
| KalmanFilter (P &&) -> KalmanFilter< P > | |
| template<typename P , typename M > | |
| KalmanFilter (P &&, M &&) -> KalmanFilter< P, M > | |
| template<typename C , typename Arg , std::enable_if_t< values::scalar< C > and indexible< Arg >, int > = 0> | |
| constant_adapter (const C &, const Arg &) -> constant_adapter< C, Arg > | |
| template<typename Arg , std::enable_if_t< constant_object< Arg > and(not is_constant_adapter< Arg >), int > = 0> | |
| constant_adapter (const Arg &) -> constant_adapter< is_constant_value< Arg >::value, Arg > | |
| template<typename M , std::enable_if_t< covariance_nestable< M >, int > = 0> | |
| Covariance (M &&) -> Covariance< Dimensions< index_dimension_of_v< M, 0 >>, passable_t< M >> | |
| Deduce Covariance type from a covariance_nestable. More... | |
| template<typename StaticDescriptor , typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and covariance_nestable< Arg > and(coordinates::dimension_of_v< StaticDescriptor >==index_dimension_of< Arg, 0 >::value), int > = 0> | |
| auto | make_covariance (Arg &&arg) |
| Make a Covariance from a covariance_nestable, specifying the fixed_pattern. More... | |
| template<typename StaticDescriptor , triangle_type tri, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and covariance_nestable< Arg > and(coordinates::dimension_of_v< StaticDescriptor >==index_dimension_of< Arg, 0 >::value) and(tri !=triangle_type::lower or triangular_matrix< Arg, triangle_type::lower >) and(tri !=triangle_type::upper or triangular_matrix< Arg, triangle_type::upper >) and(tri !=triangle_type::diagonal or diagonal_matrix< Arg >), int > = 0> | |
| auto | make_covariance (Arg &&arg) |
| Make a Covariance from a covariance_nestable, specifying the fixed_pattern. More... | |
| template<typename Arg , std::enable_if_t< covariance_nestable< Arg >, int > = 0> | |
| auto | make_covariance (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0> | |
| auto | make_covariance () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , triangle_type tri, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< Arg > and square_shaped< Arg >, int > = 0> | |
| auto | make_covariance () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0> | |
| auto | make_covariance () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg1 , typename Arg2 , std::enable_if_t<((covariance< Arg1 > and(covariance< Arg2 > or(typed_matrix< Arg2 > and square_shaped< Arg2 >))) or((typed_matrix< Arg1 > and square_shaped< Arg1 >) and covariance< Arg2 >)) and compares_with< vector_space_descriptor_of_t< Arg1, 0 >, vector_space_descriptor_of_t< Arg2, 0 >>, int > = 0> | |
| decltype(auto) constexpr | operator+ (Arg1 &&arg1, Arg2 &&arg2) |
| template<typename Arg1 , typename Arg2 , std::enable_if_t<((covariance< Arg1 > and(covariance< Arg2 > or(typed_matrix< Arg2 > and square_shaped< Arg2 >))) or((typed_matrix< Arg1 > and square_shaped< Arg1 >) and covariance< Arg2 >)) and compares_with< vector_space_descriptor_of_t< Arg1, 0 >, vector_space_descriptor_of_t< Arg2, 0 >>, int > = 0> | |
| decltype(auto) constexpr | operator- (Arg1 &&arg1, Arg2 &&arg2) |
| template<typename Arg1 , typename Arg2 , std::enable_if_t< covariance< Arg1 > and covariance< Arg2 > and compares_with< vector_space_descriptor_of_t< Arg1, 0 >, vector_space_descriptor_of_t< Arg2, 0 >>, int > = 0> | |
| decltype(auto) constexpr | operator* (Arg1 &&arg1, Arg2 &&arg2) |
| template<typename M , typename Cov , std::enable_if_t< typed_matrix< M > and covariance< Cov > and compares_with< vector_space_descriptor_of_t< M, 0 >::ColumnCoefficients, typename MatrixTraits< std::decay_t< Cov >>>, int > = 0> | |
| decltype(auto) constexpr | operator* (M &&m, Cov &&cov) |
| template<typename Cov , typename M , std::enable_if_t< covariance< Cov > and typed_matrix< M > and compares_with< vector_space_descriptor_of_t< Cov, 0 >, vector_space_descriptor_of_t< M, 0 >>, int > = 0> | |
| decltype(auto) constexpr | operator* (Cov &&cov, M &&m) |
| template<typename M , typename S , std::enable_if_t< covariance< M > and stdex::convertible_to< S, typename scalar_type_of< M >::type >, int > = 0> | |
| auto | operator* (M &&m, const S s) |
| template<typename S , typename M , std::enable_if_t< stdex::convertible_to< S, typename scalar_type_of< M >::type > and covariance< M >, int > = 0> | |
| auto | operator* (const S s, M &&m) |
| template<typename M , typename S , std::enable_if_t< covariance< M > and stdex::convertible_to< S, typename scalar_type_of< M >::type >, int > = 0> | |
| constexpr auto | operator/ (M &&m, const S s) |
| template<typename M , std::enable_if_t< covariance< M >, int > = 0> | |
| constexpr auto | operator- (M &&m) |
| template<typename Arg1 , typename Arg2 , std::enable_if_t< covariance< Arg1 > and covariance< Arg2 >, int > = 0> | |
| constexpr bool | operator== (Arg1 &&arg1, Arg2 &&arg2) |
| template<typename Arg1 , typename Arg2 , std::enable_if_t< covariance< Arg1 > and covariance< Arg2 >, int > = 0> | |
| constexpr bool | operator!= (Arg1 &&arg1, Arg2 &&arg2) |
| template<typename M , typename S , std::enable_if_t< covariance< M > and stdex::convertible_to< S, typename scalar_type_of< M >::type >, int > = 0> | |
| auto | scale (M &&m, const S s) |
| Scale a covariance by a factor. More... | |
| template<typename M , typename S , std::enable_if_t< covariance< M > and stdex::convertible_to< S, typename scalar_type_of< M >::type >, int > = 0> | |
| auto | inverse_scale (M &&m, const S s) |
| Scale a covariance by the inverse of a scalar factor. More... | |
| template<typename M , typename A , std::enable_if_t< covariance< M > and typed_matrix< A > and compares_with< vector_space_descriptor_of_t< A, 0 >::ColumnCoefficients, typename MatrixTraits< std::decay_t< M >>>and(not euclidean_transformed< A >), int > = 0> | |
| auto | scale (M &&m, A &&a) |
| Scale a covariance by a matrix. More... | |
| template<typename Arg , std::enable_if_t< self_adjoint_covariance< Arg >, int > = 0> | |
| auto | square_root (Arg &&arg) |
| template<typename Arg , std::enable_if_t< triangular_covariance< Arg >, int > = 0> | |
| auto | square (Arg &&arg) |
| template<typename M , typename ... Ms, std::enable_if_t<(covariance< M > and ... and covariance< Ms >), int > = 0> | |
| decltype(auto) constexpr | concatenate (M &&m, Ms &&... mN) |
| Concatenate one or more Covariance or SquareRootCovariance objects diagonally. | |
| template<typename ... Cs, typename M , std::enable_if_t< covariance< M >, int > = 0> | |
| auto | split_diagonal (M &&m) |
| Split Covariance or SquareRootCovariance diagonally. More... | |
| template<typename ... Cs, typename M , std::enable_if_t< covariance< M >, int > = 0> | |
| auto | split_vertical (M &&m) |
| Split Covariance or SquareRootCovariance vertically. Result is a tuple of typed matrices. More... | |
| template<typename ... Cs, typename M , std::enable_if_t< covariance< M >, int > = 0> | |
| auto | split_horizontal (M &&m) |
| Split Covariance or SquareRootCovariance vertically. Result is a tuple of typed matrices. More... | |
| template<typename Function , typename Arg , std::enable_if_t< covariance< Arg > and typed_matrix< std::invoke_result_t< Function, std::decay_t< decltype(column< 0 >(std::declval< Arg >()))>>>, int > = 0> | |
| auto | apply_columnwise (const Function &f, Arg &&arg) |
| template<typename Function , typename Arg , std::enable_if_t< covariance< Arg > and stdex::convertible_to< std::invoke_result_t< Function, typename scalar_type_of< Arg >::type >, const typename scalar_type_of< Arg >::type >, int > = 0> | |
| auto | apply_coefficientwise (const Function &f, Arg &&arg) |
| template<typename Cov , std::enable_if_t< covariance< Cov >, int > = 0> | |
| std::ostream & | operator<< (std::ostream &os, const Cov &c) |
| template<typename V1 , typename V2 , std::enable_if_t< typed_matrix< V1 > and typed_matrix< V2 >, int > = 0> | |
| auto | operator+ (V1 &&v1, V2 &&v2) |
| Add two typed matrices. If the operands are of different types, the result will be a regular typed matrix. | |
| template<typename V1 , typename V2 , std::enable_if_t< typed_matrix< V1 > and typed_matrix< V2 >, int > = 0> | |
| auto | operator- (V1 &&v1, V2 &&v2) |
| Subtract two typed matrices. The result is a regular typed matrix unless both operands are EuclideanMean. | |
| template<typename V , typename S , std::enable_if_t< typed_matrix< V > and stdex::convertible_to< S, const typename scalar_type_of< V >::type >, int > = 0> | |
| auto | operator* (V &&v, S scale) |
| Multiply a typed matrix by a scalar. The result type is the same as the operand type, so angles in the result may be wrapped. | |
| template<typename V , typename S , std::enable_if_t< typed_matrix< V > and stdex::convertible_to< S, const typename scalar_type_of< V >::type >, int > = 0> | |
| auto | operator* (S scale, V &&v) |
| Multiply a scalar by a typed matrix. The result type is the same as the operand type, so angles in the result may be wrapped. | |
| template<typename V , typename S , std::enable_if_t< typed_matrix< V > and stdex::convertible_to< S, const typename scalar_type_of< V >::type >, int > = 0> | |
| auto | operator/ (V &&v, S scale) |
| Divide a typed matrix by a scalar. The result type is the same as the operand type, so angles in the result may be wrapped. | |
| template<typename V1 , typename V2 , std::enable_if_t< typed_matrix< V1 > and typed_matrix< V2 >, int > = 0> | |
| auto | operator* (V1 &&v1, V2 &&v2) |
| Multiply a typed matrix by another typed matrix. The result is a regular typed matrix unless the first operand is EuclideanMean. | |
| template<typename V , std::enable_if_t< typed_matrix< V >, int > = 0> | |
| auto | operator- (V &&v) |
| Negate a vector object. The result is a regular typed matrix unless the operand is EuclideanMean. | |
| template<typename V1 , typename V2 , std::enable_if_t< typed_matrix< V1 > and typed_matrix< V2 >, int > = 0> | |
| constexpr bool | operator== (V1 &&v1, V2 &&v2) |
| typed_matrix == typed_matrix. | |
| template<typename V1 , typename V2 , std::enable_if_t< typed_matrix< V1 > and typed_matrix< V2 >, int > = 0> | |
| constexpr bool | operator!= (V1 &&v1, V2 &&v2) |
| typed_matrix != typed_matrix. | |
| template<typename V , typename ... Vs> | |
| decltype(auto) constexpr | concatenate_vertical (V &&v, Vs &&... vs) |
| Concatenate one or more typed matrices objects vertically. | |
| template<typename ... Vs, std::enable_if_t<(typed_matrix< Vs > and ...), int > = 0> | |
| decltype(auto) constexpr | concatenate (Vs &&... vs) |
| Concatenate one or more typed matrices vertically. (Synonym for concatenate_vertical.) | |
| template<typename V , typename ... Vs> | |
| decltype(auto) constexpr | concatenate_horizontal (V &&v, Vs &&... vs) |
| Concatenate one or more matrix objects vertically. | |
| template<typename V , typename ... Vs, std::enable_if_t<(typed_matrix< V > and ... and typed_matrix< Vs >), int > = 0> | |
| decltype(auto) constexpr | concatenate_diagonal (V &&v, Vs &&... vs) |
| Concatenate one or more typed matrices diagonally. | |
| template<typename Function , typename Arg > | |
| Arg & | apply_columnwise (const Function &f, Arg &arg) |
| template<typename Function , typename Arg , std::enable_if_t< typed_matrix< Arg > and has_untyped_index< Arg, 1 > and typed_matrix< std::invoke_result_t< const Function &, std::decay_t< decltype(column(std::declval< const Arg &>(), 0))> && >>, int > = 0> | |
| auto | apply_columnwise (const Function &f, const Arg &arg) |
| template<std::size_t count, typename Function , std::enable_if_t< typed_matrix< std::invoke_result_t< const Function &>>, int > = 0> | |
| auto | apply_columnwise (const Function &f) |
| template<typename Function , typename Arg , std::enable_if_t< typed_matrix< Arg > and std::is_void_v< std::invoke_result_t< const Function &, std::decay_t< scalar_type_of_t< Arg >> &>>, int > = 0> | |
| Arg & | apply_coefficientwise (const Function &f, Arg &arg) |
| template<typename Function , typename Arg , std::enable_if_t< typed_matrix< Arg > and stdex::convertible_to< std::invoke_result_t< const Function &, std::decay_t< typename scalar_type_of< Arg >::type >>, typename scalar_type_of< Arg >::type >, int > = 0> | |
| auto | apply_coefficientwise (const Function &f, const Arg &arg) |
| template<typename V , typename Function , std::enable_if_t< typed_matrix< V > and stdex::convertible_to< std::invoke_result_t< const Function &>, typename scalar_type_of< V >::type >, int > = 0> | |
| auto | apply_coefficientwise (const Function &f) |
| template<typename V , typename Function , std::enable_if_t< typed_matrix< V > and stdex::convertible_to< std::invoke_result_t< const Function &, std::size_t, std::size_t >, typename scalar_type_of< V >::type >, int > = 0> | |
| auto | apply_coefficientwise (Function &&f) |
| template<typename ReturnType , typename random_number_engine = std::mt19937, typename... Dists, std::enable_if_t< typed_matrix< ReturnType > and(not has_dynamic_dimensions< ReturnType >) and(sizeof...(Dists) > 0> | |
| auto | randomize (Dists &&... dists) |
| Fill a fixed-shape typed matrix with random values selected from a random distribution. More... | |
| template<typename ReturnType , typename random_number_engine = std::mt19937, typename Dist > | |
| auto | randomize (const std::size_t rows, const std::size_t columns, Dist &&dist) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename V , std::enable_if_t< typed_matrix< V >, int > = 0> | |
| std::ostream & | operator<< (std::ostream &os, const V &v) |
| Output the vector to a stream. | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| diagonal_adapter (Arg &&) -> diagonal_adapter< Arg > | |
| Deduce diagonal_adapter NestedObject from its constructor argument. | |
| template<typename V , std::enable_if_t< typed_matrix< V > and not euclidean_transformed< V > and has_untyped_index< V, 1 > andcoordinates::stat_dimension_of_v< vector_space_descriptor_of_t< V, 0 >>==index_dimension_of_v< V, 0 >, int > = 0> | |
| EuclideanMean (V &&) -> EuclideanMean< vector_space_descriptor_of_t< V, 0 >, std::remove_reference_t< decltype(to_euclidean< vector_space_descriptor_of_t< V, 0 >>(nested_object(std::declval< V &&>())))>> | |
| Deduce template parameters from a non-Euclidean-transformed typed matrix. More... | |
| template<typename StaticDescriptor , typename M , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< M > and(coordinates::stat_dimension_of_v< StaticDescriptor >==index_dimension_of< M, 0 >::value), int > = 0> | |
| auto | make_euclidean_mean (M &&arg) |
| Make a EuclideanMean from a typed_matrix_nestable, specifying the row coefficients. More... | |
| template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0> | |
| auto | make_euclidean_mean (M &&m) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , std::enable_if_t< typed_matrix< Arg > and has_untyped_index< Arg, 1 >, int > = 0> | |
| auto | make_euclidean_mean (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , typename M , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< M > and(coordinates::stat_dimension_of_v< StaticDescriptor >==index_dimension_of< M, 0 >::value), int > = 0> | |
| auto | make_euclidean_mean () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0> | |
| auto | make_euclidean_mean () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , typename V , std::enable_if_t< indexible< Arg > and coordinates::pattern< V >, int > = 0> | |
| FromEuclideanExpr (Arg &&, const V &) -> FromEuclideanExpr< Arg, V > | |
| template<typename M , std::enable_if_t< hermitian_matrix< M, applicability::permitted >, int > = 0> | |
| HermitianAdapter (M &&) -> HermitianAdapter< nested_object_of_t< M >, hermitian_adapter_type_of_v< M >> | |
| Deduction guide for converting Eigen::SelfAdjointView to HermitianAdapter. | |
| template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0> | |
| Matrix (M &&) -> Matrix< Dimensions< index_dimension_of_v< M, 0 >>, Dimensions< index_dimension_of_v< M, 1 >>, passable_t< M >> | |
| Deduce parameter types from a typed_matrix_nestable. | |
| template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0> | |
| Matrix (M &&, const Cs &...) -> Matrix< Cs..., passable_t< M >> | |
| template<typename V , std::enable_if_t< typed_matrix< V > and not euclidean_transformed< V >, int > = 0> | |
| Matrix (V &&) -> Matrix< vector_space_descriptor_of_t< V, 0 >, vector_space_descriptor_of_t< V, 1 >, passable_t< nested_object_of_t< V >>> | |
| Deduce template parameters from a non-Euclidean-transformed typed matrix. More... | |
| template<typename V , std::enable_if_t< typed_matrix_nestable< V >, int > = 0> | |
| Mean (V &&) -> Mean< Dimensions< index_dimension_of_v< V, 0 >>, passable_t< V >> | |
| Deduce template parameters from a typed_matrix_nestable, assuming untyped coordinates::pattern. More... | |
| template<typename StaticDescriptor , typename M , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< M > and(coordinates::dimension_of_v< StaticDescriptor >==index_dimension_of< M, 0 >::value), int > = 0> | |
| auto | make_mean (M &&m) |
| Make a Mean from a typed_matrix_nestable, specifying the row fixed_pattern. More... | |
| template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0> | |
| auto | make_mean (M &&m) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , std::enable_if_t< typed_matrix< Arg > and has_untyped_index< Arg, 1 >, int > = 0> | |
| auto | make_mean (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , typename M , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< M > and(index_dimension_of< M, 0 >::value==coordinates::dimension_of_v< StaticDescriptor >), int > = 0> | |
| auto | make_mean () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0> | |
| auto | make_mean () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , typename P , std::enable_if_t< indexible< Arg > and pattern_collection_for< P, Arg >, int > = 0> | |
| pattern_adapter (Arg &&, P &&) -> pattern_adapter< Arg, P > | |
| Deduction guide. | |
| template<typename M , std::enable_if_t< covariance_nestable< M >, int > = 0> | |
| SquareRootCovariance (M &&) -> SquareRootCovariance< Dimensions< index_dimension_of_v< M, 0 >>, passable_t< M >> | |
| Deduce SquareRootCovariance type from a covariance_nestable. More... | |
| template<typename StaticDescriptor , typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and covariance_nestable< Arg > and(coordinates::dimension_of_v< StaticDescriptor >==index_dimension_of< Arg, 0 >::value), int > = 0> | |
| auto | make_square_root_covariance (Arg &&arg) |
| Make a SquareRootCovariance from a covariance_nestable, specifying the coefficients. More... | |
| template<typename Arg , std::enable_if_t< covariance_nestable< Arg >, int > = 0> | |
| auto | make_square_root_covariance (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , triangle_type tri = triangle_type::lower, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< Arg > and(not covariance_nestable< Arg >) and(tri==triangle_type::lower or tri==triangle_type::upper) and(coordinates::dimension_of_v< StaticDescriptor >==index_dimension_of< Arg, 0 >::value) and(coordinates::dimension_of_v< StaticDescriptor >==index_dimension_of< Arg, 1 >::value), int > = 0> | |
| auto | make_square_root_covariance (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , triangle_type tri, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< Arg > and square_shaped< Arg >, int > = 0> | |
| auto | make_square_root_covariance () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0> | |
| auto | make_square_root_covariance () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0> | |
| auto | make_square_root_covariance () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| ToEuclideanExpr (Arg &&) -> ToEuclideanExpr< Arg > | |
| Deduction guide. | |
| template<typename M , std::enable_if_t< triangular_matrix< M >, int > = 0> | |
| TriangularAdapter (M &&) -> TriangularAdapter< std::conditional_t< triangular_adapter< M >, nested_object_of_t< M >, M >, triangle_type_of_v< M >> | |
| constexpr triangle_type | operator* (triangle_type a, triangle_type b) |
| The resulting triangle_type if two indexible objects, each having a triangle_type, are multiplied component-wise. | |
| constexpr triangle_type | operator+ (triangle_type a, triangle_type b) |
| The resulting triangle_type if two indexible objects, each having a triangle_type, are added component-wise. | |
| template<std::size_t indexa = 0, std::size_t indexb = 1, typename Arg > | |
| decltype(auto) constexpr | adjoint (Arg &&arg) |
| Take the conjugate-transpose of an indexible_object. More... | |
| template<typename Arg , typename P , std::enable_if_t< indexible< Arg > and pattern_collection_for< P, Arg >, int > = 0> | |
| constexpr auto | attach_pattern (Arg &&arg, P &&p) |
| Attach a pattern_collection to an indexible object. More... | |
| template<typename Arg , typename... Ps, std::enable_if_t< indexible< Arg > and(... and coordinates::pattern< Ps >) and pattern_collection_for< std::tuple< Ps... >, Arg >, int > = 0> | |
| constexpr auto | attach_pattern (Arg &&arg, Ps &&...ps) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename P , typename Arg , std::enable_if_t< indexible< Arg > and pattern_collection_for< P, Arg >, int > = 0> | |
| constexpr auto | attach_pattern (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<std::size_t index, std::size_t... indices, typename Arg , std::enable_if_t< internal::has_uniform_patterns< Arg, index, indices... > and(not empty_object< Arg >), int > = 0> | |
| decltype(auto) constexpr | average_reduce (Arg &&arg) |
| Perform a partial reduction by taking the average along one or more indices. More... | |
| template<typename Arg , std::enable_if_t< internal::has_uniform_patterns< Arg >, int > = 0> | |
| constexpr scalar_type_of_t< Arg > | average_reduce (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , typename... Factors, std::enable_if_t< indexible< Arg > and(... and values::index< Factors >), int > = 0> | |
| decltype(auto) constexpr | broadcast (Arg &&arg, const Factors &...factors) |
| Broadcast an object by replicating it by factors specified for each index. More... | |
| template<std::size_t... indices, typename Operation , typename... Args, std::enable_if_t<(indexible< Args > and ...) and(sizeof...(Args) > 0> | |
| constexpr auto | chipwise_operation (const Operation &operation, Args &&...args) |
| Perform a chipwise n-ary operation (n>0) on one or more indexible objects. More... | |
| template<std::size_t... indices, typename Operation , typename... Is, std::enable_if_t<(values::index< Is > and ...) and(sizeof...(Is)==sizeof...(indices)), int > = 0> | |
| constexpr auto | chipwise_operation (const Operation &operation, Is...is) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<triangle_type tri, typename A , std::enable_if_t< hermitian_matrix< A, applicability::permitted > and(tri !=triangle_type::diagonal or diagonal_matrix< A >), int > = 0> | |
| decltype(auto) constexpr | cholesky_factor (A &&a) |
| Take the Cholesky factor of a matrix. More... | |
| template<typename A , std::enable_if_t< hermitian_matrix< A, applicability::permitted >, int > = 0> | |
| decltype(auto) constexpr | cholesky_factor (A &&a) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename A , std::enable_if_t< triangular_matrix< A > and square_shaped< A, applicability::permitted >, int > = 0> | |
| decltype(auto) constexpr | cholesky_square (A &&a) |
| Take the Cholesky square of a triangular_matrix. More... | |
| template<std::size_t... indices, typename Arg , typename... Args, std::enable_if_t<(sizeof...(indices) > 0> | |
| decltype(auto) constexpr | concatenate (Arg &&arg, Args &&...args) |
| Concatenate some number of objects along one or more indices. More... | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| decltype(auto) constexpr | conjugate (Arg &&arg) |
| Take the complex conjugate of an indexible object. More... | |
| template<typename A , typename B > | |
| decltype(auto) constexpr | contract (A &&a, B &&b) |
| Matrix multiplication of A * B. | |
| template<bool on_the_right = true, typename A , typename B > | |
| constexpr A && | contract_in_place (A &&a, B &&b) |
| In-place matrix multiplication of A * B, storing the result in A. More... | |
| template<typename Source , typename Dest , std::enable_if_t< copyable_from< Dest, Source >, int > = 0> | |
| decltype(auto) constexpr | copy_from (Dest &&dest, Source &&source) |
| Copy elements from one object to another. More... | |
| template<typename Arg > | |
| constexpr auto | determinant (Arg &&arg) |
| Take the determinant of a matrix. More... | |
| template<typename Arg > | |
| decltype(auto) constexpr | diagonal_of (Arg &&arg) |
| Extract a column vector (or column slice for rank>2 tensors) comprising the diagonal elements. More... | |
| template<typename layout layout = stdex::layout_right, typename Arg , typename... S, std::enable_if_t< indexible< Arg > and(values::number< S > and ...) and(std::same_as< layout, stdex::layout_right > or std::same_as< layout, stdex::layout_left >) and internal::may_hold_components< Arg, S... > and(sizeof...(S)==0 or interface::fill_components_defined_for< Arg, layout, std::add_lvalue_reference_t< Arg >, S... >), int > = 0> | |
| Arg && | fill_components (Arg &&arg, S...s) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , typename V , std::enable_if_t< coordinates::euclidean_pattern< vector_space_descriptor_of_t< Arg, 0 >> and coordinates::pattern< V >, int > = 0> | |
| decltype(auto) constexpr | from_euclidean (Arg &&arg, const V &v) |
| Project the Euclidean vector space associated with index 0 to coordinates::pattern v after applying directional statistics. More... | |
| template<std::size_t... indices, typename Arg , typename... Ixs, std::enable_if_t< indexible< Arg > and(values::index< Ixs > and ...) and(sizeof...(indices)==sizeof...(Ixs)), int > = 0> | |
| decltype(auto) constexpr | get_chip (Arg &&arg, Ixs...ixs) |
| Extract a sub-array having rank less than the rank of the input object. More... | |
| template<std::size_t... indices, typename Arg , typename... Offset, typename... Extent, std::enable_if_t< indexible< Arg > and(values::index< Offset > and ...) and(values::index< Extent > and ...) and(sizeof...(Offset)==sizeof...(Extent)) and internal::has_uniform_patterns< Arg, indices... > and(sizeof...(indices)==0 or sizeof...(indices)==sizeof...(Offset)), int > = 0> | |
| decltype(auto) constexpr | get_slice (Arg &&arg, const std::tuple< Offset... > &offsets, const std::tuple< Extent... > &extents) |
| Extract a slice from a matrix or tensor. More... | |
| template<typename A , std::enable_if_t< indexible< A > and(not euclidean_transformed< A >), int > = 0> | |
| decltype(auto) constexpr | LQ_decomposition (A &&a) |
| Perform an LQ decomposition of matrix A=[L,0]Q, L is a lower-triangular matrix, and Q is orthogonal. More... | |
| template<typename C , typename IndexType , std::size_t... Extents, std::enable_if_t< values::value< C >, int > = 0> | |
| constexpr auto | make_constant (C c, stdex::extents< IndexType, Extents... > extents) |
| Make an indexible object in which every element is a constant value. More... | |
| template<typename C , typename P , std::enable_if_t< values::value< C > and coordinates::pattern_collection< P > and values::fixed< collections::size_of< P >>, int > = 0> | |
| constexpr auto | make_constant (C c, P &&p) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename C , typename... Ps, std::enable_if_t< values::value< C > and(... and coordinates::pattern< Ps >), int > = 0> | |
| constexpr auto | make_constant (C c, Ps &&...ps) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename C , typename P , std::enable_if_t< coordinates::pattern_collection< P > and values::value< C > and values::fixed< collections::size_of< P >>, int > = 0> | |
| constexpr auto | make_constant (C c) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename C , typename IndexType , std::size_t... Extents, std::enable_if_t< values::value< C >, int > = 0> | |
| constexpr auto | make_constant_diagonal (C c, stdex::extents< IndexType, Extents... > extents) |
| Make an indexible object in which every diagonal element is a constant value. More... | |
| template<typename C , typename P , std::enable_if_t< values::value< C > and coordinates::pattern_collection< P > and values::fixed< collections::size_of< P >>, int > = 0> | |
| constexpr auto | make_constant_diagonal (C c, P &&p) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename C , typename... Ps, std::enable_if_t< values::value< C > and(... and coordinates::pattern< Ps >), int > = 0> | |
| constexpr auto | make_constant_diagonal (C c, Ps &&...ps) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename C , typename P , std::enable_if_t< coordinates::pattern_collection< P > and values::value< C > and values::fixed< collections::size_of< P >>, int > = 0> | |
| constexpr auto | make_constant_diagonal (C c) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename T , data_layout layout = data_layout::none, typename Scalar = scalar_type_of_t<T>, typename Descriptors , std::enable_if_t< indexible< T > and values::number< Scalar > and pattern_collection< D > and(layout !=data_layout::stride) and interface::make_default_defined_for< T, layout, Scalar, decltype(internal::to_euclidean_pattern_collection(std::declval< Descriptors &&>()))>, int > = 0> | |
| constexpr auto | make_dense_object (Descriptors &&descriptors) |
| Make a default, dense, writable matrix with a set of coordinates::pattern objects defining the dimensions. More... | |
| template<typename T , data_layout layout = data_layout::none, typename Scalar = scalar_type_of_t<T>, typename... Ds, std::enable_if_t< indexible< T > and values::number< Scalar > and(... and coordinates::pattern< Ds >) and(layout !=data_layout::stride) and interface::make_default_defined_for< T, layout, Scalar, std::tuple< Ds &&... >>, int > = 0> | |
| constexpr auto | make_dense_object (Ds &&...ds) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename T , typename layout = stdex::layout_right, typename Scalar = element_type_of_t<T>, typename... Ds, typename... Args, std::enable_if_t< indexible< T > and values::number< Scalar > and(coordinates::pattern< Ds > and ...) and(stdex::convertible_to< Args, const Scalar > and ...) and(stdex::same_as< layout, stdex::layout_right > or stdex::same_as< layout, stdex::layout_left >) and(((coordinates::dimension_of< Ds >::value==0) or ...) ? sizeof...(Args)==0 :(sizeof...(Args) %((dynamic_pattern< Ds > ? 1 :coordinates::dimension_of< Ds >::value) *... *1)==0)), int > = 0> | |
| auto | make_dense_object_from (const std::tuple< Ds... > &d_tup, Args...args) |
| Create a dense, writable matrix from the library of which dummy type T is a member, filled with a set of scalar components. More... | |
| template<typename T , typename layout = std::compat::layout_right, typename Scalar = element_type_of_t<T>, typename ... Args> | |
| auto | make_dense_object_from (Args...args) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , typename D0 , typename D1 > | |
| constexpr auto | make_diagonal_adapter (Arg &&arg, D0 &&d0, D1 &&d1) |
| Make a diagonal_matrix, specifying the first two dimensions, which may not necessarily be the same. More... | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| constexpr auto | make_diagonal_adapter (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<HermitianAdapterType adapter_type = HermitianAdapterType::lower, typename Arg , std::enable_if_t< square_shaped< Arg, applicability::permitted > and(adapter_type==HermitianAdapterType::lower or adapter_type==HermitianAdapterType::upper), int > = 0> | |
| decltype(auto) constexpr | make_hermitian_matrix (Arg &&arg) |
| Creates a hermitian_matrix by, if necessary, wrapping the argument in a hermitian_adapter. More... | |
| template<typename T , typename Scalar = typename scalar_type_of<T>::type, typename Descriptors , std::enable_if_t< indexible< T > and values::number< Scalar > and pattern_collection< Descriptors >, int > = 0> | |
| constexpr auto | make_identity_matrix_like (Descriptors &&descriptors) |
| Make an identity_matrix with a particular set of coordinates::pattern objects. More... | |
| template<typename T , typename Scalar = typename scalar_type_of<T>::type, typename... Ds, std::enable_if_t< indexible< T > and values::number< Scalar > and(... and coordinates::pattern< Ds >), int > = 0> | |
| constexpr auto | make_identity_matrix_like (Ds &&...ds) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Scalar , typename Arg , std::enable_if_t< values::number< Scalar > and indexible< Arg >, int > = 0> | |
| constexpr auto | make_identity_matrix_like (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| constexpr auto | make_identity_matrix_like (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<triangle_type t = triangle_type::lower, typename Arg , std::enable_if_t< indexible< Arg > and(t==triangle_type::lower or t==triangle_type::upper or t==triangle_type::diagonal), int > = 0> | |
| decltype(auto) constexpr | make_triangular_matrix (Arg &&arg) |
| Create a triangular_matrix from a general matrix. More... | |
| template<typename C = double, typename IndexType , std::size_t... Extents, std::enable_if_t< values::value< C >, int > = 0> | |
| constexpr auto | make_zero (stdex::extents< IndexType, Extents... > extents) |
| Make an indexible object in which every element is 0. More... | |
| template<typename... Ds, typename Operation , typename... Args, std::enable_if_t<(coordinates::pattern< Ds > and ...) and(indexible< Args > and ...) and(sizeof...(Args) > 0> | |
| constexpr auto | n_ary_operation (const std::tuple< Ds... > &d_tup, Operation &&operation, Args &&...args) |
| Perform a component-wise n-ary operation, using broadcasting to match the size of a pattern matrix. More... | |
| template<typename Operation , typename... Args, std::enable_if_t<(indexible< Args > and ...) and(sizeof...(Args) > 0> | |
| constexpr auto | n_ary_operation (Operation &&operation, Args &&...args) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename PatternMatrix , std::size_t... indices, typename... Ds, typename... Operations> | |
| constexpr auto | n_ary_operation (const std::tuple< Ds... > &d_tup, const Operations &...operations) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename PatternMatrix , std::size_t... indices, typename... Ds, typename... Operations, std::enable_if_t< indexible< PatternMatrix > and(coordinates::pattern< Ds > and ...) and((not dynamic_dimension< PatternMatrix, indices >) and ...) and(sizeof...(Operations)==(1 *... *index_dimension_of< PatternMatrix, indices >::value)), int > = 0> | |
| constexpr auto | n_ary_operation (const Operations &...operations) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Operation , typename Arg , std::enable_if_t< writable< Arg > and detail::n_ary_operator< Operation, index_count_v< Arg >, Arg >, int > = 0> | |
| decltype(auto) constexpr | unary_operation_in_place (const Operation &operation, Arg &&arg) |
| Perform a component-wise, in-place unary operation. More... | |
| template<typename A , std::enable_if_t< indexible< A >, int > = 0> | |
| decltype(auto) constexpr | QR_decomposition (A &&a) |
| Perform a QR decomposition of matrix A=Q[U,0], U is a upper-triangular matrix, and Q is orthogonal. More... | |
| template<typename PatternMatrix , std::size_t... indices, typename random_number_generator , typename... Ds, typename... Dists> | |
| constexpr auto | randomize (random_number_generator &gen, const std::tuple< Ds... > &ds_tuple, Dists &&...dists) |
| Create an indexible object with random values selected from one or more random distributions. More... | |
| template<typename PatternMatrix , std::size_t... indices, typename... Ds, typename... Dists> | |
| constexpr auto | randomize (const std::tuple< Ds... > &d_tuple, Dists &&...dists) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename PatternMatrix , std::size_t... indices, typename random_number_generator , typename... Dists, std::enable_if_t< indexible< PatternMatrix > and(not has_dynamic_dimensions< PatternMatrix >) and(sizeof...(Dists)==(1 *... *index_dimension_of< PatternMatrix, indices >::value)) and((std::is_arithmetic_v< Dists > or detail::is_std_dist< Dists >::value) and ...), int > = 0> | |
| constexpr auto | randomize (random_number_generator &gen, Dists &&...dists) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename PatternMatrix , std::size_t... indices, typename... Dists, std::enable_if_t< indexible< PatternMatrix > and(not has_dynamic_dimensions< PatternMatrix >) and(sizeof...(Dists)==(1 *... *index_dimension_of< PatternMatrix, indices >::value)) and((std::is_arithmetic_v< Dists > or detail::is_std_dist< Dists >::value) and ...), int > = 0> | |
| constexpr auto | randomize (Dists &&...dists) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename A , typename U , std::enable_if_t< indexible< U > and hermitian_matrix< A, applicability::permitted > and dimension_size_of_index_is< U, 0, index_dimension_of< A, 0 >::value, applicability::permitted > and dimension_size_of_index_is< U, 0, index_dimension_of< A, 1 >::value, applicability::permitted > and stdex::convertible_to< typename scalar_type_of< U >::type, const typename scalar_type_of< A >::type >, int > = 0> | |
| decltype(auto) | rank_update_hermitian (A &&a, U &&u, scalar_type_of_t< A > alpha=1) |
| Do a rank update on a hermitian matrix. More... | |
| template<typename A , typename U , std::enable_if_t< triangular_matrix< A, triangle_type::any > and indexible< U > and dimension_size_of_index_is< U, 0, index_dimension_of< A, 0 >::value, applicability::permitted > and dimension_size_of_index_is< U, 0, index_dimension_of< A, 1 >::value, applicability::permitted > and stdex::convertible_to< scalar_type_of_t< U >, const scalar_type_of_t< A >>, int > = 0> | |
| decltype(auto) | rank_update_triangular (A &&a, U &&u, scalar_type_of_t< A > alpha=1) |
| Do a rank update on triangular matrix. More... | |
| template<std::size_t index, std::size_t... indices, typename BinaryFunction , typename Arg , std::enable_if_t< internal::has_uniform_patterns< Arg, index, indices... > and std::is_invocable_r< typename scalar_type_of< Arg >::type, BinaryFunction &&, typename scalar_type_of< Arg >::type, typename scalar_type_of< Arg >::type >::value, int > = 0> | |
| decltype(auto) constexpr | reduce (BinaryFunction &&b, Arg &&arg) |
| Perform a partial reduction based on an associative binary function, across one or more indices. More... | |
| template<typename BinaryFunction , typename Arg , std::enable_if_t< internal::has_uniform_patterns< Arg > and std::is_invocable_r< typename scalar_type_of< Arg >::type, BinaryFunction &&, typename scalar_type_of< Arg >::type, typename scalar_type_of< Arg >::type >::value, int > = 0> | |
| constexpr scalar_type_of_t< Arg > | reduce (const BinaryFunction &b, const Arg &arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<std::size_t... indices, typename Arg , typename Chip , typename... Ixs, std::enable_if_t< writable< Arg > and indexible< Chip > and(values::index< Ixs > and ...) and(sizeof...(indices)==sizeof...(Ixs)), int > = 0> | |
| constexpr Arg && | set_chip (Arg &&arg, Chip &&chip, Ixs...ixs) |
| Set a sub-array having rank less than the rank of the input object. More... | |
| template<typename Arg , typename Block , typename... Begin, std::enable_if_t< writable< Arg > and indexible< Block > and(values::index< Begin > and ...) and(sizeof...(Begin) > = index_count<Arg>::value> | |
| constexpr Arg && | set_slice (Arg &&arg, Block &&block, const Begin &...begin) |
| Assign an object to a particular slice of a matrix or tensor. More... | |
| template<bool must_be_unique = false, bool must_be_exact = false, typename A , typename B > | |
| constexpr auto | solve (A &&a, B &&b) |
| Solve the equation AX = B for X, which may or may not be a unique solution. More... | |
| template<std::size_t... indices, typename Arg , typename... Ds, std::enable_if_t< indexible< Arg > and(coordinates::pattern< Ds > and ...) and(sizeof...(indices) > 0> | |
| auto | split (Arg &&arg, Ds &&...ds) |
| Split a matrix or tensor into sub-parts, where the split is the same for every index. More... | |
| template<std::size_t... indices, typename Arg , typename... Ds_tups, std::enable_if_t< indexible< Arg > and(sizeof...(indices) > 0> | |
| auto | split (Arg &&arg, const Ds_tups &...ds_tups) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename... Ts, std::enable_if_t<(indexible< Ts > and ...) and(sizeof...(Ts) > 0> | |
| decltype(auto) constexpr | sum (Ts &&...ts) |
| Element-by-element sum of one or more objects. | |
| template<typename... Ds, typename Block , typename... Blocks, std::enable_if_t<(coordinates::pattern< Ds > and ...) and(indexible< Block > and ... and indexible< Blocks >) and(sizeof...(Ds) > = std::max({index_count<Block>::value, index_count<Blocks>::value...})> | |
| decltype(auto) constexpr | tile (const std::tuple< Ds... > &ds_tuple, Block &&block, Blocks &&...blocks) |
| Create a matrix or tensor by tiling individual blocks. More... | |
| template<typename T , data_layout layout = data_layout::none, typename Scalar = scalar_type_of_t<T>, typename Arg , std::enable_if_t< indexible< T > and(layout !=data_layout::stride) and values::number< Scalar > and indexible< Arg >, int > = 0> | |
| decltype(auto) constexpr | to_dense_object (Arg &&arg) |
| Convert the argument to a dense, writable matrix of a particular scalar type. More... | |
| template<data_layout layout, typename Scalar , typename Arg , std::enable_if_t< values::number< Scalar > and indexible< Arg > and(layout !=data_layout::stride), int > = 0> | |
| decltype(auto) constexpr | to_dense_object (Arg &&arg) |
| Convert the argument to a dense, writable matrix of a particular scalar type. More... | |
| template<data_layout layout = data_layout::none, typename Arg , std::enable_if_t< indexible< Arg > and(layout !=data_layout::stride), int > = 0> | |
| decltype(auto) constexpr | to_dense_object (Arg &&arg) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| decltype(auto) constexpr | to_diagonal (Arg &&arg) |
| Convert an indexible object into a diagonal matrix. More... | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| decltype(auto) constexpr | to_euclidean (Arg &&arg) |
| Project the vector space associated with index 0 to a Euclidean space for applying directional statistics. More... | |
| template<typename Arg > | |
| decltype(auto) constexpr | trace (Arg &&arg) |
| Take the trace of a matrix. More... | |
| template<std::size_t indexa = 0, std::size_t indexb = 1, typename Arg > | |
| decltype(auto) constexpr | transpose (Arg &&arg) |
| Swap any two indices of an indexible_object. More... | |
| template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0> | |
| decltype(auto) constexpr | wrap_angles (Arg &&arg) |
| template<typename RowCoefficients , typename ColumnCoefficients = RowCoefficients, typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| auto | make_matrix (const Args...args) |
| template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| auto | make_matrix (const Args ... args) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Scalar , typename RowCoefficients , typename ColumnCoefficients = RowCoefficients, std::enable_if_t< values::number< Scalar > and fixed_pattern< RowCoefficients > and fixed_pattern< ColumnCoefficients >, int > = 0> | |
| auto | make_matrix () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , typename ... Args, std::enable_if_t< fixed_pattern< StaticDescriptor > and(sizeof...(Args) > 0> | |
| auto | make_mean (const Args ... args) |
| template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| auto | make_mean (const Args ... args) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Scalar , typename StaticDescriptor , std::size_t cols = 1, std::enable_if_t< values::number< Scalar > and fixed_pattern< StaticDescriptor >, int > = 0> | |
| auto | make_mean () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| auto | make_euclidean_mean (const Args ... args) |
| template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| auto | make_euclidean_mean (const Args ... args) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Scalar , typename StaticDescriptor , std::size_t cols = 1, std::enable_if_t< values::number< Scalar > and fixed_pattern< StaticDescriptor >, int > = 0> | |
| auto | make_euclidean_mean () |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename StaticDescriptor , triangle_type tri, typename ... Args, std::enable_if_t< fixed_pattern< StaticDescriptor > and(values::number< Args > and ...) and(tri==triangle_type::lower or tri==triangle_type::upper) and(sizeof...(Args) > 0> | |
| auto | make_covariance (const Args ... args) |
| template<typename StaticDescriptor , typename ... Args, std::enable_if_t< fixed_pattern< StaticDescriptor > and(values::number< Args > and ...) and(sizeof...(Args) > 0> | |
| auto | make_covariance (const Args ... args) |
| template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| auto | make_covariance (const Args ... args) |
| template<typename StaticDescriptor , triangle_type tri = triangle_type::lower, typename ... Args, std::enable_if_t< fixed_pattern< StaticDescriptor > and(values::number< Args > and ...) and(tri==triangle_type::lower or tri==triangle_type::upper) and(sizeof...(Args) > 0> | |
| auto | make_square_root_covariance (const Args ... args) |
| template<triangle_type tri = triangle_type::lower, typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| auto | make_square_root_covariance (const Args ... args) |
| template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| Matrix (const Args ...) -> Matrix< Dimensions< sizeof...(Args)>, Axis, Eigen3::eigen_matrix_t< std::common_type_t< Args... >, sizeof...(Args), 1 >> | |
| template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| Mean (const Args ...) -> Mean< Dimensions< sizeof...(Args)>, Eigen3::eigen_matrix_t< std::common_type_t< Args... >, sizeof...(Args), 1 >> | |
| If the arguments are a sequence of scalars, deduce a single-column mean with all Axis coefficients. | |
| template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0> | |
| EuclideanMean (const Args ...) -> EuclideanMean< OpenKalman::Dimensions< sizeof...(Args)>, Eigen3::eigen_matrix_t< std::common_type_t< Args... >, sizeof...(Args), 1 >> | |
| If the arguments are a sequence of scalars, construct a single-column Euclidean mean. | |
| template<typename ... Args, std::enable_if_t<(values::number< Args > and ...) and(sizeof...(Args) > 0> | |
| Covariance (const Args &...) -> Covariance< Dimensions< static_cast< std::size_t >(values::sqrt(sizeof...(Args)))>, HermitianAdapter< Eigen3::eigen_matrix_t< std::common_type_t< Args... >, static_cast< std::size_t >(values::sqrt(sizeof...(Args))), static_cast< std::size_t >(values::sqrt(sizeof...(Args)))>>> | |
| If the arguments are a sequence of scalars, derive a square, self-adjoint matrix. | |
| template<typename ... Args, std::enable_if_t<(values::number< Args > and ...) and(sizeof...(Args) > 0> | |
| SquareRootCovariance (const Args &...) -> SquareRootCovariance< Dimensions< static_cast< std::size_t >(values::sqrt(sizeof...(Args)))>, TriangularAdapter< Eigen3::eigen_matrix_t< std::common_type_t< Args... >, static_cast< std::size_t >(values::sqrt(sizeof...(Args))), static_cast< std::size_t >(values::sqrt(sizeof...(Args)))>>> | |
| If the arguments are a sequence of scalars, derive a square, lower triangular matrix. | |
| template<typename Arg , typename Indices , std::enable_if_t< index_collection_for< Indices, Arg > and(not empty_object< Arg >) and(not values::size_compares_with< collections::size_of< Indices >, index_count< Arg >, &stdex::is_lt >), int > = 0> | |
| decltype(auto) constexpr | access (Arg &&arg, const Indices &indices) |
| Access a component of an indexible object at a given set of indices. More... | |
| template<typename Arg , typename... I, std::enable_if_t< indexible< Arg > and(... and values::index< I >) and(not empty_object< Arg >) and(not values::size_compares_with< std::integral_constant< std::size_t, sizeof...(I)>, index_count< Arg >, &stdex::is_lt >), int > = 0> | |
| decltype(auto) constexpr | access (Arg &&arg, I...i) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename Arg , typename Indices , std::enable_if_t< index_collection_for< Indices, Arg > and(not empty_object< Arg >) and(not values::size_compares_with< collections::size_of< Indices >, index_count< Arg >, &stdex::is_lt >), int > = 0> | |
| decltype(auto) constexpr | access_at (Arg &&arg, const Indices &indices) |
| Access a component of an indexible object at a given set of indices, with bounds checking. More... | |
| template<typename Arg , typename... I, std::enable_if_t< indexible< Arg > and(... and values::index< I >) and(not empty_object< Arg >) and(not values::size_compares_with< std::integral_constant< std::size_t, sizeof...(I)>, index_count< Arg >, &stdex::is_lt >), int > = 0> | |
| decltype(auto) constexpr | access_at (Arg &&arg, I...i) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename T , std::enable_if_t< constant_object< T > or constant_diagonal_object< T >, int > = 0> | |
| constexpr auto | constant_value (T &&t) |
| The constant value associated with a constant_object or constant_diagonal_object. | |
| template<typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | count_indices (const T &) |
| Get the number of indices necessary to address all the components of an indexible object. More... | |
| template<typename T , typename I = std::integral_constant<std::size_t, 0>, std::enable_if_t< indexible< T > and values::index< I >, int > = 0> | |
| constexpr auto | get_index_extent (T &&t, I i=I{}) |
| Get the runtime dimensions of index N of indexible T. | |
| template<std::size_t I, typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | get_index_extent (T &&t) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. | |
| template<typename T , typename I = std::integral_constant<std::size_t, 0>, std::enable_if_t< indexible< T > and values::index< I >, int > = 0> | |
| decltype(auto) constexpr | get_index_pattern (T &&t, I i={}) |
| Get the coordinates::pattern associated with indexible object T at a given index. More... | |
| template<std::size_t i, typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | get_index_pattern (T &&t) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. | |
| template<typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | get_mdspan (T &t) |
| Get the coordinates::pattern_collection associated with indexible object T. | |
| template<typename T , typename Extents , typename LayoutPolicy , typename AccessorPolicy > | |
| constexpr auto | get_mdspan (stdex::mdspan< T, Extents, LayoutPolicy, AccessorPolicy > m) |
| This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
| template<typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| decltype(auto) constexpr | get_pattern_collection (T &&t) |
| Get the coordinates::pattern_collection associated with indexible object T. | |
| template<typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0> | |
| constexpr bool | get_wrappable (const T &t) |
| Determine whether T is wrappable (i.e., all its dimensions other than potentially 0 are euclidean). More... | |
| template<typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | is_one_dimensional (const T &t) |
| Determine whether T is one_dimensional, meaning that every index has a dimension of 1. More... | |
| template<typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | is_square_shaped (const T &t) |
| Determine whether an object is square_shaped. More... | |
| template<std::size_t N = 0, typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | is_vector (const T &t) |
| Return true if T is a vector at runtime. More... | |
| template<typename Arg , std::enable_if_t< has_nested_object< Arg >, int > = 0> | |
| decltype(auto) constexpr | nested_object (Arg &&arg) |
| Retrieve a nested object of Arg, if it exists. More... | |
| template<typename... Ts, std::enable_if_t<(indexible< Ts > and ...), int > = 0> | |
| constexpr bool | patterns_match (const Ts &...ts) |
| Return true if every set of coordinates::pattern of a set of objects are equivalent. More... | |
| template<typename T , std::enable_if_t< indexible< T >, int > = 0> | |
| constexpr auto | tensor_order (const T &t) |
| Return the tensor order of T (i.e., the number of indices of dimension greater than 1). More... | |
| template<typename OutputCoefficients , typename In , typename ... Perturbations> | |
| auto | zero_hessian () |
| A tuple of zero-filled arrays of Hessian matrices, based on the input and each perturbation term. | |
| template<typename OutputCoefficients , typename In , typename ... Perturbations> | |
| auto | zero_hessian (In &&, Perturbations &&...) |
| A tuple of zero-filled arrays of Hessian matrices, based on the input and each perturbation term. | |
| template<typename Function , typename InDelta , typename ... PsDelta> | |
| FiniteDifferenceLinearization (Function &&, InDelta &&, PsDelta &&...) -> FiniteDifferenceLinearization< std::decay_t< Function >, std::decay_t< InDelta >, std::decay_t< PsDelta >... > | |
| template<typename T , typename ... Ps> | |
| LinearTransformation (T &&, Ps &&...) -> LinearTransformation< vector_space_descriptor_of_t< T, 1 >, vector_space_descriptor_of_t< T, 0 >, equivalent_self_contained_t< nested_object_of_t< T >>, equivalent_self_contained_t< std::conditional_t< typed_matrix< Ps >, nested_object_of_t< Ps >, Ps >>... > | |
| template<typename Function , typename ... TaylorDerivatives> | |
| Transformation (Function &&, TaylorDerivatives &&...) -> Transformation< std::decay_t< Function >, std::decay_t< TaylorDerivatives > ... > | |
| template<typename Function , std::enable_if_t< linearized_function< Function, 0 > and(not linearized_function< Function, 1 >), int > = 0> | |
| Transformation (Function &&) -> Transformation< std::decay_t< Function >> | |
| constexpr applicability | operator not (applicability x) |
| constexpr applicability | operator and (applicability x, applicability y) |
| constexpr applicability | operator or (applicability x, applicability y) |
Variables | |
| template<typename T > | |
| constexpr bool | from_euclidean_expr = detail::is_from_euclidean_expr<std::decay_t<T>>::value |
| Specifies that T is an expression converting coefficients from Euclidean space (i.e., FromEuclideanExpr). | |
| template<typename T > | |
| constexpr bool | to_euclidean_expr = detail::is_to_euclidean_expr<std::decay_t<T>>::value |
| Specifies that T is an expression converting coefficients to Euclidean space (i.e., ToEuclideanExpr). | |
| template<typename T > | |
| constexpr bool | euclidean_expr = from_euclidean_expr<T> or to_euclidean_expr<T> |
| Specifies that T is either to_euclidean_expr or from_euclidean_expr. | |
| template<typename T > | |
| constexpr bool | all_fixed_indices_are_euclidean |
| Specifies that every fixed-size index of T is euclidean. More... | |
| template<typename T , typename D , auto comp = &stdex::is_eq, applicability a = applicability::permitted> | |
| constexpr bool | compares_with_pattern_collection |
| Compares the associated pattern collection of indexible T with pattern_collection D. More... | |
| template<typename T > | |
| constexpr bool | constant_diagonal_object |
| Specifies that all diagonal elements of a diagonal object are known at compile time to be the same constant value. More... | |
| template<typename T > | |
| constexpr bool | constant_object |
| Specifies that all elements of an object are known at compile time to be the same constant value. More... | |
| template<typename Dest , typename Source > | |
| constexpr bool | copyable_from |
| Specifies that an indexible object is copyable from another indexible object. More... | |
| template<typename T > | |
| constexpr bool | diagonal_matrix |
| Specifies that a type is a diagonal matrix or tensor. More... | |
| template<typename T , std::size_t index, std::size_t value, auto comp = &stdex::is_eq, applicability b = applicability::guaranteed> | |
| constexpr bool | dimension_size_of_index_is |
| Specifies that a given index of T has a specified size. More... | |
| template<typename T , std::size_t N> | |
| constexpr bool | dynamic_dimension = detail::is_dynamic_dimension<T, N>::value |
| Specifies that T's index N has a dimension defined at run time. More... | |
| template<typename T > | |
| constexpr bool | empty_object = detail::empty_object_impl<T>() |
| Specifies that an object is empty (i.e., at least one index is zero-dimensional). | |
| template<typename T > | |
| constexpr bool | has_dynamic_dimensions |
| Specifies that T has at least one index with dynamic dimensions. More... | |
| template<typename T > | |
| constexpr bool | has_nested_object |
| A matrix that has a nested matrix, if it is a wrapper type. More... | |
| template<typename T , std::size_t N> | |
| constexpr bool | has_untyped_index |
| Specifies that T has an untyped index N. More... | |
| template<typename T , HermitianAdapterType t = HermitianAdapterType::any> | |
| constexpr bool | hermitian_adapter = hermitian_matrix<T> and detail::hermitian_adapter_impl<std::decay_t<T>, t>::value |
| Specifies that a type is a hermitian matrix adapter of a particular type. More... | |
| template<typename T > | |
| constexpr bool | hermitian_matrix |
| Specifies that a type is a hermitian matrix. More... | |
| template<typename T > | |
| constexpr bool | identity_matrix |
| Specifies that a type is known at compile time to be a rank-2 or lower identity matrix. More... | |
| template<typename Indices , typename T > | |
| constexpr bool | index_collection_for |
| Indices is a collection of indices that are compatible with indexible object T. More... | |
| template<typename T > | |
| constexpr bool | indexible |
| T is a multidimensional array type. More... | |
| template<typename T > | |
| constexpr bool | mean = internal::is_mean<std::decay_t<T>>::value |
| Specifies that T is a mean (i.e., is a specialization of the class Mean). | |
| template<typename T > | |
| constexpr bool | wrapped_mean |
| Specifies that T is a wrapped mean (i.e., its row fixed_pattern have at least one type that requires wrapping). More... | |
| template<typename T > | |
| constexpr bool | euclidean_mean = internal::is_euclidean_mean<std::decay_t<T>>::value |
| Specifies that T is a Euclidean mean (i.e., is a specialization of the class EuclideanMean). | |
| template<typename T > | |
| constexpr bool | euclidean_transformed |
| Specifies that T is a Euclidean mean that actually has coefficients that are transformed to Euclidean space. More... | |
| template<typename T > | |
| constexpr bool | typed_matrix = mean<T> or euclidean_mean<T> or internal::is_matrix<std::decay_t<T>>::value |
| Specifies that T is a typed matrix (i.e., is a specialization of Matrix, Mean, or EuclideanMean). | |
| template<typename T > | |
| constexpr bool | self_adjoint_covariance = internal::is_self_adjoint_covariance<std::decay_t<T>>::value |
| T is a self-adjoint covariance matrix (i.e., a specialization of Covariance). | |
| template<typename T > | |
| constexpr bool | triangular_covariance = internal::is_triangular_covariance<std::decay_t<T>>::value |
| T is a square root (Cholesky) covariance matrix (i.e., a specialization of SquareRootCovariance). | |
| template<typename T > | |
| constexpr bool | covariance = self_adjoint_covariance<T> or triangular_covariance<T> |
| T is a specialization of either Covariance or SquareRootCovariance. | |
| template<typename T > | |
| constexpr bool | gaussian_distribution = internal::is_gaussian_distribution<std::decay_t<T>>::value |
| T is a Gaussian distribution. | |
| template<typename T > | |
| constexpr bool | distribution = gaussian_distribution<T> |
| T is a statistical distribution of any kind that is defined in OpenKalman. | |
| template<typename T > | |
| constexpr bool | cholesky_form = detail::is_cholesky_form<std::decay_t<T>>::value |
| Specifies that a type has a nested native matrix that is a Cholesky square root. More... | |
| template<typename T > | |
| constexpr bool | covariance_nestable |
| T is an acceptable nested matrix for a covariance (including triangular_covariance). More... | |
| template<typename T > | |
| constexpr bool | typed_matrix_nestable |
| Specifies a type that is nestable in a general typed matrix (e.g., matrix, mean, or euclidean_mean) More... | |
| template<typename T , applicability b = applicability::guaranteed> | |
| constexpr bool | one_dimensional |
| Specifies that a type is one-dimensional in every index. More... | |
| template<typename P , typename T , applicability a = applicability::permitted> | |
| constexpr bool | pattern_collection_for = detail::compatible_shape_with_impl_cpp17<P, T, a>::value |
| pattern collection P is compatible with indexible T. More... | |
| template<typename... Ts> | |
| constexpr bool | patterns_match_with |
| Specifies that a set of indexible objects have equivalent vector space descriptors for each index. More... | |
| template<typename... Ts> | |
| constexpr bool | patterns_may_match_with |
| Specifies that indexible objects Ts may have equivalent dimensions and vector-space types. More... | |
| template<typename T , applicability b = applicability::guaranteed> | |
| constexpr bool | square_shaped |
| Specifies that an object is square (i.e., has equivalent coordinates::pattern along each dimension). More... | |
| template<typename T > | |
| constexpr bool | triangular_adapter |
| Specifies that a type is a triangular adapter of triangle type tri. More... | |
| template<typename T , triangle_type t = triangle_type::any> | |
| constexpr bool | triangular_matrix |
| Specifies that an argument is an indexible object having a given triangle_type (e.g., upper, lower, or diagonal). More... | |
| template<typename T > | |
| constexpr bool | typed_adapter |
| Specifies that T is a typed adapter expression. More... | |
| template<typename T > | |
| constexpr bool | untyped_adapter |
| Specifies that T is an untyped adapter expression. More... | |
| template<typename T , std::size_t N = 0, applicability b = applicability::guaranteed> | |
| constexpr bool | vector |
| T is a vector (e.g., column or row vector). More... | |
| template<typename T > | |
| constexpr bool | wrappable = detail::is_wrappable<T>::value |
| Specifies that every fixed-size index of T (other than potentially index 0) is euclidean. More... | |
| template<typename T , unsigned int epsilon_factor = 0> | |
| constexpr bool | zero |
| Specifies that a type is known at compile time to be a constant matrix of value zero. More... | |
| template<typename T > | |
| constexpr auto | constant_value_of_v = constant_value_of<T>::value |
| helper template for constant_value_of. | |
| template<typename T , typename... Ts> | |
| constexpr auto | hermitian_adapter_type_of_v = hermitian_adapter_type_of<T, Ts...>::value |
| The triangle_type associated with the storage triangle of a hermitian_matrix. More... | |
| template<typename T > | |
| constexpr auto | triangle_type_of_v = triangle_type_of<T>::value |
| Helper template for triangle_type_of. | |
| template<typename T , std::size_t order = 1> | |
| constexpr bool | linearized_function |
| A linearized function (with defined Jacobian and optionally Hessian functions). More... | |
| template<typename T , typename Coeffs = typename oin::PerturbationTraits<T>::RowCoefficients> | |
| constexpr bool | transformation_input |
| T is an acceptable input to a tests. More... | |
| template<typename T , typename Coeffs = typename oin::PerturbationTraits<T>::RowCoefficients> | |
| constexpr bool | perturbation = OpenKalman::detail::is_perturbation<T, Coeffs>::value |
The root namespace for OpenKalman.
The namespace for all OpenKalman-specific classes and methods.
| using OpenKalman::dense_writable_matrix_t = typedef std::decay_t<decltype(make_dense_object<T, layout, S>(std::declval<D>()))> |
An alias for a dense, writable matrix, patterned on parameter T.
| T | A matrix or array from the relevant matrix library. |
| S | A scalar type (may or may not be scalar_type_of_t<T>. |
| layout | The /ref data_layout of the result. |
| D | A pattern_collection defining the new object. This will be derived from T if omitted. |
| using OpenKalman::nested_object_of_t = typedef typename nested_object_of<T>::type |
Helper type for nested_object_of.
| T | A wrapper type that has a nested matrix. |
| using OpenKalman::zero_adapter = typedef constant_adapter<values::fixed_value<N, 0>, Shape> |
A constant_adapter in which all elements are 0.
| Shape | An indexible object reflecting the size and shape of the adapter object. |
| N | A values::number type (by default, derived from Shape). |
|
strong |
The applicability of a concept, trait, or restraint.
Determines whether something is necessarily applicable, or alternatively just permissible, at compile time. Examples:
square_shaped<T, applicability::guaranteed> means that T is known at compile time to be square shaped.square_shaped<T, applicability::permitted> means that T could be square shaped, but whether it actually is cannot be determined at compile time.
|
strong |
The type of a hermitian adapter, indicating which triangle of the nested matrix is used.
This type can be statically cast from triangle_type so that lower, upper, and any correspond to each other. The value none corresponds to triangle_type::diagonal.
| Enumerator | |
|---|---|
| none | Not a hermitian adapter. |
| any | Either lower or upper hermitian adapter. |
| lower | A lower-left hermitian adapter. |
| upper | An upper-right hermitian adapter. |
|
strong |
The type of a triangular matrix.
This is generally applicable to a rank-2 tensor (e.g., a matrix). It also applies to tensors of rank > 2, in which case every rank-2 slice over dimensions 0 and 1 must be a triangle of this type.
| decltype(auto) constexpr OpenKalman::access | ( | Arg && | arg, |
| const Indices & | indices | ||
| ) |
Access a component of an indexible object at a given set of indices.
This performs no bounds checking
| Arg | The indexible object to be accessed. |
| Indices | A sized input range containing the indices. |
| decltype(auto) constexpr OpenKalman::access | ( | Arg && | arg, |
| I... | i | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Access a component based on a pack of indices.
| decltype(auto) constexpr OpenKalman::access_at | ( | Arg && | arg, |
| const Indices & | indices | ||
| ) |
Access a component of an indexible object at a given set of indices, with bounds checking.
This is the same as access, except with added bounds checking
| Arg | The object to be accessed. |
| Indices | A sized input range containing the indices. |
| decltype(auto) constexpr OpenKalman::access_at | ( | Arg && | arg, |
| I... | i | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Access a component based on a pack of indices.
| decltype(auto) constexpr OpenKalman::adjoint | ( | Arg && | arg | ) |
Take the conjugate-transpose of an indexible_object.
By default, the first two indices are transposed.
| constexpr auto OpenKalman::attach_pattern | ( | Arg && | arg, |
| P && | p | ||
| ) |
Attach a pattern_collection to an indexible object.
Any pattern_collection already associated with the argument will be overwritten.
| constexpr auto OpenKalman::attach_pattern | ( | Arg && | arg, |
| Ps &&... | ps | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
The pattern_collection is constructed from a list of coordinates::pattern objects.
| constexpr auto OpenKalman::attach_pattern | ( | Arg && | arg | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
The pattern_collection is default initializable.
| decltype(auto) constexpr OpenKalman::average_reduce | ( | Arg && | arg | ) |
Perform a partial reduction by taking the average along one or more indices.
| index | an index to be reduced. For example, if the index is 0, the result will have only one row. If the index is 1, the result will have only one column. |
| indices | Other indices to be reduced. Because the binary function is associative, the order of the indices does not matter. |
| constexpr scalar_type_of_t<Arg> OpenKalman::average_reduce | ( | Arg && | arg | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Perform a complete reduction by taking the average along all indices and returning a scalar value.
| decltype(auto) constexpr OpenKalman::broadcast | ( | Arg && | arg, |
| const Factors &... | factors | ||
| ) |
Broadcast an object by replicating it by factors specified for each index.
The operation may increase the order of the object by specifying factors greater than 1 for higher indices. Any such higher indices will have a coordinates::pattern of Dimensions<n> where n is the factor.
| Arg | The object. |
| Factors | A set of factors, each an values::index, indicating the increase in size of each index. Any omitted trailing factors are treated as factor 1 (no broadcasting along that index). |
| constexpr auto OpenKalman::chipwise_operation | ( | const Operation & | operation, |
| Args &&... | args | ||
| ) |
Perform a chipwise n-ary operation (n>0) on one or more indexible objects.
Given an indexible object of order k, a "chip" is a subset of that object, having order in the range (0, k]. This function takes same-size chips from each of the arguments and performs an operation returning a chip (of the same size), for every possible chip within the result.
| indices | The one-dimensional indices of the chip (optionally excluding any trailing 1D indices). If omitted, the order of the chip is the same as that of the highest-order indexible argument. Note: the list of indices must be non-repeating, or a compile-time assertion will fail. |
| Operation | An n-ary operation (unary, binary, etc.) on n chips of the same size. In addition to taking one or more chips as arguments, the operation may optionally take sizeof...(indices) indices (in the same order as indices). |
| Args | The arguments, which must be the same size. |
| constexpr auto OpenKalman::chipwise_operation | ( | const Operation & | operation, |
| Is... | is | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Perform a chipwise nullary operation.
The nullary operation returns a chip, and that chip is replicated along the specified indices a number of times indicated by Is.
| Operation | A nullary operation. The operation may optionally take, as arguments, sizeof...(indices) indices (in the same order as indices). |
| Is | Number of dimensions corresponding to each of indices.... |
| decltype(auto) constexpr OpenKalman::cholesky_factor | ( | A && | a | ) |
Take the Cholesky factor of a matrix.
| A | A hermitian matrix. |
| tri | Either triangle_type::upper, triangle_type::lower, or triangle_type::diagonal (only if A is a diagonal_matrix). |
| decltype(auto) constexpr OpenKalman::cholesky_factor | ( | A && | a | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
This overload does not require specifying the triangle_type, which is either
| decltype(auto) constexpr OpenKalman::cholesky_square | ( | A && | a | ) |
Take the Cholesky square of a triangular_matrix.
| A | A square matrix. |
| decltype(auto) constexpr OpenKalman::concatenate | ( | Arg && | arg, |
| Args &&... | args | ||
| ) |
Concatenate some number of objects along one or more indices.
| indices | The indices along which the concatenation occurs. For example,
|
| Arg | First object to be concatenated |
| Args | Other objects to be concatenated |
| decltype(auto) constexpr OpenKalman::conjugate | ( | Arg && | arg | ) |
Take the complex conjugate of an indexible object.
The resulting object has every element substituted with its complex conjugate.
| constexpr A&& OpenKalman::contract_in_place | ( | A && | a, |
| B && | b | ||
| ) |
In-place matrix multiplication of A * B, storing the result in A.
| on_the_right | Whether the application is on the right (true) or on the left (false) |
| decltype(auto) constexpr OpenKalman::copy_from | ( | Dest && | dest, |
| Source && | source | ||
| ) |
Copy elements from one object to another.
| dest | The destination object. |
| source | The source object. |
By default, this simply loops through each element of the associated mdspans.
| constexpr auto OpenKalman::count_indices | ( | const T & | ) |
Get the number of indices necessary to address all the components of an indexible object.
|
explicit |
Deduce Covariance type from a covariance_nestable.
Deduce Covariance type from a square typed_matrix_nestable.
Deduce Covariance type from a square typed_matrix.
| constexpr auto OpenKalman::determinant | ( | Arg && | arg | ) |
Take the determinant of a matrix.
| Arg | A square matrix |
| decltype(auto) constexpr OpenKalman::diagonal_of | ( | Arg && | arg | ) |
Extract a column vector (or column slice for rank>2 tensors) comprising the diagonal elements.
| Arg | An indexible object, which can have any rank and may or may not be square |
|
explicit |
Deduce template parameters from a non-Euclidean-transformed typed matrix.
Deduce template parameters from a typed_matrix_nestable, assuming axis-only coefficients.
Deduce template parameters from a Euclidean-transformed typed matrix.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Fill the components of an object from a list of scalar values.
The scalar components are listed in the specified layout order, as follows:
| layout | The layout_mapping_policy of Args and the resulting object (std::layout_right if unspecified). |
| arg | The object to be modified. |
| s | Scalar values to fill the new matrix. |
| decltype(auto) constexpr OpenKalman::from_euclidean | ( | Arg && | arg, |
| const V & | v | ||
| ) |
Project the Euclidean vector space associated with index 0 to coordinates::pattern v after applying directional statistics.
| Arg | A matrix or tensor. |
| V | The new coordinate_list of index 0. |
| decltype(auto) constexpr OpenKalman::get_chip | ( | Arg && | arg, |
| Ixs... | ixs | ||
| ) |
Extract a sub-array having rank less than the rank of the input object.
A chip is a special type of "thin" slice of width 1 in one or more dimensions, and otherwise no reduction in extents. For example, the result could be a row vector, a column vector, a matrix (e.g., if the input object is a rank-3 or higher tensor), etc.
| indices | The index or indices of the dimension(s) to be collapsed to a single dimension. For example, if the input object is a matrix, a value of {0} will result in a row vector, a value of {1} will result in a column vector, and a value of {0, 1} will result in a one-dimensional vector. If the input object is a rank-3 tensor, a value of {1, 2} will result in a row vector. If no indices are listed, the argument will be returned unchanged. |
| ixs | The index value corresponding to each of the indices, in the same order. The values may be positive std::integral types or a positive std::integral_constant. |
| decltype(auto) constexpr OpenKalman::get_index_pattern | ( | T && | t, |
| I | i = {} |
||
| ) |
Get the coordinates::pattern associated with indexible object T at a given index.
If the index exceeds count_indices(t), the result is coordinates::Dimensions<1>{}, coordinates::Any{1UZ}, or 1UZ.
| constexpr auto OpenKalman::get_mdspan | ( | stdex::mdspan< T, Extents, LayoutPolicy, AccessorPolicy > | m | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
If argument is already an mdspan, return it unchanged.
| decltype(auto) constexpr OpenKalman::get_slice | ( | Arg && | arg, |
| const std::tuple< Offset... > & | offsets, | ||
| const std::tuple< Extent... > & | extents | ||
| ) |
Extract a slice from a matrix or tensor.
If indices are specified, only those indices will be subsetted. Otherwise, the Offset and Extent parameters are taken in index order. Any omitting trailing indices (for which there are no Offset or Extent parameters) are included whole.
| indices | The index or indices of the particular dimensions to be specified, in any order (optional). If this is omitted, the Offset and Extent parameters proceed in index order. |
| arg | The indexible object from which a slice is to be taken. |
| offsets | A tuple corresponding to each of indices, each element specifying the offsetning values::index. If indices are not specified, the tuple proceeds in normal index order. |
| extents | A tuple corresponding to each of indices, each element specifying the dimensions of the extracted block. If indices are not specified, the tuple proceeds in normal index order. |
| constexpr bool OpenKalman::get_wrappable | ( | const T & | t | ) |
|
inline |
Scale a covariance by the inverse of a scalar factor.
Equivalent by division by the square of a scalar. For a square root covariance, this is equivalent to division by the scalar.
| constexpr auto OpenKalman::is_one_dimensional | ( | const T & | t | ) |
Determine whether T is one_dimensional, meaning that every index has a dimension of 1.
Each index need not have an equivalent coordinates::pattern.
| constexpr auto OpenKalman::is_square_shaped | ( | const T & | t | ) |
Determine whether an object is square_shaped.
An object is square-shaped if it has the same extents and equivalent coordinates::pattern types for each index (excluding trailing 1D indices). A rank-0 object is square because all indices are implicitly 1D. An empty object in which the first positive n dimensions are 0 is also considered to be square.
| T | A tensor or matrix |
| constexpr auto OpenKalman::is_vector | ( | const T & | t | ) |
| decltype(auto) constexpr OpenKalman::LQ_decomposition | ( | A && | a | ) |
Perform an LQ decomposition of matrix A=[L,0]Q, L is a lower-triangular matrix, and Q is orthogonal.
| A | The matrix to be decomposed satisfying triangular_matrix<A, triangle_type::lower> |
| constexpr auto OpenKalman::make_constant | ( | C | c, |
| stdex::extents< IndexType, Extents... > | extents | ||
| ) |
| constexpr auto OpenKalman::make_constant | ( | C | c, |
| P && | p | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a constant_object based on a pattern_collection.
| constexpr auto OpenKalman::make_constant | ( | C | c, |
| Ps &&... | ps | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
The pattern_collection is constructed from a list of patterns.
| constexpr auto OpenKalman::make_constant | ( | C | c | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a constant_object based on a default-initializable pattern_collection.
| constexpr auto OpenKalman::make_constant_diagonal | ( | C | c, |
| stdex::extents< IndexType, Extents... > | extents | ||
| ) |
| constexpr auto OpenKalman::make_constant_diagonal | ( | C | c, |
| P && | p | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a constant_diagonal_object based on a pattern_collection.
| constexpr auto OpenKalman::make_constant_diagonal | ( | C | c, |
| Ps &&... | ps | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
The pattern_collection is constructed from a list of patterns.
| constexpr auto OpenKalman::make_constant_diagonal | ( | C | c | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a constant_diagonal_object based on a default-initializable pattern_collection.
|
inline |
Make a Covariance from a covariance_nestable, specifying the fixed_pattern.
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| Arg | A covariance_nestable with size matching StaticDescriptor. |
Make a Covariance from a self-adjoint typed_matrix_nestable, specifying the coefficients.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| Arg | A square typed_matrix_nestable with size matching StaticDescriptor. |
Make a default Axis Covariance (with nested triangular matrix) from a self-adjoint typed_matrix_nestable.
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Arg | A square, self-adjoint typed_matrix_nestable. |
Make a Covariance, with a nested triangular matrix, from a typed_matrix.
|
inline |
Make a Covariance from a covariance_nestable, specifying the fixed_pattern.
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| triangle_type | The type of the nested triangular matrix (upper, lower, diagonal). |
| Arg | A covariance_nestable with size matching StaticDescriptor. |
Make a Covariance (with nested triangular matrix) from a self-adjoint typed_matrix_nestable.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Arg | A square, self-adjoint typed_matrix_nestable with size matching StaticDescriptor. |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a Covariance from a covariance_nestable, with default Axis coefficients.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| Arg | A covariance_nestable. |
Make a Covariance from a self-adjoint typed_matrix_nestable, using default Axis coefficients.
| Arg | A square typed_matrix_nestable. |
Make a Covariance based on another non-square-root covariance.
Make a Covariance from a typed_matrix.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a writable, uninitialized Covariance, specifying the fixed_pattern.
For Eigen3: Make a writable, uninitialized Covariance with nested triangular matrix.
For Eigen3: Make a Covariance from a list of coefficients, with default Axis coefficients.
For Eigen3: Make a default Axis Covariance, with nested triangular type, from a list of coefficients.
For Eigen3: Make a Covariance from a list of coefficients, specifying the coefficients.
For Eigen3: Make a Covariance, with nested triangular type, from a list of coefficients.
Make a writable, uninitialized Covariance from a covariance_nestable or typed_matrix_nestable.
Make a writable, uninitialized Covariance based on a nested triangle, with default Axis coefficients.
Make a writable, uninitialized Covariance, with nested triangular type based on a typed_matrix.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must equal coordinates::dimension_of_v<StaticDescriptor> * coordinates::dimension_of_v<StaticDescriptor>. |
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must equal coordinates::dimension_of_v<StaticDescriptor> * coordinates::dimension_of_v<StaticDescriptor>. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must be the square of an integer. |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must be the square of an integer. |
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Scalar | The scalar type (integral or floating-point). |
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| Scalar | The scalar type (integral or floating-point). |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a writable, uninitialized Covariance with a nested triangular matrix, from a typed_matrix_nestable.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a writable, uninitialized Covariance from a typed_matrix_nestable or covariance_nestable.
The coefficients will be Axis.
Make a writable, uninitialized Covariance from a non-square-root covariance.
Make a writable, uninitialized Covariance, based on a typed_matrix.
| constexpr auto OpenKalman::make_dense_object | ( | Descriptors && | descriptors | ) |
Make a default, dense, writable matrix with a set of coordinates::pattern objects defining the dimensions.
The result will be uninitialized.
| T | A dummy matrix or array from the relevant library (size, shape, and layout are ignored) |
| layout | The data_layout of the resulting object. If this is data_layout::none, it will be the default layout for the library of T. |
| Scalar | The scalar type of the resulting object (by default, it is the same scalar type as T). |
| d | a tuple of coordinates::pattern describing dimensions of each index. Trailing 1D indices my be omitted. |
| constexpr auto OpenKalman::make_dense_object | ( | Ds &&... | ds | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
coordinates::pattern object are specified as parameters.
|
inline |
Create a dense, writable matrix from the library of which dummy type T is a member, filled with a set of scalar components.
The scalar components are listed in the specified layout order, as follows:
| T | Any dummy type from the relevant library. Its characteristics are ignored. |
| layout | The layout_mapping_policy of Args and the resulting object (std::layout_right by default). |
| Scalar | An scalar type for the new matrix. By default, it is the same as T. |
| Ds | coordinates::pattern objects describing the size of the resulting object. |
| d_tup | A tuple of coordinates::pattern Ds |
| args | Scalar values to fill the new matrix. |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Create a dense, writable matrix from a set of components, with size and shape inferred from dummy type T.
The coordinates::pattern of the result must be unambiguously inferrable from T and the number of indices.
| T | The matrix or array on which the new matrix is patterned. |
| layout | The layout_mapping_policy of Args and the resulting object layout of the resulting object is unspecified). |
| Scalar | An scalar type for the new matrix. By default, it is the same as T. |
| args | Scalar values to fill the new matrix. |
| constexpr auto OpenKalman::make_diagonal_adapter | ( | Arg && | arg, |
| D0 && | d0, | ||
| D1 && | d1 | ||
| ) |
Make a diagonal_matrix, specifying the first two dimensions, which may not necessarily be the same.
| Arg | A vector or higher-order tensor reflecting the diagonal(s). |
| D0 | The coordinates::pattern for the rows. |
| D1 | The coordinates::pattern for the columns. |
| constexpr auto OpenKalman::make_diagonal_adapter | ( | Arg && | arg | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make an square diagonal_matrix that is square with respect to dimensions 0 and 1.
| Arg | A vector or higher-order tensor reflecting the diagonal(s). |
| auto OpenKalman::make_euclidean_mean | ( | const Args ... | args | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a one-column EuclideanMean from a list of coefficients, with default Axis coefficients.
| Args | A list of numerical coefficients (either integral or floating-point). |
| auto OpenKalman::make_euclidean_mean | ( | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a EuclideanMean based on a scalar type, row coefficients, and a number of columns.
| Scalar | A scalar type (integral or floating-point). |
| StaticDescriptor | The coefficient types corresponding to the rows. |
| cols | The number of columns. |
| auto OpenKalman::make_euclidean_mean | ( | M && | arg | ) |
Make a EuclideanMean from a typed_matrix_nestable, specifying the row coefficients.
| StaticDescriptor | The coefficient types corresponding to the rows. |
| M | A typed_matrix_nestable with size matching ColumnCoefficients. |
| auto OpenKalman::make_euclidean_mean | ( | M && | m | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a EuclideanMean from a typed_matrix_nestable object, with default Axis coefficients.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a EuclideanMean from another typed_matrix.
| Arg | A typed_matrix (i.e., Matrix, Mean, or EuclideanMean). |
| OpenKalman::make_euclidean_mean | ( | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a EuclideanMean from a list of coefficients, specifying the row coefficients.
Make a default, self-contained EuclideanMean.
| StaticDescriptor | The coefficient types corresponding to the rows. |
| M | a typed_matrix_nestable on which the new matrix is based. It will be converted to a self_contained type if it is not already self-contained. |
| StaticDescriptor | The coefficient types corresponding to the rows. |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must be divisible by coordinates::stat_dimension_of_v<StaticDescriptor>. |
| auto OpenKalman::make_euclidean_mean | ( | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a self-contained EuclideanMean with default Axis coefficients.
| M | a typed_matrix_nestable on which the new Euclidean mean is based. It will be converted to a self_contained type if it is not already self-contained. |
|
inline |
Make a Gaussian distribution.
| D | Another gaussian_distribution. |
|
inline |
Make a Gaussian distribution.
| re | A random number engine. |
| M | A typed_matrix. |
| Cov | A covariance or typed_matrix. |
|
inline |
Make a Gaussian distribution.
| re | A random number engine. |
| M | A typed_matrix. |
| Cov | A covariance_nestable or typed_matrix_nestable. |
| re | A random number engine. |
| M | A typed_matrix_nestable. |
| Cov | A covariance, typed_matrix, covariance_nestable, or typed_matrix_nestable. |
|
inline |
Make a Gaussian distribution.
| StaticDescriptor | The types of the fixed_pattern for the distribution. |
| re | A random number engine. |
| M | A typed_matrix_nestable. |
| Cov | A covariance_nestable or typed_matrix_nestable. |
|
inline |
Make a default Gaussian distribution.
| M | A typed_matrix. |
| Cov | A covariance. |
| re | A random number engine. |
| M | A typed_matrix or typed_matrix_nestable. |
| Cov | A covariance or covariance_nestable. |
| re | A random number engine. |
|
inline |
Make a default Gaussian distribution.
| StaticDescriptor | The types of the fixed_pattern for the distribution. |
| M | A typed_matrix_nestable |
| Cov | A covariance_nestable. |
| re | A random number engine |
| decltype(auto) constexpr OpenKalman::make_hermitian_matrix | ( | Arg && | arg | ) |
Creates a hermitian_matrix by, if necessary, wrapping the argument in a hermitian_adapter.
| adapter_type | The intended HermitianAdapterType of the result (lower op upper). |
| Arg | A square matrix. |
| constexpr auto OpenKalman::make_identity_matrix_like | ( | Descriptors && | descriptors | ) |
Make an identity_matrix with a particular set of coordinates::pattern objects.
| T | Any matrix or tensor within the relevant library. |
| Scalar | An optional scalar type for the new zero matrix. By default, T's scalar type is used. |
| Ds | A set of coordinates::pattern items defining the dimensions of each index. |
| constexpr auto OpenKalman::make_identity_matrix_like | ( | Ds &&... | ds | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
coordinates::pattern objects are passed as arguments.
| constexpr auto OpenKalman::make_identity_matrix_like | ( | Arg && | arg | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make an identity matrix with the same size and shape as an argument, specifying a new scalar type.
| Arg | The matrix or array on which the new identity matrix is patterned. It need not be square. |
| Scalar | A scalar type for the new matrix. |
| constexpr auto OpenKalman::make_identity_matrix_like | ( | Arg && | arg | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make an identity matrix with the same size and shape as an argument.
| Arg | The matrix or array on which the new zero matrix is patterned. |
| auto OpenKalman::make_matrix | ( | const Args ... | args | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a one-column Matrix from a list of coefficients, with default Axis coefficients.
| Args | A list of numerical coefficients (either integral or floating-point). |
| OpenKalman::make_matrix | ( | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a Matrix from a list of coefficients, specifying the row and column coefficients.
For Eigen3: Make a Matrix based on a scalar type and row and column coefficients.
| Scalar | A scalar type (integral or floating-point). |
| RowCoefficients | The coefficient types corresponding to the rows. |
| ColumnCoefficients | The coefficient types corresponding to the columns. |
| RowCoefficients | The coefficient types corresponding to the rows. |
| ColumnCoefficients | The coefficient types corresponding to the columns. |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must equal coordinates::dimension_of_v<RowCoefficients> * coordinates::dimension_of_v<ColumnCoefficients>. |
| auto OpenKalman::make_mean | ( | const Args ... | args | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a one-column Mean from a list of coefficients, with default Axis coefficients.
| Args | A list of numerical coefficients (either integral or floating-point). |
| auto OpenKalman::make_mean | ( | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a Mean based on a scalar type, a set of row coefficients, and a number of columns.
| Scalar | A scalar type (integral or floating-point). |
| StaticDescriptor | The coefficient types corresponding to the rows. |
| cols | The number of columns. |
|
inline |
Make a Mean from a typed_matrix_nestable, specifying the row fixed_pattern.
| StaticDescriptor | The coefficient types corresponding to the rows. |
| M | A typed_matrix_nestable with size matching ColumnCoefficients. |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a Mean from a typed_matrix_nestable object, with default Axis fixed_pattern.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a Mean from another typed_matrix.
| Arg | A typed_matrix (i.e., Matrix, Mean, or EuclideanMean). |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a Mean from a list of coefficients, specifying the row coefficients.
Make a default, self-contained Mean.
| StaticDescriptor | The coefficient types corresponding to the rows. |
| M | a typed_matrix_nestable on which the new matrix is based. It will be converted to a self_contained type if it is not already self-contained. |
| StaticDescriptor | The coefficient types corresponding to the rows. |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must be divisible by coordinates::dimension_of_v<StaticDescriptor>. |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a self-contained Mean with default Axis fixed_pattern.
| M | a typed_matrix_nestable on which the new mean is based. It will be converted to a self_contained type if it is not already self-contained. |
|
inline |
Make a SquareRootCovariance from a covariance_nestable, specifying the coefficients.
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| Arg | A covariance_nestable with size matching StaticDescriptor. |
Make a default Axis SquareRootCovariance from a self-adjoint typed_matrix_nestable.
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Arg | A square, self-adjoint typed_matrix_nestable. |
Make a SquareRootCovariance from a typed_matrix.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a SquareRootCovariance from a covariance_nestable, with default Axis coefficients.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| Arg | A covariance_nestable. |
Make a SquareRootCovariance based on another triangular_covariance.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a SquareRootCovariance (with nested triangular matrix) from a self-adjoint typed_matrix_nestable.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Arg | A square, self-adjoint typed_matrix_nestable with size matching StaticDescriptor. |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
For Eigen3: Make a writable, uninitialized SquareRootCovariance.
For Eigen3: Make a default Axis SquareRootCovariance from a list of coefficients.
For Eigen3: Make a SquareRootCovariance from a list of coefficients.
Make a writable, uninitialized SquareRootCovariance from a typed_matrix_nestable.
Only the coefficients in the associated upper or lower triangle are significant.
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must equal coordinates::dimension_of_v<StaticDescriptor> * coordinates::dimension_of_v<StaticDescriptor>. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Args | A list of numerical coefficients (either integral or floating-point). The number of coefficients must be the square of an integer. |
| StaticDescriptor | The coefficient types corresponding to the rows and columns. |
| triangle_type | The type of the nested triangular matrix (upper, lower). |
| Scalar | The scalar type (integral or floating-point). |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a writable, uninitialized SquareRootCovariance from a covariance_nestable or typed_matrix_nestable.
Make a writable, uninitialized SquareRootCovariance, with default Axis coefficients.
Make a writable, uninitialized SquareRootCovariance based on a typed_matrix.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Make a writable, uninitialized SquareRootCovariance from a typed_matrix_nestable or covariance_nestable.
The coefficients will be Axis.
Make a writable, uninitialized SquareRootCovariance from a triangular_covariance.
Make a writable, uninitialized SquareRootCovariance based on a typed_matrix.
| decltype(auto) constexpr OpenKalman::make_triangular_matrix | ( | Arg && | arg | ) |
Create a triangular_matrix from a general matrix.
| t | The intended triangle_type of the result. |
| Arg | A general matrix to be made triangular. |
| constexpr auto OpenKalman::make_zero | ( | stdex::extents< IndexType, Extents... > | extents | ) |
Make an indexible object in which every element is 0.
| extents | An std::extents object defining the extents. |
| OpenKalman::Matrix | ( | V && | ) | -> Matrix< vector_space_descriptor_of_t< V, 0 >, vector_space_descriptor_of_t< V, 1 >, passable_t< nested_object_of_t< V >>> |
Deduce template parameters from a non-Euclidean-transformed typed matrix.
Deduce parameter types from a Covariance.
Deduce template parameters from a Euclidean-transformed typed matrix.
|
explicit |
Deduce template parameters from a typed_matrix_nestable, assuming untyped coordinates::pattern.
Deduce template parameters from a Euclidean-transformed typed matrix.
Deduce template parameters from a non-Euclidean-transformed typed matrix.
| constexpr auto OpenKalman::n_ary_operation | ( | const std::tuple< Ds... > & | d_tup, |
| Operation && | operation, | ||
| Args &&... | args | ||
| ) |
Perform a component-wise n-ary operation, using broadcasting to match the size of a pattern matrix.
This overload is for unary, binary, and higher n-ary operations. Examples:
| Ds | coordinates::pattern objects defining the size of the result. |
| Operation | The n-ary operation taking n arguments and, optionally, a set of indices indicating the location within the result. The operation must return a scalar value. |
| Args | The arguments |
| constexpr auto OpenKalman::n_ary_operation | ( | Operation && | operation, |
| Args &&... | args | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Perform a component-wise n-ary operation, using broadcasting if necessary to make the arguments the same size.
Each of the arguments may be expanded by broadcasting. The result will derive each dimension from the largest corresponding dimension among the arguments. Examples:
| Operation | The n-ary operation taking n arguments and, optionally, a set of indices. The operation must return a scalar value. |
| Args | The arguments |
| constexpr auto OpenKalman::n_ary_operation | ( | const std::tuple< Ds... > & | d_tup, |
| const Operations &... | operations | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Perform a component-wise nullary operation with potentially multiple operations for different blocks.
Examples:
| PatternMatrix | A matrix or array corresponding to the result type. Its purpose is to indicate the library from which to create a resulting matrix, and its dimensions need not match the specified dimensions Ds |
| indices | The indices, if any, along which there will be a different operator for each element along that index. |
| Ds | coordinates::pattern objects for each index of the result. coordinates::pattern objects corresponding to indices must be of a fixed_pattern type. |
| Operations | The nullary operations. The number of operations must equal the product of each dimension Ds corresponding to indices. The order of the operations depends on the order of indices, with the left-most index being the most major, and the right-most index being the most minor. For example, if indices are {0, 1} for a matrix result, the operations must be in row-major order. If the indices are {1, 0}, the operations must be in column-major order. Each operation may be invocable with no arguments or invocable with as many indices as there are coordinates::pattern Ds. (If the index corresponds to one of designaged indices, then the operation will be called with std::integral_constant<std::size_t, index>{} for that index, instead of std::size_t.)) |
| constexpr auto OpenKalman::n_ary_operation | ( | const Operations &... | operations | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Perform a component-wise nullary operation, deriving the resulting size from a pattern matrix.
| PatternMatrix | A matrix or array corresponding to the result type. Its purpose is to indicate the library from which to create a resulting matrix, and its dimensions need not match the specified dimensions Ds. Dimensions of PatternMatrix corresponding to indices must be of a fixed_pattern type. |
| indices | The indices, if any, along which there will be a different operator for each element along that index. |
| Operations | The nullary operations. The number of operations must equal the product of each dimension Ds corresponding to indices. |
| decltype(auto) constexpr OpenKalman::nested_object | ( | Arg && | arg | ) |
Retrieve a nested object of Arg, if it exists.
| i | Index of the nested matrix (0 for the 1st, 1 for the 2nd, etc.). |
| Arg | A wrapper that has at least one nested object. |
| constexpr bool OpenKalman::patterns_match | ( | const Ts &... | ts | ) |
Return true if every set of coordinates::pattern of a set of objects are equivalent.
| Ts | A set of tensors or matrices |
| decltype(auto) constexpr OpenKalman::QR_decomposition | ( | A && | a | ) |
Perform a QR decomposition of matrix A=Q[U,0], U is a upper-triangular matrix, and Q is orthogonal.
| A | The matrix to be decomposed |
| constexpr auto OpenKalman::randomize | ( | random_number_generator & | gen, |
| const std::tuple< Ds... > & | ds_tuple, | ||
| Dists &&... | dists | ||
| ) |
Create an indexible object with random values selected from one or more random distributions.
This is essentially a specialized version of n_ary_operation with the nullary operator being a randomization function. The distributions are allocated to each element of the object, according to one of the following options:
| PatternMatrix | An indexible object corresponding to the result type. Its dimensions need not match the specified dimensions Ds |
| indices | The indices, if any, for which there is a distinct distribution. If not provided, this can in some cases be inferred from the number of Dists provided. |
| random_number_generator | The random number generator (e.g., std::mt19937). |
| Ds | coordinates::pattern objects for each index the result. They need not correspond to the dimensions of PatternMatrix. |
| Dists | One or more distributions (e.g., std::normal_distribution<double>) |
| constexpr auto OpenKalman::randomize | ( | const std::tuple< Ds... > & | d_tuple, |
| Dists &&... | dists | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Create an indexible object with random values, using std::mt19937 as the random number engine.
| constexpr auto OpenKalman::randomize | ( | random_number_generator & | gen, |
| Dists &&... | dists | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Fill a fixed-sized indexible object with random values selected from one or more random distributions.
The distributions are allocated to each element of the matrix, according to one of the following options:
| PatternMatrix | A fixed-size matrix |
| random_number_generator | The random number generator (e.g., std::mt19937). |
| constexpr auto OpenKalman::randomize | ( | Dists &&... | dists | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Fill a fixed-sized indexible object with random values using std::mt19937 as the random number generator.
|
inline |
Fill a fixed-shape typed matrix with random values selected from a random distribution.
The distributions are allocated to each element of the matrix, according to one of the following options:
| ReturnType | The return type reflecting the size of the matrix to be filled. The actual result will be a fixed typed matrix. |
| random_number_engine | The random number engine. |
| Dists | A set of distributions (e.g., std::normal_distribution<double>) or, alternatively, means (a definite, non-stochastic value). |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Fill a dynamic-shape typed_matrix with random values selected from a single random distribution.
The following example constructs two 2-by-2 matrices (m, n, and p) in which each element is a random value selected based on a distribution with mean 1.0 and standard deviation 0.3:
| ReturnType | The type of the matrix to be filled. |
| random_number_engine | The random number engine (e.g., std::mt19937). |
| rows | Number of rows, decided at runtime. Must match rows of ReturnType if they are fixed. |
| columns | Number of columns, decided at runtime. Must match columns of ReturnType if they are fixed. |
| Dist | A distribution (type distribution_type). |
|
inline |
Do a rank update on a hermitian matrix.
The update is A += αUU*, returning the updated hermitian A. If A is an lvalue reference, hermitian, and writable, it will be updated in place and the return value will be an lvalue reference to the same, updated A. Otherwise, the function returns a new matrix.
| A | The hermitian matrix to be rank updated. |
| U | The update vector or matrix. |
|
inline |
Do a rank update on triangular matrix.
| A | The matrix to be rank updated. |
| U | The update vector or matrix. |
| decltype(auto) constexpr OpenKalman::reduce | ( | BinaryFunction && | b, |
| Arg && | arg | ||
| ) |
Perform a partial reduction based on an associative binary function, across one or more indices.
The binary function must be associative. (This is not enforced, but the order of operation is undefined.)
| index | an index to be reduced. For example, if the index is 0, the result will have only one row. If the index is 1, the result will have only one column. |
| indices | Other indices to be reduced. Because the binary function is associative, the order of the indices does not matter. |
| BinaryFunction | A binary function invocable with two values of type scalar_type_of_t<Arg>. It must be an associative function. Preferably, it should be a constexpr function, and even more preferably, it should be a standard c++ function such as std::plus or std::multiplies. |
| Arg | The tensor |
| constexpr scalar_type_of_t<Arg> OpenKalman::reduce | ( | const BinaryFunction & | b, |
| const Arg & | arg | ||
| ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Perform a complete reduction based on an associative binary function, and return a scalar.
The binary function must be associative. (This is not enforced, but the order of operation is undefined.)
| BinaryFunction | A binary function invocable with two values of type scalar_type_of_t<Arg>. It must be an associative function. Preferably, it should be a constexpr function, and even more preferably, it should be a standard c++ function such as std::plus or std::multiplies. |
| Arg | The tensor |
|
inline |
Scale a covariance by a factor.
Equivalent to multiplication by the square of a scalar. For a square root covariance, this is equivalent to multiplication by the scalar.
|
inline |
Scale a covariance by a matrix.
| M | A covariance. |
| A | A typed_matrix. |
A scaled covariance Arg is A * Arg * adjoint(A). A scaled square root covariance L or U is also scaled accordingly, so that scale(L * adjoint(L)) = A * L * adjoint(L) * adjoint(A) or scale(adjoint(U) * U) = A * adjoint(U) * U * adjoint(A).
| constexpr Arg&& OpenKalman::set_chip | ( | Arg && | arg, |
| Chip && | chip, | ||
| Ixs... | ixs | ||
| ) |
Set a sub-array having rank less than the rank of the input object.
A chip is a special type of "thin" slice of width 1 in one or more dimensions, and otherwise no reduction in extents. For example, the result could be a row vector, a column vector, a matrix (e.g., if the input object is a rank-3 or higher tensor), etc.
| indices | The index or indices of the dimension(s) that have been collapsed to a single dimension. For example, if the input object is a matrix, a value of {0} will result in a row vector and a value of {1} will result in a column vector. If the input object is a rank-3 tensor, a value of {0, 1} will result in a matrix. |
| arg | The indexible object in which the chip is to be set. |
| chip | The chip to be set. It must be a chip, meaning that the dimension is 1 for each of indices. |
| is | The index value(s) corresponding to indices, in the same order. The values may be positive std::integral types or a positive std::integral_constant. |
| constexpr Arg&& OpenKalman::set_slice | ( | Arg && | arg, |
| Block && | block, | ||
| const Begin &... | begin | ||
| ) |
Assign an object to a particular slice of a matrix or tensor.
| arg | The writable object in which the slice is to be assigned. |
| block | The block to be set. |
| begin | A tuple specifying, for each index of Arg in order, the beginning values::index. |
| size | A tuple specifying, for each index of Arg in order, the dimensions of the extracted block. |
| constexpr auto OpenKalman::solve | ( | A && | a, |
| B && | b | ||
| ) |
Solve the equation AX = B for X, which may or may not be a unique solution.
The interface to the relevant linear algebra library determines what happens if A is not invertible.
| must_be_unique | Determines whether the function throws an exception if the solution X is non-unique (e.g., if the equation is under-determined) |
| must_be_exact | Determines whether the function throws an exception if it cannot return an exact solution, such as if the equation is over-determined. If false |
| A | |
| B | |
|
inline |
Split a matrix or tensor into sub-parts, where the split is the same for every index.
This is an inverse of the concatenate operation. In other words, for all std::size_t i..., j... and indexible a..., and given the function template<std::size_t...i> auto f(auto a) { return get_pattern_collection<i>(a)...}; } ((split<i...>(concatenate<i...>(a...), get_pattern_collection<j>(a)...) == std::tuple{a...}) and ...).
| indices | The indices along which to make the split. E.g., 0 means to split along rows, 1 means to split along columns, {0, 1} means to split diagonally. |
| Arg | The matrix or tensor to be split. |
| Ds | A set of coordinates::pattern (the same for for each of indices) |
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Split a matrix or tensor into sub-parts of a size defined independently for each index.
This is an inverse of the concatenate operation. In other words, for all std::size_t i... and indexible a..., and given the function template<std::size_t...i> auto f(auto a) { return std::tuple{get_pattern_collection<i>(a)...}; } split<i...>(concatenate<i...>(a...), f<i...>(a)...) == std::tuple{a...}.
| indices | The indices along which to make the split. E.g., 0 means to split along rows, 1 means to split along columns, {0, 1} means to split diagonally. |
| Arg | The matrix or tensor to be split. |
| Ds_tups | A set of tuples of coordinates::pattern objects, each tuple having sizeof...(indices) elements |
|
inline |
Split Covariance or SquareRootCovariance diagonally.
Split typed matrix into one or more typed matrices diagonally.
|
inline |
Split Covariance or SquareRootCovariance vertically. Result is a tuple of typed matrices.
Split typed matrix into one or more typed matrices horizontally. Column coefficients must all be Axis.
Split typed matrix into one or more typed matrices horizontally.
|
inline |
Split Covariance or SquareRootCovariance vertically. Result is a tuple of typed matrices.
Split typed matrix into one or more typed matrices vertically.
|
explicit |
Deduce SquareRootCovariance type from a covariance_nestable.
Deduce SquareRootCovariance type from a square typed_matrix_nestable.
Deduce SquareRootCovariance type from a square typed_matrix.
| constexpr auto OpenKalman::tensor_order | ( | const T & | t | ) |
Return the tensor order of T (i.e., the number of indices of dimension greater than 1).
If T has any zero-dimensional indices, the tensor order is considered to be 0, based on the theory that a zero-dimensional vector space has 0 as its only element, and 0 is a scalar value. This may be subject to change.
| T | A matrix or array |
| decltype(auto) constexpr OpenKalman::tile | ( | const std::tuple< Ds... > & | ds_tuple, |
| Block && | block, | ||
| Blocks &&... | blocks | ||
| ) |
Create a matrix or tensor by tiling individual blocks.
| Ds | A set of coordinates::pattern for the resulting matrix or tensor. |
| Block | The first block |
| Blocks | Subsequent blocks |
| decltype(auto) constexpr OpenKalman::to_dense_object | ( | Arg && | arg | ) |
Convert the argument to a dense, writable matrix of a particular scalar type.
| T | A dummy matrix or array from the relevant library (size, shape, and layout are ignored) |
| layout | The data_layout of the resulting object. If this is data_layout::none, the interface will decide the layout. |
| Scalar | The Scalar type of the new matrix, if different than that of Arg |
| arg | The object from which the new matrix is based |
| decltype(auto) constexpr OpenKalman::to_dense_object | ( | Arg && | arg | ) |
Convert the argument to a dense, writable matrix of a particular scalar type.
| layout | The data_layout of the resulting object. If this is data_layout::none, the interface will decide the layout. |
| Scalar | The Scalar type of the new matrix, if different than that of Arg |
| arg | The object from which the new matrix is based |
| decltype(auto) constexpr OpenKalman::to_dense_object | ( | Arg && | arg | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Convert the argument to a dense, writable matrix with the same scalar type as the argument.
| layout | The data_layout of the resulting object (optional). If this is omitted or data_layout::none, the interface will decide the layout. |
| arg | The object from which the new matrix is based |
| decltype(auto) constexpr OpenKalman::to_diagonal | ( | Arg && | arg | ) |
| decltype(auto) constexpr OpenKalman::to_euclidean | ( | Arg && | arg | ) |
Project the vector space associated with index 0 to a Euclidean space for applying directional statistics.
| Arg | A matrix or tensor. |
| decltype(auto) constexpr OpenKalman::trace | ( | Arg && | arg | ) |
Take the trace of a matrix.
This is a generalized trace that applies to rectangular matrices. If the argument is rectangular, this function returns the trace of the square sub-matrix.
| Arg | The matrix |
| decltype(auto) constexpr OpenKalman::transpose | ( | Arg && | arg | ) |
Swap any two indices of an indexible_object.
By default, the first two indices are transposed.
| decltype(auto) constexpr OpenKalman::unary_operation_in_place | ( | const Operation & | operation, |
| Arg && | arg | ||
| ) |
Perform a component-wise, in-place unary operation.
Examples:
| Operation | The n-ary operation taking an argument and, optionally, a set of indices. The argument to the operation is a component of Arg and will be assignable as a non-const lvalue reference. The operation may either return the result (as a value or reference) or return void (in which case any changes to the component argument will be treated as an in-place modification). |
| Arg | The argument, which must be non-const and writable. |
| constexpr bool OpenKalman::all_fixed_indices_are_euclidean |
Specifies that every fixed-size index of T is euclidean.
No fixed_size index of T is, e.g., Angle, Polar, Spherical, etc.
| constexpr bool OpenKalman::cholesky_form = detail::is_cholesky_form<std::decay_t<T>>::value |
Specifies that a type has a nested native matrix that is a Cholesky square root.
If this is true, then nested_object_of_t<T> is true.
| constexpr bool OpenKalman::compares_with_pattern_collection |
Compares the associated pattern collection of indexible T with pattern_collection D.
| T | An indexible object |
| D | A pattern_collection |
| constexpr bool OpenKalman::constant_diagonal_object |
Specifies that all diagonal elements of a diagonal object are known at compile time to be the same constant value.
A constant diagonal matrix is also a diagonal_matrix. It is not necessarily square. If T is a rank >2 tensor, every rank-2 slice comprising dimensions 0 and 1 must be constant diagonal matrix. To check if the constant is zero, it is better to use zero, which might catch more cases.
| constexpr bool OpenKalman::constant_object |
Specifies that all elements of an object are known at compile time to be the same constant value.
To check if the constant is zero, it is better to use zero.
| constexpr bool OpenKalman::copyable_from |
Specifies that an indexible object is copyable from another indexible object.
| Dest | The object to be copied to |
| Source | The object to be copied from |
| constexpr bool OpenKalman::covariance_nestable |
T is an acceptable nested matrix for a covariance (including triangular_covariance).
| constexpr bool OpenKalman::diagonal_matrix |
Specifies that a type is a diagonal matrix or tensor.
A diagonal matrix has zero components everywhere except the main diagonal. It is not necessarily square. For rank >2 tensors, every rank-2 slice comprising dimensions 0 and 1 must be diagonal.
| constexpr bool OpenKalman::dimension_size_of_index_is |
Specifies that a given index of T has a specified size.
If b == applicability::permitted, then the concept will apply if there is a possibility that the specified index of T is value.
| comp | A consteval-callable object taking the comparison result (e.g., std::partial_ordering) and returning a bool value |
| constexpr bool OpenKalman::dynamic_dimension = detail::is_dynamic_dimension<T, N>::value |
Specifies that T's index N has a dimension defined at run time.
The matrix library interface will specify this for native matrices and expressions.
| constexpr bool OpenKalman::euclidean_transformed |
Specifies that T is a Euclidean mean that actually has coefficients that are transformed to Euclidean space.
| constexpr bool OpenKalman::has_dynamic_dimensions |
Specifies that T has at least one index with dynamic dimensions.
| constexpr bool OpenKalman::has_nested_object |
A matrix that has a nested matrix, if it is a wrapper type.
| constexpr bool OpenKalman::has_untyped_index |
Specifies that T has an untyped index N.
Index N of T is Euclidean and non-modular (e.g., Axis, Dimensions<2>, etc.).
| constexpr bool OpenKalman::hermitian_adapter = hermitian_matrix<T> and detail::hermitian_adapter_impl<std::decay_t<T>, t>::value |
Specifies that a type is a hermitian matrix adapter of a particular type.
A hermitian adapter may or may not actually be a hermitian_matrix, depending on whether it is a square_shaped. If it is not a square matrix, it can still be a hermitian adapter, but only the truncated square portion of the matrix would be hermitian.
| T | A matrix or tensor. |
| t | The HermitianAdapterType of T. |
| constexpr auto OpenKalman::hermitian_adapter_type_of_v = hermitian_adapter_type_of<T, Ts...>::value |
The triangle_type associated with the storage triangle of a hermitian_matrix.
| constexpr bool OpenKalman::hermitian_matrix |
Specifies that a type is a hermitian matrix.
For rank >2 tensors, this must be applicable on every rank-2 slice comprising dimensions 0 and 1.
| constexpr bool OpenKalman::identity_matrix |
Specifies that a type is known at compile time to be a rank-2 or lower identity matrix.
This is a generalized identity matrix which may be rectangular (with zeros in all non-diagonal components. A 1D vector with constant element 1 and an empty_matrix are also considered to be identity matrices.
| constexpr bool OpenKalman::index_collection_for |
Indices is a collection of indices that are compatible with indexible object T.
This performs static bounds checking.
| constexpr bool OpenKalman::indexible |
T is a multidimensional array type.
T can be a vector, matrix, tensor, or other generalized array in which elements are accessed by a set of indices. It includes any type for which interface::object_traits is specialized.
| constexpr bool OpenKalman::linearized_function |
A linearized function (with defined Jacobian and optionally Hessian functions).
If order == 1, then the Jacobian is defined. If order == 2, then the Hessian is defined.
| T | The function. |
| order | The maximum order in which T's Taylor series is defined. |
|
inline |
Specifies that a type is one-dimensional in every index.
Each index also must have an equivalent coordinates::pattern object.
| constexpr bool OpenKalman::pattern_collection_for = detail::compatible_shape_with_impl_cpp17<P, T, a>::value |
pattern collection P is compatible with indexible T.
If one or the other is dynamic, both must be dynamic, otherwise, the static dimensions must match. Any trailing patterns in P must be equivalent to Dimensions<1>.
| P | a coordinates::pattern_collection |
| T | an indexible object |
| constexpr bool OpenKalman::patterns_match_with |
Specifies that a set of indexible objects have equivalent vector space descriptors for each index.
| Ts | A set of indexible objects |
| constexpr bool OpenKalman::patterns_may_match_with |
Specifies that indexible objects Ts may have equivalent dimensions and vector-space types.
Two dimensions are considered the same if their coordinates::pattern are equivalent.
| constexpr bool OpenKalman::square_shaped |
Specifies that an object is square (i.e., has equivalent coordinates::pattern along each dimension).
Any trailing 1D Euclidean descriptors are disregarded. A vector must be one-dimensional. A 0-by-0 matrix or tensor is considered to be square.
| b | Defines what happens when one or more of the indices has dynamic dimension:
|
| constexpr bool OpenKalman::transformation_input |
T is an acceptable input to a tests.
| Coeffs | The expected coefficients of the tests input. |
| constexpr bool OpenKalman::triangular_adapter |
Specifies that a type is a triangular adapter of triangle type tri.
A triangular adapter takes a matrix and presents a view in which, in one or both triangular (or trapezoidal) sides on either side of the diagonal are zero. The matrix need not be square.
| T | A matrix or tensor. |
| constexpr bool OpenKalman::triangular_matrix |
Specifies that an argument is an indexible object having a given triangle_type (e.g., upper, lower, or diagonal).
This can also test whether the argument is triangular (triangle_type::none). To test whether the argument has any triangle type, use triangle_type::any (which is the default). Diagonal matrices are considered to also be both upper and lower.
| t | The triangle_type |
| constexpr bool OpenKalman::typed_adapter |
Specifies that T is a typed adapter expression.
| constexpr bool OpenKalman::typed_matrix_nestable |
Specifies a type that is nestable in a general typed matrix (e.g., matrix, mean, or euclidean_mean)
| constexpr bool OpenKalman::untyped_adapter |
Specifies that T is an untyped adapter expression.
Untyped adapter expressions are generally used whenever the native matrix library does not have an important built-in matrix type, such as a diagonal matrix, a triangular matrix, or a hermitian matrix.
| constexpr bool OpenKalman::vector |
T is a vector (e.g., column or row vector).
In this context, a vector is an object in which every index but one is 1D.
| T | An indexible object |
| N | An index designating the "large" index (e.g., 0 for a column vector, 1 for a row vector) |
| b | Whether the vector status is guaranteed known at compile time (applicability::guaranteed), or only known at runtime (applicability::permitted) |
| constexpr bool OpenKalman::wrappable = detail::is_wrappable<T>::value |
Specifies that every fixed-size index of T (other than potentially index 0) is euclidean.
This indicates that T is suitable for wrapping along index 0.
| constexpr bool OpenKalman::wrapped_mean |
Specifies that T is a wrapped mean (i.e., its row fixed_pattern have at least one type that requires wrapping).
| constexpr bool OpenKalman::zero |
Specifies that a type is known at compile time to be a constant matrix of value zero.
| epsilon_factor | An epsilon value to account for rounding error. This is multiplied by std::numeric_limits<std::decay_t<T::epsilon(), if it exists. If it is zero, the match must be exact. |
1.8.13