Skip to content

Commit a12cb6c

Browse files
authored
Cleanup around Quaternion (#228)
* update compat table for Quaternions.jl * cleanup with Quaternions.imag_part * fix parenthesis
1 parent fe2cbd0 commit a12cb6c

File tree

9 files changed

+50
-74
lines changed

9 files changed

+50
-74
lines changed

Project.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ StaticArrays = "90137ffa-7385-5640-81b9-e52037218182"
1010
Statistics = "10745b16-79ce-11e8-11f9-7d13ad32a3b2"
1111

1212
[compat]
13-
Quaternions = "0.4.5, 0.5"
13+
Quaternions = "0.5.3"
1414
StaticArrays = "1.2.12"
1515
julia = "1.6"
1616

src/angleaxis_types.jl

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -78,10 +78,8 @@ end
7878
end
7979

8080
@inline function (::Type{AA})(q::QuatRotation) where AA <: AngleAxis
81-
w = q.q.s
82-
x = q.q.v1
83-
y = q.q.v2
84-
z = q.q.v3
81+
w = real(q.q)
82+
x, y, z = imag_part(q.q)
8583
s2 = x * x + y * y + z * z
8684
sin_t2 = sqrt(s2)
8785
theta = 2 * atan(sin_t2, w)

src/derivatives.jl

Lines changed: 6 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -31,10 +31,8 @@ to the output parameterization, centered at the value of R.
3131
Returns the jacobian for rotating the vector X by R.
3232
"""
3333
function jacobian(::Type{RotMatrix}, q::QuatRotation)
34-
w = q.q.s
35-
x = q.q.v1
36-
y = q.q.v2
37-
z = q.q.v3
34+
w = real(q.q)
35+
x, y, z = imag_part(q.q)
3836

3937
# let q = s * qhat where qhat is a unit quaternion and s is a scalar,
4038
# then R = RotMatrix(q) = RotMatrix(s * qhat) = s * RotMatrix(qhat)
@@ -138,10 +136,8 @@ end
138136
# Jacobian converting from a Quaternion to an MRP
139137
#
140138
function jacobian(::Type{MRP}, q::QuatRotation{T}) where T
141-
w = q.q.s
142-
x = q.q.v1
143-
y = q.q.v2
144-
z = q.q.v3
139+
w = real(q.q)
140+
x, y, z = imag_part(q.q)
145141

146142
den = 1 + w
147143
scale = 1 / den
@@ -184,10 +180,8 @@ end
184180

185181
# TODO: should this be jacobian(:rotate, q, X) # or something?
186182
function jacobian(q::QuatRotation, X::AbstractVector)
187-
w = q.q.s
188-
x = q.q.v1
189-
y = q.q.v2
190-
z = q.q.v3
183+
w = real(q.q)
184+
x, y, z = imag_part(q.q)
191185

192186
@assert length(X) === 3
193187
T = eltype(q)

src/error_maps.jl

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -220,10 +220,8 @@ end
220220

221221

222222
function jacobian(::InvCayleyMap, q::QuatRotation)
223-
w = q.q.s
224-
x = q.q.v1
225-
y = q.q.v2
226-
z = q.q.v3
223+
w = real(q.q)
224+
x, y, z = imag_part(q.q)
227225

228226
μ = scaling(CayleyMap)
229227
si = 1/w
@@ -234,10 +232,8 @@ end
234232

235233

236234
function jacobian(::InvMRPMap, q::QuatRotation)
237-
w = q.q.s
238-
x = q.q.v1
239-
y = q.q.v2
240-
z = q.q.v3
235+
w = real(q.q)
236+
x, y, z = imag_part(q.q)
241237

242238
μ = scaling(MRPMap)
243239
si = 1/(1+w)

src/mrps.jl

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -35,10 +35,8 @@ Base.one(::Type{RP}) where RP <: MRP = RP(0.0, 0.0, 0.0)
3535
end
3636

3737
@inline function (::Type{RP})(q::QuatRotation) where RP<:MRP
38-
w = q.q.s
39-
x = q.q.v1
40-
y = q.q.v2
41-
z = q.q.v3
38+
w = real(q.q)
39+
x, y, z = imag_part(q.q)
4240

4341
M = 1/(1+w)
4442
RP(x*M, y*M, z*M)

src/rodrigues_params.jl

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,10 +32,8 @@ params(g::RodriguesParam) = SVector{3}(g.x, g.y, g.z)
3232
end
3333

3434
@inline function (::Type{G})(q::QuatRotation) where G<:RodriguesParam
35-
w = q.q.s
36-
x = q.q.v1
37-
y = q.q.v2
38-
z = q.q.v3
35+
w = real(q.q)
36+
x, y, z = imag_part(q.q)
3937

4038
return G(x/w, y/w, z/w)
4139
end

src/unitquaternion.jl

Lines changed: 31 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ end
6161

6262
function QuatRotation(q::T) where T<:Quaternion
6363
if q.norm
64-
return QuatRotation(q.s, q.v1, q.v2, q.v3, false)
64+
return QuatRotation(real(q), imag_part(q)..., false)
6565
else
6666
throw(InexactError(nameof(T), T, q))
6767
end
@@ -125,10 +125,8 @@ end
125125

126126

127127
function Base.getindex(q::QuatRotation, i::Int)
128-
w = q.q.s
129-
x = q.q.v1
130-
y = q.q.v2
131-
z = q.q.v3
128+
w = real(q.q)
129+
x, y, z = imag_part(q.q)
132130

133131
if i == 1
134132
ww = (w * w)
@@ -187,10 +185,8 @@ function Base.getindex(q::QuatRotation, i::Int)
187185
end
188186

189187
function Base.Tuple(q::QuatRotation)
190-
w = q.q.s
191-
x = q.q.v1
192-
y = q.q.v2
193-
z = q.q.v3
188+
w = real(q.q)
189+
x, y, z = imag_part(q.q)
194190

195191
ww = (w * w)
196192
xx = (x * x)
@@ -218,7 +214,7 @@ end
218214
# ~~~~~~~~~~~~~~~ Getters ~~~~~~~~~~~~~~~ #
219215
@inline scalar(q::QuatRotation) = real(q.q)
220216
@inline vector(q::QuatRotation) = vector(q.q)
221-
@inline vector(q::Quaternion) = SVector{3}(q.v1, q.v2, q.v3)
217+
@inline vector(q::Quaternion) = SVector{3}(imag_part(q))
222218

223219
"""
224220
params(R::Rotation)
@@ -231,7 +227,7 @@ p = MRP(1.0, 2.0, 3.0)
231227
Rotations.params(p) == @SVector [1.0, 2.0, 3.0] # true
232228
```
233229
"""
234-
@inline params(q::QuatRotation) = SVector{4}(q.q.s, q.q.v1, q.q.v2, q.q.v3)
230+
@inline params(q::QuatRotation) = SVector{4}(real(q.q), imag_part(q.q)...)
235231

236232
# ~~~~~~~~~~~~~~~ Initializers ~~~~~~~~~~~~~~~ #
237233
@inline Base.one(::Type{Q}) where Q <: QuatRotation = Q(1.0, 0.0, 0.0, 0.0)
@@ -243,10 +239,8 @@ Rotations.params(p) == @SVector [1.0, 2.0, 3.0] # true
243239
Base.inv(q::Q) where Q <: QuatRotation = Q(conj(q.q))
244240

245241
function _normalize(q::Q) where Q <: QuatRotation
246-
w = q.q.s
247-
x = q.q.v1
248-
y = q.q.v2
249-
z = q.q.v3
242+
w = real(q.q)
243+
x, y, z = imag_part(q.q)
250244

251245
n = norm(params(q))
252246
Q(w/n, x/n, y/n, z/n)
@@ -279,10 +273,8 @@ function expm(ϕ::AbstractVector)
279273
end
280274

281275
function _log_as_quat(q::Q, eps=1e-6) where Q <: QuatRotation
282-
w = q.q.s
283-
x = q.q.v1
284-
y = q.q.v2
285-
z = q.q.v3
276+
w = real(q.q)
277+
x, y, z = imag_part(q.q)
286278

287279
# Assumes unit quaternion
288280
θ = sqrt(x^2 + y^2 + z^2)
@@ -384,10 +376,8 @@ end
384376
`lmult(q2)*params(q1)` returns a vector equivalent to `q2*q1` (quaternion composition)
385377
"""
386378
function lmult(q::QuatRotation)
387-
w = q.q.s
388-
x = q.q.v1
389-
y = q.q.v2
390-
z = q.q.v3
379+
w = real(q.q)
380+
x, y, z = imag_part(q.q)
391381

392382
SA[
393383
w -x -y -z;
@@ -397,11 +387,14 @@ function lmult(q::QuatRotation)
397387
]
398388
end
399389
function lmult(q::Quaternion)
390+
w = real(q)
391+
x, y, z = imag_part(q)
392+
400393
SA[
401-
q.s -q.v1 -q.v2 -q.v3;
402-
q.v1 q.s -q.v3 q.v2;
403-
q.v2 q.v3 q.s -q.v1;
404-
q.v3 -q.v2 q.v1 q.s;
394+
w -x -y -z;
395+
x w -z y;
396+
y z w -x;
397+
z -y x w;
405398
]
406399
end
407400
lmult(q::StaticVector{4}) = lmult(QuatRotation(q, false))
@@ -413,10 +406,8 @@ lmult(q::StaticVector{4}) = lmult(QuatRotation(q, false))
413406
`rmult(q1)*params(q2)` return a vector equivalent to `q2*q1` (quaternion composition)
414407
"""
415408
function rmult(q::QuatRotation)
416-
w = q.q.s
417-
x = q.q.v1
418-
y = q.q.v2
419-
z = q.q.v3
409+
w = real(q.q)
410+
x, y, z = imag_part(q.q)
420411

421412
SA[
422413
w -x -y -z;
@@ -426,11 +417,14 @@ function rmult(q::QuatRotation)
426417
]
427418
end
428419
function rmult(q::Quaternion)
420+
w = real(q)
421+
x, y, z = imag_part(q)
422+
429423
SA[
430-
q.s -q.v1 -q.v2 -q.v3;
431-
q.v1 q.s q.v3 -q.v2;
432-
q.v2 -q.v3 q.s q.v1;
433-
q.v3 q.v2 -q.v1 q.s;
424+
w -x -y -z;
425+
x w z -y;
426+
y -z w x;
427+
z y -x w;
434428
]
435429
end
436430
rmult(q::SVector{4}) = rmult(QuatRotation(q, false))
@@ -497,10 +491,8 @@ Useful for converting Jacobians from R⁴ to R³ and
497491
differential quaternion parameterization are the same up to a constant.
498492
"""
499493
function ∇differential(q::QuatRotation)
500-
w = q.q.s
501-
x = q.q.v1
502-
y = q.q.v2
503-
z = q.q.v3
494+
w = real(q.q)
495+
x, y, z = imag_part(q.q)
504496

505497
SA[
506498
-x -y -z;

test/rodrigues_params.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ end
6868
@test ω 2*vmat()*lmult(q)'qdot
6969
@test ω 2*vmat()*lmult(inv(q))*qdot
7070
q2 = Quaternion(q)*pure_quaternion(ω)
71-
@test qdot SVector(q2.s, q2.v1, q2.v2, q2.v3)/2
71+
@test qdot SVector(real(q2), imag_part(q2)...)/2
7272

7373
# MRPs
7474
ω = @SVector rand(3)

test/rotation_tests.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -205,7 +205,7 @@ all_types = (RotMatrix3, RotMatrix{3}, AngleAxis, RotationVec,
205205
@test Rotations.params(q2) -Rotations.params(q) atol = 100 * eps()
206206
@test q q2 atol = 100 * eps()
207207

208-
q3 = QuatRotation(-q.q.s, -q.q.v1, -q.q.v2, -q.q.v3, false) # don't normalize: everything is exact
208+
q3 = QuatRotation(-real(q.q), (-).(imag_part(q.q))..., false) # don't normalize: everything is exact
209209
@test Rotations.params(q3) == -Rotations.params(q)
210210
@test q == q3
211211

0 commit comments

Comments
 (0)