Skip to content

Commit 265a949

Browse files
committed
namespace updates
1 parent 7b9d31e commit 265a949

File tree

2 files changed

+42
-55
lines changed

2 files changed

+42
-55
lines changed

docs/src/examples/pendulum.md

Lines changed: 40 additions & 53 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ D = Differential(t)
6565
defs = Dict() # We may specify the initial condition here
6666
prob = ODEProblem(ssys, defs, (0, 3.35))
6767
68-
sol = solve(prob, Rodas4())
68+
sol = solve(prob, Tsit5())
6969
plot(sol, idxs = joint.phi, title="Pendulum")
7070
```
7171
The solution `sol` can be plotted directly if the Plots package is loaded. The figure indicates that the pendulum swings back and forth without any damping. To add damping as well, we could add a `Damper` from the `ModelingToolkitStandardLibrary.Mechanical.Rotational` module to the revolute joint. We do this below
@@ -74,7 +74,7 @@ The solution `sol` can be plotted directly if the Plots package is loaded. The f
7474
Multibody.jl supports automatic 3D rendering of mechanisms, we use this feature to illustrate the result of the simulation below:
7575

7676
```@example pendulum
77-
import GLMakie # GLMakie is another alternative, suitable for interactive plots
77+
import GLMakie
7878
Multibody.render(model, sol; filename = "pendulum.gif") # Use "pendulum.mp4" for a video file
7979
nothing # hide
8080
```
@@ -95,12 +95,11 @@ connections = [connect(world.frame_b, joint.frame_a)
9595
connect(body.frame_a, joint.frame_b)]
9696
9797
@named model = System(connections, t, systems = [world, joint, body, damper])
98-
model = complete(model)
9998
ssys = multibody(model)
10099
101-
prob = ODEProblem(ssys, [damper.phi_rel => 1], (0, 10))
100+
prob = ODEProblem(ssys, [], (0, 10))
102101
103-
sol = solve(prob, Rodas4())
102+
sol = solve(prob, Tsit5())
104103
plot(sol, idxs = joint.phi, title="Damped pendulum")
105104
```
106105
This time we see that the pendulum loses energy and eventually comes to rest at the stable equilibrium point ``\pi / 2``.
@@ -128,12 +127,11 @@ connections = [connect(world.frame_b, joint.frame_a)
128127
connect(body_0.frame_a, joint.frame_b)]
129128
130129
@named model = System(connections, t, systems = [world, joint, body_0, damper, spring])
131-
model = complete(model)
132130
ssys = multibody(model)
133131
134-
prob = ODEProblem(ssys, [], (0, 10))
132+
prob = ODEProblem(ssys, [ssys.joint.s => 0, ssys.joint.v => 0], (0, 10))
135133
136-
sol = solve(prob, Rodas4())
134+
sol = solve(prob, Tsit5())
137135
Plots.plot(sol, idxs = joint.s, title="Mass-spring-damper system")
138136
```
139137

@@ -155,14 +153,13 @@ connections = [connect(world.frame_b, multibody_spring.frame_a)
155153
connect(root_body.frame_a, multibody_spring.frame_b)]
156154
157155
@named model = System(connections, t, systems = [world, multibody_spring, root_body])
158-
model = complete(model)
159156
ssys = multibody(model)
160157
161-
defs = Dict(root_body.r_0 .=> [0, 1e-3, 0]) # The spring has a singularity at zero length, so we start some distance away
158+
defs = Dict(collect(ssys.root_body.r_0) .=> [0, 1e-3, 0]) # The spring has a singularity at zero length, so we start some distance away
162159
163160
prob = ODEProblem(ssys, defs, (0, 10))
164161
165-
sol = solve(prob, Rodas4())
162+
sol = solve(prob, Tsit5())
166163
plot(sol, idxs = multibody_spring.r_rel_0[2], title="Mass-spring system without joint")
167164
```
168165
Here, we used a [`Multibody.Spring`](@ref) instead of connecting a `Translational.Spring` to a joint. The `Translational.Spring`, alongside other components from `ModelingToolkitStandardLibrary.Mechanical`, is a 1-dimensional object, whereas multibody components are 3-dimensional objects.
@@ -173,7 +170,6 @@ push!(connections, connect(multibody_spring.spring2d.flange_a, damper.flange_a))
173170
push!(connections, connect(multibody_spring.spring2d.flange_b, damper.flange_b))
174171
175172
@named model = System(connections, t, systems = [world, multibody_spring, root_body, damper])
176-
model = complete(model)
177173
ssys = multibody(model)
178174
prob = ODEProblem(ssys, defs, (0, 10))
179175
@@ -224,18 +220,17 @@ import Multibody.Rotations
224220
end
225221
226222
@named model = FurutaPendulum()
227-
model = complete(model)
228223
ssys = multibody(model)
229224
230-
prob = ODEProblem(ssys, [model.shoulder_joint.phi => 0.0, model.elbow_joint.phi => 0.1], (0, 10))
231-
sol = solve(prob, Rodas4())
225+
prob = ODEProblem(ssys, [ssys.shoulder_joint.phi => 0.0, ssys.elbow_joint.phi => 0.1], (0, 10))
226+
sol = solve(prob, Tsit5())
232227
plot(sol, layout=4)
233228
```
234229

235230
In the animation below, we visualize the path that the origin of the pendulum tip traces by providing the tip frame in a vector of frames passed to `traces`
236231
```@example pendulum
237232
import GLMakie
238-
Multibody.render(model, sol, filename = "furuta.gif", traces=[model.tip.frame_a])
233+
Multibody.render(model, sol, filename = "furuta.gif", traces=[ssys.tip.frame_a])
239234
nothing # hide
240235
```
241236
![furuta](furuta.gif)
@@ -245,11 +240,11 @@ nothing # hide
245240
Let's break down how to think about directions and orientations when building 3D mechanisms. In the example above, we started with the shoulder joint, this joint rotated around the gravitational axis, `n = [0, 1, 0]`. When this joint is positioned in joint coordinate `shoulder_joint.phi = 0`, its `frame_a` and `frame_b` will coincide. When the joint rotates, `frame_b` will rotate around the axis `n` of `frame_a`. The `frame_a` of the joint is attached to the world, so the joint will rotate around the world's `y`-axis:
246241

247242
```@example pendulum
248-
get_rot(sol, model.shoulder_joint.frame_b, 0)
243+
get_rot(sol, ssys.shoulder_joint.frame_b, 0)
249244
```
250245
we see that at time $t = 0$, we have no rotation of `frame_b` around the $y$ axis of the world (frames are always resolved in the world frame), but a second into the simulation, we have:
251246
```@example pendulum
252-
R1 = get_rot(sol, model.shoulder_joint.frame_b, 1)
247+
R1 = get_rot(sol, ssys.shoulder_joint.frame_b, 1)
253248
```
254249
Here, the `frame_b` has rotated around the $y$ axis of the world (if you are not familiar with rotation matrices, we can ask for the rotation axis and angle)
255250
```@example pendulum
@@ -259,7 +254,7 @@ rotation_axis(R1), rotation_angle(R1)
259254

260255
This rotation axis and angle should correspond to the joint coordinate (the orientation described by an axis and an angle is invariant to a multiplication of both by -1)
261256
```@example pendulum
262-
sol(1, idxs=model.shoulder_joint.phi)
257+
sol(1, idxs=ssys.shoulder_joint.phi)
263258
```
264259

265260
!!! note "Convention"
@@ -271,25 +266,25 @@ Here, we made use of the function [`get_rot`](@ref), we will now make use of als
271266

272267
The next body is the upper arm. This body has an extent of `0.6` in the $z$ direction, as measured in its local `frame_a`
273268
```@example pendulum
274-
get_trans(sol, model.upper_arm.frame_b, 0)
269+
get_trans(sol, ssys.upper_arm.frame_b, 0)
275270
```
276271
One second into the simulation, the upper arm has rotated around the $y$ axis of the world
277272
```@example pendulum
278-
rb1 = get_trans(sol, model.upper_arm.frame_b, 1)
273+
rb1 = get_trans(sol, ssys.upper_arm.frame_b, 1)
279274
```
280275

281-
If we look at the variable `model.upper_arm.r`, we do not see this rotation!
276+
If we look at the variable `ssys.upper_arm.r`, we do not see this rotation!
282277
```@example pendulum
283-
arm_r = sol(1, idxs=model.upper_arm.r)
278+
arm_r = sol(1, idxs=ssys.upper_arm.r)
284279
```
285280
The reason is that this variable is resolved in the local `frame_a` and not in the world frame. To transform this variable to the world frame, we may multiply with the rotation matrix of `frame_a` which is always resolved in the world frame:
286281
```@example pendulum
287-
get_rot(sol, model.upper_arm.frame_a, 1)*arm_r
282+
get_rot(sol, ssys.upper_arm.frame_a, 1)*arm_r
288283
```
289284
We now get the same result has when we asked for the translation vector of `frame_b` above.
290285
```@example pendulum
291286
using Test # hide
292-
get_rot(sol, model.upper_arm.frame_a, 1)*arm_r ≈ rb1 # hide
287+
get_rot(sol, ssys.upper_arm.frame_a, 1)*arm_r ≈ rb1 # hide
293288
nothing # hide
294289
```
295290

@@ -300,23 +295,23 @@ The next joint, the elbow joint, has the rotational axis `n = [0, 0, 1]`. This i
300295

301296
The lower arm is finally having an extent along the $y$-axis. At the final time when the pendulum motion has been fully damped, we see that the second frame of this body ends up with an $y$-coordinate of `-0.6`:
302297
```@example pendulum
303-
get_trans(sol, model.lower_arm.frame_b, 12)
298+
get_trans(sol, ssys.lower_arm.frame_b, 12)
304299
```
305300

306301
If we rotate the vector of extent of the lower arm to the world frame, we indeed see that the only coordinate that is nonzero is the $y$ coordinate:
307302
```@example pendulum
308-
get_rot(sol, model.lower_arm.frame_a, 12)*sol(12, idxs=model.lower_arm.r)
303+
get_rot(sol, ssys.lower_arm.frame_a, 12)*sol(12, idxs=ssys.lower_arm.r)
309304
```
310305

311-
The reason that the latter vector differs from `get_trans(sol, model.lower_arm.frame_b, 12)` above is that `get_trans(sol, model.lower_arm.frame_b, 12)` has been _translated_ as well. To both translate and rotate `model.lower_arm.r` into the world frame, we must use the full transformation matrix $T_W^A \in SE(3)$:
306+
The reason that the latter vector differs from `get_trans(sol, ssys.lower_arm.frame_b, 12)` above is that `get_trans(sol, ssys.lower_arm.frame_b, 12)` has been _translated_ as well. To both translate and rotate `ssys.lower_arm.r` into the world frame, we must use the full transformation matrix $T_W^A \in SE(3)$:
312307

313308
```@example pendulum
314-
r_A = sol(12, idxs=model.lower_arm.r)
309+
r_A = sol(12, idxs=ssys.lower_arm.r)
315310
r_A = [r_A; 1] # Homogeneous coordinates
316311
317-
get_frame(sol, model.lower_arm.frame_a, 12)*r_A
312+
get_frame(sol, ssys.lower_arm.frame_a, 12)*r_A
318313
```
319-
the vector is now coinciding with `get_trans(sol, model.lower_arm.frame_b, 12)`.
314+
the vector is now coinciding with `get_trans(sol, ssys.lower_arm.frame_b, 12)`.
320315

321316

322317
## Control-design example: Pendulum on cart
@@ -336,12 +331,7 @@ using Plots
336331
gray = [0.5, 0.5, 0.5, 1]
337332
@component function Cartpole(; name, use_world = false)
338333
systems = @named begin
339-
if use_world
340-
fixed = World()
341-
else
342-
# In case we wrap this model in an outer model below, we place the world there instead
343-
fixed = Fixed()
344-
end
334+
fixed = Fixed()
345335
cart = BodyShape(m = 1, r = [0.2, 0, 0], color=[0.2, 0.2, 0.2, 1], shape="box")
346336
mounting_point = FixedTranslation(r = [0.1, 0, 0])
347337
prismatic = Prismatic(n = [1, 0, 0], axisflange = true, color=gray, state_priority=100)
@@ -352,7 +342,7 @@ gray = [0.5, 0.5, 0.5, 1]
352342
end
353343
354344
vars = @variables begin
355-
u(t) = 0
345+
u(t)
356346
x(t)
357347
v(t)
358348
phi(t)
@@ -374,7 +364,7 @@ gray = [0.5, 0.5, 0.5, 1]
374364
w ~ revolute.w
375365
]
376366
377-
return System(equations, t; name, systems)
367+
return System(equations, t, vars, []; name, systems)
378368
end
379369
@component function CartWithInput(; name)
380370
systems = @named begin
@@ -390,16 +380,15 @@ end
390380
return System(equations, t; name, systems)
391381
end
392382
@named model = CartWithInput()
393-
model = complete(model)
394383
ssys = multibody(model)
395-
prob = ODEProblem(ssys, [model.cartpole.prismatic.s => 0.0, model.cartpole.revolute.phi => 0.1], (0, 10))
384+
prob = ODEProblem(ssys, [ssys.cartpole.prismatic.s => 0.0, ssys.cartpole.prismatic.v => 0.0, ssys.cartpole.revolute.phi => 0.1], (0, 10))
396385
sol = solve(prob, Tsit5())
397386
plot(sol, layout=4)
398387
```
399388
As usual, we render the simulation in 3D to get a better feel for the system:
400389
```@example pendulum
401390
import GLMakie
402-
Multibody.render(model, sol, filename = "cartpole.gif", traces=[model.cartpole.pendulum.frame_b])
391+
Multibody.render(model, sol, filename = "cartpole.gif", traces=[ssys.cartpole.pendulum.frame_b])
403392
nothing # hide
404393
```
405394
![cartpole](cartpole.gif)
@@ -413,7 +402,7 @@ We start by linearizing the model in the upward equilibrium position using the f
413402
```@example pendulum
414403
import ModelingToolkit: D_nounits as D
415404
using LinearAlgebra
416-
@named cp = Cartpole(use_world = true)
405+
@named cp = Cartpole()
417406
cp = complete(cp)
418407
inputs = [cp.u] # Input to the linearized system
419408
outputs = [cp.x, cp.phi, cp.v, cp.w] # These are the outputs of the linearized system
@@ -422,13 +411,13 @@ op = Dict([ # Operating point to linearize in
422411
cp.revolute.phi => 0 # Pendulum pointing upwards
423412
]
424413
)
425-
matrices, simplified_sys = linearize(multibody(cp), inputs, outputs; op)
414+
matrices, simplified_sys = linearize(cp, inputs, outputs; op)
426415
matrices
427416
```
428417
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:
429418
```@example pendulum
430419
using ControlSystemsMTK
431-
lsys = named_ss(multibody(cp), inputs, outputs; op) # identical to linearize, but packages the resulting matrices in a named statespace object for convenience
420+
lsys = named_ss(cp, inputs, outputs; op) # identical to linearize, but packages the resulting matrices in a named statespace object for convenience
432421
```
433422

434423
### LQR and LQG Control design
@@ -486,13 +475,12 @@ LQGSystem(args...; kwargs...) = System(Ce; kwargs...)
486475
return System(equations, t; name, systems)
487476
end
488477
@named model = CartWithFeedback()
489-
model = complete(model)
490478
ssys = multibody(model)
491-
prob = ODEProblem(ssys, [model.cartpole.prismatic.s => 0.1, model.cartpole.revolute.phi => 0.35], (0, 12))
479+
prob = ODEProblem(ssys, [ssys.cartpole.prismatic.s => 0.1, ssys.cartpole.revolute.phi => 0.35], (0, 12))
492480
sol = solve(prob, Tsit5())
493-
cp = model.cartpole
481+
cp = ssys.cartpole
494482
plot(sol, idxs=[cp.prismatic.s, cp.revolute.phi, cp.motor.f.u], layout=3)
495-
plot!(sol, idxs=model.reference.output.u, sp=1, l=(:black, :dash), legend=:bottomright)
483+
plot!(sol, idxs=ssys.reference.output.u, sp=1, l=(:black, :dash), legend=:bottomright)
496484
```
497485

498486
```@example pendulum
@@ -557,14 +545,13 @@ normalize_angle(x::Number) = mod(x+3.1415, 2pi)-3.1415
557545
return System(equations, t; name, systems)
558546
end
559547
@named model = CartWithSwingup()
560-
model = complete(model)
561548
ssys = multibody(model)
562-
cp = model.cartpole
549+
cp = ssys.cartpole
563550
prob = ODEProblem(ssys, [cp.prismatic.s => 0.0, cp.revolute.phi => 0.99pi], (0, 5))
564551
sol = solve(prob, Tsit5(), dt = 1e-2, adaptive=false)
565-
plot(sol, idxs=[cp.prismatic.s, cp.revolute.phi, cp.motor.f.u, model.E], layout=4)
552+
plot(sol, idxs=[cp.prismatic.s, cp.revolute.phi, cp.motor.f.u, ssys.E], layout=4)
566553
hline!([0, 2pi], sp=2, l=(:black, :dash), primary=false)
567-
plot!(sol, idxs=[model.switching_condition], sp=2)
554+
plot!(sol, idxs=[ssys.switching_condition], sp=2)
568555
```
569556

570557

src/orientation.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -372,12 +372,12 @@ function resolve_dyade2(R, D1)
372372
R*D1*R'
373373
end
374374

375-
function is_frame(x)
375+
function is_frame(frame)
376376
md = get_metadata(frame)
377377
get(md, Multibody.ModelingToolkit.IsFrame, false)
378378
end
379379

380-
function is_frame_2d(x)
380+
function is_frame_2d(frame)
381381
md = get_metadata(frame)
382382
get(md, Multibody.PlanarMechanics.IsFrame2D, false)
383383
end

0 commit comments

Comments
 (0)