Rotations.Angle2d
— Typestruct Angle2d{T} <: Rotation{2,T}
theta::T
end
A 2×2 rotation matrix parameterized by a 2D rotation by angle. Only the angle is stored inside the Angle2d
type, values of getindex
etc. are computed on the fly.
Rotations.Angle2dGenerator
— Typestruct Angle2dGenerator{T} <: RotationGenerator{2,T}
v::T
end
A 2×2 rotation generator matrix (i.e. skew-symmetric matrix). [ 0 -v v 0 ]
Rotations.AngleAxis
— Typestruct AngleAxis{T} <: Rotation{3,T}
AngleAxis(Θ, x, y, z)
A 3×3 rotation matrix parameterized by a 3D rotation by angle θ about an arbitrary axis [x, y, z]
.
Note that the axis is not unique for θ = 0, and that this parameterization does not continuously map the neighbourhood of the identity rotation (and therefore might not be suitable for autodifferentation and optimization purposes).
Note: by default, the constructor will renormalize the input so that the axis has length 1 (x² + y² + z² = 1).
Renormalization can be skipped by passing false
as an additional constructor argument, in which case the user provides the guarantee that the input arguments represent a normalized rotation axis. Operations on an AngleAxis
with a rotation axis that does not have unit norm, created by skipping renormalization in this fashion, are not guaranteed to do anything sensible.
Rotations.ErrorMap
— TypeErrorMap
A nonlinear mapping between the space of unit quaternions and three-dimensional rotation errors.
These mappings are extremely useful for converting from globally nonsingular 3D rotation representations such as QuatRotation
or RotMatrix3
to a three-parameter error that can be efficiently used in gradient-based optimization methods that optimize deviations about a current iterate using first or second-order information.
Usage
errmap(v::AbstractVector) # "forward" map from a 3D error to a `QuatRotation`
inv(errmap)(R::Rotation) # "inverse" map from a rotation (via `QuatRotation`) to a 3D error
where errmap <: ErrorMap
Implemented Maps
CayleyMap
: UsesRodriguesParam
as the error representation (default). Goes singular at 180° and does not have a sign ambiguity.ExponentialMap
: Uses the canonical exponential map from Lie Group theory. Computationally expensive to compute. Exhibits kinematic singularities.MRPMap
: Uses a scaledMRP
as the error representation. Singular at 360° but has a sign ambiguity (with the "shadow" MRP set).QuatVecMap
: Uses the vector part of the quaternions. Cheapest map to compute, but goes singular at 180° and suffers from sign ambiguity.IdentityMap
: Maps values through directly. Only works with three-parameter rotation representations with the following methods:R(::SVector{3})
andSVector(::R)::SVector{3}
Rotations.InvErrorMap
— TypeInvErrorMap
The nonlinear mapping from unit quaternions to a three-dimensional error state. Obtained by inverting an ErrorMap
, i.e.
InvCayleyMap() = inv(CayleyMap())
Usage
imap(R::Rotation) # "inverse" map from a rotation to a 3D error
inv(imap)(v::AbstractVector) # "forward" map from a 3D error to a `QuatRotation`
where imap <: InvErrorMap
.
See ErrorMap
for documentation on the implemented maps.
Rotations.MRP
— TypeMRP{T} <: Rotation
Modified Rodrigues Parameter. Is a 3D parameterization of attitude, and is a sterographic projection of the 4D unit sphere onto the plane tangent to the negative real pole. They have a singularity at θ = ±360°.
Constructors
MRP(x, y, z) MRP(r::AbstractVector)
Rotations.QuatRotation
— TypeQuatRotation{T} <: Rotation
4-parameter attitute representation that is singularity-free. Quaternions with unit norm represent a double-cover of SO(3). The QuatRotation
does NOT strictly enforce the unit norm constraint, but certain methods will assume you have a unit quaternion. Follows the Hamilton convention for quaternions.
Constructors
QuatRotation(w,x,y,z)
QuatRotation(q::AbstractVector)
where w
is the scalar (real) part, x
, y
, and z
are the vector (imaginary) part, and q = [w,x,y,z]
.
Rotations.RodriguesParam
— TypeRodriguesParam{T}
Rodrigues parameters are a three-dimensional parameterization of rotations. They have a singularity at 180° but do not inherit the sign ambiguities of quaternions or MRPs
Rotations.RotMatrix
— Typestruct RotMatrix{N,T} <: Rotation{N,T}
A statically-sized, N×N unitary (orthogonal) matrix.
Note: the orthonormality of the input matrix is not checked by the constructor.
Rotations.RotMatrixGenerator
— Typestruct RotMatrixGenerator{N,T} <: RotationGenerator{N,T}
A statically-sized, N×N skew-symmetric matrix.
Note: the skew-symmetricity of the input matrix is not checked by the constructor.
Rotations.RotX
— Typestruct RotX{T} <: Rotation{3,T}
RotX(theta)
A 3×3 rotation matrix which represents a rotation by theta
about the X axis.
Rotations.RotXY
— Typestruct RotXY{T} <: Rotation{3,T}
RotXY(theta_x, theta_y)
A 3×3 rotation matrix which represents a rotation by theta_y
about the Y axis, followed by a rotation by theta_x
about the X axis.
Rotations.RotXYX
— Typestruct RotXYX{T} <: Rotation{3,T}
RotXYX(theta1, theta2, theta3)
A 3×3 rotation matrix parameterized by the "proper" XYX Euler angle convention, consisting of first a rotation about the X axis by theta3
, followed by a rotation about the Y axis by theta2
, and finally a rotation about the X axis by theta1
.
Rotations.RotXYZ
— Typestruct RotXYZ{T} <: Rotation{3,T}
RotXYZ(theta1, theta2, theta3)
RotXYZ(roll=r, pitch=p, yaw=y)
A 3×3 rotation matrix parameterized by the "Tait-Bryant" XYZ Euler angle convention, consisting of first a rotation about the Z axis by theta3
, followed by a rotation about the Y axis by theta2
, and finally a rotation about the X axis by theta1
.
The keyword argument form applies roll, pitch and yaw to the X, Y and Z axes respectively, in XYZ order. (Because it is a right-handed coordinate system, note that positive pitch is heading in the negative Z axis).
Rotations.RotXZ
— Typestruct RotXZ{T} <: Rotation{3,T}
RotXZ(theta_x, theta_z)
A 3×3 rotation matrix which represents a rotation by theta_z
about the Z axis, followed by a rotation by theta_x
about the X axis.
Rotations.RotXZX
— Typestruct RotXZX{T} <: Rotation{3,T}
RotXZX(theta1, theta2, theta3)
A 3×3 rotation matrix parameterized by the "proper" XZX Euler angle convention, consisting of first a rotation about the X axis by theta3
, followed by a rotation about the Z axis by theta2
, and finally a rotation about the X axis by theta1
.
Rotations.RotXZY
— Typestruct RotXZY{T} <: Rotation{3,T}
RotXZY(theta1, theta2, theta3)
RotXZY(roll=r, pitch=p, yaw=y)
A 3×3 rotation matrix parameterized by the "Tait-Bryant" XZY Euler angle convention, consisting of first a rotation about the Y axis by theta3
, followed by a rotation about the Z axis by theta2
, and finally a rotation about the X axis by theta1
.
The keyword argument form applies roll, pitch and yaw to the X, Y and Z axes respectively, in XZY order. (Because it is a right-handed coordinate system, note that positive pitch is heading in the negative Z axis).
Rotations.RotY
— Typestruct RotY{T} <: Rotation{3,T}
RotY(theta)
A 3×3 rotation matrix which represents a rotation by theta
about the Y axis.
Rotations.RotYX
— Typestruct RotYX{T} <: Rotation{3,T}
RotYX(theta_y, theta_x)
A 3×3 rotation matrix which represents a rotation by theta_x
about the X axis, followed by a rotation by theta_y
about the Y axis.
Rotations.RotYXY
— Typestruct RotYXY{T} <: Rotation{3,T}
RotYXY(theta1, theta2, theta3)
A 3×3 rotation matrix parameterized by the "proper" YXY Euler angle convention, consisting of first a rotation about the Y axis by theta3
, followed by a rotation about the X axis by theta2
, and finally a rotation about the Y axis by theta1
.
Rotations.RotYXZ
— Typestruct RotYXZ{T} <: Rotation{3,T}
RotYXZ(theta1, theta2, theta3)
RotYXZ(roll=r, pitch=p, yaw=y)
A 3×3 rotation matrix parameterized by the "Tait-Bryant" YXZ Euler angle convention, consisting of first a rotation about the Z axis by theta3
, followed by a rotation about the X axis by theta2
, and finally a rotation about the Y axis by theta1
.
The keyword argument form applies roll, pitch and yaw to the X, Y and Z axes respectively, in YXZ order. (Because it is a right-handed coordinate system, note that positive pitch is heading in the negative Z axis).
Rotations.RotYZ
— Typestruct RotYZ{T} <: Rotation{3,T}
RotYZ(theta_y, theta_z)
A 3×3 rotation matrix which represents a rotation by theta_z
about the Z axis, followed by a rotation by theta_y
about the Y axis.
Rotations.RotYZX
— Typestruct RotYZX{T} <: Rotation{3,T}
RotYZX(theta1, theta2, theta3)
RotYZX(roll=r, pitch=p, yaw=y)
A 3×3 rotation matrix parameterized by the "Tait-Bryant" YZX Euler angle convention, consisting of first a rotation about the X axis by theta3
, followed by a rotation about the Z axis by theta2
, and finally a rotation about the Y axis by theta1
.
The keyword argument form applies roll, pitch and yaw to the X, Y and Z axes respectively, in YZX order. (Because it is a right-handed coordinate system, note that positive pitch is heading in the negative Z axis).
Rotations.RotYZY
— Typestruct RotYZY{T} <: Rotation{3,T}
RotYZY(theta1, theta2, theta3)
A 3×3 rotation matrix parameterized by the "proper" YXY Euler angle convention, consisting of first a rotation about the Y axis by theta3
, followed by a rotation about the Z axis by theta2
, and finally a rotation about the Y axis by theta1
.
Rotations.RotZ
— Typestruct RotZ{T} <: Rotation{3,T}
RotZ(theta)
A 3×3 rotation matrix which represents a rotation by theta
about the Z axis.
Rotations.RotZX
— Typestruct RotZX{T} <: Rotation{3,T}
RotZX(theta_z, theta_x)
A 3×3 rotation matrix which represents a rotation by theta_x
about the X axis, followed by a rotation by theta_z
about the Z axis.
Rotations.RotZXY
— Typestruct RotZXY{T} <: Rotation{3,T}
RotZXY(theta1, theta2, theta3)
RotZXY(roll=r, pitch=p, yaw=y)
A 3×3 rotation matrix parameterized by the "Tait-Bryant" ZXY Euler angle convention, consisting of first a rotation about the Y axis by theta3
, followed by a rotation about the X axis by theta2
, and finally a rotation about the Z axis by theta1
.
The keyword argument form applies roll, pitch and yaw to the X, Y and Z axes respectively, in ZXY order. (Because it is a right-handed coordinate system, note that positive pitch is heading in the negative Z axis).
Rotations.RotZXZ
— Typestruct RotZXZ{T} <: Rotation{3,T}
RotZXZ(theta1, theta2, theta3)
A 3×3 rotation matrix parameterized by the "proper" ZXZ Euler angle convention, consisting of first a rotation about the Z axis by theta3
, followed by a rotation about the X axis by theta2
, and finally a rotation about the Z axis by theta1
.
Rotations.RotZY
— Typestruct RotZY{T} <: Rotation{3,T}
RotZY(theta_z, theta_y)
A 3×3 rotation matrix which represents a rotation by theta_y
about the Y axis, followed by a rotation by theta_z
about the Z axis.
Rotations.RotZYX
— Typestruct RotZYX{T} <: Rotation{3,T}
RotZYX(theta1, theta2, theta3)
RotZYX(roll=r, pitch=p, yaw=y)
A 3×3 rotation matrix parameterized by the "Tait-Bryant" ZYX Euler angle convention, consisting of first a rotation about the X axis by theta3
, followed by a rotation about the Y axis by theta2
, and finally a rotation about the Z axis by theta1
.
The keyword argument form applies roll, pitch and yaw to the X, Y and Z axes respectively, in ZYX order. (Because it is a right-handed coordinate system, note that positive pitch is heading in the negative Z axis).
Rotations.RotZYZ
— Typestruct RotZYZ{T} <: Rotation{3,T}
RotZYZ(theta1, theta2, theta3)
A 3×3 rotation matrix parameterized by the "proper" ZXZ Euler angle convention, consisting of first a rotation about the Z axis by theta3
, followed by a rotation about the Y axis by theta2
, and finally a rotation about the Z axis by theta1
.
Rotations.Rotation
— Typeabstract type Rotation{N,T} <: StaticMatrix{N,N,T}
An abstract type representing N
-dimensional rotations. More abstractly, they represent unitary (orthogonal) N
×N
matrices.
Rotations.RotationError
— TypeRotationError{T<:Real, D<:ErrorMap} <: StaticVector{3,T}
A three-parameter rotation error, converted to/from a QuatRotation
using the ErrorMap
D
.
Usage
A RotationError
is typically created using one of the following methods
rotation_error(R1::Rotation, R2::Rotation, error_map::ErrorMap)
R1 ⊖ R2
which compute the difference between the rotations R1
and R2
and convert the result to a 3D rotation error using error_map
.
The error can be "added" back to a rotation using the inverse operation:
add_error(R1::Rotation, e::RotationError)
R1::Rotation ⊕ e::RotationError
Rotations.RotationGenerator
— Typeabstract type RotationGenerator{N,T} <: StaticMatrix{N,N,T}
An abstract type representing N
-dimensional rotation generator. More abstractly, they represent skew-symmetric real N
×N
matrices.
Rotations.RotationVec
— Typestruct RotationVec{T} <: Rotation{3,T}
RotationVec(sx, sy, sz)
Rodrigues vector parameterization of a 3×3 rotation matrix. The direction of the vector [sx, sy, sz] defines the axis of rotation, and the rotation angle is given by its norm.
Rotations.RotationVecGenerator
— Typestruct RotationVecGenerator{T} <: RotationGenerator{2,T}
x::T
y::T
z::T
end
A 3×3 rotation generator matrix (i.e. skew-symmetric matrix). [ 0 -z y z 0 -x -y x 0]
Base.:*
— Method(*)(q::QuatRotation, w::QuatRotation)
Quternion Composition
Equivalent to
lmult(q) * SVector(w)
rmult(w) * SVector(q)
Sets the output mapping equal to the mapping of w
Base.:*
— Method(*)(q::QuatRotation, r::StaticVector)
Rotate a vector
Equivalent to hmat()' lmult(q) * rmult(q)' hmat() * r
Quaternions.slerp
— Methodslerp(R1::Rotaion{3}, R2::Rotaion{3}, t::Real)
Perform spherical linear interpolation (Slerp) between rotations R1
and R2
.
Rotations.add_error
— Methodadd_error(R1::Rotation, e::RotationError)
"Adds" the rotation error e
to the rotation R1
by converting e
to a quaternion via its ErrorMap
and then composing with R1
.
Equivalent to
R1 ⊕ e
Rotations.hmat
— Methodhmat()
hmat(r::AbstractVector)
hmat()*r
or hmat(r)
converts r
into a pure quaternion, where r
is 3-dimensional.
hmat() == vmat()'
Rotations.isrotation
— Functionisrotation(r)
isrotation(r, tol)
Check whether r
is a rotation matrix, where r * r'
is within tol
of the identity matrix (using the Frobenius norm). tol
defaults to 1000 * eps(float(eltype(r)))
or zero(T)
for integer T
.
Rotations.isrotationgenerator
— Functionisrotationgenerator(r)
Check whether r
is a rotation generator matrix (skew-symmetric matrix).
Rotations.jacobian
— Functionjacobian(::ErrorMap, ϕ)
Jacobian of the quaternion map that takes a three-dimensional vector ϕ
and returns a unit quaternion. Returns a 4x3 Static Matrix
For all the maps (except the IdentityMap
) jacobian(::ErrorMap, zeros(3)) = [0; I] = Hmat()'
Rotations.jacobian
— Functionjacobian(::InvErrorMap, q::QuatRotation)
Jacobian of the inverse quaternion map, returning a 3×4 matrix. For all maps: jacobian(::InvErrorMap, QuatRotation(I)) = [0 I] = Hmat()'
Rotations.jacobian
— Methodjacobian(::Type{output_param}, R::input_param)
Returns the jacobian for transforming from the input rotation parameterization to the output parameterization, centered at the value of R.
jacobian(R::rotation_type, X::AbstractVector)
Returns the jacobian for rotating the vector X by R.
Rotations.kinematics
— Methodkinematics(R::Rotation{3}, ω::AbstractVector)
The time derivative of the rotation R, according to the definition
\[Ṙ = \lim_{Δt → 0} \frac{R(t + Δt) - R(t)}{Δt}\]
where ω
is the angular velocity. This is equivalent to
\[Ṙ = \lim_{Δt → 0} \frac{R δR - R}{Δt}\]
where $δR$ is some small rotation, parameterized by a small rotation $δθ$ about an axis $r$, such that $\lim_{Δt → 0} \frac{δθ r}{Δt} = ω$
The kinematics are extremely useful when computing the dynamics of rigid bodies, since Ṙ = kinematics(R,ω)
is the first-order ODE for the evolution of the attitude dynamics.
See "Fundamentals of Spacecraft Attitude Determination and Control" by Markley and Crassidis Sections 3.1-3.2 for more details.
Rotations.lmult
— Methodlmult(q::QuatRotation)
lmult(q::StaticVector{4})
lmult(q2)*params(q1)
returns a vector equivalent to q2*q1
(quaternion composition)
Rotations.nearest_rotation
— Methodnearest_rotation(M) -> RotMatrix
Get the nearest special orthonormal matrix from given matrix M
. See Wahba's problem for more information.
Rotations.params
— Methodparams(R::Rotation)
Return an SVector
of the underlying parameters used by the rotation representation.
Example
p = MRP(1.0, 2.0, 3.0)
Rotations.params(p) == @SVector [1.0, 2.0, 3.0] # true
Rotations.perpendicular_vector
— Methodperpendicular_vector(vec)
Compute a vector perpendicular to vec
by switching the two elements with largest absolute value, flipping the sign of the second largest, and setting the remaining element to zero.
Rotations.principal_value
— Methodprincipal_value(R::Rotation{3})
Background: All non RotMatrix
rotation types can represent the same RotMatrix
in two or more ways. Sometimes a particular set of numbers is better conditioned (e.g. MRP
) or obeys a particular convention (e.g. AngleAxis
has non-negative rotation). In order to preserve differentiability it is necessary to allow rotation representations to travel slightly away from the nominal domain; this is critical for applications such as optimization or dynamics.
This function takes a rotation type (e.g. QuatRotation
, RotXY
) and outputs a new rotation of the same type that corresponds to the same RotMatrix
, but that obeys certain conventions or is better conditioned. The outputs of the function have the following properties:
- all angles are between between
-pi
topi
(except forAngleAxis
which is between0
andpi
). - all `QuatRotation have non-negative real part
- the components of all
MRP
have a norm that is at most 1. - the
RotationVec
rotation is at mostpi
Rotations.pure_quaternion
— Methodpure_quaternion(v::AbstractVector)
pure_quaternion(x, y, z)
Create a Quaternion
with zero scalar part (i.e. q.q.s == 0
).
Rotations.rmult
— Methodrmult(q::QuatRotation)
rmult(q::StaticVector{4})
rmult(q1)*params(q2)
return a vector equivalent to q2*q1
(quaternion composition)
Rotations.rot_eltype
— MethodThe element type for a rotation matrix with a given angle type is composed of trigonometric functions of that type.
Rotations.rotation_between
— Functionrotation_between(u, v)
Compute the quaternion that rotates vector u
so that it aligns with vector v
, along the geodesic (shortest path).
Rotations.rotation_error
— Methodrotation_error(R1::Rotation, R2::Rotation, error_map::ErrorMap)
Compute the RotationError
by calculating the "difference" between R1
and R2
, i.e. R2\R1
, then mapped to a three-parameter error using error_map
.
Can be equivalently called using the default map with R1 ⊖ R2
If error_map::IdentityMap
, then SVector(R1\R2)::SVector{3}
is used as the error. Note this only works for three-parameter rotation representations such as RodriguesParam
or MRP
.
Rotations.tmat
— Methodtmat()
tmat()*params(q)
return a vector equivalent to inv(q)
, where q
is a QuatRotation
Rotations.vmat
— Methodvmat()
vmat()*params(q)
returns the imaginary (vector) part of the quaternion
q(equivalent to
vector(q)``)
Rotations.∇composition1
— Method∇composition1(R2::Rotation{3}, R1::Rotation{3})
Jacobian of R2*R1
with respect to R1
Rotations.∇composition2
— Method∇composition2(R2::Rotation{3}, R1::Rotation{3})
Jacobian of R2*R1
with respect to R2
Rotations.∇differential
— Method∇differential(q::QuatRotation)
Jacobian of lmult(q) QuatMap(ϕ)
, when ϕ is near zero.
Useful for converting Jacobians from R⁴ to R³ and correctly account for unit norm constraint. Jacobians for different differential quaternion parameterization are the same up to a constant.
Rotations.∇err
— Method∇err(p1::MRP, p2::MRP)
Jacobian of p1\p2
wrt p2
Rotations.∇jacobian
— Function∇jacobian(::InvErrorMap, q::QuatRotation, b::SVector{3})
Jacobian of G(q)'b, where G(q) = jacobian(::InvErrorMap, q), b is a 3-element vector
Rotations.∇rotate
— Method∇rotate(R::Rotation{3}, r::AbstractVector)
Jacobian of R*r
with respect to the rotation
Rotations.∇²differential
— Method∇²differential(q::QuatRotation, b::AbstractVector)
Jacobian of (∂/∂ϕ lmult(q) QuatMap(ϕ))
b, evaluated at ϕ=0, and b
has length 4.
Rotations.∇²err
— Method∇²err(p1::MRP, p2::MRP, b::StaticVector{3})
Jacobian of (∂/∂p p1\p2)'b
wrt p2