Skip to content

Commit b10750a

Browse files
committed
adding mechanism building tutorial
1 parent ae22b3e commit b10750a

File tree

9 files changed

+122
-50
lines changed

9 files changed

+122
-50
lines changed

docs/src/assets/logo.png

27.1 KB
Loading

docs/src/assets/tippetop_real.gif

1.6 MB
Loading

docs/src/define_mechanism.md

Lines changed: 99 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,102 @@
11
# Defining a Mechanism
22
Here, we describe how to define your own dynamical system of [`Mechanism`](@ref). After it has been defined, it will be extremely easy to simulate it, control it, perform trajectory optimization on it, or even policy optimization.
33

4-
We're going to build a tippe top.
4+
We're going to build a tippe top,
5+
6+
7+
```@raw html
8+
<img src="./assets/tippetop_real.gif" width="300"/>
9+
```
10+
11+
```@raw html
12+
<img src="./../../examples/animations/tippetop.gif" width="300"/>
13+
```
14+
15+
### Build Mechanism
16+
17+
To do this, we need to define two methods. The first one is named `get_...` where `...` is the name of the mechanism. So here we define `get_tippetop`. This function return a [`Mechanism`](@ref) and takes as input a variety of parameters like the simulation time step, gravity etc. You can add as many parameters you want. This example is typical of what you will find in Dojo.
18+
19+
To build the mechanism corresponding to the tippe top, we decompose it into two spherical bodies. Each body has its own spherical contact constraint with the floor. The joint between the two bodies is a `fixed_joint` and the joint between the main body and the [`Origin`](@ref) of the frame is a floating joint.
20+
21+
```julia
22+
function get_tippetop(;
23+
timestep=0.01,
24+
gravity=[0.0; 0.0; -9.81],
25+
friction_coefficient=0.4,
26+
contact_type=:nonlinear,
27+
T=Float64)
28+
29+
# define origin
30+
origin = Origin{T}(name=:origin)
31+
# define the two bodies which will form the tippe top once assembled
32+
radius = 0.5
33+
mass = 1.0
34+
α = 0.2
35+
bodies = [
36+
Sphere(radius, mass, name=:sphere1, color=gray_light),
37+
Sphere(radius*α, mass*α^3, name=:sphere2, color=gray_light)]
38+
# modify inertia of the first body to ensure we obtain the desired behavior
39+
bodies[1].inertia = Diagonal([1.9, 2.1, 2.0])
40+
41+
# define the joints, the 1st joint is between Origin and :sphere1
42+
# the 2nd joint is between :sphere1 and :sphere2
43+
joints = [
44+
JointConstraint(Floating(origin, bodies[1]),
45+
name=:floating_joint),
46+
JointConstraint(Fixed(bodies[1], bodies[2],
47+
parent_vertex=[0,0,radius],
48+
child_vertex=zeros(3)),
49+
name = :fixed_joint)]
50+
51+
# define the two spherical contacts, each contact is attached to a body.
52+
contact_point = [0.0, 0.0, 0.0] # both contact spheres are located at the center of the bodies they are attached to.
53+
normal = [0.0, 0.0, 1.0] # the normal of the contact is always pointing in the upright direction because the floor is flat.
54+
# we specify the type of contact (impact, linear, nonlinear), the coefficient of friction, the radius of the contact sphere, etc.
55+
contacts = [
56+
contact_constraint(get_body(mechanism, :sphere1), normal,
57+
friction_coefficient=friction_coefficient,
58+
contact_point=contact_point, offset=[0.0, 0.0, radius],
59+
contact_type=contact_type),
60+
contact_constraint(get_body(mechanism, :sphere2), normal,
61+
friction_coefficient=friction_coefficient,
62+
contact_point=contact_point,
63+
offset=[0.0, 0.0, radius * α],
64+
contact_type=contact_type)
65+
]
66+
67+
# we build the mechanism by combining together the the origin, the bodies, the joints, and the contacts.
68+
mechanism = Mechanism(origin, bodies, joints, contacts,
69+
gravity=gravity,
70+
timestep=timestep)
71+
72+
# we make sure that the mechanism is never initialized with its contact spheres below the ground.
73+
set_minimal_coordinates!(mechanism, get_joint(mechanism, :floating_joint), [0.0; 0.0; radius; zeros(3)])
74+
return mechanism
75+
end
76+
```
77+
78+
### Initialize Mechanism
79+
The second method that we need to define is `initialize_...` where `...` is the name of the mechanism. So here we define `initialize_tippetop`. This function initialize the dynamical system to a certain state. This means that we set the position orientation, linear and angular velocity of each body in the mechanism.
80+
81+
82+
```julia
83+
function initialize_tippetop!(mechanism::Mechanism{T};
84+
x=zeros(3),
85+
θ=zeros(3),
86+
v=zeros(3),
87+
ω=zeros(3)) where T
88+
89+
# we retrieve the joints from the mechanism by their names
90+
floating_joint = get_joint(mechanism, :floating_joint)
91+
fixed_joint = get_joint(mechanism, :fixed_joint)
92+
radius = fixed_joint.translational.vertices[1][3]
93+
94+
# we set all the bodies' velocities to zeros
95+
zero_velocity!(mechanism)
96+
# we set to minimal coordinates of the floating joint
97+
set_minimal_coordinates_velocities!(mechanism, floating_joint, xmin=[x; θ; v; ω])
98+
# we set to minimal coordinates of the fixed joint (this joint has zero minimal coordinate).
99+
set_minimal_coordinates_velocities!(mechanism, fixed_joint)
100+
return nothing
101+
end
102+
```

environments/tippetop/methods/initialize.jl

Lines changed: 18 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -10,12 +10,17 @@ function get_tippetop(;
1010
radius = 0.5
1111
mass = 1.0
1212
α = 0.2
13-
bodies = [Sphere(radius, mass, name=:sphere1, color=cyan), Sphere(radius*α, mass*α^3, name=:sphere2, color=cyan)]
14-
joints = [JointConstraint(Floating(origin, bodies[1]),
13+
bodies = [
14+
Sphere(radius, mass, name=:sphere1, color=gray_light),
15+
Sphere(radius*α, mass*α^3, name=:sphere2, color=gray_light)]
16+
17+
joints = [
18+
JointConstraint(Floating(origin, bodies[1]),
1519
name=:floating_joint),
16-
JointConstraint(Fixed(bodies[1], bodies[2],
20+
JointConstraint(Fixed(bodies[1], bodies[2],
1721
parent_vertex=[0,0,radius],
18-
child_vertex=zeros(3)), name = :fixed_joint),]
22+
child_vertex=zeros(3)),
23+
name = :fixed_joint)]
1924
mechanism = Mechanism(origin, bodies, joints,
2025
timestep=timestep,
2126
gravity=gravity)
@@ -24,16 +29,16 @@ function get_tippetop(;
2429
mechanism.bodies[1].inertia = Diagonal([1.9, 2.1, 2.0])
2530

2631
if contact
27-
contact = [0.0, 0.0, 0.0]
32+
contact_point = [0.0, 0.0, 0.0]
2833
normal = [0.0, 0.0, 1.0]
2934
contacts = [
3035
contact_constraint(get_body(mechanism, :sphere1), normal,
3136
friction_coefficient=friction_coefficient,
32-
contact_point=contact, offset=[0.0, 0.0, radius],
37+
contact_point=contact_point, offset=[0.0, 0.0, radius],
3338
contact_type=contact_type),
3439
contact_constraint(get_body(mechanism, :sphere2), normal,
3540
friction_coefficient=friction_coefficient,
36-
contact_point=contact,
41+
contact_point=contact_point,
3742
offset=[0.0, 0.0, radius * α],
3843
contact_type=contact_type)
3944
]
@@ -48,48 +53,16 @@ end
4853

4954
function initialize_tippetop!(mechanism::Mechanism{T};
5055
x=zeros(3),
51-
q=one(UnitQuaternion),
56+
θ=zeros(3),
5257
v=zeros(3),
5358
ω=zeros(3)) where T
5459

55-
joint2 = get_joint(mechanism, :fixed_joint)
56-
radius = joint2.translational.vertices[1][3]
57-
origin = mechanism.origin
58-
pbody = get_body(mech, :sphere1)
59-
cbody = get_body(mech, :sphere2)
60+
floating_joint = get_joint(mechanism, :floating_joint)
61+
fixed_joint = get_joint(mechanism, :fixed_joint)
62+
radius = fixed_joint.translational.vertices[1][3]
6063

6164
zero_velocity!(mechanism)
62-
63-
set_maximal_configurations!(origin, pbody;
64-
parent_vertex=[0.0; 0.0; radius],
65-
child_vertex=[0.0; 0.0; 0.0],
66-
Δx=x,
67-
Δq=q)
68-
set_maximal_configurations!(pbody, cbody;
69-
parent_vertex=[0.0; 0.0; radius],
70-
child_vertex=[0.0; 0.0; 0.0],
71-
Δx=[0.0; 0.0; 0.0],
72-
Δq=one(UnitQuaternion))
73-
set_maximal_velocities!(origin, pbody;
74-
parent_vertex=[0.0; 0.0; radius],
75-
child_vertex=[0.0; 0.0; 0.0],
76-
Δv=v,
77-
Δω=ω)
78-
set_maximal_velocities!(pbody, cbody;
79-
parent_vertex=[0.0; 0.0; radius],
80-
child_vertex=[0.0; 0.0; 0.0],
81-
Δv=[0.0; 0.0; 0.0],
82-
Δω=[0.0; 0.0; 0.0])
65+
set_minimal_coordinates_velocities!(mechanism, floating_joint, xmin=[x; θ; v; ω])
66+
set_minimal_coordinates_velocities!(mechanism, fixed_joint)
8367
return nothing
8468
end
85-
86-
87-
88-
mech = get_tippetop(timestep=0.01)
89-
initialize!(mech, :tippetop, ω=[0,0.05,5.0])
90-
91-
storage = simulate!(mech, 3.0, verbose=false, record=true)
92-
93-
# vis = Visualizer()
94-
# open(vis)
95-
visualize(mech, storage, vis=vis)

examples/animations/tippetop.gif

4.05 MB
Loading

examples/animations/tippetop.mp4

133 KB
Binary file not shown.

examples/simulation/tippetop.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ mech = get_mechanism(:tippetop,
1616
# ## Simulate
1717
initialize!(mech, :tippetop,
1818
x=[0.0, 0.0, 1.0],
19-
q=UnitQuaternion(RotX(0.01 * π)),
19+
θ=[0,0.01,0],
2020
ω=[0.0, 0.01, 50.0])
2121

2222
storage = simulate!(mech, 10.0,
@@ -25,6 +25,6 @@ storage = simulate!(mech, 10.0,
2525
opts=SolverOptions(verbose=false, btol=1e-5))
2626

2727
# ## Open visualizer
28-
vis = Visualizer()
29-
render(vis)
28+
# vis = Visualizer()
29+
# render(vis)
3030
visualize(mech, storage, vis=vis)

src/visuals/colors.jl

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,3 +8,4 @@ gray = RGBA(0.7, 0.7, 0.7, 1.0)
88
orange_light = RGBA(1.0, 153.0 / 255.0 + 0.2, 51.0 / 255.0 + 0.2, 1.0)
99
cyan_light = RGBA(51.0 / 255.0 + 0.6, 1.0, 1.0, 1.0)
1010
magenta_light = RGBA(255.0 / 255.0, 0.75, 255.0 / 255.0, 1.0)
11+
gray_light = RGBA(0.9, 0.9, 0.9, 1.0)

src/visuals/convert.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,4 +38,4 @@ function convert_frames_to_video_and_gif(filename, overwrite::Bool=true)
3838
homedir() * "/Documents/video/$filename.mp4",
3939
homedir() * "/Documents/video/$filename.gif", overwrite=overwrite)
4040
return nothing
41-
end
41+
end

0 commit comments

Comments
 (0)