Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

some updates for MTK v9 #53

Merged
merged 18 commits into from
Jun 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
147 changes: 104 additions & 43 deletions Manifest.toml

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion Project.toml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ Makie = "ee78f7c6-11fb-53f2-987a-cfe4a2b5a57a"
Render = ["Makie"]

[compat]
ModelingToolkit = "8.30"
ModelingToolkit = "9"
ModelingToolkitStandardLibrary = "2"
Rotations = "1.4"
CoordinateTransformations = "0.6"
Expand Down
7 changes: 6 additions & 1 deletion docs/src/examples/free_motion.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ prob = ODEProblem(ssys, [
D.(freeMotion.phi) .=> randn();
D.(D.(freeMotion.phi)) .=> randn();
D.(body.w_a) .=> randn();
collect(body.w_a .=> 0);
collect(body.v_0 .=> 0);
], (0, 10))

sol = solve(prob, Rodas4())
Expand Down Expand Up @@ -73,7 +75,10 @@ eqs = [connect(bar2.frame_a, world.frame_b)
spring2,
])
ssys = structural_simplify(IRSystem(model))
prob = ODEProblem(ssys, [], (0, 10))
prob = ODEProblem(ssys, [
collect(body.body.v_0 .=> 0);
collect(body.body.w_a .=> 0);
], (0, 10))

sol = solve(prob, Rodas5P())
@assert SciMLBase.successful_retcode(sol)
Expand Down
1 change: 1 addition & 0 deletions docs/src/examples/gearbox.md
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ cm = complete(model)
ssys = structural_simplify(IRSystem(model))
prob = ODEProblem(ssys, [
D(cm.idealGear.phi_b) => 0
cm.idealGear.phi_b => 0
], (0, 10))
sol = solve(prob, Rodas4())
plot(sol, idxs=[
Expand Down
24 changes: 12 additions & 12 deletions docs/src/examples/kinematic_loops.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@ systems = @named begin
j3 = Revolute()
j4 = RevolutePlanarLoopConstraint()
j5 = Revolute()
b1 = BodyShape(m=1, r = [2.0, 0, 0])
b2 = BodyShape(m=1, r = [0.0, 2.0, 0])
b3 = BodyShape(m=1, r = [-2.0, 0, 0])
b4 = BodyShape(m=1, r = [0.0, -2.0, 0])
b1 = BodyShape(m=1, r = [2.0, 0, 0], radius=0.03)
b2 = BodyShape(m=1, r = [0.0, 2.0, 0], radius=0.03)
b3 = BodyShape(m=1, r = [-2.0, 0, 0], radius=0.03)
b4 = BodyShape(m=1, r = [0.0, -2.0, 0], radius=0.03)
damper1 = Rotational.Damper(d=0.5)
damper2 = Rotational.Damper(d=0.1)
end
Expand Down Expand Up @@ -58,8 +58,8 @@ connections = [
connect(j2.support, damper2.flange_b)

]
@named fourbar2 = ODESystem(connections, t, systems = [world; systems])
m = structural_simplify(IRSystem(fourbar2))
@named fourbar = ODESystem(connections, t, systems = [world; systems])
m = structural_simplify(IRSystem(fourbar))
prob = ODEProblem(m, [], (0.0, 30.0))
sol = solve(prob, Rodas4(autodiff=false))

Expand All @@ -80,7 +80,7 @@ Multibody.jl supports automatic 3D rendering of mechanisms, we use this feature

```@example kinloop
import CairoMakie
Multibody.render(fourbar2, sol, 0:0.033:10; z = -7, R=Multibody.rotx(20, true)*Multibody.roty(20, true), filename = "fourbar.gif") # Use "fourbar.mp4" for a video file
Multibody.render(fourbar, sol, 0:0.033:10; z = -7, R=Multibody.rotx(20, true)*Multibody.roty(20, true), filename = "fourbar.gif") # Use "fourbar.mp4" for a video file
nothing # hide
```

Expand All @@ -91,18 +91,18 @@ nothing # hide

The mechanism below is another instance of a 4-bar linkage, this time with 6 revolute joints, 1 prismatic joint and 4 bodies. In order to simulate this mechanism, the user must
1. Use the `iscut=true` keyword argument to one of the `Revolute` joints to indicate that the joint is a cut joint. A cut joint behaves similarly to a regular joint, but it introduces fewer constraints in order to avoid the otherwise over-constrained system resulting from closing the kinematic loop.
2. Increase the `state_priority` of the joint `j1` above the default joint priority 3. This encourages the model compiler to choose the joint coordinate of `j1` as state variable. The joint coordinate of `j1` is the only coordinate that uniquely determines the configuration of the mechanism. The choice of any other joint coordinate would lead to a singular representation in at least one configuration of the mechanism. The joint `j1` is the revolute joint located in the origin, see the animation below.
2. Increase the `state_priority` of the joint `j1` above the default joint priority 3. This encourages the model compiler to choose the joint coordinate of `j1` as state variable. The joint coordinate of `j1` is the only coordinate that uniquely determines the configuration of the mechanism. The choice of any other joint coordinate would lead to a singular representation in at least one configuration of the mechanism. The joint `j1` is the revolute joint located in the origin, see the animation below where this joint is made larger than the others.


To drive the mechanism, we set the initial velocity of the joint j1 to some non-zero value.

```@example kinloop
systems = @named begin
j1 = Revolute(n = [1, 0, 0], w0 = 5.235987755982989, state_priority=10.0) # Increase state priority to ensure that this joint coordinate is chosen as state variable
j1 = Revolute(n = [1, 0, 0], w0 = 5.235987755982989, state_priority=10.0, radius=0.1f0) # Increase state priority to ensure that this joint coordinate is chosen as state variable
j2 = Prismatic(n = [1, 0, 0], s0 = -0.2)
b1 = BodyShape(r = [0, 0.5, 0.1])
b2 = BodyShape(r = [0, 0.2, 0])
b3 = BodyShape(r = [-1, 0.3, 0.1])
b1 = BodyShape(r = [0, 0.5, 0.1], radius=0.03)
b2 = BodyShape(r = [0, 0.2, 0], radius=0.03)
b3 = BodyShape(r = [-1, 0.3, 0.1], radius=0.03)
rev = Revolute(n = [0, 1, 0], iscut=true)
rev1 = Revolute()
j3 = Revolute(n = [1, 0, 0])
Expand Down
6 changes: 4 additions & 2 deletions docs/src/examples/pendulum.md
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ The `ODESystem` is the fundamental model type in ModelingToolkit used for multib

Before we can simulate the system, we must perform model compilation using [`structural_simplify`](@ref)
```@example pendulum
ssys = structural_simplify(model, allow_parameter = false)
ssys = structural_simplify(IRSystem(model))
```
This results in a simplified model with the minimum required variables and equations to be able to simulate the system efficiently. This step rewrites all `connect` statements into the appropriate equations, and removes any redundant variables and equations.

Expand Down Expand Up @@ -90,7 +90,7 @@ connections = [connect(world.frame_b, joint.frame_a)
connect(body.frame_a, joint.frame_b)]

@named model = ODESystem(connections, t, systems = [world, joint, body, damper])
ssys = structural_simplify(model, allow_parameter = false)
ssys = structural_simplify(IRSystem(model))

prob = ODEProblem(ssys, [damper.phi_rel => 1, D(joint.phi) => 0, D(D(joint.phi)) => 0],
(0, 30))
Expand Down Expand Up @@ -157,6 +157,8 @@ defs = Dict(collect(multibody_spring.r_rel_0 .=> [0, 1, 0])...,
collect((D.(root_body.phi)) .=> [0, 0, 0])...,
collect(D.(D.(root_body.phi)) .=> [0, 0, 0])...,
collect(D.(root_body.phid) .=> [0, 0, 0])...,
collect(root_body.w_a .=> [0, 0, 0])...,
collect(root_body.v_0 .=> [0, 0, 0])...,
)

prob = ODEProblem(ssys, defs, (0, 30))
Expand Down
6 changes: 3 additions & 3 deletions docs/src/examples/robot.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@ The robot is a medium sized system with some 2000 equations before simplificatio
After simplification, the following states are chosen:
```@example robot
ssys = structural_simplify(IRSystem(robot))
states(ssys)
unknowns(ssys)
```

```@example robot
prob = ODEProblem(ssys, [
prob = ODEProblem(ssys, Dict([
robot.mechanics.r1.phi => deg2rad(-60)
robot.mechanics.r2.phi => deg2rad(20)
robot.mechanics.r3.phi => deg2rad(90)
Expand All @@ -37,7 +37,7 @@ prob = ODEProblem(ssys, [
robot.axis1.motor.Jmotor.phi => deg2rad(-60) * -105 # Multiply by gear ratio
robot.axis2.motor.Jmotor.phi => deg2rad(20) * 210
robot.axis3.motor.Jmotor.phi => deg2rad(90) * 60
], (0.0, 4.0))
]), (0.0, 4.0))
sol = solve(prob, Rodas5P(autodiff=false));
@test SciMLBase.successful_retcode(sol)

Expand Down
2 changes: 1 addition & 1 deletion docs/src/examples/sensors.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ connections = [connect(world.frame_b, joint.frame_a)
@named model = ODESystem(connections, t,
systems = [world, joint, body, torquesensor, forcesensor])
modele = ModelingToolkit.expand_connections(model)
ssys = structural_simplify(model, allow_parameter = false)
ssys = structural_simplify(IRSystem(model))


D = Differential(t)
Expand Down
8 changes: 1 addition & 7 deletions docs/src/examples/spring_damper_system.md
Original file line number Diff line number Diff line change
Expand Up @@ -57,13 +57,7 @@ eqs = [connect(world.frame_b, bar1.frame_a)

ssys = structural_simplify(IRSystem(model))

prob = ODEProblem(ssys,
[D.(body1.phi) .=> 0;
D.(D.(body1.phi)) .=> 0;
D.(body1.phid) .=> 0;
D(p2.s) => 0;
D(D(p2.s)) => 0;
damper1.d => 2], (0, 10))
prob = ODEProblem(ssys, [damper1.d => 2], (0, 10))

sol = solve(prob, Rodas4())
@assert SciMLBase.successful_retcode(sol)
Expand Down
75 changes: 47 additions & 28 deletions ext/Render.jl
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,20 @@ using LinearAlgebra
using ModelingToolkit
export render


function get_rot(sol, frame, t)
reshape(sol(t, idxs = vec(ori(frame).R.mat)), 3, 3)
end

"""
get_frame(sol, frame, t)

Extract a 4×4 transformation matrix ∈ SE(3) from a solution at time `t`.
"""
function get_frame(sol, frame, t)
R = reshape(sol(t, idxs = vec(ori(frame).R.mat)), 3, 3)
t = sol(t, idxs = collect(frame.r_0))
[R' t; 0 0 0 1]
R = get_rot(sol, frame, t)
tr = sol(t, idxs = collect(frame.r_0))
[R' tr; 0 0 0 1]
end


Expand Down Expand Up @@ -101,8 +106,9 @@ end
render!(scene, ::Any, args...) = false # Fallback for systems that have no rendering

function render!(scene, ::typeof(Body), sys, sol, t)
r_cm = collect(sys.r_cm)
thing = @lift begin # Sphere
r_cm = sol($t, idxs=collect(sys.r_cm))
r_cm = sol($t, idxs=r_cm)
Ta = get_frame(sol, sys.frame_a, $t)
coords = (Ta*[r_cm; 1])[1:3] # TODO: make use of a proper transformation library instead of rolling own?
point = Point3f(coords)
Expand All @@ -115,13 +121,12 @@ function render!(scene, ::typeof(Body), sys, sol, t)
end
mesh!(scene, thing, color=:purple)

r_cm = sol(0.0, idxs=collect(sys.r_cm))
iszero(r_cm) && (return true)
iszero(sol(0.0, idxs=collect(r_cm))) && (return true)

thing = @lift begin # Cylinder
Ta = get_frame(sol, sys.frame_a, $t)

r_cm = sol($t, idxs=collect(sys.r_cm)) # r_cm is the center of the sphere in frame a
r_cm = sol($t, idxs=r_cm) # r_cm is the center of the sphere in frame a
iszero(r_cm)
coords = (Ta*[r_cm; 1])[1:3]
point = Point3f(coords) # Sphere center in world coords
Expand All @@ -144,42 +149,46 @@ end

function render!(scene, ::typeof(World), sys, sol, t)
radius = 0.01f0
r_0 = collect(sys.frame_b.r_0)

thing = @lift begin
O = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
O = Point3f(sol($t, idxs=r_0))
x = O .+ Point3f(1,0,0)
Makie.GeometryBasics.Cylinder(O, x, radius)
end
mesh!(scene, thing, color=:red)

thing = @lift begin
O = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
O = Point3f(sol($t, idxs=r_0))
y = O .+ Point3f(0,1,0)
Makie.GeometryBasics.Cylinder(O, y, radius)
end
mesh!(scene, thing, color=:green)

thing = @lift begin
O = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
O = Point3f(sol($t, idxs=r_0))
z = O .+ Point3f(0,0,1)
Makie.GeometryBasics.Cylinder(O, z, radius)
end
mesh!(scene, thing, color=:blue)
true
end

function render!(scene, ::typeof(Revolute), sys, sol, t)
function render!(scene, ::Union{typeof(Revolute), typeof(RevolutePlanarLoopConstraint)}, sys, sol, t)
# TODO: change to cylinder
r_0 = collect(sys.frame_a.r_0)
n = collect(sys.n)
thing = @lift begin
# radius = sol($t, idxs=sys.radius)
O = sol($t, idxs=collect(sys.frame_a.r_0))
n_a = sol($t, idxs=collect(sys.n))
R_w_a = get_frame(sol, sys.frame_a, $t)[1:3, 1:3]
n_w = R_w_a*n_a # Rotate to the world frame
O = sol($t, idxs=r_0)
n_a = sol($t, idxs=n)
R_w_a = get_rot(sol, sys.frame_a, $t)
n_w = R_w_a'*n_a # Rotate to the world frame
radius = try
sol($t, idxs=sys.radius)
catch
0.02f0
end
0.05f0
end |> Float32
p1 = Point3f(O + radius*n_w)
p2 = Point3f(O - radius*n_w)
Makie.GeometryBasics.Cylinder(p1, p2, radius)
Expand All @@ -189,8 +198,8 @@ function render!(scene, ::typeof(Revolute), sys, sol, t)
end

function render!(scene, ::typeof(Spherical), sys, sol, t)
vars = collect(sys.frame_a.r_0)
thing = @lift begin
vars = collect(sys.frame_a.r_0)
coords = sol($t, idxs=vars)
point = Point3f(coords)
Sphere(point, 0.1)
Expand All @@ -203,9 +212,11 @@ render!(scene, ::typeof(FreeMotion), sys, sol, t) = true


function render!(scene, ::typeof(FixedTranslation), sys, sol, t)
r_0a = collect(sys.frame_a.r_0)
r_0b = collect(sys.frame_b.r_0)
thing = @lift begin
r1 = Point3f(sol($t, idxs=collect(sys.frame_a.r_0)))
r2 = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
r1 = Point3f(sol($t, idxs=r_0a))
r2 = Point3f(sol($t, idxs=r_0b))
origin = r1#(r1+r2) ./ 2
extremity = r2#-r1 # Double pendulum is a good test for this
radius = Float32(sol($t, idxs=sys.radius))
Expand All @@ -216,9 +227,11 @@ function render!(scene, ::typeof(FixedTranslation), sys, sol, t)
end

function render!(scene, ::typeof(BodyShape), sys, sol, t)
r_0a = collect(sys.frame_a.r_0)
r_0b = collect(sys.frame_b.r_0)
thing = @lift begin
r1 = Point3f(sol($t, idxs=collect(sys.frame_a.r_0)))
r2 = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
r1 = Point3f(sol($t, idxs=r_0a))
r2 = Point3f(sol($t, idxs=r_0b))
origin = r1
extremity = r2
radius = Float32(sol($t, idxs=sys.radius))
Expand All @@ -244,9 +257,11 @@ end


function render!(scene, ::typeof(Damper), sys, sol, t)
r_0a = collect(sys.frame_a.r_0)
r_0b = collect(sys.frame_b.r_0)
thing = @lift begin
r1 = Point3f(sol($t, idxs=collect(sys.frame_a.r_0)))
r2 = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
r1 = Point3f(sol($t, idxs=r_0a))
r2 = Point3f(sol($t, idxs=r_0b))
origin = r1
d = r2 - r1
extremity = d / norm(d) * 0.2f0 + r1
Expand All @@ -259,9 +274,11 @@ end


function render!(scene, ::typeof(Spring), sys, sol, t)
r_0a = collect(sys.frame_a.r_0)
r_0b = collect(sys.frame_b.r_0)
thing = @lift begin
r1 = Point3f(sol($t, idxs=collect(sys.frame_a.r_0)))
r2 = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
r1 = Point3f(sol($t, idxs=r_0a))
r2 = Point3f(sol($t, idxs=r_0b))
spring_mesh(r1,r2)
end
plot!(scene, thing, color=:blue)
Expand All @@ -271,10 +288,12 @@ end

function render!(scene, ::Function, sys, sol, t, args...) # Fallback for systems that have at least two frames
count(ModelingToolkit.isframe, sys.systems) == 2 || return false
r_0a = collect(sys.frame_a.r_0)
r_0b = collect(sys.frame_b.r_0)
try
thing = @lift begin
r1 = Point3f(sol($t, idxs=collect(sys.frame_a.r_0)))
r2 = Point3f(sol($t, idxs=collect(sys.frame_b.r_0)))
r1 = Point3f(sol($t, idxs=r_0a))
r2 = Point3f(sol($t, idxs=r_0b))
origin = r1
extremity = r2
radius = 0.05f0
Expand Down
Loading
Loading