Skip to content

Commit

Permalink
add more details on orientation transformations
Browse files Browse the repository at this point in the history
  • Loading branch information
baggepinnen committed Jun 14, 2024
1 parent 67016dd commit 1f04f99
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 5 deletions.
22 changes: 17 additions & 5 deletions src/orientation.jl
Original file line number Diff line number Diff line change
Expand Up @@ -421,10 +421,16 @@ function resolve_dyade2(R, D1)
end

"""
get_rot(sol, frame, t)
R_W_F = get_rot(sol, frame, t)
Extract a 3×3 rotation matrix ∈ SO(3) from a solution at time `t`.
See also [`get_trans`](@ref), [`get_frame`](@ref)
The rotation matrix returned, ``R_W^F``, is such that when a vector ``p_F`` expressed in the local `frame` of reference ``F`` is multiplied by ``R_W^F`` as ``Rp``, the resulting vector is ``p_W`` expressed in the world frame:
```math
p_W = R_W^F * p_F
```
See also [`get_trans`](@ref), [`get_frame`](@ref), [Orientations and directions](@ref) (docs section).
"""
function get_rot(sol, frame, t)
Rotations.RotMatrix3(reshape(sol(t, idxs = vec(ori(frame).R.mat')), 3, 3))
Expand All @@ -434,17 +440,23 @@ end
get_trans(sol, frame, t)
Extract the translational part of a frame from a solution at time `t`.
See also [`get_rot`](@ref), [`get_frame`](@ref)
See also [`get_rot`](@ref), [`get_frame`](@ref), [Orientations and directions](@ref) (docs section).
"""
function get_trans(sol, frame, t)
SVector{3}(sol(t, idxs = collect(frame.r_0)))
end

"""
get_frame(sol, frame, t)
T_W_F = get_frame(sol, frame, t)
Extract a 4×4 transformation matrix ∈ SE(3) from a solution at time `t`.
See also [`get_trans`](@ref), [`get_rot`](@ref)
The transformation matrix returned, ``T_W^F``, is such that when a homogenous-coordinate vector ``p_F``, expressed in the local `frame` of reference ``F`` is multiplied by ``T_W^F`` as ``Tp``, the resulting vector is ``p_W`` expressed in the world frame:
```math
p_W = T_W^F * p_F
```
See also [`get_trans`](@ref) and [`get_rot`](@ref), [Orientations and directions](@ref) (docs section).
"""
function get_frame(sol, frame, t)
R = get_rot(sol, frame, t)
Expand Down
3 changes: 3 additions & 0 deletions test/test_orientation_getters.jl
Original file line number Diff line number Diff line change
Expand Up @@ -89,3 +89,6 @@ r_A = [r_A; 1] # Homogeneous coordinates
@test (get_frame(sol, model.lower_arm.frame_a, 12)*r_A)[1:3] t1

# the vector is now coinciding with `get_trans(sol, model.lower_arm.frame_b, 12)`.

@test get_trans(sol, model.tip.frame_a, 12) t1
@test get_frame(sol, model.tip.frame_a, 12)[1:3, 4] t1

0 comments on commit 1f04f99

Please sign in to comment.