Quaternion Distributions
Sample truly uniform from quaternions and robust implementations for small normally distributed quaternion perturbations.
KernelDistributions.QuaternionUniform
KernelDistributions.:⊕
KernelDistributions.:⊖
KernelDistributions.exp_map
KernelDistributions.log_map
KernelDistributions.nonzero_sign
KernelDistributions.outer_product
Statistics.cov
Statistics.mean
StatsBase.mean_and_cov
KernelDistributions.QuaternionUniform
— TypeQuaternionUniform
Allows true uniform sampling of 3D rotations on CPU & GPU (CUDA).
KernelDistributions.nonzero_sign
— Methodnonzero_sign(q)
Compared to the implementation in Quaternions.jl, this implementation does not return a Quaternion with (0,0,0,0) but the identity with (1,0,0,0). Eq. (44) in J. Sola, „Quaternion kinematics for the error-state KF“.
KernelDistributions.:⊕
— Method⊕(q, θ)
'The ‘plus’ operator [qs = qr ⊕ θ] : SO(3) × R3 → SO(3) produces an element S of SO(3) which is the result of composing a reference element R of SO(3) with a (often small) rotation. This rotation is specified by a vector of θ ∈ R3 in the vector space tangent [...]' (eq. 158, Sola 2012)
KernelDistributions.:⊖
— Method⊖(qs, qr)
'The ‘minus’ operator [θ = qs ⊖ qr] : SO(3) × SO(3) → R3 is the inverse of [qs = qr ⊕ θ]. It returns the vectorial angular difference θ ∈ R3 between two elements of SO(3). This difference is expressed in the vector space tangent to the reference element [...]' (eq. 161, Sola 2012)
KernelDistributions.exp_map
— Methodexp_map(x, y, z)
Convert an axis-angle rotation vector to a Quaternion (formerly qrotation in Quaternions.jl, Sola 2012)). Exponential for quaternions can be reformulated to the exponential map using (eq. 46, Sola 2012)).
KernelDistributions.log_map
— Methodlog_map(q)
Convert a Quaternion to an axis angle rotation vector. Exponential for quaternions can be reformulated to the exponential map using (eq. 46, Sola 2012) - log similar.
KernelDistributions.outer_product
— Methodouter_product(q)
Interprets q as vector and calculates q * q'.
Statistics.cov
— Methodcov(x::AbstractVector{<:Quaternion}, w::AbstractWeights, dims::Int; corrected=false)
For particle filters use analytic / reliability weights which describe an importance of each observation. Compatibility with matrix function by ignoring dims.
Statistics.mean
— Methodmean(q::AbstractVector{<:Quaternion}, w::AbstractWeights)
Calculate the weighted mean Quaternion via eigenvalue decomposition. Based on "Averaging Quaternions", Markley et al. 2007.
StatsBase.mean_and_cov
— Functionmean_and_cov(x::AbstractVector{<:Quaternion}, w::AbstractWeights, dims::Int; corrected=false)
For particle filters use analytic / reliability weights which describe an importance of each observation. Compatibility with matrix function by ignoring dims.