Skip to content

Commit c5bd24a

Browse files
committed
Renames UnitQuaternion to QuatRotation
See JuliaGeometry/Rotations.jl#201, from the latest Rotations.jl release https://github.com/JuliaGeometry/Rotations.jl/releases/tag/v1.1.0 (cherry picked from commit 0482ed2)
1 parent 166d3d0 commit c5bd24a

File tree

5 files changed

+22
-22
lines changed

5 files changed

+22
-22
lines changed

src/joint_types/quaternion_floating.jl

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -27,13 +27,13 @@ has_fixed_subspaces(jt::QuaternionFloating) = true
2727
isfloating(::Type{<:QuaternionFloating}) = true
2828

2929
@propagate_inbounds function rotation(jt::QuaternionFloating, q::AbstractVector, normalize::Bool = true)
30-
quat = UnitQuaternion(q[1], q[2], q[3], q[4], normalize)
30+
quat = QuatRotation(q[1], q[2], q[3], q[4], normalize)
3131
quat
3232
end
3333

3434
@propagate_inbounds function set_rotation!(q::AbstractVector, jt::QuaternionFloating, rot::Rotation{3})
3535
T = eltype(rot)
36-
quat = convert(UnitQuaternion{T}, rot)
36+
quat = convert(QuatRotation{T}, rot)
3737
q[1] = quat.w
3838
q[2] = quat.x
3939
q[3] = quat.y
@@ -114,7 +114,7 @@ end
114114

115115
@propagate_inbounds function configuration_derivative_to_velocity_adjoint!(fq, jt::QuaternionFloating, q::AbstractVector, fv)
116116
quatnorm = sqrt(q[1]^2 + q[2]^2 + q[3]^2 + q[4]^2) # TODO: make this nicer
117-
quat = UnitQuaternion(q[1] / quatnorm, q[2] / quatnorm, q[3] / quatnorm, q[4] / quatnorm, false)
117+
quat = QuatRotation(q[1] / quatnorm, q[2] / quatnorm, q[3] / quatnorm, q[4] / quatnorm, false)
118118
rot = (velocity_jacobian(angular_velocity_in_body, quat)' * angular_velocity(jt, fv)) ./ quatnorm
119119
trans = quat * linear_velocity(jt, fv)
120120
set_rotation!(fq, jt, rot)
@@ -166,14 +166,14 @@ end
166166

167167
@propagate_inbounds function zero_configuration!(q::AbstractVector, jt::QuaternionFloating)
168168
T = eltype(q)
169-
set_rotation!(q, jt, one(UnitQuaternion{T}))
169+
set_rotation!(q, jt, one(QuatRotation{T}))
170170
set_translation!(q, jt, zero(SVector{3, T}))
171171
nothing
172172
end
173173

174174
@propagate_inbounds function rand_configuration!(q::AbstractVector, jt::QuaternionFloating)
175175
T = eltype(q)
176-
set_rotation!(q, jt, rand(UnitQuaternion{T}))
176+
set_rotation!(q, jt, rand(QuatRotation{T}))
177177
set_translation!(q, jt, rand(SVector{3, T}) .- 0.5)
178178
nothing
179179
end

src/joint_types/quaternion_spherical.jl

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,12 @@ has_fixed_subspaces(jt::QuaternionSpherical) = true
2424
isfloating(::Type{<:QuaternionSpherical}) = false
2525

2626
@propagate_inbounds function rotation(jt::QuaternionSpherical, q::AbstractVector, normalize::Bool = true)
27-
UnitQuaternion(q[1], q[2], q[3], q[4], normalize)
27+
QuatRotation(q[1], q[2], q[3], q[4], normalize)
2828
end
2929

3030
@propagate_inbounds function set_rotation!(q::AbstractVector, jt::QuaternionSpherical, rot::Rotation{3})
3131
T = eltype(rot)
32-
quat = convert(UnitQuaternion{T}, rot)
32+
quat = convert(QuatRotation{T}, rot)
3333
q[1] = quat.w
3434
q[2] = quat.x
3535
q[3] = quat.y
@@ -79,7 +79,7 @@ end
7979

8080
@propagate_inbounds function configuration_derivative_to_velocity_adjoint!(fq, jt::QuaternionSpherical, q::AbstractVector, fv)
8181
quatnorm = sqrt(q[1]^2 + q[2]^2 + q[3]^2 + q[4]^2) # TODO: make this nicer
82-
quat = UnitQuaternion(q[1] / quatnorm, q[2] / quatnorm, q[3] / quatnorm, q[4] / quatnorm, false)
82+
quat = QuatRotation(q[1] / quatnorm, q[2] / quatnorm, q[3] / quatnorm, q[4] / quatnorm, false)
8383
fq .= (velocity_jacobian(angular_velocity_in_body, quat)' * fv) ./ quatnorm
8484
nothing
8585
end
@@ -103,13 +103,13 @@ end
103103

104104
@propagate_inbounds function zero_configuration!(q::AbstractVector, jt::QuaternionSpherical)
105105
T = eltype(q)
106-
set_rotation!(q, jt, one(UnitQuaternion{T}))
106+
set_rotation!(q, jt, one(QuatRotation{T}))
107107
nothing
108108
end
109109

110110
@propagate_inbounds function rand_configuration!(q::AbstractVector, jt::QuaternionSpherical)
111111
T = eltype(q)
112-
set_rotation!(q, jt, rand(UnitQuaternion{T}))
112+
set_rotation!(q, jt, rand(QuatRotation{T}))
113113
nothing
114114
end
115115

@@ -147,7 +147,7 @@ end
147147

148148
@propagate_inbounds function global_coordinates!(q::AbstractVector, jt::QuaternionSpherical, q0::AbstractVector, ϕ::AbstractVector)
149149
quat0 = rotation(jt, q0, false)
150-
quat = quat0 * UnitQuaternion(RotationVec(ϕ[1], ϕ[2], ϕ[3]))
150+
quat = quat0 * QuatRotation(RotationVec(ϕ[1], ϕ[2], ϕ[3]))
151151
set_rotation!(q, jt, quat)
152152
nothing
153153
end

src/spatial/util.jl

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ function quaternion_derivative end
124124
function spquat_derivative end
125125
function angular_velocity_in_body end
126126

127-
@inline function velocity_jacobian(::typeof(quaternion_derivative), q::UnitQuaternion)
127+
@inline function velocity_jacobian(::typeof(quaternion_derivative), q::QuatRotation)
128128
(@SMatrix [
129129
-q.x -q.y -q.z;
130130
q.w -q.z q.y;
@@ -133,27 +133,27 @@ function angular_velocity_in_body end
133133
end
134134

135135
@inline function velocity_jacobian(::typeof(spquat_derivative), q::ModifiedRodriguesParam)
136-
quat = UnitQuaternion(q)
136+
quat = QuatRotation(q)
137137
dQuat_dW = velocity_jacobian(quaternion_derivative, quat)
138138
dSPQuat_dQuat = Rotations.jacobian(ModifiedRodriguesParam, quat)
139139
dSPQuat_dQuat * dQuat_dW
140140
end
141141

142-
@inline function velocity_jacobian(::typeof(angular_velocity_in_body), q::UnitQuaternion)
142+
@inline function velocity_jacobian(::typeof(angular_velocity_in_body), q::QuatRotation)
143143
2 * @SMatrix [
144144
-q.x q.w q.z -q.y;
145145
-q.y -q.z q.w q.x;
146146
-q.z q.y -q.x q.w]
147147
end
148148

149149
@inline function velocity_jacobian(::typeof(angular_velocity_in_body), q::ModifiedRodriguesParam)
150-
quat = UnitQuaternion(q)
150+
quat = QuatRotation(q)
151151
dW_dQuat = velocity_jacobian(angular_velocity_in_body, quat)
152-
dQuat_dSPQuat = Rotations.jacobian(UnitQuaternion, q)
152+
dQuat_dSPQuat = Rotations.jacobian(QuatRotation, q)
153153
dW_dQuat * dQuat_dSPQuat
154154
end
155155

156-
@inline function quaternion_derivative(q::UnitQuaternion, angular_velocity_in_body::AbstractVector)
156+
@inline function quaternion_derivative(q::QuatRotation, angular_velocity_in_body::AbstractVector)
157157
@boundscheck length(angular_velocity_in_body) == 3 || error("size mismatch")
158158
velocity_jacobian(quaternion_derivative, q) * angular_velocity_in_body
159159
end
@@ -163,7 +163,7 @@ end
163163
velocity_jacobian(spquat_derivative, q) * angular_velocity_in_body
164164
end
165165

166-
@inline function angular_velocity_in_body(q::UnitQuaternion, quat_derivative::AbstractVector)
166+
@inline function angular_velocity_in_body(q::QuatRotation, quat_derivative::AbstractVector)
167167
@boundscheck length(quat_derivative) == 4 || error("size mismatch")
168168
velocity_jacobian(angular_velocity_in_body, q) * quat_derivative
169169
end

src/util.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ end
4444
## VectorSegment: type of a view of a vector
4545
const VectorSegment{T} = SubArray{T,1,Array{T, 1},Tuple{UnitRange{Int64}},true} # TODO: a bit too specific
4646

47-
quatnorm(quat::UnitQuaternion) = sqrt(quat.w^2 + quat.x^2 + quat.y^2 + quat.z^2)
47+
quatnorm(quat::QuatRotation) = sqrt(quat.w^2 + quat.x^2 + quat.y^2 + quat.z^2)
4848

4949

5050
## Modification count stuff

test/test_mechanism_algorithms.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -242,10 +242,10 @@ end
242242
@test velocity(x, joint)[1] == vj
243243
end
244244
if joint_type(joint) isa QuaternionSpherical
245-
quat = rand(UnitQuaternion{Float64})
245+
quat = rand(QuatRotation{Float64})
246246
set_configuration!(x, joint, quat)
247247
tf = RigidBodyDynamics.joint_transform(joint, configuration(x, joint))
248-
@test UnitQuaternion(rotation(tf)) quat atol = 1e-12
248+
@test QuatRotation(rotation(tf)) quat atol = 1e-12
249249
end
250250
if joint_type(joint) isa SinCosRevolute
251251
qj = rand()
@@ -886,7 +886,7 @@ end
886886
for joint_k = tree_joints(state_orig.mechanism)
887887
joint_type_k = joint_type(joint_k)
888888
if isa(joint_type_k, SPQuatFloating)
889-
RigidBodyDynamics.set_rotation!(state_orig.q[joint_k], joint_type_k, ModifiedRodriguesParam(UnitQuaternion(-0.5, randn(), randn(), randn())))
889+
RigidBodyDynamics.set_rotation!(state_orig.q[joint_k], joint_type_k, ModifiedRodriguesParam(QuatRotation(-0.5, randn(), randn(), randn())))
890890
end
891891
end
892892
setdirty!(state_orig)

0 commit comments

Comments
 (0)