Skip to content

Commit

Permalink
Multibody validity check (#168)
Browse files Browse the repository at this point in the history
* add multibody check function

* use multibody check function

* better world handling in examples and tests

* remove hacky `W` world constructor

* add support for planar mechanics in `multibody`

* handle components without gui metadata
  • Loading branch information
baggepinnen authored Oct 3, 2024
1 parent 3bf6cf6 commit fffb39d
Show file tree
Hide file tree
Showing 33 changed files with 198 additions and 178 deletions.
4 changes: 2 additions & 2 deletions docs/src/examples/free_motion.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ eqs = [connect(world.frame_b, freeMotion.frame_a)
systems = [world;
freeMotion;
body])
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [], (0, 10))
Expand Down Expand Up @@ -69,7 +69,7 @@ eqs = [connect(bar2.frame_a, world.frame_b)
spring2,
])
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [
collect(body.body.v_0 .=> 0);
collect(body.body.w_a .=> 0);
Expand Down
2 changes: 1 addition & 1 deletion docs/src/examples/gearbox.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ eqs = [connect(world.frame_b, gearConstraint.bearing)
@named model = ODESystem(eqs, t, systems = [world; systems])
cm = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [
D(cm.idealGear.phi_b) => 0
cm.idealGear.phi_b => 0
Expand Down
2 changes: 1 addition & 1 deletion docs/src/examples/gyroscopic_effects.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ connections = [
@named model = ODESystem(connections, t, systems = [world; systems])
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [model.world.g => 9.80665, model.revolute.w => 10], (0, 5))
Expand Down
6 changes: 3 additions & 3 deletions docs/src/examples/kinematic_loops.md
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ connections = [
]
@named fourbar = ODESystem(connections, t, systems = [world; systems])
fourbar = complete(fourbar)
ssys = structural_simplify(IRSystem(fourbar))
ssys = structural_simplify(multibody(fourbar))
prob = ODEProblem(ssys, [fourbar.j1.phi => 0.1], (0.0, 10.0))
sol = solve(prob, FBDF(autodiff=true))
Expand Down Expand Up @@ -146,7 +146,7 @@ connections = [connect(j2.frame_b, b2.frame_a)
]
@named fourbar2 = ODESystem(connections, t, systems = [world; systems])
fourbar2 = complete(fourbar2)
ssys = structural_simplify(IRSystem(fourbar2))
ssys = structural_simplify(multibody(fourbar2))
prob = ODEProblem(ssys, [], (0.0, 1.4399)) # The end time is chosen to make the animation below appear to loop forever
Expand Down Expand Up @@ -187,7 +187,7 @@ connections = [connect(j2.frame_b, b2.frame_a)
@named fourbar_analytic = ODESystem(connections, t, systems = [world; systems])
fourbar_analytic = complete(fourbar_analytic)
ssys_analytic = structural_simplify(IRSystem(fourbar_analytic))
ssys_analytic = structural_simplify(multibody(fourbar_analytic))
prob = ODEProblem(ssys_analytic, [], (0.0, 1.4399))
sol2 = solve(prob, FBDF(autodiff=true)) # about 4x faster than the simulation above
plot!(sol2, idxs=[j2.s]) # Plot the same coordinate as above
Expand Down
33 changes: 18 additions & 15 deletions docs/src/examples/pendulum.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# Pendulum--The "Hello World of multi-body dynamics"
This beginners tutorial will start by modeling a pendulum pivoted around the origin in the world frame. The world frame is a constant that lives inside the Multibody module, all multibody models are "grounded" in the same world, i.e., the `world` component must be included in all models.
This beginners tutorial will start by modeling a pendulum pivoted around the origin in the world frame. The world frame is a constant that lives inside the Multibody module, all multibody models are "grounded" in the same world, i.e., the `world` component must be included exactly once in all models, at the top level.

To start, we load the required packages
```@example pendulum
Expand Down Expand Up @@ -47,12 +47,16 @@ nothing # hide
```
The `ODESystem` is the fundamental model type in ModelingToolkit used for multibody-type models.

Before we can simulate the system, we must perform model compilation using [`structural_simplify`](@ref)
Before we can simulate the system, we must perform model check using the function [`multibody`](@ref) and compilation using [`structural_simplify`](@ref)
```@example pendulum
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(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. To simulate the pendulum, we require two state variables, one for angle and one for angular velocity, we can see above that these state variables have indeed been chosen.

```@docs
multibody
```

We are now ready to create an `ODEProblem` and simulate it. We use the `Rodas4` solver from OrdinaryDiffEq.jl, and pass a dictionary for the initial conditions. We specify only initial condition for some variables, for those variables where no initial condition is specified, the default initial condition defined the model will be used.
```@example pendulum
D = Differential(t)
Expand Down Expand Up @@ -90,7 +94,7 @@ connections = [connect(world.frame_b, joint.frame_a)
@named model = ODESystem(connections, t, systems = [world, joint, body, damper])
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [damper.phi_rel => 1], (0, 10))
Expand Down Expand Up @@ -123,7 +127,7 @@ connections = [connect(world.frame_b, joint.frame_a)
@named model = ODESystem(connections, t, systems = [world, joint, body_0, damper, spring])
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [], (0, 10))
Expand All @@ -150,7 +154,7 @@ connections = [connect(world.frame_b, multibody_spring.frame_a)
@named model = ODESystem(connections, t, systems = [world, multibody_spring, root_body])
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
defs = Dict(collect(root_body.r_0) .=> [0, 1e-3, 0]) # The spring has a singularity at zero length, so we start some distance away
Expand All @@ -168,7 +172,7 @@ push!(connections, connect(multibody_spring.spring2d.flange_b, damper.flange_b))
@named model = ODESystem(connections, t, systems = [world, multibody_spring, root_body, damper])
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, defs, (0, 10))
sol = solve(prob, Rodas4(), u0 = prob.u0 .+ 1e-5 .* randn.())
Expand All @@ -186,11 +190,10 @@ This pendulum, sometimes referred to as a _rotary pendulum_, has two joints, one
using ModelingToolkit, Multibody, JuliaSimCompiler, OrdinaryDiffEq, Plots
import ModelingToolkitStandardLibrary.Mechanical.Rotational.Damper as RDamper
import Multibody.Rotations
W(args...; kwargs...) = Multibody.world
@mtkmodel FurutaPendulum begin
@components begin
world = W()
world = World()
shoulder_joint = Revolute(n = [0, 1, 0], axisflange = true)
elbow_joint = Revolute(n = [0, 0, 1], axisflange = true, phi0=0.1)
upper_arm = BodyShape(; m = 0.1, r = [0, 0, 0.6], radius=0.04)
Expand Down Expand Up @@ -218,7 +221,7 @@ end
@named model = FurutaPendulum()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [model.shoulder_joint.phi => 0.0, model.elbow_joint.phi => 0.1], (0, 10))
sol = solve(prob, Rodas4())
Expand Down Expand Up @@ -380,7 +383,7 @@ end
end
@named model = CartWithInput()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [model.cartpole.prismatic.s => 0.0, model.cartpole.revolute.phi => 0.1], (0, 10))
sol = solve(prob, Tsit5())
plot(sol, layout=4)
Expand Down Expand Up @@ -411,13 +414,13 @@ op = Dict([ # Operating point to linearize in
cp.revolute.phi => 0 # Pendulum pointing upwards
]
)
matrices, simplified_sys = linearize(IRSystem(cp), inputs, outputs; op)
matrices, simplified_sys = linearize(multibody(cp), inputs, outputs; op)
matrices
```
This gives us the matrices $A,B,C,D$ in a linearized statespace representation of the system. To make these easier to work with, we load the control packages and call `named_ss` instead of `linearize` to get a named statespace object instead:
```@example pendulum
using ControlSystemsMTK
lsys = named_ss(IRSystem(cp), inputs, outputs; op) # identical to linearize, but packages the resulting matrices in a named statespace object for convenience
lsys = named_ss(multibody(cp), inputs, outputs; op) # identical to linearize, but packages the resulting matrices in a named statespace object for convenience
```

### LQR Control design
Expand Down Expand Up @@ -466,7 +469,7 @@ LQGSystem(args...; kwargs...) = ODESystem(observer_controller(lqg); kwargs...)
end
@named model = CartWithFeedback()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [model.cartpole.prismatic.s => 0.1, model.cartpole.revolute.phi => 0.35], (0, 10))
sol = solve(prob, Tsit5())
cp = model.cartpole
Expand Down Expand Up @@ -533,7 +536,7 @@ normalize_angle(x::Number) = mod(x+3.1415, 2pi)-3.1415
end
@named model = CartWithSwingup()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
cp = model.cartpole
prob = ODEProblem(ssys, [cp.prismatic.s => 0.0, cp.revolute.phi => 0.99pi], (0, 5))
sol = solve(prob, Tsit5(), dt = 1e-2, adaptive=false)
Expand Down
6 changes: 3 additions & 3 deletions docs/src/examples/prescribed_pose.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ using Test
t = Multibody.t
D = Differential(t)
W(args...; kwargs...) = Multibody.world
n = [1, 0, 0]
AB = 146.5 / 1000
Expand Down Expand Up @@ -131,7 +131,7 @@ end
rod_radius = 0.02
end
@components begin
world = W()
world = World()
mass = Body(m=ms, r_cm = 0.5DA*normalize([0, 0.2, 0.2*sin(t5)]))
excited_suspension = ExcitedWheelAssembly(; rod_radius)
prescribed_motion = Pose(; r = [0, 0.1 + 0.1sin(t), 0], R = RotXYZ(0, 0.5sin(t), 0))
Expand All @@ -144,7 +144,7 @@ end
@named model = SuspensionWithExcitationAndMass()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
display([unknowns(ssys) diag(ssys.mass_matrix)])
defs = [
Expand Down
6 changes: 3 additions & 3 deletions docs/src/examples/quad.md
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ function RotorCraft(; closed_loop = true, addload=true, L=nothing, outputs = not
end
model = RotorCraft(closed_loop=true, addload=true, pid=true)
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
# display(unknowns(ssys))
op = [
model.body.v_0[1] => 0;
Expand Down Expand Up @@ -234,7 +234,7 @@ op = [
inputs .=> 1;
] |> Dict
@time lsys = named_ss(IRSystem(quad), inputs, outputs; op)
@time lsys = named_ss(multibody(quad), inputs, outputs; op)
rsys = minreal(sminreal(lsys))
C = rsys.C
rank(C) >= rsys.nx || @warn "The output matrix C is not full rank"
Expand Down Expand Up @@ -265,7 +265,7 @@ L
ModelingToolkit.get_iv(i::IRSystem) = i.t
model = RotorCraft(; closed_loop=true, addload=true, L=-L, outputs) # Negate L for negative feedback
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
op = [
model.body.r_0[2] => 1e-3
Expand Down
2 changes: 1 addition & 1 deletion docs/src/examples/robot.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ 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))
ssys = structural_simplify(multibody(robot))
unknowns(ssys)
```

Expand Down
6 changes: 3 additions & 3 deletions docs/src/examples/ropes_and_cables.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ connections = [connect(world.frame_b, rope.frame_a)
@named stiff_rope = ODESystem(connections, t, systems = [world, body, rope])
stiff_rope = complete(stiff_rope)
ssys = structural_simplify(IRSystem(stiff_rope))
ssys = structural_simplify(multibody(stiff_rope))
prob = ODEProblem(ssys, [], (0, 5))
sol = solve(prob, Rodas4(autodiff=false))
@test SciMLBase.successful_retcode(sol)
Expand All @@ -55,7 +55,7 @@ connections = [connect(world.frame_b, rope.frame_a)
@named flexible_rope = ODESystem(connections, t, systems = [world, body, rope])
flexible_rope = complete(flexible_rope)
ssys = structural_simplify(IRSystem(flexible_rope))
ssys = structural_simplify(multibody(flexible_rope))
prob = ODEProblem(ssys, [], (0, 8))
sol = solve(prob, Rodas4(autodiff=false));
@test SciMLBase.successful_retcode(sol)
Expand Down Expand Up @@ -88,7 +88,7 @@ connections = [connect(world.frame_b, fixed.frame_a, chain.frame_a)
@named mounted_chain = ODESystem(connections, t, systems = [systems; world])
mounted_chain = complete(mounted_chain)
ssys = structural_simplify(IRSystem(mounted_chain))
ssys = structural_simplify(multibody(mounted_chain))
prob = ODEProblem(ssys, [
collect(chain.link_8.body.w_a) .=> [0,0,0];
collect(chain.link_8.frame_b.r_0) .=> [x_dist,0,0];
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])
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
D = Differential(t)
Expand Down
5 changes: 2 additions & 3 deletions docs/src/examples/space.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,10 @@ using OrdinaryDiffEq
t = Multibody.t
D = Differential(t)
W(;kwargs...) = Multibody.world
@mtkmodel PointGrav begin
@components begin
world = W()
world = World()
body1 = Body(
m=1,
I_11=0.1,
Expand All @@ -50,7 +49,7 @@ W(;kwargs...) = Multibody.world
end
@named model = PointGrav()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
defs = [
model.world.mu => 1
model.world.point_gravity => true # The gravity model is selected here
Expand Down
2 changes: 1 addition & 1 deletion docs/src/examples/spherical_pendulum.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ connections = [connect(world.frame_b, joint.frame_a)
@named model = ODESystem(connections, t, systems = [world; systems])
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [], (0, 5))
Expand Down
2 changes: 1 addition & 1 deletion docs/src/examples/spring_damper_system.md
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ eqs = [connect(world.frame_b, bar1.frame_a)
damper1,
])
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys, [
damper1.d => 2;
Expand Down
2 changes: 1 addition & 1 deletion docs/src/examples/spring_mass_system.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ eqs = [
]
@named model = ODESystem(eqs, t, systems = [world; systems])
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
prob = ODEProblem(ssys,[], (0, 5))
sol = solve(prob, Rodas4())
Expand Down
13 changes: 6 additions & 7 deletions docs/src/examples/suspension.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ using Test
t = Multibody.t
D = Differential(t)
W(args...; kwargs...) = Multibody.world
n = [1, 0, 0]
AB = 146.5 / 1000
Expand Down Expand Up @@ -137,7 +136,7 @@ end
dir = mirror ? -1 : 1
end
@components begin
world = W()
world = World()
mass = Body(m=ms, r_cm = 0.5DA*normalize([0, 0.2, 0.2*sin(t5)*dir]))
excited_suspension = SuspensionWithExcitation(; suspension.spring=true, mirror, rod_radius)
body_upright = Prismatic(n = [0, 1, 0], render = false, state_priority=1000)
Expand All @@ -151,7 +150,7 @@ end
@named model = SuspensionWithExcitationAndMass()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
defs = [
model.body_upright.s => 0.17
Expand Down Expand Up @@ -230,7 +229,7 @@ end
@named model = DoubleSuspensionWithExcitationAndMass()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
defs = [
model.excited_suspension_r.amplitude => 0.05
Expand Down Expand Up @@ -343,7 +342,7 @@ end
@named model = SuspensionWithExcitationAndMass()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
display([unknowns(ssys) diag(ssys.mass_matrix)])
defs = [
Expand Down Expand Up @@ -398,7 +397,7 @@ end
@named model = HalfCar()
model = complete(model)
ssys = structural_simplify(IRSystem(model))
ssys = structural_simplify(multibody(model))
defs = [
model.excited_suspension_r.amplitude => 0.015
Expand Down Expand Up @@ -477,7 +476,7 @@ end
@named model = FullCar()
model = complete(model)
@time "simplification" ssys = structural_simplify(IRSystem(model))
@time "simplification" ssys = structural_simplify(multibody(model))
defs = [
model.excited_suspension_br.wheel.wheeljoint.v_small => 1e-3
Expand Down
Loading

0 comments on commit fffb39d

Please sign in to comment.