Skip to content

Commit e261bdb

Browse files
committed
adding urdf docs
1 parent 070c8b9 commit e261bdb

File tree

4 files changed

+47
-12
lines changed

4 files changed

+47
-12
lines changed

docs/src/assets/rexhopper.png

192 KB
Loading

docs/src/assets/rexhopper_contact.png

194 KB
Loading

docs/src/load_mechanism.md

Lines changed: 46 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,11 @@
11
# Loading Mechanism via URDF
2-
Another way to build a mechanism is to directly load it from a URDF file. We can do this is the mechanism builder function. We illustrate this with the RExLab hopper.
2+
Another way to build a mechanism is to directly load it from a URDF file. We illustrate this with the RExLab hopper.
33

44
```julia
55
function get_rexhopper(;
66
timestep=0.01,
77
gravity=[0.0; 0.0; -9.81],
88
friction_coefficient=1.0,
9-
contact_foot=true,
109
contact_body=true,
1110
limits=true,
1211
model=:rexhopper,
@@ -16,16 +15,48 @@ function get_rexhopper(;
1615
damper=1.0,
1716
T=Float64)
1817

18+
# we define the path of the URDF file
1919
path = joinpath(@__DIR__, "../deps/$(String(model)).urdf")
20+
# we load the URDF file into a Mechanism object
2021
mech = Mechanism(path, floating, T,
2122
gravity=gravity,
2223
timestep=timestep,
2324
spring=spring,
2425
damper=damper)
26+
return mech
27+
end
28+
```
29+
Here, we have created a mechanism, that contains all the bodies and the joint and also the meshes loaded from the path contained in the URDF file. This is the resulting robot;
30+
![rexhopper](./assets/rexhopper.png)
2531

26-
# joint limits
27-
joints = deepcopy(mech.joints)
32+
However, we are still missing the joint limits and the contact spheres. The following methods provides an example for adding joint limits and contact spheres. Our goal here was to best approximate the mesh shapes using as few spheres as possible.
33+
Parsing joint limits from the URDF to add them automatically to the mechanism should be easily feasible. That could be a great way to contribute and familiarize yourself with the code!
2834

35+
```julia
36+
function get_rexhopper(;
37+
timestep=0.01,
38+
gravity=[0.0; 0.0; -9.81],
39+
friction_coefficient=1.0,
40+
contact_body=true,
41+
limits=true,
42+
model=:rexhopper,
43+
floating=true,
44+
contact_type=:nonlinear,
45+
spring=0.0,
46+
damper=1.0,
47+
T=Float64)
48+
49+
# we define the path of the URDF file
50+
path = joinpath(@__DIR__, "../deps/$(String(model)).urdf")
51+
# we load the URDF file into a Mechanism object
52+
mech = Mechanism(path, floating, T,
53+
gravity=gravity,
54+
timestep=timestep,
55+
spring=spring,
56+
damper=damper)
57+
58+
# we add joint limits to the mechanism
59+
joints = deepcopy(mech.joints)
2960
if limits
3061
joint1 = get_joint(mech, :joint1)
3162
joint3 = get_joint(mech, :joint3)
@@ -40,13 +71,14 @@ function get_rexhopper(;
4071
damper=damper)
4172
end
4273

43-
if contact_foot
74+
# we attach spherical collisions zones to certain bodies
75+
if contact_body
4476
origin = Origin{T}()
4577
bodies = mech.bodies
4678
joints = mech.joints
4779

4880
normal = [0.0; 0.0; 1.0]
49-
models = []
81+
contacts = []
5082

5183
link3 = get_body(mech, :link3)
5284
link2 = get_body(mech, :link2)
@@ -55,22 +87,22 @@ function get_rexhopper(;
5587
base_radius = 0.125
5688
p = [0.1685; 0.0025; -0.0055]
5789
o = [0;0; foot_radius]
58-
push!(models, contact_constraint(link3, normal,
90+
push!(contacts, contact_constraint(link3, normal,
5991
friction_coefficient=friction_coefficient,
6092
contact_point=p,
6193
offset=o,
6294
contact_type=contact_type,
6395
name=:foot))
6496
p = [-0.10; -0.002; 0.01]
6597
o = [0;0; ankle_radius]
66-
push!(models, contact_constraint(link3, normal,
98+
push!(contacts, contact_constraint(link3, normal,
6799
friction_coefficient=friction_coefficient,
68100
contact_point=p,
69101
offset=o,
70102
contact_type=contact_type,
71103
name=:ankle3))
72104
p = [0.24; 0.007; 0.005]
73-
push!(models, contact_constraint(link2, normal,
105+
push!(contacts, contact_constraint(link2, normal,
74106
friction_coefficient=friction_coefficient,
75107
contact_point=p,
76108
offset=o,
@@ -79,15 +111,15 @@ function get_rexhopper(;
79111
base_link = get_body(mech, :base_link)
80112
p = [0.0; 0.0; 0.0]
81113
o = [0;0; base_radius]
82-
push!(models, contact_constraint(base_link, normal,
114+
push!(contacts, contact_constraint(base_link, normal,
83115
friction_coefficient=friction_coefficient,
84116
contact_point=p,
85117
offset=o,
86118
contact_type=contact_type,
87119
name=:torso))
88120

89121
set_minimal_coordinates!(mech, get_joint(mech, :auto_generated_floating_joint), [0,0,1.0, 0,0,0])
90-
mech = Mechanism(origin, bodies, joints, [models...],
122+
mech = Mechanism(origin, bodies, joints, [contacts...],
91123
gravity=gravity,
92124
timestep=timestep,
93125
spring=spring,
@@ -96,3 +128,6 @@ function get_rexhopper(;
96128
return mech
97129
end
98130
```
131+
132+
This is the result, we added three spherical contacts to the robot. There is one coverinn the torso one covering the knee and one covering the foot, they are shown in red;
133+
![rexhopper_contact](./assets/rexhopper_contact.png)

examples/dev/rexhopper.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,4 +22,4 @@ storage = simulate!(mechanism, 1.5, record=true, opts=SolverOptions(undercut=10.
2222
btol=1.0e-4, rtol=1.0e-4, verbose=false));
2323

2424
# Visualize
25-
visualize(mechanism, storage, vis=vis, show_contact=true, build=false);
25+
visualize(mechanism, storage, vis=vis, show_contact=true, build=true);

0 commit comments

Comments
 (0)