OpenKalman
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
OpenKalman Namespace Reference

The root namespace for OpenKalman. More...

Namespaces

 collections
 Namespace for collections.
 
 detail
 T is an acceptable noise perturbation input to a tests.
 
 values
 Definition for values::abs.
 

Classes

struct  common_reference
 
struct  common_reference< T >
 
struct  common_reference< T1, T2, Ts... >
 
struct  common_reference<>
 
struct  compare_three_way
 
struct  ConstantAdapter
 A tensor or other matrix in which all elements are a constant scalar value. More...
 
struct  ContinuousPropertyParticleDistribution
 
struct  Covariance
 A self-adjoint Covariance matrix. More...
 
struct  CubaturePoints
 Implementation of a cubature points transform. More...
 
struct  DiagonalAdapter
 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<(index_count< T >::value !=dynamic_size)> >
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
struct  equal_to
 A generalization of std::equal_to in which the arguments may be of different types. More...
 
struct  equal_to< void >
 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  greater
 A generalization of std::greater in which the arguments may be of different types. More...
 
struct  greater< void >
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
struct  greater_equal
 A generalization of std::less_equal in which the arguments may be of different types. More...
 
struct  greater_equal< void >
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
struct  hermitian_adapter_type_of
 The TriangleType associated with the storage triangle of one or more matrices. More...
 
struct  HermitianAdapter
 A hermitian matrix wrapper. More...
 
struct  identity
 
struct  IdentityTransform
 An identity transform from one statistical distribution to another. More...
 
struct  IdentityTransformation
 
struct  incrementable_traits
 
struct  incrementable_traits< const T >
 
struct  incrementable_traits< T *, std::enable_if_t< std::is_object_v< T > > >
 
struct  incrementable_traits< T, std::enable_if_t< detail::has_member_difference_type< T >::value > >
 
struct  incrementable_traits< T, std::enable_if_t< not detail::has_member_difference_type< T >::value and std::is_integral_v< decltype(std::declval< const T & >() - std::declval< const T & >())> > >
 
struct  index_count
 The minimum number of indices need to access all the components of an object. More...
 
struct  index_count< T, std::enable_if_t< detail::dynamic_count_indices_defined< T >::value > >
 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_count< T, std::enable_if_t< detail::static_count_indices_defined< T >::value > >
 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::void_t< typename vector_space_descriptor_of< T, N >::type > >
 
struct  indirectly_readable_traits
 
struct  indirectly_readable_traits< const T >
 
struct  indirectly_readable_traits< I, std::enable_if_t< std::is_array_v< I > > >
 
struct  indirectly_readable_traits< T * >
 
struct  indirectly_readable_traits< T, std::enable_if_t< detail_indirectly_readable::has_member_value_type< T > and detail_indirectly_readable::has_member_element_type< T > > >
 
struct  indirectly_readable_traits< T, std::enable_if_t< detail_indirectly_readable::has_member_value_type< T > and not detail_indirectly_readable::has_member_element_type< T > > >
 
struct  indirectly_readable_traits< T, std::enable_if_t< not detail_indirectly_readable::has_member_value_type< T > and detail_indirectly_readable::has_member_element_type< T > > >
 
struct  is_bounded_array
 
struct  is_bounded_array< T[N]>
 
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 row dimension of a matrix, expression, or array. More...
 
struct  layout_of< T, std::enable_if_t< detail::has_layout< std::decay_t< T > >::value > >
 
struct  less
 A generalization of std::less in which the arguments may be of different types. More...
 
struct  less< void >
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
struct  less_equal
 A generalization of std::less_equal in which the arguments may be of different types. More...
 
struct  less_equal< void >
 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 !=dynamic_size > >
 
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  not_equal_to
 A generalization of std::not_equal_to in which the arguments may be of different types. More...
 
struct  not_equal_to< void >
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
class  partial_ordering
 
struct  ParticleDistribution
 Distribution of particles. More...
 
struct  ParticleFilter
 
struct  pattern_matrix_of
 The native matrix on which an OpenKalman matrix adapter is patterned. More...
 
struct  pattern_matrix_of< ConstantAdapter< PatternMatrix, Scalar, constant... > >
 
struct  pattern_matrix_of< T, std::enable_if_t< has_nested_object< T > > >
 
struct  RecursiveLeastSquaresTransform
 Propagates a recursive least squares error distribution of parameters, with a forgetting factor λ. More...
 
class  reference_wrapper
 
struct  SamplePointsTransform
 Scaled points transform. More...
 
struct  scalar_type_of
 Type scalar type (e.g., std::float, std::double, std::complex<double>) of a tensor. More...
 
struct  scalar_type_of< T, std::enable_if_t< interface::scalar_type_defined_for< 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  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 common TriangleType associated with a set of triangular matrices. More...
 
struct  TriangularAdapter
 A triangular_adapter, where components above or below the diagonal (or both) are zero. More...
 
struct  type_identity
 
struct  unreachable_sentinel_t
 
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  vector_space_descriptor_of
 The coordinates::pattern for index N of object T. More...
 
struct  vector_space_descriptor_of< T, N, std::enable_if_t< coordinates::pattern< decltype(get_vector_space_descriptor< N >(std::declval< T >()))> > >
 
struct  VectorSpaceAdapter
 An adapter that adds vector space descriptors for each index. More...
 
struct  WeightedParticleDistribution
 

Typedefs

template<typename... T>
using common_reference_t = typename common_reference< T... >::type
 
template<typename I >
using iter_value_t = typename detail::iter_value_impl< remove_cvref_t< I > >::value_type
 
template<typename I >
using iter_reference_t = decltype(*std::declval< I & >())
 
template<typename I >
using iter_difference_t = typename detail::iter_difference_impl< remove_cvref_t< I > >::difference_type
 
template<typename I >
using iter_rvalue_reference_t = decltype(std::move(*std::declval< I & >()))
 
template<typename T , std::enable_if_t< indirectly_readable< T >, int > = 0>
using iter_const_reference_t = common_reference_t< const iter_value_t< T > &&, iter_reference_t< T > >
 
template<typename T , std::enable_if_t< indirectly_readable< T >, int > = 0>
using iter_common_reference_t = common_reference_t< iter_reference_t< T >, iter_value_t< T > & >
 
template<typename T >
using type_identity_t = typename type_identity< T >::type
 
template<typename PatternObject , typename Scalar = scalar_type_of_t<PatternObject>>
using ZeroAdapter = ConstantAdapter< PatternObject, Scalar, 0 >
 A ConstantAdapter in which all elements are 0. More...
 
template<typename T >
using pattern_matrix_of_t = typename pattern_matrix_of< std::decay_t< T > >::type
 Helper template for pattern_matrix_of.
 
template<typename T , Layout layout = 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 nested_object_of_t = typename nested_object_of< T >::type
 Helper type for nested_object_of. More...
 
template<typename T >
using scalar_type_of_t = typename scalar_type_of< T >::type
 helper template for scalar_type_of.
 
template<typename T , std::size_t N>
using vector_space_descriptor_of_t = typename vector_space_descriptor_of< T, N >::type
 helper template for vector_space_descriptor_of.
 
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  Layout : int { Layout::none, Layout::right, Layout::left, Layout::stride }
 The layout format of a multidimensional array. More...
 
enum  TriangleType : int { TriangleType::diagonal, TriangleType::lower, TriangleType::upper, TriangleType::any }
 The type of a triangular matrix. More...
 
enum  HermitianAdapterType : int { HermitianAdapterType::any = static_cast<int>(TriangleType::diagonal), HermitianAdapterType::lower = static_cast<int>(TriangleType::lower), HermitianAdapterType::upper = static_cast<int>(TriangleType::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

template<typename T , typename U >
constexpr bool cmp_equal (T t, U u) noexcept
 
template<typename T , typename U >
constexpr bool cmp_not_equal (T t, U u) noexcept
 
template<typename T , typename U >
constexpr bool cmp_less (T t, U u) noexcept
 
template<typename T , typename U >
constexpr bool cmp_greater (T t, U u) noexcept
 
template<typename T , typename U >
constexpr bool cmp_less_equal (T t, U u) noexcept
 
template<typename T , typename U >
constexpr bool cmp_greater_equal (T t, U u) noexcept
 
template<typename T >
 reference_wrapper (T &) -> reference_wrapper< T >
 
template<typename T >
constexpr std::reference_wrapper< T > ref (T &t) noexcept
 
template<typename T >
constexpr std::reference_wrapper< T > ref (std::reference_wrapper< T > t) noexcept
 
template<typename T >
void ref (const T &&)=delete
 
template<typename T >
constexpr std::reference_wrapper< const T > cref (const T &t) noexcept
 
template<typename T >
constexpr std::reference_wrapper< const T > cref (std::reference_wrapper< T > t) noexcept
 
template<typename T >
void cref (const T &&)=delete
 
template<typename R , typename F , typename... Args, std::enable_if_t< std::is_invocable_r_v< R, F, Args... >, int > = 0>
constexpr R invoke_r (F &&f, Args &&... args) noexcept(std::is_nothrow_invocable_r_v< R, F, Args... >)
 
constexpr Applicability operator not (Applicability x)
 
constexpr Applicability operator and (Applicability x, Applicability y)
 
constexpr Applicability operator or (Applicability x, Applicability y)
 
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==dynamic_size ? 1 :0)) and(std::is_convertible_v< 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==dynamic_size ? 1 :0)) and(std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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>
 ConstantAdapter (const C &, const Arg &) -> ConstantAdapter< Arg, C >
 
template<typename Arg , std::enable_if_t< constant_matrix< Arg > and(not constant_adapter< Arg >), int > = 0>
 ConstantAdapter (const Arg &) -> ConstantAdapter< Arg, constant_coefficient< 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 , TriangleType triangle_type, 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(triangle_type !=TriangleType::lower or triangular_matrix< Arg, TriangleType::lower >) and(triangle_type !=TriangleType::upper or triangular_matrix< Arg, TriangleType::upper >) and(triangle_type !=TriangleType::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 , TriangleType triangle_type, 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 std::is_convertible_v< 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< std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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 std::is_convertible_v< 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>
 DiagonalAdapter (Arg &&) -> DiagonalAdapter< Arg >
 Deduce DiagonalAdapter 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 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 , TriangleType triangle_type = TriangleType::lower, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< Arg > and(not covariance_nestable< Arg >) and(triangle_type==TriangleType::lower or triangle_type==TriangleType::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 , TriangleType triangle_type, 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 >>
 
template<typename Arg , typename... Vs, std::enable_if_t< indexible< Arg > and pattern_collection< Descriptors > and(not internal::vector_space_adapter< Arg >), int > = 0>
 VectorSpaceAdapter (Arg &&, Descriptors &&) -> VectorSpaceAdapter< Arg, std::decay_t< Descriptors >>
 
template<typename Arg >
decltype(auto) constexpr adjoint (Arg &&arg)
 Take the adjoint of a matrix. More...
 
template<typename To , typename From , std::enable_if_t< indexible< To > and vector_space_descriptors_may_match_with< From, To >, int > = 0>
constexpr To && assign (To &&a, From &&b)
 Assign a writable object from an indexible object. More...
 
template<std::size_t index, std::size_t... indices, typename Arg , std::enable_if_t< internal::has_uniform_static_vector_space_descriptors< 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_static_vector_space_descriptors< 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<TriangleType triangle_type, typename A , std::enable_if_t< hermitian_matrix< A, Applicability::permitted > and(triangle_type !=TriangleType::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 conjugate of a matrix. 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 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<Layout layout = Layout::right, typename Arg , typename... S, std::enable_if_t< indexible< Arg > and(values::number< S > and ...) and(layout==Layout::right or layout==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<typename Arg , typename Indices , std::enable_if_t< index_range_for< Indices, Arg > and(not empty_object< Arg >), int > = 0>
decltype(auto) constexpr get_component (Arg &&arg, const Indices &indices)
 Get a component of an object at a particular set of indices. More...
 
template<typename Arg , typename Ix , std::enable_if_t< values::index< Ix > and(not empty_object< Arg >), int > = 0>
decltype(auto) constexpr get_component (Arg &&arg, const std::initializer_list< Ix > &indices)
 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... I, std::enable_if_t< indexible< Arg > and(... and values::index< I >) and(index_count< Arg >::value==dynamic_size or sizeof...(I) > = index_count<Arg>::value>
decltype(auto) constexpr get_component (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<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_static_vector_space_descriptors< 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 T , typename C , typename Ds , std::enable_if_t< indexible< T > and values::scalar< C > and pattern_collection< Ds >, int > = 0>
constexpr auto make_constant (C &&c, Descriptors &&descriptors)
 Make a constant object based on a particular library object. More...
 
template<typename T , typename C , typename... Ds, std::enable_if_t< indexible< T > and values::scalar< C > and(coordinates::pattern< Ds > and ...), int > = 0>
constexpr auto make_constant (C &&c, 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 C , std::enable_if_t< indexible< T > and values::scalar< C >, int > = 0>
constexpr auto make_constant (const T &t, 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 , typename C , auto... constant, typename Ds , std::enable_if_t< indexible< T > and values::scalar< C > and pattern_collection< Ds > and((values::fixed< C > and sizeof...(constant)==0) or std::is_constructible< C, decltype(constant)... >::value), int > = 0>
constexpr auto make_constant (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 , auto constant, typename Ds , std::enable_if_t< indexible< T > and values::number< decltype(constant)> and pattern_collection< Ds >, int > = 0>
constexpr auto make_constant (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 C , auto... constant, typename... Ds, std::enable_if_t< indexible< T > and values::scalar< C > and(coordinates::pattern< Ds > and ...) and((values::fixed< C > and sizeof...(constant)==0) or std::is_constructible< C, decltype(constant)... >::value), int > = 0>
constexpr auto make_constant (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 , auto constant, typename... Ds, std::enable_if_t< indexible< T > and values::number< decltype(constant)> and(coordinates::pattern< Ds > and ...), int > = 0>
constexpr auto make_constant (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 C , auto... constant, typename T , std::enable_if_t< values::scalar< C > and indexible< T > and((values::fixed< C > and sizeof...(constant)==0) or std::is_constructible< C, decltype(constant)... >::value), int > = 0>
constexpr auto make_constant (const T &t)
 This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More...
 
template<auto constant, typename T , std::enable_if_t< values::number< decltype(constant)> and indexible< T >, int > = 0>
constexpr auto make_constant (const T &t)
 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 , Layout layout = 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 !=Layout::stride) and interface::make_default_defined_for< T, layout, Scalar, decltype(internal::to_euclidean_vector_space_descriptor_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 , Layout layout = 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 !=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 , Layout layout = Layout::none, typename Scalar = scalar_type_of_t<T>, typename... Ds, typename... Args, std::enable_if_t< indexible< T > and values::number< Scalar > and(coordinates::pattern< Ds > and ...) and(std::is_convertible_v< Args, const Scalar > and ...) and(layout !=Layout::stride) 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 , Layout layout = Layout::none, typename Scalar = scalar_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<TriangleType t = TriangleType::lower, typename Arg , std::enable_if_t< indexible< Arg > and(t==TriangleType::lower or t==TriangleType::upper or t==TriangleType::diagonal), int > = 0>
decltype(auto) constexpr make_triangular_matrix (Arg &&arg)
 Create a triangular_matrix from a general matrix. More...
 
template<typename Arg , typename Descriptors , std::enable_if_t< indexible< Arg > and pattern_collection< Descriptors > and internal::not_more_fixed_than< Arg, Descriptors > and(not internal::less_fixed_than< Arg, Descriptors >) and internal::maybe_same_shape_as_vector_space_descriptors< Arg, Descriptors >, int > = 0>
auto make_vector_space_adapter (Arg &&arg, Descriptors &&descriptors)
 If necessary, wrap an object in a wrapper that adds vector space descriptors for each index. More...
 
template<typename Arg , typename... Ds>
auto make_vector_space_adapter (Arg &&arg, 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... Ds, typename Arg , std::enable_if_t< indexible< Arg > and(... and fixed_pattern< Ds >) and(not has_dynamic_dimensions< Arg >) and(sizeof...(Ds) > 0>
auto make_vector_space_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<typename T , typename Scalar = scalar_type_of_t<T>, typename... Ds, std::enable_if_t< indexible< T > and values::number< Scalar > and pattern_collection< Descriptors >, int > = 0>
constexpr auto make_zero (Descriptors &&descriptors)
 Make a zero associated with a particular library. More...
 
template<typename T , typename Scalar = scalar_type_of_t<T>, typename... Ds, std::enable_if_t< indexible< T > and values::number< Scalar > and(... and coordinates::pattern< Ds >), int > = 0>
constexpr auto make_zero (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 T , std::enable_if_t< values::number< Scalar > and indexible< T >, int > = 0>
constexpr auto make_zero (const T &t)
 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>
constexpr auto make_zero (const T &t)
 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... 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((fixed_pattern< typename vector_space_descriptor_of< PatternMatrix, indices >::type >) 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 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 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 std::is_convertible_v< 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, TriangleType::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 std::is_convertible_v< 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_static_vector_space_descriptors< 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_static_vector_space_descriptors< 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 Indices , std::enable_if_t< indexible< Arg > and index_range_for< Indices, Arg > and writable_by_component< Arg, Indices >, int > = 0>
Arg && set_component (Arg &&arg, const scalar_type_of_t< Arg > &s, const Indices &indices)
 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 Ix , std::enable_if_t< indexible< Arg > and values::index< Ix > and writable_by_component< Arg, const std::initializer_list< Ix > &>, int > = 0>
Arg && set_component (Arg &&arg, const scalar_type_of_t< Arg > &s, const std::initializer_list< Ix > &indices)
 Set a component of an object at an initializer list of indices.
 
template<typename Arg , typename... I, std::enable_if_t<(values::index< I > and ...) and writable_by_component< Arg, std::array< std::size_t, sizeof...(I)>> and(index_count< Arg >::value==dynamic_size or sizeof...(I) > = index_count<Arg>::value>
Arg && set_component (Arg &&arg, const scalar_type_of_t< Arg > &s, 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 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 , Layout layout = Layout::none, typename Scalar = scalar_type_of_t<T>, typename Arg , std::enable_if_t< indexible< T > and(layout !=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<Layout layout, typename Scalar , typename Arg , std::enable_if_t< values::number< Scalar > and indexible< Arg > and(layout !=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<Layout layout = Layout::none, typename Arg , std::enable_if_t< indexible< Arg > and(layout !=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 LibraryObject , typename Arg , std::enable_if_t< indexible< LibraryObject > and indexible< Arg >, int > = 0>
decltype(auto) to_native_matrix (Arg &&arg)
 If it isn't already, convert Arg to a native object in the library associated with LibraryObject. More...
 
template<typename Arg >
decltype(auto) constexpr trace (Arg &&arg)
 Take the trace of a matrix. More...
 
template<typename Arg >
decltype(auto) constexpr transpose (Arg &&arg)
 Take the transpose of a matrix. 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 , TriangleType triangle_type, typename ... Args, std::enable_if_t< fixed_pattern< StaticDescriptor > and(values::number< Args > and ...) and(triangle_type==TriangleType::lower or triangle_type==TriangleType::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 , TriangleType triangle_type = TriangleType::lower, typename ... Args, std::enable_if_t< fixed_pattern< StaticDescriptor > and(values::number< Args > and ...) and(triangle_type==TriangleType::lower or triangle_type==TriangleType::upper) and(sizeof...(Args) > 0>
auto make_square_root_covariance (const Args ... args)
 
template<TriangleType triangle_type = TriangleType::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 T , std::enable_if_t< indexible< T > and interface::get_vector_space_descriptor_defined_for< T >, int > = 0>
decltype(auto) constexpr all_vector_space_descriptors (const T &t)
 Return a collection of coordinates::pattern objects associated with T. More...
 
template<typename T , std::enable_if_t< indexible< T > and(index_count< T >::value !=dynamic_size) and(not has_dynamic_dimensions< T >), int > = 0>
constexpr auto all_vector_space_descriptors ()
 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< interface::count_indices_defined_for< T >, int > = 0>
constexpr auto count_indices (const T &t)
 Get the number of indices available to address the components of an indexible object. More...
 
template<typename T , typename N = std::integral_constant<std::size_t, 0>, std::enable_if_t< coordinates::pattern< decltype(get_vector_space_descriptor(std::declval< T >(), std::declval< N >()))>, int > = 0>
constexpr auto get_index_dimension_of (const T &t, N n=N{})
 Get the runtime dimensions of index N of indexible T.
 
template<std::size_t N, typename T , std::enable_if_t< coordinates::pattern< decltype(get_vector_space_descriptor< N >(std::declval< T >()))>, int > = 0>
constexpr auto get_index_dimension_of (const 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 N , std::enable_if_t< values::index< N > and(interface::get_vector_space_descriptor_defined_for< T > or detail::count_is_zero< T >::value), int > = 0>
constexpr auto get_vector_space_descriptor (const T &t, const N &n)
 Get the coordinates::pattern object for index N of indexible object T.
 
template<std::size_t N = 0, typename T , std::enable_if_t<(interface::get_vector_space_descriptor_defined_for< T > or detail::count_is_zero< T >::value), int > = 0>
constexpr auto get_vector_space_descriptor (const T &t)
 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< 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< interface::count_indices_defined_for< T >, int > = 0>
constexpr bool is_one_dimensional (const T &t)
 Return true if T is a one_dimensional at runtime. More...
 
template<typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0>
constexpr auto is_square_shaped (const T &t)
 Determine whether an object is square_shaped at runtime. More...
 
template<std::size_t N = 0, typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0>
constexpr bool is_vector (const T &t)
 Return true if T is a vector at runtime. More...
 
template<typename T , std::enable_if_t< interface::count_indices_defined_for< T > and interface::get_vector_space_descriptor_defined_for< 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... Ts, std::enable_if_t<(interface::count_indices_defined_for< Ts > and ...), int > = 0>
constexpr bool vector_space_descriptors_match (const Ts &...ts)
 Return true if every set of coordinates::pattern of a set of objects match. 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 >>
 

Variables

template<typename I >
constexpr bool indirectly_readable = detail::is_indirectly_readable<remove_cvref_t<I>>::value
 
template<typename Out , typename T >
constexpr bool indirectly_writable = detail::is_indirectly_readable<Out, T>::value
 
template<typename I >
constexpr bool weakly_incrementable = detail::is_weakly_incrementable<I>::value
 
template<typename I >
constexpr bool input_or_output_iterator = detail::is_input_or_output_iterator<I>::value and weakly_incrementable<I>
 
template<typename I >
constexpr bool input_iterator
 
template<typename I , typename T >
constexpr bool output_iterator
 
template<typename I >
constexpr bool incrementable
 
template<typename I >
constexpr bool forward_iterator
 
template<typename I >
constexpr bool bidirectional_iterator
 
template<typename I >
constexpr bool random_access_iterator
 
template<typename S , typename I >
constexpr bool sentinel_for
 
template<typename S , typename I >
constexpr bool sized_sentinel_for
 
constexpr unreachable_sentinel_t unreachable_sentinel {}
 
template<typename T >
constexpr bool is_bounded_array_v = is_bounded_array<T>::value
 
template<typename T , typename... Args>
constexpr bool destructible = std::is_nothrow_destructible_v<T>
 
template<typename T , typename... Args>
constexpr bool constructible_from = destructible<T> and std::is_constructible_v<T, Args...>
 
template<typename From , typename To >
constexpr bool convertible_to = std::is_convertible_v<From, To> and detail::convertible_to_impl<From, To>::value
 
template<typename T >
constexpr bool move_constructible = constructible_from<T, T> and convertible_to<T, T>
 
template<typename T >
constexpr bool copy_constructible
 
template<typename T >
constexpr bool movable
 
template<typename T >
constexpr bool copyable
 
template<typename T >
constexpr bool semiregular = copyable<T> and std::is_default_constructible_v<T>
 
constexpr std::size_t dynamic_size = std::numeric_limits<std::size_t>::max()
 A constant indicating that a size or index is dynamic. More...
 
constexpr std::ptrdiff_t dynamic_difference = std::numeric_limits<std::ptrdiff_t>::max()
 A constant indicating that a difference in sizes or indices is dynamic. More...
 
template<typename T >
constexpr bool constant_adapter = detail::is_constant_adapter<std::decay_t<T>>::value
 Specifies that T is a ConstantAdapter.
 
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 >
constexpr bool compatible_with_vector_space_descriptor_collection
 indexible T is compatible with pattern_collection D. More...
 
template<typename T >
constexpr bool constant_diagonal_matrix
 Specifies that all diagonal elements of a diagonal object are the same constant value. More...
 
template<typename T >
constexpr bool constant_matrix
 Specifies that all components of an object are the same constant value. More...
 
template<typename T , std::size_t N = 0>
constexpr bool diagonal_adapter = internal::is_explicitly_triangular<T, TriangleType::diagonal>::value and detail::nested_is_vector<T, N>::value
 Specifies that a type is a diagonal matrix adapter. 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, 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 >
constexpr bool directly_accessible
 The underlying raw data for T is directly accessible. 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 , std::size_t N>
constexpr bool element_gettable
 Specifies that a type has components addressable by N indices. More...
 
template<typename T , Applicability b = Applicability::guaranteed>
constexpr bool empty_object
 Specifies that an object is empty (i.e., at least one index is zero-dimensional). More...
 
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
 Specifies that a type is a hermitian matrix adapter of a particular type. More...
 
template<typename T , Applicability b = Applicability::guaranteed>
constexpr bool hermitian_matrix
 Specifies that a type is a hermitian matrix (assuming it is square_shaped). More...
 
template<typename T >
constexpr bool identity_matrix
 Specifies that a type is an identity matrix. More...
 
template<typename Indices , typename T >
constexpr bool index_range_for
 Indices is a std::ranges::sized_range of indices that are compatible with indexible object T. More...
 
template<typename T >
constexpr bool indexible
 T is a generalized tensor 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 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 triangle_type. More...
 
template<typename T , TriangleType t = TriangleType::any>
constexpr bool triangular_matrix = internal::is_explicitly_triangular<T, t>::value or constant_diagonal_matrix<T>
 Specifies that a type is a triangular matrix (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... Ts>
constexpr bool vector_space_descriptors_match_with
 Specifies that a set of indexible objects have equivalent vector space descriptors for each index. More...
 
template<typename... Ts>
constexpr bool vector_space_descriptors_may_match_with
 Specifies that indexible objects Ts may have equivalent dimensions and vector-space types. 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 >
constexpr bool writable
 
template<typename T , typename Indices = std::conditional_t<index_count_v<T> == dynamic_size, std::vector<std::size_t>, std::array<std::size_t, index_count_v<T>>>>
constexpr bool writable_by_component
 Specifies that a type has components that can be set with Indices (an std::ranges::input_range) of type std::size_t. More...
 
template<typename T >
constexpr bool zero = detail::is_zero<T>::value
 Specifies that a type is known at compile time to be a constant matrix of value zero.
 
template<typename T , typename C >
constexpr bool equivalent_to_uniform_static_vector_space_descriptor_component_of = detail::equivalent_to_uniform_static_vector_space_descriptor_component_of_impl<T, C>::value
 T is equivalent to the uniform dimension type of C. More...
 
template<typename T , typename... Ts>
constexpr auto hermitian_adapter_type_of_v = hermitian_adapter_type_of<T, Ts...>::value
 The TriangleType associated with the storage triangle of a hermitian_matrix. More...
 
template<typename T , typename... Ts>
constexpr auto triangle_type_of_v = triangle_type_of<T, Ts...>::value
 The TriangleType associated with a triangular_matrix.
 
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
 

Detailed Description

The root namespace for OpenKalman.

The namespace for all OpenKalman-specific classes and methods.

Typedef Documentation

◆ dense_writable_matrix_t

template<typename T , Layout layout = 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 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.

Template Parameters
TA matrix or array from the relevant matrix library.
SA scalar type (may or may not be scalar_type_of_t<T>.
layoutThe /ref Layout of the result.
DA pattern_collection defining the new object. This will be derived from T if omitted.

◆ nested_object_of_t

template<typename T >
using OpenKalman::nested_object_of_t = typedef typename nested_object_of<T>::type

Helper type for nested_object_of.

Template Parameters
TA wrapper type that has a nested matrix.
iIndex of the dependency (0 by default)

◆ ZeroAdapter

template<typename PatternObject , typename Scalar = scalar_type_of_t<PatternObject>>
using OpenKalman::ZeroAdapter = typedef ConstantAdapter<PatternObject, Scalar, 0>

A ConstantAdapter in which all elements are 0.

Template Parameters
PatternObjectAn indexible object, in some library, defining the shape of the resulting zero object

Enumeration Type Documentation

◆ Applicability

enum OpenKalman::Applicability : int
strong

The applicability of a concept, trait, or restraint.

Determines whether something is necessarily applicable, or alternatively just permissible, at compile time. Examples:

Enumerator
guaranteed 

The concept, trait, or restraint represents a compile-time guarantee.

permitted 

The concept, trait, or restraint is permitted, but whether it applies is not necessarily known at compile time.

◆ HermitianAdapterType

The type of a hermitian adapter, indicating which triangle of the nested matrix is used.

This type can be statically cast from TriangleType so that lower, upper, and any correspond to each other. The value none corresponds to TriangleType::diagonal.

Enumerator
any 

Either lower or upper hermitian adapter.

lower 

A lower-left hermitian adapter.

upper 

An upper-right hermitian adapter.

◆ Layout

enum OpenKalman::Layout : int
strong

The layout format of a multidimensional array.

Enumerator
none 

No storage layout (e.g., if the elements are calculated rather than stored).

right 

Row-major storage (C or C++ style): contiguous storage in which the right-most index has a stride of 1.

left 

Column-major storage (Fortran, Matlab, or Eigen style): contiguous storage in which the left-most extent has a stride of 1.

stride 

A generalization of the above: a custom stride is specified for each index.

◆ TriangleType

enum OpenKalman::TriangleType : int
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.

Enumerator
diagonal 

A diagonal matrix (both a lower-left and an upper-right triangular matrix).

lower 

A lower-left triangular matrix.

upper 

An upper-right triangular matrix.

any 

Lower, upper, or diagonal matrix.

Function Documentation

◆ adjoint()

template<typename Arg >
decltype(auto) constexpr OpenKalman::adjoint ( Arg &&  arg)

Take the adjoint of a matrix.

Template Parameters
ArgThe matrix

◆ all_vector_space_descriptors() [1/2]

template<typename T , std::enable_if_t< indexible< T > and interface::get_vector_space_descriptor_defined_for< T >, int > = 0>
decltype(auto) constexpr OpenKalman::all_vector_space_descriptors ( const T &  t)

Return a collection of coordinates::pattern objects associated with T.

This will be a pattern_collection in the form of a std::tuple or a std::vector.

◆ all_vector_space_descriptors() [2/2]

template<typename T , std::enable_if_t< indexible< T > and(index_count< T >::value !=dynamic_size) and(not has_dynamic_dimensions< T >), int > = 0>
constexpr auto OpenKalman::all_vector_space_descriptors ( )

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Return a collection of fixed_pattern objects associated with T.

This overload is only enabled if all vector space descriptors are static.

◆ assign()

template<typename To , typename From , std::enable_if_t< indexible< To > and vector_space_descriptors_may_match_with< From, To >, int > = 0>
constexpr To&& OpenKalman::assign ( To &&  a,
From &&  b 
)

Assign a writable object from an indexible object.

Template Parameters
ToThe writable object to be assigned.
FromThe indexible object from which to assign.
Returns
the assigned object as modified

◆ average_reduce() [1/2]

template<std::size_t index, std::size_t... indices, typename Arg , std::enable_if_t< internal::has_uniform_static_vector_space_descriptors< Arg, index, indices... > and(not empty_object< Arg >), int > = 0>
decltype(auto) constexpr OpenKalman::average_reduce ( Arg &&  arg)

Perform a partial reduction by taking the average along one or more indices.

Template Parameters
indexan 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.
indicesOther indices to be reduced. Because the binary function is associative, the order of the indices does not matter.
Returns
A vector or tensor with reduced dimensions.

◆ average_reduce() [2/2]

template<typename Arg , std::enable_if_t< internal::has_uniform_static_vector_space_descriptors< Arg >, int > = 0>
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.

Returns
A scalar representing the average of all components.

◆ broadcast()

template<typename Arg , typename... Factors, std::enable_if_t< indexible< Arg > and(... and values::index< Factors >), int > = 0>
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.

Template Parameters
ArgThe object.
FactorsA 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).

◆ chipwise_operation() [1/2]

template<std::size_t... indices, typename Operation , typename... Args, std::enable_if_t<(indexible< Args > and ...) and(sizeof...(Args) > 0>
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.

Template Parameters
indicesThe 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.
OperationAn 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).
ArgsThe arguments, which must be the same size.
Returns
An object of the same size as the highest-order argument. For example, a chipwise operation between a 3×4 matrix and either a 3×1 row or 1×4 column vector is a 3×4 matrix. (The vector is replicated vertically or horizontally, respectively, to fill the size of the matrix.)

◆ chipwise_operation() [2/2]

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 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.

Template Parameters
OperationA nullary operation. The operation may optionally take, as arguments, sizeof...(indices) indices (in the same order as indices).
IsNumber of dimensions corresponding to each of indices....

◆ cholesky_factor() [1/2]

template<TriangleType triangle_type, typename A , std::enable_if_t< hermitian_matrix< A, Applicability::permitted > and(triangle_type !=TriangleType::diagonal or diagonal_matrix< A >), int > = 0>
decltype(auto) constexpr OpenKalman::cholesky_factor ( A &&  a)

Take the Cholesky factor of a matrix.

Template Parameters
AA hermitian matrix.
triangle_typeEither TriangleType::upper, TriangleType::lower, or TriangleType::diagonal (only if A is a diagonal_matrix).
Returns
T, where the argument is in the form A = TTT.

◆ cholesky_factor() [2/2]

template<typename A , std::enable_if_t< hermitian_matrix< A, Applicability::permitted >, int > = 0>
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 TriangleType, which is either

TriangleType::diagonal if A is diagonal;

the hermitian adapter triangle type of A, if it exists; or

TriangleType::lower, by default.

◆ cholesky_square()

template<typename A , std::enable_if_t< triangular_matrix< A > and square_shaped< A, Applicability::permitted >, int > = 0>
decltype(auto) constexpr OpenKalman::cholesky_square ( A &&  a)

Take the Cholesky square of a triangular_matrix.

Template Parameters
AA square matrix.
Returns
AA* (if A is lower triangular_matrix) or otherwise A*A.

◆ concatenate()

template<std::size_t... indices, typename Arg , typename... Args, std::enable_if_t<(sizeof...(indices) > 0>
decltype(auto) constexpr OpenKalman::concatenate ( Arg &&  arg,
Args &&...  args 
)

Concatenate some number of objects along one or more indices.

Template Parameters
indicesThe indices along which the concatenation occurs. For example,
  • if indices is {0}, concatenation is along row index 0, and is a vertical concatenation;
  • if indices is {1}, concatenation is along column index 1, and is a horizontal concatenation; and
  • if indices is {0, 1} or {1, 0}, concatenation is diagonal along both row and column directions.
ArgFirst object to be concatenated
ArgsOther objects to be concatenated
Returns
The concatenated object
Todo:
Deal with case where there are a dynamic number of indices

◆ conjugate()

template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0>
decltype(auto) constexpr OpenKalman::conjugate ( Arg &&  arg)

Take the conjugate of a matrix.

Template Parameters
ArgThe matrix

◆ contract_in_place()

template<bool on_the_right = true, typename A , typename B >
constexpr A&& OpenKalman::contract_in_place ( A &&  a,
B &&  b 
)

In-place matrix multiplication of A * B, storing the result in A.

Template Parameters
on_the_rightWhether the application is on the right (true) or on the left (false)
Returns
Either A * B (if on_the_right == true) or B * A (if on_the_right == false)

◆ count_indices()

template<typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0>
constexpr auto OpenKalman::count_indices ( const T &  t)

Get the number of indices available to address the components of an indexible object.

See also
index_count

◆ Covariance()

template<typename M , std::enable_if_t< covariance_nestable< M >, int > = 0>
OpenKalman::Covariance ( M &&  ) -> Covariance< Dimensions< index_dimension_of_v< M, 0 >>, passable_t< M >>
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.

◆ determinant()

template<typename Arg >
constexpr auto OpenKalman::determinant ( Arg &&  arg)

Take the determinant of a matrix.

Template Parameters
ArgA square matrix

◆ diagonal_of()

template<typename Arg >
decltype(auto) constexpr OpenKalman::diagonal_of ( Arg &&  arg)

Extract a column vector (or column slice for rank>2 tensors) comprising the diagonal elements.

Template Parameters
ArgAn indexible object, which can have any rank and may or may not be square
Returns
Arg A column vector whose coordinates::pattern corresponds to the smallest-dimension index.

◆ EuclideanMean()

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>
OpenKalman::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 &&>())))>>
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.

◆ fill_components()

template<Layout layout = Layout::right, typename Arg , typename... S, std::enable_if_t< indexible< Arg > and(values::number< S > and ...) and(layout==Layout::right or layout==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&& OpenKalman::fill_components ( Arg &&  arg,
S...  s 
)
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::left: column-major;
  • Layout::right: row-major (the default).
    Template Parameters
    layoutThe Layout of Args and the resulting object (Layout::right if unspecified).
    Parameters
    argThe object to be modified.
    sScalar values to fill the new matrix.

◆ from_euclidean()

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 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.

Template Parameters
ArgA matrix or tensor.
VThe new coordinate_list of index 0.

◆ get_chip()

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 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.

Template Parameters
indicesThe 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.
Parameters
ixsThe 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.
Returns
A sub-array of the argument

◆ get_component() [1/3]

template<typename Arg , typename Indices , std::enable_if_t< index_range_for< Indices, Arg > and(not empty_object< Arg >), int > = 0>
decltype(auto) constexpr OpenKalman::get_component ( Arg &&  arg,
const Indices &  indices 
)

Get a component of an object at a particular set of indices.

Template Parameters
ArgThe object to be accessed.
IndicesA sized input range containing the indices.
Returns
a values::scalar

◆ get_component() [2/3]

template<typename Arg , typename Ix , std::enable_if_t< values::index< Ix > and(not empty_object< Arg >), int > = 0>
decltype(auto) constexpr OpenKalman::get_component ( Arg &&  arg,
const std::initializer_list< Ix > &  indices 
)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Get a component of an object at an initializer list of indices.

◆ get_component() [3/3]

template<typename Arg , typename... I, std::enable_if_t< indexible< Arg > and(... and values::index< I >) and(index_count< Arg >::value==dynamic_size or sizeof...(I) > = index_count<Arg>::value>
decltype(auto) constexpr OpenKalman::get_component ( 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.

Get a component of an object using a fixed number of indices.

The number of indices must be at least index_count_v<Arg>. If the indices are integral constants, the function performs compile-time bounds checking to the extent possible.

◆ get_slice()

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_static_vector_space_descriptors< Arg, indices... > and(sizeof...(indices)==0 or sizeof...(indices)==sizeof...(Offset)), int > = 0>
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.

Template Parameters
indicesThe 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.
Parameters
argThe indexible object from which a slice is to be taken.
offsetsA 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.
extentsA 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.

◆ get_vector_space_descriptor()

template<std::size_t N = 0, typename T , std::enable_if_t<(interface::get_vector_space_descriptor_defined_for< T > or detail::count_is_zero< T >::value), int > = 0>
constexpr auto OpenKalman::get_vector_space_descriptor ( const 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 Parameters
NAn index value known at compile time.

◆ get_wrappable()

template<typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0>
constexpr bool OpenKalman::get_wrappable ( const T &  t)

Determine whether T is wrappable (i.e., all its dimensions other than potentially 0 are euclidean).

Template Parameters
TA matrix or array
Todo:
Is this necessary?
See also
wrappable

◆ inverse_scale()

template<typename M , typename S , std::enable_if_t< covariance< M > and std::is_convertible_v< S, typename scalar_type_of< M >::type >, int > = 0>
auto OpenKalman::inverse_scale ( M &&  m,
const S  s 
)
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.

◆ is_one_dimensional()

template<typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0>
constexpr bool OpenKalman::is_one_dimensional ( const T &  t)

Return true if T is a one_dimensional at runtime.

Each index also must have an equivalent coordinates::pattern object.

Template Parameters
TA tensor or matrix

◆ is_square_shaped()

template<typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0>
constexpr auto OpenKalman::is_square_shaped ( const T &  t)

Determine whether an object is square_shaped at runtime.

An object is square-shaped if it has the same size and coordinates::pattern type along every index (excluding trailing 1D indices).

Template Parameters
TA tensor or matrix
Returns
a std::optional which includes the coordinates::pattern object if T is square. The result is convertible to bool: if true, then T is square.
See also
square_shaped

◆ is_vector()

template<std::size_t N = 0, typename T , std::enable_if_t< interface::count_indices_defined_for< T >, int > = 0>
constexpr bool OpenKalman::is_vector ( const T &  t)

Return true if T is a vector at runtime.

In this context, a vector is an object in which every index but one is 1D.

Template Parameters
NAn index designating the "large" index (e.g., 0 for a column vector, 1 for a row vector)
TA tensor or matrix
See also
vector

◆ LQ_decomposition()

template<typename A , std::enable_if_t< indexible< A > and(not euclidean_transformed< A >), int > = 0>
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.

Template Parameters
AThe matrix to be decomposed satisfying triangular_matrix<A, TriangleType::lower>
Returns
L as a lower triangular_matrix which is also square_shaped

◆ make_constant() [1/9]

template<typename T , typename C , typename Ds , std::enable_if_t< indexible< T > and values::scalar< C > and pattern_collection< Ds >, int > = 0>
constexpr auto OpenKalman::make_constant ( C &&  c,
Descriptors &&  descriptors 
)

Make a constant object based on a particular library object.

A constant object is a matrix or tensor in which every component is the same scalar value.

Template Parameters
TAn object (matrix or tensor) from a particular library. Its shape and contents are irrelevant.
CA values::scalar
DescriptorsA pattern_collection defining the dimensions of each index.

◆ make_constant() [2/9]

template<typename T , typename C , typename... Ds, std::enable_if_t< indexible< T > and values::scalar< C > and(coordinates::pattern< Ds > and ...), int > = 0>
constexpr auto OpenKalman::make_constant ( C &&  c,
Ds &&...  ds 
)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

vector_space_descriptors are specified as arguments.

◆ make_constant() [3/9]

template<typename T , typename C , std::enable_if_t< indexible< T > and values::scalar< C >, int > = 0>
constexpr auto OpenKalman::make_constant ( const T &  t,
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 new constant object based on a library object.

Template Parameters
TThe object on which the new matrix is patterned. This need not itself be constant, as only its dimensions are used.
CA values::scalar.

◆ make_constant() [4/9]

template<typename T , typename C , auto... constant, typename Ds , std::enable_if_t< indexible< T > and values::scalar< C > and pattern_collection< Ds > and((values::fixed< C > and sizeof...(constant)==0) or std::is_constructible< C, decltype(constant)... >::value), int > = 0>
constexpr auto OpenKalman::make_constant ( Ds &&  ds)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Make a compile-time constant based on a particular library object and a scalar constant value known at compile time

Template Parameters
TA matrix or tensor from a particular library.
CA values::scalar for the new zero matrix. Must be constructible from {constant...}
constantA constant or set of coefficients in a vector space defining a constant (e.g., real and imaginary parts of a complex number).
Parameters
DsA pattern_collection defining the dimensions of each index.

◆ make_constant() [5/9]

template<typename T , auto constant, typename Ds , std::enable_if_t< indexible< T > and values::number< decltype(constant)> and pattern_collection< Ds >, int > = 0>
constexpr auto OpenKalman::make_constant ( Ds &&  ds)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Same as above, except that the scalar type is derived from the constant template parameter

Template Parameters
constantThe constant

◆ make_constant() [6/9]

template<typename T , typename C , auto... constant, typename... Ds, std::enable_if_t< indexible< T > and values::scalar< C > and(coordinates::pattern< Ds > and ...) and((values::fixed< C > and sizeof...(constant)==0) or std::is_constructible< C, decltype(constant)... >::value), int > = 0>
constexpr auto OpenKalman::make_constant ( Ds &&...  ds)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Make a compile-time constant based on a particular library object and a scalar constant value known at compile time

Template Parameters
TA matrix or tensor from a particular library.
CA values::scalar for the new zero matrix. Must be constructible from {constant...}
constantA constant or set of coefficients in a vector space defining a constant (e.g., real and imaginary parts of a complex number).
Parameters
DsA set of coordinates::pattern defining the dimensions of each index.

◆ make_constant() [7/9]

template<typename T , auto constant, typename... Ds, std::enable_if_t< indexible< T > and values::number< decltype(constant)> and(coordinates::pattern< Ds > and ...), int > = 0>
constexpr auto OpenKalman::make_constant ( Ds &&...  ds)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Same as above, except that the scalar type is derived from the constant template parameter

Template Parameters
constantThe constant

◆ make_constant() [8/9]

template<typename C , auto... constant, typename T , std::enable_if_t< values::scalar< C > and indexible< T > and((values::fixed< C > and sizeof...(constant)==0) or std::is_constructible< C, decltype(constant)... >::value), int > = 0>
constexpr auto OpenKalman::make_constant ( const T &  t)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Construct a constant object, where the shape of the new object is derived from t.

◆ make_constant() [9/9]

template<auto constant, typename T , std::enable_if_t< values::number< decltype(constant)> and indexible< T >, int > = 0>
constexpr auto OpenKalman::make_constant ( const T &  t)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Same as above, except that the scalar type is derived from the constant template parameter

◆ make_covariance() [1/6]

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 OpenKalman::make_covariance ( Arg &&  arg)
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
ArgA covariance_nestable with size matching StaticDescriptor.

Make a Covariance from a self-adjoint typed_matrix_nestable, specifying the coefficients.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
ArgA square typed_matrix_nestable with size matching StaticDescriptor.

Make a default Axis Covariance (with nested triangular matrix) from a self-adjoint typed_matrix_nestable.

Template Parameters
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgA square, self-adjoint typed_matrix_nestable.

Make a Covariance, with a nested triangular matrix, from a typed_matrix.

◆ make_covariance() [2/6]

template<typename StaticDescriptor , TriangleType triangle_type, 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(triangle_type !=TriangleType::lower or triangular_matrix< Arg, TriangleType::lower >) and(triangle_type !=TriangleType::upper or triangular_matrix< Arg, TriangleType::upper >) and(triangle_type !=TriangleType::diagonal or diagonal_matrix< Arg >), int > = 0>
auto OpenKalman::make_covariance ( Arg &&  arg)
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
TriangleTypeThe type of the nested triangular matrix (upper, lower, diagonal).
ArgA covariance_nestable with size matching StaticDescriptor.

Make a Covariance (with nested triangular matrix) from a self-adjoint typed_matrix_nestable.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgA square, self-adjoint typed_matrix_nestable with size matching StaticDescriptor.

◆ make_covariance() [3/6]

template<typename Arg , std::enable_if_t< covariance_nestable< Arg >, int > = 0>
auto OpenKalman::make_covariance ( Arg &&  arg)
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
ArgA covariance_nestable.

Make a Covariance from a self-adjoint typed_matrix_nestable, using default Axis coefficients.

Template Parameters
ArgA square typed_matrix_nestable.

Make a Covariance based on another non-square-root covariance.

Make a Covariance from a typed_matrix.

◆ make_covariance() [4/6]

template<typename StaticDescriptor , typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0>
auto OpenKalman::make_covariance ( )
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgsA 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>.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
ArgsA 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>.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgsA list of numerical coefficients (either integral or floating-point). The number of coefficients must be the square of an integer.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
ArgsA list of numerical coefficients (either integral or floating-point). The number of coefficients must be the square of an integer.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ScalarThe scalar type (integral or floating-point).
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
ScalarThe scalar type (integral or floating-point).

◆ make_covariance() [5/6]

template<typename StaticDescriptor , TriangleType triangle_type, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< Arg > and square_shaped< Arg >, int > = 0>
auto OpenKalman::make_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 writable, uninitialized Covariance with a nested triangular matrix, from a typed_matrix_nestable.

◆ make_covariance() [6/6]

template<typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0>
auto OpenKalman::make_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 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.

◆ make_dense_object() [1/2]

template<typename T , Layout layout = 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 !=Layout::stride) and interface::make_default_defined_for< T, layout, Scalar, decltype(internal::to_euclidean_vector_space_descriptor_collection(std::declval< Descriptors &&>()))>, int > = 0>
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.

Template Parameters
TA dummy matrix or array from the relevant library (size, shape, and layout are ignored)
layoutThe Layout of the resulting object. If this is Layout::none, it will be the default layout for the library of T.
ScalarThe scalar type of the resulting object (by default, it is the same scalar type as T).
Parameters
da tuple of coordinates::pattern describing dimensions of each index. Trailing 1D indices my be omitted.

◆ make_dense_object() [2/2]

template<typename T , Layout layout = 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 !=Layout::stride) and interface::make_default_defined_for< T, layout, Scalar, std::tuple< Ds &&... >>, int > = 0>
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.

◆ make_dense_object_from() [1/2]

template<typename T , Layout layout = Layout::none, typename Scalar = scalar_type_of_t<T>, typename... Ds, typename... Args, std::enable_if_t< indexible< T > and values::number< Scalar > and(coordinates::pattern< Ds > and ...) and(std::is_convertible_v< Args, const Scalar > and ...) and(layout !=Layout::stride) 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 OpenKalman::make_dense_object_from ( const std::tuple< Ds... > &  d_tup,
Args...  args 
)
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:

  • Layout::left: column-major;
  • Layout::right: row-major;
  • Layout::none (the default): although the elements are listed in row-major order, the layout of the resulting object is unspecified.
    Template Parameters
    TAny dummy type from the relevant library. Its characteristics are ignored.
    layoutThe Layout of Args and the resulting object (Layout::none if unspecified).
    ScalarAn scalar type for the new matrix. By default, it is the same as T.
    Dscoordinates::pattern objects describing the size of the resulting object.
    Parameters
    d_tupA tuple of coordinates::pattern Ds
    argsScalar values to fill the new matrix.

◆ make_dense_object_from() [2/2]

template<typename T , Layout layout = Layout::none, typename Scalar = scalar_type_of_t<T>, typename ... Args>
auto OpenKalman::make_dense_object_from ( Args...  args)
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.

Template Parameters
TThe matrix or array on which the new matrix is patterned.
layoutThe Layout of Args and the resulting object (Layout::none if unspecified, which means that the values are in Layout::right order but layout of the resulting object is unspecified).
ScalarAn scalar type for the new matrix. By default, it is the same as T.
Parameters
argsScalar values to fill the new matrix.

◆ make_diagonal_adapter() [1/2]

template<typename Arg , typename D0 , typename D1 >
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.

Template Parameters
ArgA vector or higher-order tensor reflecting the diagonal(s).
D0The coordinates::pattern for the rows.
D1The coordinates::pattern for the columns.

◆ make_diagonal_adapter() [2/2]

template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0>
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.

Template Parameters
ArgA vector or higher-order tensor reflecting the diagonal(s).

◆ make_euclidean_mean() [1/7]

template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0>
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
ArgsA list of numerical coefficients (either integral or floating-point).

◆ make_euclidean_mean() [2/7]

template<typename Scalar , typename StaticDescriptor , std::size_t cols = 1, std::enable_if_t< values::number< Scalar > and fixed_pattern< StaticDescriptor >, int > = 0>
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
ScalarA scalar type (integral or floating-point).
StaticDescriptorThe coefficient types corresponding to the rows.
colsThe number of columns.

◆ make_euclidean_mean() [3/7]

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 OpenKalman::make_euclidean_mean ( M &&  arg)

Make a EuclideanMean from a typed_matrix_nestable, specifying the row coefficients.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows.
MA typed_matrix_nestable with size matching ColumnCoefficients.

◆ make_euclidean_mean() [4/7]

template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0>
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.

◆ make_euclidean_mean() [5/7]

template<typename Arg , std::enable_if_t< typed_matrix< Arg > and has_untyped_index< Arg, 1 >, int > = 0>
auto OpenKalman::make_euclidean_mean ( Arg &&  arg)
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.

Template Parameters
ArgA typed_matrix (i.e., Matrix, Mean, or EuclideanMean).

◆ make_euclidean_mean() [6/7]

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>
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows.
Ma 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.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows.
ArgsA list of numerical coefficients (either integral or floating-point). The number of coefficients must be divisible by coordinates::stat_dimension_of_v<StaticDescriptor>.

◆ make_euclidean_mean() [7/7]

template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0>
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.

Template Parameters
Ma 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.

◆ make_GaussianDistribution() [1/6]

template<typename D , std::enable_if_t< gaussian_distribution< D >, int > = 0>
auto OpenKalman::make_GaussianDistribution ( D &&  dist)
inline

Make a Gaussian distribution.

Template Parameters
DAnother gaussian_distribution.
Returns
A gaussian_distribution.

◆ make_GaussianDistribution() [2/6]

template<typename re = std::mt19937, typename M , typename Cov >
auto OpenKalman::make_GaussianDistribution ( M &&  mean,
Cov &&  cov 
)
inline

Make a Gaussian distribution.

Template Parameters
reA random number engine.
MA typed_matrix.
CovA covariance or typed_matrix.
Returns
A gaussian_distribution.

◆ make_GaussianDistribution() [3/6]

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 OpenKalman::make_GaussianDistribution ( M &&  mean,
Cov &&  cov 
)
inline

Make a Gaussian distribution.

Template Parameters
reA random number engine.
MA typed_matrix.
CovA covariance_nestable or typed_matrix_nestable.
Returns
A gaussian_distribution.
Template Parameters
reA random number engine.
MA typed_matrix_nestable.
CovA covariance, typed_matrix, covariance_nestable, or typed_matrix_nestable.
Returns
A gaussian_distribution.

◆ make_GaussianDistribution() [4/6]

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 OpenKalman::make_GaussianDistribution ( M &&  mean,
Cov &&  cov 
)
inline

Make a Gaussian distribution.

Template Parameters
StaticDescriptorThe types of the fixed_pattern for the distribution.
reA random number engine.
MA typed_matrix_nestable.
CovA covariance_nestable or typed_matrix_nestable.
Returns
A gaussian_distribution.

◆ make_GaussianDistribution() [5/6]

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 OpenKalman::make_GaussianDistribution ( )
inline

Make a default Gaussian distribution.

Template Parameters
MA typed_matrix.
CovA covariance.
reA random number engine.
Returns
A gaussian_distribution.
Template Parameters
MA typed_matrix or typed_matrix_nestable.
CovA covariance or covariance_nestable.
reA random number engine.
Returns
A gaussian_distribution.
Note
This overload excludes the case in which M is typed_matrix and Cov is covariance.

◆ make_GaussianDistribution() [6/6]

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 OpenKalman::make_GaussianDistribution ( )
inline

Make a default Gaussian distribution.

Template Parameters
StaticDescriptorThe types of the fixed_pattern for the distribution.
MA typed_matrix_nestable
CovA covariance_nestable.
reA random number engine
Returns
A gaussian_distribution

◆ make_hermitian_matrix()

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 OpenKalman::make_hermitian_matrix ( Arg &&  arg)

Creates a hermitian_matrix by, if necessary, wrapping the argument in a hermitian_adapter.

Note
The result is guaranteed to be hermitian, but is not guaranteed to be an adapter or have the requested adapter_type.
Template Parameters
adapter_typeThe intended HermitianAdapterType of the result (lower op upper).
ArgA square matrix.

◆ make_identity_matrix_like() [1/4]

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 OpenKalman::make_identity_matrix_like ( Descriptors &&  descriptors)

Make an identity_matrix with a particular set of coordinates::pattern objects.

Template Parameters
TAny matrix or tensor within the relevant library.
ScalarAn optional scalar type for the new zero matrix. By default, T's scalar type is used.
Parameters
DsA set of coordinates::pattern items defining the dimensions of each index.

◆ make_identity_matrix_like() [2/4]

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 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.

◆ make_identity_matrix_like() [3/4]

template<typename Scalar , typename Arg , std::enable_if_t< values::number< Scalar > and indexible< Arg >, int > = 0>
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.

Template Parameters
ArgThe matrix or array on which the new identity matrix is patterned. It need not be square.
ScalarA scalar type for the new matrix.
Returns
An identity matrix of the same dimensions as Arg (even if not square).

◆ make_identity_matrix_like() [4/4]

template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0>
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.

Template Parameters
ArgThe matrix or array on which the new zero matrix is patterned.
Returns
An identity matrix of the same dimensions as Arg (even if not square).

◆ make_matrix() [1/2]

template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0>
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
ArgsA list of numerical coefficients (either integral or floating-point).

◆ make_matrix() [2/2]

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>
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
ScalarA scalar type (integral or floating-point).
RowCoefficientsThe coefficient types corresponding to the rows.
ColumnCoefficientsThe coefficient types corresponding to the columns.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
RowCoefficientsThe coefficient types corresponding to the rows.
ColumnCoefficientsThe coefficient types corresponding to the columns.
ArgsA 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>.

◆ make_mean() [1/7]

template<typename ... Args, std::enable_if_t<(sizeof...(Args) > 0>
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
ArgsA list of numerical coefficients (either integral or floating-point).

◆ make_mean() [2/7]

template<typename Scalar , typename StaticDescriptor , std::size_t cols = 1, std::enable_if_t< values::number< Scalar > and fixed_pattern< StaticDescriptor >, int > = 0>
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
ScalarA scalar type (integral or floating-point).
StaticDescriptorThe coefficient types corresponding to the rows.
colsThe number of columns.

◆ make_mean() [3/7]

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 OpenKalman::make_mean ( M &&  m)
inline

Make a Mean from a typed_matrix_nestable, specifying the row fixed_pattern.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows.
MA typed_matrix_nestable with size matching ColumnCoefficients.

◆ make_mean() [4/7]

template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0>
auto OpenKalman::make_mean ( M &&  m)
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.

◆ make_mean() [5/7]

template<typename Arg , std::enable_if_t< typed_matrix< Arg > and has_untyped_index< Arg, 1 >, int > = 0>
auto OpenKalman::make_mean ( Arg &&  arg)
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.

Template Parameters
ArgA typed_matrix (i.e., Matrix, Mean, or EuclideanMean).

◆ make_mean() [6/7]

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>
OpenKalman::make_mean ( )
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows.
Ma 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.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows.
ArgsA list of numerical coefficients (either integral or floating-point). The number of coefficients must be divisible by coordinates::dimension_of_v<StaticDescriptor>.

◆ make_mean() [7/7]

template<typename M , std::enable_if_t< typed_matrix_nestable< M >, int > = 0>
auto OpenKalman::make_mean ( )
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.

Template Parameters
Ma 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.

◆ make_square_root_covariance() [1/6]

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 OpenKalman::make_square_root_covariance ( Arg &&  arg)
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
ArgA covariance_nestable with size matching StaticDescriptor.

Make a default Axis SquareRootCovariance from a self-adjoint typed_matrix_nestable.

Template Parameters
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgA square, self-adjoint typed_matrix_nestable.

Make a SquareRootCovariance from a typed_matrix.

◆ make_square_root_covariance() [2/6]

template<typename Arg , std::enable_if_t< covariance_nestable< Arg >, int > = 0>
auto OpenKalman::make_square_root_covariance ( Arg &&  arg)
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
ArgA covariance_nestable.

Make a SquareRootCovariance based on another triangular_covariance.

◆ make_square_root_covariance() [3/6]

template<typename StaticDescriptor , TriangleType triangle_type = TriangleType::lower, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< Arg > and(not covariance_nestable< Arg >) and(triangle_type==TriangleType::lower or triangle_type==TriangleType::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 OpenKalman::make_square_root_covariance ( Arg &&  arg)
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.

Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgA square, self-adjoint typed_matrix_nestable with size matching StaticDescriptor.

◆ make_square_root_covariance() [4/6]

template<typename StaticDescriptor , TriangleType triangle_type, typename Arg , std::enable_if_t< fixed_pattern< StaticDescriptor > and typed_matrix_nestable< Arg > and square_shaped< Arg >, int > = 0>
auto OpenKalman::make_square_root_covariance ( )
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.

Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgsA 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>.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ArgsA list of numerical coefficients (either integral or floating-point). The number of coefficients must be the square of an integer.
Note
This function is imported into the OpenKalman namespace if Eigen3 is the first-included interface.
Template Parameters
StaticDescriptorThe coefficient types corresponding to the rows and columns.
TriangleTypeThe type of the nested triangular matrix (upper, lower).
ScalarThe scalar type (integral or floating-point).

◆ make_square_root_covariance() [5/6]

template<typename StaticDescriptor , typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0>
auto OpenKalman::make_square_root_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 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.

◆ make_square_root_covariance() [6/6]

template<typename Arg , std::enable_if_t<(covariance_nestable< Arg > or typed_matrix_nestable< Arg >) and square_shaped< Arg >, int > = 0>
auto OpenKalman::make_square_root_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 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.

◆ make_triangular_matrix()

template<TriangleType t = TriangleType::lower, typename Arg , std::enable_if_t< indexible< Arg > and(t==TriangleType::lower or t==TriangleType::upper or t==TriangleType::diagonal), int > = 0>
decltype(auto) constexpr OpenKalman::make_triangular_matrix ( Arg &&  arg)

Create a triangular_matrix from a general matrix.

Template Parameters
tThe intended TriangleType of the result.
ArgA general matrix to be made triangular.

◆ make_vector_space_adapter() [1/3]

template<typename Arg , typename Descriptors , std::enable_if_t< indexible< Arg > and pattern_collection< Descriptors > and internal::not_more_fixed_than< Arg, Descriptors > and(not internal::less_fixed_than< Arg, Descriptors >) and internal::maybe_same_shape_as_vector_space_descriptors< Arg, Descriptors >, int > = 0>
auto OpenKalman::make_vector_space_adapter ( Arg &&  arg,
Descriptors &&  descriptors 
)
inline

If necessary, wrap an object in a wrapper that adds vector space descriptors for each index.

Any vector space descriptors in the argument are overwritten.

Template Parameters
ArgAn indexible object. Ds A set of coordinates::pattern objects

◆ make_vector_space_adapter() [2/3]

template<typename Arg , typename... Ds>
auto OpenKalman::make_vector_space_adapter ( Arg &&  arg,
Ds &&...  ds 
)
inline

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.

◆ make_vector_space_adapter() [3/3]

template<typename... Ds, typename Arg , std::enable_if_t< indexible< Arg > and(... and fixed_pattern< Ds >) and(not has_dynamic_dimensions< Arg >) and(sizeof...(Ds) > 0>
auto OpenKalman::make_vector_space_adapter ( Arg &&  arg)
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Create an adapter in which all vector space descriptors are static.

◆ make_zero() [1/4]

template<typename T , typename Scalar = scalar_type_of_t<T>, typename... Ds, std::enable_if_t< indexible< T > and values::number< Scalar > and pattern_collection< Descriptors >, int > = 0>
constexpr auto OpenKalman::make_zero ( Descriptors &&  descriptors)

Make a zero associated with a particular library.

Template Parameters
TAn object (matrix or tensor) from a particular library. Its shape and contents are irrelevant.
ScalarAn optional scalar type for the new zero matrix. By default, T's scalar type is used.
Parameters
DescriptorsA pattern_collection defining the dimensions of each index. If none are provided and T has no dynamic dimensions, the function takes coordinates::pattern from T.

◆ make_zero() [2/4]

template<typename T , typename Scalar = scalar_type_of_t<T>, typename... Ds, std::enable_if_t< indexible< T > and values::number< Scalar > and(... and coordinates::pattern< Ds >), int > = 0>
constexpr auto OpenKalman::make_zero ( Ds &&...  ds)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Specify coordinates::pattern objects as arguments.

◆ make_zero() [3/4]

template<typename Scalar , typename T , std::enable_if_t< values::number< Scalar > and indexible< T >, int > = 0>
constexpr auto OpenKalman::make_zero ( const T &  t)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Make a zero based on an argument.

Template Parameters
TThe matrix or array on which the new zero matrix is patterned.
ScalarA scalar type for the new matrix.

◆ make_zero() [4/4]

template<typename T , std::enable_if_t< indexible< T >, int > = 0>
constexpr auto OpenKalman::make_zero ( const T &  t)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Make a zero matrix based on T.

The new scalar type is also derived from T.

◆ Matrix()

template<typename V , std::enable_if_t< typed_matrix< V > and not euclidean_transformed< V >, int > = 0>
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.

◆ Mean()

template<typename V , std::enable_if_t< typed_matrix_nestable< V >, int > = 0>
OpenKalman::Mean ( V &&  ) -> Mean< Dimensions< index_dimension_of_v< V, 0 >>, passable_t< V >>
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.

◆ n_ary_operation() [1/4]

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 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:

  • Unary operation, no broadcasting:
    auto ds32 = std::tuple {Dimensions<3>{}, Dimensions<2>{}};
    auto op1 = [](auto arg){return 3 * arg;};
    auto M = Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>
    auto m32 = make_dense_object_from<M>(ds32, 1, 2, 3, 4, 5, 6);
    std::cout << n_ary_operation(ds32, op1, m32) << std::endl;
    Output:
    3, 6,
    9, 12,
    15, 18
  • Unary operation, broadcasting:
    auto ds31 = std::tuple {Dimensions<3>{}, Dimensions<1>{}};
    auto m31 = make_dense_object_from<M>(ds31, 1, 2, 3);
    std::cout << n_ary_operation(ds32, op1, m31) << std::endl;
    Output:
    3, 3,
    6, 6,
    9, 9
  • Binary operation, no broadcasting:
    auto op2 = [](auto arg1, auto arg2){return 3 * arg1 + arg2;};
    std::cout << n_ary_operation(ds32, op2, m32, 2 * m32) << std::endl;
    Output:
    5, 10,
    15, 20,
    25, 30
  • Binary operation, broadcasting:
    std::cout << n_ary_operation(ds32, op2, m31, 2 * m32) << std::endl;
    Output:
    5, 7,
    12, 14,
    19, 21
  • Binary operation, broadcasting, with indices:
    auto op2b = [](auto arg1, auto arg2, std::size_t row, std::size_t col){return 3 * arg1 + arg2 + row + col;};
    std::cout << n_ary_operation(ds32, op2b, m31, 2 * m32) << std::endl;
    Output:
    5, 8,
    13, 16,
    21, 24
    Template Parameters
    Dscoordinates::pattern objects defining the size of the result.
    OperationThe 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.
    ArgsThe arguments
    Returns
    A matrix or array in which each component is the result of calling Operation on corresponding components from each of the arguments, in the order specified.

◆ n_ary_operation() [2/4]

template<typename Operation , typename... Args, std::enable_if_t<(indexible< Args > and ...) and(sizeof...(Args) > 0>
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:

  • Binary operation, broadcasting:
    auto M = Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>
    auto op2a = [](auto arg1, auto arg2){return 3 * arg1 + arg2;};
    auto m31 = make_dense_object_from<M>(ds31, 1, 2, 3);
    auto m32 = make_dense_object_from<M>(ds32, 1, 2, 3, 4, 5, 6);
    std::cout << n_ary_operation(op2a, m31, 2 * m32) << std::endl;
    Output:
    5, 7,
    12, 14,
    19, 21
  • Binary operation, broadcasting, with indices:
    auto op2b = [](auto arg1, auto arg2, std::size_t row, std::size_t col){return 3 * arg1 + arg2 + row + col;};
    std::cout << n_ary_operation(op2b, m31, 2 * m32) << std::endl;
    Output:
    5, 8,
    13, 16,
    21, 24
  • Unary operation, with indices:
    auto op1a = [](auto& arg, std::size_t row, std::size_t col){return arg + row + col;};
    std::cout << n_ary_operation(op1a, m32) << std::endl;
    Output:
    1, 3,
    4, 6,
    7, 9
    Template Parameters
    OperationThe n-ary operation taking n arguments and, optionally, a set of indices. The operation must return a scalar value.
    ArgsThe arguments
    Returns
    A matrix or array in which each component is the result of calling Operation on corresponding components from each of the arguments, in the order specified.

◆ n_ary_operation() [3/4]

template<typename PatternMatrix , std::size_t... indices, typename... Ds, typename... Operations>
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:

  • One operation for the entire matrix
    auto ds23 = std::tuple {Dimensions<2>{}, Dimensions<3>{}};
    auto M = Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>
    std::cout << n_ary_operation<M>(ds23, [](auto arg){return 7;}) << std::endl;
    Output:
    7, 7, 7,
    7, 7, 7
  • One operation for each element
    std::cout << n_ary_operation<M, 0, 1>(ds23, []{return 4;}, []{return 5;}, []{return 6;}, []{return 7;}, []{return 8;}, []{return 9;});
    Output:
    4, 5, 6,
    7, 8, 9
  • One operation for each row
    auto ds23a = std::tuple {Dimensions<2>{}, Dimensions{3}};
    std::cout << n_ary_operation<M, 0>(ds23a, []{return 5;}, []{return 6;});
    Output:
    5, 5, 5,
    6, 6, 6
  • One operation for each column
    auto ds23b = std::tuple {Dimensions{2}, Dimensions<3>{}};
    std::cout << n_ary_operation<M, 1>(ds23b, []{return 5;}, []{return 6;}, []{return 7;});
    Output:
    5, 6, 7,
    5, 6, 7
  • One operation for each column, with indices
    auto ds23b = std::tuple {Dimensions{2}, Dimensions<3>{}};
    auto op1 = [](std::size_t r, std::size_t c){ return 5 + r + c; };
    auto op2 = [](std::size_t r, std::size_t c){ return 6 + r + c; };
    auto op3 = [](std::size_t r, std::size_t c){ return 7 + r + c; };
    std::cout << n_ary_operation<M, 1>(ds23b, []{return 5;}, []{return 6;}, []{return 7;});
    Output:
    5, 7, 9,
    6, 8, 10
    Template Parameters
    PatternMatrixA 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
    indicesThe indices, if any, along which there will be a different operator for each element along that index.
    Dscoordinates::pattern objects for each index of the result. coordinates::pattern objects corresponding to indices must be of a fixed_pattern type.
    OperationsThe 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.))
    Returns
    A matrix or array in which each component is the result of calling Operation and which has dimensions corresponding to Ds

◆ n_ary_operation() [4/4]

template<typename PatternMatrix , std::size_t... indices, typename... Ds, typename... Operations, std::enable_if_t< indexible< PatternMatrix > and(coordinates::pattern< Ds > and ...) and((fixed_pattern< typename vector_space_descriptor_of< PatternMatrix, indices >::type >) and ...) and(sizeof...(Operations)==(1 *... *index_dimension_of< PatternMatrix, indices >::value)), int > = 0>
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.

  • One operation for the entire matrix
    auto M = Eigen::Matrix<double, 2, 3>
    std::cout << n_ary_operation<M>([](auto arg){return 7;}) << std::endl;
    Output:
    7, 7, 7,
    7, 7, 7
  • One operation for each element
    std::cout << n_ary_operation<M, 0, 1>([]{return 4;}, []{return 5;}, []{return 6;}, []{return 7;}, []{return 8;}, []{return 9;});
    Output:
    4, 5, 6,
    7, 8, 9
  • One operation for each row
    std::cout << n_ary_operation<M, 0>([]{return 5;}, []{return 6;});
    Output:
    5, 5, 5,
    6, 6, 6
  • One operation for each column
    std::cout << n_ary_operation<M, 1>([]{return 5;}, []{return 6;}, []{return 7;});
    Output:
    5, 6, 7,
    5, 6, 7
    Template Parameters
    PatternMatrixA 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.
    indicesThe indices, if any, along which there will be a different operator for each element along that index.
    OperationsThe nullary operations. The number of operations must equal the product of each dimension Ds corresponding to indices.
    Returns
    A matrix or array in which each component is the result of calling Operation and which has dimensions corresponding to Ds

◆ nested_object()

template<typename Arg , std::enable_if_t< has_nested_object< Arg >, int > = 0>
decltype(auto) constexpr OpenKalman::nested_object ( Arg &&  arg)

Retrieve a nested object of Arg, if it exists.

Template Parameters
iIndex of the nested matrix (0 for the 1st, 1 for the 2nd, etc.).
ArgA wrapper that has at least one nested object.

◆ QR_decomposition()

template<typename A , std::enable_if_t< indexible< A >, int > = 0>
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.

Template Parameters
AThe matrix to be decomposed
Returns
U as an upper triangular_matrix

◆ randomize() [1/6]

template<typename PatternMatrix , std::size_t... indices, typename random_number_generator , typename... Ds, typename... Dists>
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:

  • One distribution for all elements. The following example constructs a 2-by-2 matrix (m) in which each element is a random value selected based on a distribution with mean 1.0 and standard deviation 0.3:
    using N = std::normal_distribution<double>;
    using Mat = Eigen::Matrix<double, 2, 2>;
    auto g = std::mt19937 {};
    Mat m = randomize<Mat>(g, std::tuple {2, 2}, N {1.0, 0.3}));
  • One distribution for each element. The following code constructs a 2-by-2 matrix m containing random values around mean 1.0, 2.0, 3.0, and 4.0 (in row-major order), with standard deviations of 0.3, 0.3, 0.0 (by default, since no s.d. is specified as a parameter), and 0.3:
    using N = std::normal_distribution<double>;
    auto m = randomize<Eigen::Matrix<double, 2, 2>, 0, 1>(g,
    std::tuple {Dimensions<2>{}, Dimensions<2>{}}, N {1.0, 0.3}, N {2.0, 0.3}, 3.0, N {4.0, 0.3})));
  • One distribution for each row. The following code constructs a 3-by-2 (n) or 2-by-2 (o) matrices in which elements in each row are selected according to the three (n) or two (o) listed distribution parameters:
    auto n = randomize<Eigen::Matrix<double, 3, 2>, 0>(g, std::tuple {Dimensions<3>{}, 2},
    N {1.0, 0.3}, 2.0, N {3.0, 0.3})));
    auto o = randomize<Eigen::Matrix<double, 2, 2>, 0>(g, std::tuple {Dimensions<2>{}, 2},
    N {1.0, 0.3}, N {2.0, 0.3})));
  • One distribution for each column. The following code constructs 2-by-3 matrix p in which elements in each column are selected according to the three listed distribution parameters:
    auto p = randomize<Eigen::Matrix<double, 2, 3>, 1>(g, std::tuple {2, Dimensions<3>{}},
    N {1.0, 0.3}, 2.0, N {3.0, 0.3})));
    Template Parameters
    PatternMatrixAn indexible object corresponding to the result type. Its dimensions need not match the specified dimensions Ds
    indicesThe 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_generatorThe random number generator (e.g., std::mt19937).
    Dscoordinates::pattern objects for each index the result. They need not correspond to the dimensions of PatternMatrix.
    DistsOne or more distributions (e.g., std::normal_distribution<double>)
    See also
    n_ary_operation

◆ randomize() [2/6]

template<typename PatternMatrix , std::size_t... indices, typename... Ds, typename... Dists>
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.

◆ randomize() [3/6]

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 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:

  • One distribution for all matrix elements. The following example constructs a 2-by-2 matrix (m) in which each element is a random value selected based on a distribution with mean 1.0 and standard deviation 0.3:
    using N = std::normal_distribution<double>;
    using Mat = Eigen::Matrix<double, 2, 2>;
    auto g = std::mt19937 {};
    Mat m = randomize<Mat>(N {1.0, 0.3}));
  • One distribution for each matrix element. The following code constructs a 2-by-2 matrix m containing random values around mean 1.0, 2.0, 3.0, and 4.0 (in row-major order), with standard deviations of 0.3, 0.3, 0.0 (by default, since no s.d. is specified as a parameter), and 0.3:
    using N = std::normal_distribution<double>;
    auto m = randomize<Eigen::Matrix<double, 2, 2>, 0, 1>(g, N {1.0, 0.3}, N {2.0, 0.3}, 3.0, N {4.0, 0.3})));
  • One distribution for each row. The following code constructs a 3-by-2 (n) or 2-by-2 (o) matrices in which elements in each row are selected according to the three (n) or two (o) listed distribution parameters:
    auto n = randomize<Eigen::Matrix<double, 3, 2>, 0>(g, N {1.0, 0.3}, 2.0, N {3.0, 0.3})));
    auto o = randomize<Eigen::Matrix<double, 2, 2>, 0>(g, N {1.0, 0.3}, N {2.0, 0.3})));
  • One distribution for each column. The following code constructs 2-by-3 matrix p in which elements in each column are selected according to the three listed distribution parameters:
    auto p = randomize<Eigen::Matrix<double, 2, 3>, 1>(g, N {1.0, 0.3}, 2.0, N {3.0, 0.3})));
    Template Parameters
    PatternMatrixA fixed-size matrix
    random_number_generatorThe random number generator (e.g., std::mt19937).

◆ randomize() [4/6]

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 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.

◆ randomize() [5/6]

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 OpenKalman::randomize ( Dists &&...  dists)
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:

  • One distribution for the entire matrix. The following example constructs a 2-by-2 matrix (m) in which each element is a random value selected based on a distribution with mean 1.0 and standard deviation 0.3:
    using N = std::normal_distribution<double>;
    auto m = randomize<Matrix<Dimensions<2>, Dimensions<2>, Eigen::Matrix<double, 2, 2>>>(N {1.0, 0.3}));
  • One distribution for each matrix element. The following code constructs a 2-by-2 matrix n containing random values around mean 1.0, 2.0, 3.0, and 4.0 (in row-major order), with standard deviations of 0.3, 0.3, 0.0 (by default, since no s.d. is specified as a parameter), and 0.3:
    auto n = randomize<Matrix<Dimensions<2>, Dimensions<2>, Eigen::Matrix<double, 2, 2>>>(N {1.0, 0.3}, N {2.0, 0.3}, 3.0, N {4.0, 0.3})));
  • One distribution for each row. The following code constructs a 3-by-2 (o) or 2-by-2 (p) matrices in which elements in each row are selected according to the three (o) or two (p) listed distribution parameters:
    auto o = randomize<Matrix<Dimensions<3>, std::array<angle::Radians, 2>, Eigen::Matrix<double, 3, 2>>>(N {1.0, 0.3}, 2.0, N {3.0, 0.3})));
    auto p = randomize<Matrix<Dimensions<2>, std::array<angle::Radians, 2>, Eigen::Matrix<double, 2, 2>>>(N {1.0, 0.3}, N {2.0, 0.3})));
    Note that in the case of p, there is an ambiguity as to whether the listed distributions correspond to rows or columns. In case of such an ambiguity, this function assumes that the parameters correspond to the rows.
  • One distribution for each column. The following code constructs 2-by-3 matrix m in which elements in each column are selected according to the three listed distribution parameters:
    auto m = randomize<Matrix<std::tuple<angle::Radians, angle::Radians>, Dimensions<3>, Eigen::Matrix<double, 2, 3>>>(N {1.0, 0.3}, 2.0, N {3.0, 0.3})));
Template Parameters
ReturnTypeThe return type reflecting the size of the matrix to be filled. The actual result will be a fixed typed matrix.
random_number_engineThe random number engine.
DistsA set of distributions (e.g., std::normal_distribution<double>) or, alternatively, means (a definite, non-stochastic value).

◆ randomize() [6/6]

template<typename ReturnType , typename random_number_engine = std::mt19937, typename Dist >
auto OpenKalman::randomize ( const std::size_t  rows,
const std::size_t  columns,
Dist &&  dist 
)
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:

auto m = randomize<Matrix<Dimensions<2>, Dimensions<2>, Eigen::Matrix<float, 2, Eigen::Dynamic>>>(2, 2, std::normal_distribution<float> {1.0, 0.3}));
auto n = randomize<Matrix<Dimensions<2>, Dimensions<2>, Eigen::Matrix<double, Eigen::Dynamic, 2>>>(2, 2, std::normal_distribution<double> {1.0, 0.3}));
auto p = randomize<Matrix<Dimensions<2>, Dimensions<2>, Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>>>(2, 2, std::normal_distribution<double> {1.0, 0.3});
Template Parameters
ReturnTypeThe type of the matrix to be filled.
random_number_engineThe random number engine (e.g., std::mt19937).
Parameters
rowsNumber of rows, decided at runtime. Must match rows of ReturnType if they are fixed.
columnsNumber of columns, decided at runtime. Must match columns of ReturnType if they are fixed.
Template Parameters
DistA distribution (type distribution_type).

◆ rank_update_hermitian()

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 std::is_convertible_v< typename scalar_type_of< U >::type, const typename scalar_type_of< A >::type >, int > = 0>
decltype(auto) OpenKalman::rank_update_hermitian ( A &&  a,
U &&  u,
scalar_type_of_t< A >  alpha = 1 
)
inline

Do a rank update on a hermitian matrix.

Note
This may (or may not) be performed as an in-place operation if argument A is writable and hermitian.

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.

Template Parameters
AThe hermitian matrix to be rank updated.
UThe update vector or matrix.
Returns
an updated native, writable matrix in hermitian form.

◆ rank_update_triangular()

template<typename A , typename U , std::enable_if_t< triangular_matrix< A, TriangleType::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 std::is_convertible_v< scalar_type_of_t< U >, const scalar_type_of_t< A >>, int > = 0>
decltype(auto) OpenKalman::rank_update_triangular ( A &&  a,
U &&  u,
scalar_type_of_t< A >  alpha = 1 
)
inline

Do a rank update on triangular matrix.

Note
This may (or may not) be performed as an in-place operation if argument A is writable.
  • If A is lower-triangular, diagonal, or one-by-one, the update is AA* += αUU*, returning the updated A.
  • If A is upper-triangular, the update is A*A += αUU*, returning the updated A.
  • If A is an lvalue reference and is 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.
    Template Parameters
    AThe matrix to be rank updated.
    UThe update vector or matrix.
    Returns
    an updated native, writable matrix in triangular (or diagonal) form.

◆ reduce() [1/2]

template<std::size_t index, std::size_t... indices, typename BinaryFunction , typename Arg , std::enable_if_t< internal::has_uniform_static_vector_space_descriptors< 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 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.)

Template Parameters
indexan 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.
indicesOther indices to be reduced. Because the binary function is associative, the order of the indices does not matter.
BinaryFunctionA 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.
ArgThe tensor
Returns
A vector or tensor with reduced dimensions.

◆ reduce() [2/2]

template<typename BinaryFunction , typename Arg , std::enable_if_t< internal::has_uniform_static_vector_space_descriptors< 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> 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.)

Template Parameters
BinaryFunctionA 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.
ArgThe tensor
Returns
A scalar representing a complete reduction.

◆ scale() [1/2]

template<typename M , typename S , std::enable_if_t< covariance< M > and std::is_convertible_v< S, typename scalar_type_of< M >::type >, int > = 0>
auto OpenKalman::scale ( M &&  m,
const S  s 
)
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.

◆ scale() [2/2]

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 OpenKalman::scale ( M &&  m,
A &&  a 
)
inline

Scale a covariance by a matrix.

Template Parameters
MA covariance.
AA 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).

◆ set_chip()

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&& 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.

Template Parameters
indicesThe 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.
Parameters
argThe indexible object in which the chip is to be set.
chipThe chip to be set. It must be a chip, meaning that the dimension is 1 for each of indices.
isThe index value(s) corresponding to indices, in the same order. The values may be positive std::integral types or a positive std::integral_constant.
Returns
arg as modified

◆ set_component() [1/2]

template<typename Arg , typename Indices , std::enable_if_t< indexible< Arg > and index_range_for< Indices, Arg > and writable_by_component< Arg, Indices >, int > = 0>
Arg&& OpenKalman::set_component ( Arg &&  arg,
const scalar_type_of_t< Arg > &  s,
const Indices &  indices 
)
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Set a component of an object at a particular set of indices.

Template Parameters
ArgThe object to be accessed.
IndicesAn input range object containing the indices.
Returns
The modified Arg

◆ set_component() [2/2]

template<typename Arg , typename... I, std::enable_if_t<(values::index< I > and ...) and writable_by_component< Arg, std::array< std::size_t, sizeof...(I)>> and(index_count< Arg >::value==dynamic_size or sizeof...(I) > = index_count<Arg>::value>
Arg&& OpenKalman::set_component ( Arg &&  arg,
const scalar_type_of_t< Arg > &  s,
I &&...  i 
)
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Set a component of an object using a fixed number of indices.

The number of indices must be at least index_count_v<Arg>. If the indices are integral constants, the function performs compile-time bounds checking to the extent possible.

◆ set_slice()

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&& OpenKalman::set_slice ( Arg &&  arg,
Block &&  block,
const Begin &...  begin 
)

Assign an object to a particular slice of a matrix or tensor.

Parameters
argThe writable object in which the slice is to be assigned.
blockThe block to be set.
beginA tuple specifying, for each index of Arg in order, the beginning values::index.
sizeA tuple specifying, for each index of Arg in order, the dimensions of the extracted block.
Returns
A reference to arg as modified.
Todo:
Add a static check that Block has the correct vector space descriptors

◆ solve()

template<bool must_be_unique = false, bool must_be_exact = false, typename A , typename B >
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.

Template Parameters
must_be_uniqueDetermines whether the function throws an exception if the solution X is non-unique (e.g., if the equation is under-determined)
must_be_exactDetermines whether the function throws an exception if it cannot return an exact solution, such as if the equation is over-determined. If false, then the function will return an estimate instead of throwing an exception.
AThe matrix A in the equation AX = B
BThe matrix B in the equation AX = B
Returns
The unique solution X of the equation AX = B. If must_be_unique, then the function can return any valid solution for X. In particular, if must_be_unique, the function has the following behavior:
  • If A is a zero, then the result X will also be a zero

◆ split() [1/2]

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 OpenKalman::split ( Arg &&  arg,
Ds &&...  ds 
)
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_vector_space_descriptor<i>(a)...}; } ((split<i...>(concatenate<i...>(a...), get_vector_space_descriptor<j>(a)...) == std::tuple{a...}) and ...).

Template Parameters
indicesThe 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.
ArgThe matrix or tensor to be split.
DsA set of coordinates::pattern (the same for for each of indices)

◆ split() [2/2]

template<std::size_t... indices, typename Arg , typename... Ds_tups, std::enable_if_t< indexible< Arg > and(sizeof...(indices) > 0>
auto OpenKalman::split ( Arg &&  arg,
const Ds_tups &...  ds_tups 
)
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_vector_space_descriptor<i>(a)...}; } split<i...>(concatenate<i...>(a...), f<i...>(a)...) == std::tuple{a...}.

Template Parameters
indicesThe 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.
ArgThe matrix or tensor to be split.
Ds_tupsA set of tuples of coordinates::pattern objects, each tuple having sizeof...(indices) elements

◆ split_diagonal()

template<typename ... Cs, typename M , std::enable_if_t< covariance< M >, int > = 0>
auto OpenKalman::split_diagonal ( M &&  m)
inline

Split Covariance or SquareRootCovariance diagonally.

Split typed matrix into one or more typed matrices diagonally.

◆ split_horizontal()

template<typename ... Cs, typename M , std::enable_if_t< covariance< M >, int > = 0>
auto OpenKalman::split_horizontal ( M &&  m)
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.

◆ split_vertical()

template<typename ... Cs, typename M , std::enable_if_t< covariance< M >, int > = 0>
auto OpenKalman::split_vertical ( M &&  m)
inline

Split Covariance or SquareRootCovariance vertically. Result is a tuple of typed matrices.

Split typed matrix into one or more typed matrices vertically.

◆ SquareRootCovariance()

template<typename M , std::enable_if_t< covariance_nestable< M >, int > = 0>
OpenKalman::SquareRootCovariance ( M &&  ) -> SquareRootCovariance< Dimensions< index_dimension_of_v< M, 0 >>, passable_t< M >>
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.

◆ tensor_order()

template<typename T , std::enable_if_t< interface::count_indices_defined_for< T > and interface::get_vector_space_descriptor_defined_for< T >, int > = 0>
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.

Template Parameters
TA matrix or array

◆ tile()

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 OpenKalman::tile ( const std::tuple< Ds... > &  ds_tuple,
Block &&  block,
Blocks &&...  blocks 
)

Create a matrix or tensor by tiling individual blocks.

Template Parameters
DsA set of coordinates::pattern for the resulting matrix or tensor.
BlockThe first block
BlocksSubsequent blocks

◆ to_dense_object() [1/3]

template<typename T , Layout layout = Layout::none, typename Scalar = scalar_type_of_t<T>, typename Arg , std::enable_if_t< indexible< T > and(layout !=Layout::stride) and values::number< Scalar > and indexible< Arg >, int > = 0>
decltype(auto) constexpr OpenKalman::to_dense_object ( Arg &&  arg)

Convert the argument to a dense, writable matrix of a particular scalar type.

Template Parameters
TA dummy matrix or array from the relevant library (size, shape, and layout are ignored)
layoutThe Layout of the resulting object. If this is Layout::none, the interface will decide the layout.
ScalarThe Scalar type of the new matrix, if different than that of Arg
Parameters
argThe object from which the new matrix is based

◆ to_dense_object() [2/3]

template<Layout layout, typename Scalar , typename Arg , std::enable_if_t< values::number< Scalar > and indexible< Arg > and(layout !=Layout::stride), int > = 0>
decltype(auto) constexpr OpenKalman::to_dense_object ( Arg &&  arg)

Convert the argument to a dense, writable matrix of a particular scalar type.

Template Parameters
layoutThe Layout of the resulting object. If this is Layout::none, the interface will decide the layout.
ScalarThe Scalar type of the new matrix, if different than that of Arg
Parameters
argThe object from which the new matrix is based

◆ to_dense_object() [3/3]

template<Layout layout = Layout::none, typename Arg , std::enable_if_t< indexible< Arg > and(layout !=Layout::stride), int > = 0>
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.

Template Parameters
layoutThe Layout of the resulting object (optional). If this is omitted or Layout::none, the interface will decide the layout.
Parameters
argThe object from which the new matrix is based

◆ to_diagonal()

template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0>
decltype(auto) constexpr OpenKalman::to_diagonal ( Arg &&  arg)

Convert an indexible object into a diagonal matrix.

Returns
A diagonal matrix

◆ to_euclidean()

template<typename Arg , std::enable_if_t< indexible< Arg >, int > = 0>
decltype(auto) constexpr OpenKalman::to_euclidean ( Arg &&  arg)

Project the vector space associated with index 0 to a Euclidean space for applying directional statistics.

Template Parameters
ArgA matrix or tensor.

◆ to_native_matrix()

template<typename LibraryObject , typename Arg , std::enable_if_t< indexible< LibraryObject > and indexible< Arg >, int > = 0>
decltype(auto) OpenKalman::to_native_matrix ( Arg &&  arg)
inline

If it isn't already, convert Arg to a native object in the library associated with LibraryObject.

The new object will be one that is fully treated as native by the library associated with LibraryObject and that can be an input in any OpenKalman function associated with library LibraryObject.

Template Parameters
LibraryObjectAny indexible object from the library to which Arg is to be converted. It's shape or scalar type are irrelevant.
ArgThe argument

◆ trace()

template<typename Arg >
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.

Template Parameters
ArgThe matrix
Todo:
Redefine as a particular tensor contraction.

◆ transpose()

template<typename Arg >
decltype(auto) constexpr OpenKalman::transpose ( Arg &&  arg)

Take the transpose of a matrix.

Template Parameters
ArgThe matrix

◆ unary_operation_in_place()

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 OpenKalman::unary_operation_in_place ( const Operation &  operation,
Arg &&  arg 
)

Perform a component-wise, in-place unary operation.

Examples:

  • In-place unary operation without indices:
    auto m23 = make_dense_object_from<Eigen::Matrix<double, 3, 2>>(1, 2, 3, 4, 5, 6);
    auto opa = [](auto& arg){return ++arg;};
    std::cout << n_ary_operation(opa, m32) << std::endl;
    Output:
    2, 3,
    4, 5,
    6, 7
  • In-place unary operation with indices:
    auto opb = [](auto& arg, std::size_t row, std::size_t col){arg += row + col;};
    std::cout << n_ary_operation(opb, m32) << std::endl;
    Output:
    1, 3,
    4, 6,
    7, 9
    Template Parameters
    OperationThe 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).
    ArgThe argument, which must be non-const and writable.
    Returns
    A matrix or array in which each component is the result of calling Operation on corresponding components from each of the arguments, in the order specified.

◆ vector_space_descriptors_match()

template<typename... Ts, std::enable_if_t<(interface::count_indices_defined_for< Ts > and ...), int > = 0>
constexpr bool OpenKalman::vector_space_descriptors_match ( const Ts &...  ts)

Return true if every set of coordinates::pattern of a set of objects match.

Template Parameters
TsA set of tensors or matrices
See also
vector_space_descriptors_match_with
vector_space_descriptors_may_match_with

Variable Documentation

◆ all_fixed_indices_are_euclidean

template<typename T >
constexpr bool OpenKalman::all_fixed_indices_are_euclidean
Initial value:
=
indexible<T> and (detail::all_fixed_indices_are_euclidean_impl<T>(std::make_index_sequence<index_count_v<T>> {}))

Specifies that every fixed-size index of T is euclidean.

No fixed_size index of T is, e.g., Angle, Polar, Spherical, etc.

◆ bidirectional_iterator

template<typename I >
constexpr bool OpenKalman::bidirectional_iterator
inline
Initial value:
=
forward_iterator<I> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

◆ cholesky_form

template<typename T >
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.

◆ compatible_with_vector_space_descriptor_collection

template<typename T , typename D >
constexpr bool OpenKalman::compatible_with_vector_space_descriptor_collection
Initial value:
=
indexible<T> and pattern_collection<D> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

indexible T is compatible with pattern_collection D.

Template Parameters
TAn indexible object
DA pattern_collection

◆ constant_diagonal_matrix

template<typename T >
constexpr bool OpenKalman::constant_diagonal_matrix
Initial value:
=
indexible<T> and values::scalar<constant_diagonal_coefficient<T>>

Specifies that all diagonal elements of a diagonal object are 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.

◆ constant_matrix

template<typename T >
constexpr bool OpenKalman::constant_matrix
Initial value:
=
indexible<T> and values::scalar<constant_coefficient<T>>

Specifies that all components of an object are the same constant value.

◆ copy_constructible

template<typename T >
constexpr bool OpenKalman::copy_constructible
inline
Initial value:
=
move_constructible<T> and
constructible_from<T, T&> and convertible_to<T&, T> and
constructible_from<T, const T&> && convertible_to<const T&, T> and
constructible_from<T, const T> && convertible_to<const T, T>

◆ copyable

template<typename T >
constexpr bool OpenKalman::copyable
inline
Initial value:
=
std::is_copy_constructible_v<T> and
movable<T> and
std::is_assignable_v<T&, T&> and
std::is_assignable_v<T&, const T&> and
std::is_assignable_v<T&, const T>

◆ covariance_nestable

template<typename T >
constexpr bool OpenKalman::covariance_nestable
Initial value:
=
triangular_matrix<T> or hermitian_matrix<T>

T is an acceptable nested matrix for a covariance (including triangular_covariance).

◆ diagonal_adapter

template<typename T , std::size_t N = 0>
constexpr bool OpenKalman::diagonal_adapter = internal::is_explicitly_triangular<T, TriangleType::diagonal>::value and detail::nested_is_vector<T, N>::value

Specifies that a type is a diagonal matrix adapter.

This is an adapter that takes a vector and produces a diagonal_matrix. Components outside the diagonal are zero.

Template Parameters
TA matrix or tensor.
NAn index designating the "large" index of the vector (0 for a column vector, 1 for a row vector)

◆ diagonal_matrix

template<typename T >
constexpr bool OpenKalman::diagonal_matrix
Initial value:
=
triangular_matrix<T, TriangleType::diagonal>

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.

Note
A diagonal_adapter is an diagonal matrix, but not all diagonal matrices are diagonal adapters.

◆ dimension_size_of_index_is

template<typename T , std::size_t index, std::size_t value, Applicability b = Applicability::guaranteed>
constexpr bool OpenKalman::dimension_size_of_index_is
Initial value:
(b == Applicability::permitted and (value == dynamic_size or dynamic_dimension<T, index>))
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31
constexpr std::size_t dynamic_size
A constant indicating that a size or index is dynamic.
Definition: global-definitions.hpp:33

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.

◆ directly_accessible

template<typename T >
constexpr bool OpenKalman::directly_accessible
Initial value:
=
indexible<T> and interface::raw_data_defined_for<std::decay_t<T>&>

The underlying raw data for T is directly accessible.

◆ dynamic_difference

constexpr std::ptrdiff_t OpenKalman::dynamic_difference = std::numeric_limits<std::ptrdiff_t>::max()
inline

A constant indicating that a difference in sizes or indices is dynamic.

A dynamic difference can be set, or change, during runtime and is not known at compile time.

◆ dynamic_dimension

template<typename T , std::size_t N>
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.

◆ dynamic_size

constexpr std::size_t OpenKalman::dynamic_size = std::numeric_limits<std::size_t>::max()
inline

A constant indicating that a size or index is dynamic.

A dynamic size or index can be set, or change, during runtime and is not known at compile time.

◆ element_gettable

template<typename T , std::size_t N>
constexpr bool OpenKalman::element_gettable
Initial value:
= (N == dynamic_size or N >= index_count_v<T>) and
interface::get_component_defined_for<T, T, std::array<std::size_t, index_count<T>::value>>
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31
constexpr std::size_t dynamic_size
A constant indicating that a size or index is dynamic.
Definition: global-definitions.hpp:33

Specifies that a type has components addressable by N indices.

This concept should include anything for which get_component(...) is properly defined with N std::size_t arguments.

See also
get_component
Deprecated:

◆ empty_object

template<typename T , Applicability b = Applicability::guaranteed>
constexpr bool OpenKalman::empty_object
Initial value:
=
indexible<T> and (index_count_v<T> != dynamic_size or b != Applicability::guaranteed) and
(index_count_v<T> == dynamic_size or detail::has_0_dim<T, b>(std::make_index_sequence<index_count_v<T>>{}))
constexpr std::size_t dynamic_size
A constant indicating that a size or index is dynamic.
Definition: global-definitions.hpp:33

Specifies that an object is empty (i.e., at least one index is zero-dimensional).

◆ equivalent_to_uniform_static_vector_space_descriptor_component_of

template<typename T , typename C >
constexpr bool OpenKalman::equivalent_to_uniform_static_vector_space_descriptor_component_of = detail::equivalent_to_uniform_static_vector_space_descriptor_component_of_impl<T, C>::value

T is equivalent to the uniform dimension type of C.

Template Parameters
TA 1D coordinates::descriptor
Ca uniform_static_vector_space_descriptor

◆ euclidean_transformed

template<typename T >
constexpr bool OpenKalman::euclidean_transformed
Initial value:
=
euclidean_mean<T> and (not has_untyped_index<T, 0>)

Specifies that T is a Euclidean mean that actually has coefficients that are transformed to Euclidean space.

◆ forward_iterator

template<typename I >
constexpr bool OpenKalman::forward_iterator
inline
Initial value:
=
input_iterator<I> and
incrementable<I>

◆ has_dynamic_dimensions

template<typename T >
constexpr bool OpenKalman::has_dynamic_dimensions
Initial value:
=
(dynamic_index_count_v<T> == dynamic_size) or (dynamic_index_count_v<T> > 0)
constexpr std::size_t dynamic_size
A constant indicating that a size or index is dynamic.
Definition: global-definitions.hpp:33

Specifies that T has at least one index with dynamic dimensions.

◆ has_nested_object

template<typename T >
constexpr bool OpenKalman::has_nested_object
Initial value:
=
interface::nested_object_defined_for<T>

A matrix that has a nested matrix, if it is a wrapper type.

◆ has_untyped_index

template<typename T , std::size_t N>
constexpr bool OpenKalman::has_untyped_index
Initial value:
=
coordinates::euclidean_pattern<vector_space_descriptor_of_t<T, N>>

Specifies that T has an untyped index N.

Index N of T is Euclidean and non-modular (e.g., Axis, Dimensions<2>, etc.).

◆ hermitian_adapter

template<typename T , HermitianAdapterType t = HermitianAdapterType::any>
constexpr bool OpenKalman::hermitian_adapter
Initial value:
= hermitian_matrix<T, Applicability::permitted> and has_nested_object<T> and
detail::hermitian_adapter_impl<std::decay_t<T>, t>::value
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

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.

Template Parameters
TA matrix or tensor.
tThe HermitianAdapterType of T.

◆ hermitian_adapter_type_of_v

template<typename T , typename... Ts>
constexpr auto OpenKalman::hermitian_adapter_type_of_v = hermitian_adapter_type_of<T, Ts...>::value

The TriangleType associated with the storage triangle of a hermitian_matrix.

Possible values are lower, upper, or any.

◆ hermitian_matrix

template<typename T , Applicability b = Applicability::guaranteed>
constexpr bool OpenKalman::hermitian_matrix
Initial value:
= square_shaped<T, b> and
((constant_matrix<T> or diagonal_matrix<T>) and detail::is_inferred_hermitian_matrix<T>::value))
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

Specifies that a type is a hermitian matrix (assuming it is square_shaped).

For rank >2 tensors, this must be applicable on every rank-2 slice comprising dimensions 0 and 1.

Template Parameters
TA matrix or tensor.
bWhether T must be known to be a square matrix at compile time.

◆ identity_matrix

template<typename T >
constexpr bool OpenKalman::identity_matrix
Initial value:
empty_object<T>
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

Specifies that a type is an identity matrix.

This is a generalized identity matrix which may be rectangular (with zeros in all non-diagonal components. For rank >2 tensors, every rank-2 slice comprising dimensions 0 and 1 must be an identity matrix as defined here. Every empty_object is also an identity matrix.

◆ incrementable

template<typename I >
constexpr bool OpenKalman::incrementable
inline
Initial value:
=
std::is_copy_constructible_v<I> and
std::is_object_v<I> and
std::is_move_constructible_v<I> and
std::is_assignable_v<I&, I> and
std::is_assignable_v<I&, I&> and
std::is_assignable_v<I&, const I&> and
std::is_assignable_v<I&, const I> and
std::is_default_constructible_v<I> and
weakly_incrementable<I> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

◆ index_range_for

template<typename Indices , typename T >
constexpr bool OpenKalman::index_range_for
Initial value:
=
indexible<T> and
interface::get_component_defined_for<T, T, Indices> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

Indices is a std::ranges::sized_range of indices that are compatible with indexible object T.

◆ indexible

template<typename T >
constexpr bool OpenKalman::indexible
Initial value:
=
interface::count_indices_defined_for<std::decay_t<T>>

T is a generalized tensor type.

T can be a tensor over a vector space, but can also be an analogous algebraic structure over a tensor product of modules over division rings (e.g., an vector-like structure that contains angles).

◆ input_iterator

template<typename I >
constexpr bool OpenKalman::input_iterator
inline
Initial value:
=
input_or_output_iterator<I> and
indirectly_readable<I>

◆ linearized_function

template<typename T , std::size_t order = 1>
constexpr bool OpenKalman::linearized_function
Initial value:
=
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31
Definition: TransformationTraits.hpp:39

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.

Template Parameters
TThe function.
orderThe maximum order in which T's Taylor series is defined.

◆ movable

template<typename T >
constexpr bool OpenKalman::movable
inline
Initial value:
=
std::is_object_v<T> and
std::is_move_constructible_v<T> and
std::is_assignable_v<T&, T>

◆ one_dimensional

template<typename T , Applicability b = Applicability::guaranteed>
constexpr bool OpenKalman::one_dimensional
Initial value:
= indexible<T> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

Specifies that a type is one-dimensional in every index.

Each index also must have an equivalent coordinates::pattern object.

◆ output_iterator

template<typename I , typename T >
constexpr bool OpenKalman::output_iterator
inline
Initial value:
=
input_or_output_iterator<I> and
indirectly_writable<I, T> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

◆ random_access_iterator

template<typename I >
constexpr bool OpenKalman::random_access_iterator
inline
Initial value:
=
bidirectional_iterator<I> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

◆ sentinel_for

template<typename S , typename I >
constexpr bool OpenKalman::sentinel_for
inline
Initial value:
=
semiregular<S> and input_or_output_iterator<I> and detail::WeaklyEqualityComparableWith<S, I>::value
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

◆ sized_sentinel_for

template<typename S , typename I >
constexpr bool OpenKalman::sized_sentinel_for
inline
Initial value:
= sentinel_for<S, I> and
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

◆ square_shaped

template<typename T , Applicability b = Applicability::guaranteed>
constexpr bool OpenKalman::square_shaped
Initial value:
= one_dimensional<T, b> or (indexible<T> and
(not interface::is_square_defined_for<T, b> or internal::is_explicitly_square<T, b>::value) and
(interface::is_square_defined_for<T, b> or detail::square_shaped_impl<T, b>::value or
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

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. An empty (0-by-0) matrix or tensor is considered to be square.

Template Parameters
bDefines what happens when one or more of the indices has dynamic dimension:

◆ transformation_input

template<typename T , typename Coeffs = typename oin::PerturbationTraits<T>::RowCoefficients>
constexpr bool OpenKalman::transformation_input
Initial value:
=
typed_matrix<T> and vector<T> and has_untyped_index<T, 1> and (not euclidean_transformed<T>) and
coordinates::compares_with<typename oin::PerturbationTraits<T>::RowCoefficients, Coeffs>

T is an acceptable input to a tests.

Template Parameters
CoeffsThe expected coefficients of the tests input.

◆ triangular_adapter

template<typename T >
constexpr bool OpenKalman::triangular_adapter
Initial value:
= detail::is_triangular_adapter<T>::value and has_nested_object<T> and
has_nested_object<T>
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

Specifies that a type is a triangular adapter of triangle type triangle_type.

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.

Template Parameters
TA matrix or tensor.

◆ triangular_matrix

template<typename T , TriangleType t = TriangleType::any>
constexpr bool OpenKalman::triangular_matrix = internal::is_explicitly_triangular<T, t>::value or constant_diagonal_matrix<T>

Specifies that a type is a triangular matrix (upper, lower, or diagonal).

A triangular matrix need not be square_shaped, but it must be zero either above or below the diagonal (or both). For rank >2 tensors, this must be applicable on every rank-2 slice comprising dimensions 0 and 1.

Note
One-dimensional matrices or vectors are considered to be triangular, and a vector is triangular if every component other than its first component is zero.
Template Parameters
TA matrix or tensor.
tThe TriangleType triangular if it is one-dimensional, and that is not necessarily known at compile time.

◆ typed_adapter

template<typename T >
constexpr bool OpenKalman::typed_adapter
Initial value:
=
typed_matrix<T> or covariance<T> or euclidean_expr<T>

Specifies that T is a typed adapter expression.

◆ typed_matrix_nestable

template<typename T >
constexpr bool OpenKalman::typed_matrix_nestable
Initial value:
=
indexible<T>

Specifies a type that is nestable in a general typed matrix (e.g., matrix, mean, or euclidean_mean)

◆ untyped_adapter

template<typename T >
constexpr bool OpenKalman::untyped_adapter
Initial value:
=
internal::diagonal_expr<T> or internal::hermitian_expr<T> or internal::triangular_expr<T>

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.

◆ vector

template<typename T , std::size_t N = 0, Applicability b = Applicability::guaranteed>
constexpr bool OpenKalman::vector
Initial value:
=
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

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.

Template Parameters
TAn indexible object
NAn index designating the "large" index (0 for a column vector, 1 for a row vector)
bWhether the vector status is guaranteed known at compile time (Applicability::guaranteed), or only known at runtime (Applicability::permitted)
See also
is_vector

◆ vector_space_descriptors_match_with

template<typename... Ts>
constexpr bool OpenKalman::vector_space_descriptors_match_with
Initial value:
=
vector_space_descriptors_may_match_with<Ts...> and ((not has_dynamic_dimensions<Ts>) and ...)
constexpr bool vector_space_descriptors_may_match_with
Specifies that indexible objects Ts may have equivalent dimensions and vector-space types...
Definition: vector_space_descriptors_may_match_with.hpp:49

Specifies that a set of indexible objects have equivalent vector space descriptors for each index.

Template Parameters
TsA set of indexible objects
See also
vector_space_descriptors_may_match_with
vector_space_descriptors_match

◆ vector_space_descriptors_may_match_with

template<typename... Ts>
constexpr bool OpenKalman::vector_space_descriptors_may_match_with
Initial value:
=
(indexible<Ts> and ...) and
detail::vector_space_descriptors_may_match_with_impl<Ts...>(std::make_index_sequence<std::max({std::size_t{0}, index_count_v<Ts>...})>{})

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.

See also
vector_space_descriptors_match_with
vector_space_descriptors_match

◆ wrappable

template<typename T >
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.

See also
get_wrappable

◆ wrapped_mean

template<typename T >
constexpr bool OpenKalman::wrapped_mean
Initial value:
=
mean<T> and (not has_untyped_index<T, 0>)

Specifies that T is a wrapped mean (i.e., its row fixed_pattern have at least one type that requires wrapping).

◆ writable

template<typename T >
constexpr bool OpenKalman::writable
Initial value:
=
indexible<T> and interface::is_explicitly_writable<T>::value and (not std::is_const_v<std::remove_reference_t<T>>) and
std::is_copy_constructible_v<std::decay_t<T>> and std::is_move_constructible_v<std::decay_t<T>>
Definition: tuple_reverse.hpp:103
constexpr bool value
T is numerical value or is reducible to a numerical value.
Definition: value.hpp:31

◆ writable_by_component

template<typename T , typename Indices = std::conditional_t<index_count_v<T> == dynamic_size, std::vector<std::size_t>, std::array<std::size_t, index_count_v<T>>>>
constexpr bool OpenKalman::writable_by_component
Initial value:
=
indexible<T> and index_range_for<Indices, T> and
(not std::is_const_v<std::remove_reference_t<T>>) and (not empty_object<T>) and
interface::set_component_defined_for<
T, std::add_lvalue_reference_t<T>, const typename scalar_type_of<T>::type&, const Indices&>
Definition: tuple_reverse.hpp:103
constexpr bool empty_object
Specifies that an object is empty (i.e., at least one index is zero-dimensional). ...
Definition: empty_object.hpp:39

Specifies that a type has components that can be set with Indices (an std::ranges::input_range) of type std::size_t.

If T satisfies this concept, then set_component(...) is available with Indices.

See also
set_component