Skip to content

Commit 8fab3a7

Browse files
authored
handle massless components in URDF models (#145)
* handle massless components in URDF models * add file
1 parent 1875e73 commit 8fab3a7

File tree

4 files changed

+181
-14
lines changed

4 files changed

+181
-14
lines changed

ext/Render.jl

Lines changed: 93 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -949,4 +949,97 @@ function perp(r)
949949
end
950950
end
951951

952+
953+
# ==============================================================================
954+
## Visualizers
955+
# ==============================================================================
956+
957+
function render!(scene, ::typeof(Multibody.BoxVisualizer), sys, sol, t)
958+
959+
# NOTE: This draws a solid box without the hole in the middle. Cannot figure out how to render a hollow box
960+
color = get_color(sys, sol, [1, 0.2, 1, 0.9])
961+
width = Float32(sol(sol.t[1], idxs=sys.width))
962+
height = Float32(sol(sol.t[1], idxs=sys.height))
963+
length = Float32(sol(sol.t[1], idxs=sys.length))
964+
965+
length_dir = sol(sol.t[1], idxs=collect(sys.render_length_dir))
966+
width_dir = sol(sol.t[1], idxs=collect(sys.render_width_dir))
967+
height_dir = normalize(cross(normalize(length_dir), normalize(width_dir)))
968+
width_dir = normalize(cross(height_dir, length_dir))
969+
970+
Rfun = get_rot_fun(sol, sys.frame_a)
971+
r_0a = get_fun(sol, collect(sys.frame_a.r_0)) # Origin is translated by r_shape
972+
r_shape = sol(sol.t[1], idxs=collect(sys.r_shape))
973+
# r = sol(sol.t[1], idxs=collect(sys.r))
974+
975+
R0 = [length_dir width_dir height_dir]
976+
# R0 = Multibody.from_nxy(r, width_dir).R'
977+
@assert isapprox(det(R0), 1.0, atol=1e-5) "Rotation matrix R0 is not a valid rotation matrix, got `R0 = $R0` with determinant `det(R0) = $(det(R0))`"
978+
# NOTE: The rotation by this R and the translation with r_shape needs to be double checked
979+
980+
origin = Vec3f(-length/2, -width/2, -height/2) + r_shape
981+
extent = Vec3f(length, width, height)
982+
thing = Makie.Rect3f(origin, extent)
983+
m = mesh!(scene, thing; color, specular = Vec3f(1.5))
984+
on(t) do t
985+
r1 = Point3f(r_0a(t))
986+
R = Rfun(t)
987+
q = Rotations.QuatRotation(R*R0).q
988+
Q = Makie.Quaternionf(q.v1, q.v2, q.v3, q.s)
989+
Makie.transform!(m, translation=r1, rotation=Q)
990+
end
991+
992+
true
993+
end
994+
995+
function render!(scene, ::typeof(Multibody.SphereVisualizer), sys, sol, t)
996+
sol(sol.t[1], idxs=sys.render)==true || return true # yes, == true
997+
color = get_color(sys, sol, :purple)
998+
framefun = get_frame_fun(sol, sys.frame_a)
999+
radius = sol(sol.t[1], idxs=sys.radius) |> Float32
1000+
thing = @lift begin # Sphere
1001+
Ta = framefun($t)
1002+
coords = Ta[1:3, 4]
1003+
point = Point3f(coords)
1004+
Sphere(point, Float32(radius))
1005+
end
1006+
mesh!(scene, thing; color, specular = Vec3f(1.5), shininess=20f0, diffuse=Vec3f(1))
1007+
end
1008+
1009+
function render!(scene, ::typeof(Multibody.CylinderVisualizer), sys, sol, t)
1010+
color = get_color(sys, sol, :purple)
1011+
radius = Float32(sol(sol.t[1], idxs=sys.radius))
1012+
r_0a = get_fun(sol, collect(sys.frame_a.r_0))
1013+
1014+
1015+
1016+
1017+
length_dir = sol(sol.t[1], idxs=collect(sys.render_length_dir))
1018+
width_dir = randn(3,3)
1019+
height_dir = normalize(cross(normalize(length_dir), normalize(width_dir)))
1020+
width_dir = normalize(cross(height_dir, length_dir))
1021+
1022+
Rfun = get_rot_fun(sol, sys.frame_a)
1023+
1024+
R0 = [length_dir width_dir height_dir]
1025+
1026+
r1 = Point3f(0,0,0)
1027+
r2 = Point3f((length*length_direction)...)
1028+
origin = r1
1029+
extremity = r2
1030+
thing = Makie.GeometryBasics.Cylinder(origin, extremity, radius)
1031+
m = mesh!(scene, thing; color, specular = Vec3f(1.5), shininess=20f0, diffuse=Vec3f(1), transparency=true)
1032+
1033+
1034+
on(t) do t
1035+
r1 = Point3f(r_0a(t))
1036+
R = Rfun(t)
1037+
q = Rotations.QuatRotation(R*R0).q
1038+
Q = Makie.Quaternionf(q.v1, q.v2, q.v3, q.s)
1039+
Makie.transform!(m, translation=r1, rotation=Q)
1040+
end
1041+
1042+
true
1043+
end
1044+
9521045
end

ext/URDF.jl

Lines changed: 43 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ function parse_pose(xml_pose::XMLElement)
5555
rot, trans
5656
end
5757

58-
function parse_joint(xml_joint::XMLElement)
58+
function parse_joint(xml_joint::XMLElement, render_fixed, render_joints)
5959
urdf_joint_type = attribute(xml_joint, "type")
6060
name = getname(xml_joint)
6161

@@ -69,7 +69,7 @@ function parse_joint(xml_joint::XMLElement)
6969
components = "$name = URDFRevolute(; r=$r, R=$R, n=$axis)"
7070
else
7171
components = """
72-
$name = URDFRevolute(; r=$r, R=$R, n=$axis, axisflange=true)
72+
$name = URDFRevolute(; r=$r, R=$R, n=$axis, axisflange=true, render=$render_joints)
7373
$(name)_damper = Rotational.Damper(; d=$damping)
7474
"""
7575
connections = """
@@ -81,7 +81,7 @@ function parse_joint(xml_joint::XMLElement)
8181
axis = parse_vector(T, find_element(xml_joint, "axis"), "xyz", "1 0 0")
8282
damping = parse_scalar(Float64, find_element(xml_joint, "dynamics"), "damping", "0")
8383
if iszero(damping)
84-
components = "$name = URDFPrismatic(; r=$r, R=$R, n=$axis)"
84+
components = "$name = URDFPrismatic(; r=$r, R=$R, n=$axis, render=$render_joints)"
8585
else
8686
components = """
8787
$name = URDFPrismatic(; r=$r, R=$R, n=$axis, axisflange=true)
@@ -99,9 +99,9 @@ function parse_joint(xml_joint::XMLElement)
9999
if norm(r) == 0 && R == I
100100
components = "$name = NullJoint()" # Null joint
101101
elseif R == I(3)
102-
components = "$name = FixedTranslation(; r=$r)"
102+
components = "$name = FixedTranslation(; r=$r, render=$render_fixed)"
103103
else
104-
components = "$name = FixedTranslation(; r=$r)"
104+
components = "$name = FixedTranslation(; r=$r, render=$render_fixed)"
105105
@warn "Ignoring rotation of joint $name"
106106
# R = RotMatrix3(R)
107107
# components = "$name = FixedRotation(; r=$r, n = $(rotation_axis(R)), angle = $(rotation_angle(R)))"
@@ -130,6 +130,7 @@ function parse_inertia(xml_inertial::XMLElement)
130130
moment = R * moment * R'
131131
# TODO: Double-check and test inertia transform, rotation convention RotXYZ? Transformation RIR' or R'IR?
132132
end
133+
133134
mass, moment, r_cm
134135
end
135136

@@ -138,7 +139,8 @@ getname(xml_link::XMLElement) = attribute(xml_link, "name")
138139
function parse_geometry(xml_link::XMLElement)
139140
xml_geometry = find_element(xml_link, "visual", "geometry")
140141
if xml_geometry === nothing
141-
return 0.1, 1, :sphere
142+
@error "No geometry found for link $(getname(xml_link)), using sphere"
143+
return (; radius=0.1), :sphere
142144
elseif (cylinder = find_element(xml_geometry, "cylinder")) !== nothing
143145
radius = parse_scalar(Float64, cylinder, "radius", "0.1")
144146
length = parse_scalar(Float64, cylinder, "length", "1")
@@ -166,22 +168,47 @@ function parse_geometry(xml_link::XMLElement)
166168
return geometry, type
167169
end
168170

169-
function parse_body(graph, xml_link::XMLElement)
171+
function parse_body(graph, xml_link::XMLElement; min_mass)
170172
xml_inertial = find_element(xml_link, "inertial")
171-
mass,inertia,r_cm = xml_inertial == nothing ? (0,0*I(3),zeros(3)) : parse_inertia(xml_inertial)
173+
mass,inertia,r_cm = xml_inertial == nothing ? (0.0,0.0*I(3),zeros(3)) : parse_inertia(xml_inertial)
174+
if min_mass > 0
175+
mass = max(mass, min_mass)
176+
for i = 1:3
177+
inertia[i,i] = max(inertia[i,i], min_mass*0.01)
178+
end
179+
end
172180
linkname = getname(xml_link)
173181

174182
R, r = parse_pose(find_element(xml_link, "visual", "origin"))
175183
color = parse_color(xml_link, "1 0 0 1")
176184
geometry, type = parse_geometry(xml_link)
185+
if geometry === nothing
186+
error("No geometry found for link $linkname")
187+
end
177188
if R != I
178189
@warn "Ignoring rotation of link $linkname"
179190
end
180-
if type === :sphere
191+
if mass == 0
192+
# We special case this since the dynamics becomes strange with zero mass
193+
if type === :sphere
194+
return "$(Symbol(linkname)) = SphereVisualizer(; radius=$(geometry.radius))" # color=$(color),
195+
elseif type === :cylinder
196+
if iszero(r)
197+
r = [1, 0, 0]
198+
end
199+
return "$(Symbol(linkname)) = CylinderVisualizer(; length_direction=$(r), radius=$(geometry.radius), length=$(geometry.length))" # color=$(color),
200+
elseif type === :box
201+
return "$(Symbol(linkname)) = BoxVisualizer(; length_direction=[1,0,0], width_direction=[0,1,0], length=$(geometry.size[1]), width=$(geometry.size[2]), height=$(geometry.size[3]))" # color=$(color),
202+
end
203+
204+
elseif type === :sphere
181205
radius = geometry.radius
182206
"$(Symbol(linkname)) = Body(; m=$(mass), r_cm=$(r_cm), I_11 = $(inertia[1,1]), I_22 = $(inertia[2,2]), I_33 = $(inertia[3,3]), I_21 = $(inertia[2,1]), I_31 = $(inertia[3,1]), I_32 = $(inertia[3,2]), color=$(color), radius=$(radius), sparse_I=true)"
183207
elseif type === :cylinder
184208
(; radius, length) = geometry
209+
if iszero(r)
210+
r = [1, 0, 0]
211+
end
185212
r = normalize(r)*length
186213
"$(Symbol(linkname)) = BodyShape(; r=$(r), m=$(mass), r_cm=$(r_cm), I_11 = $(inertia[1,1]), I_22 = $(inertia[2,2]), I_33 = $(inertia[3,3]), I_21 = $(inertia[2,1]), I_31 = $(inertia[3,1]), I_32 = $(inertia[3,2]), color=$(color), radius=$(radius), sparse_I=true)"
187214
elseif type === :box
@@ -193,6 +220,8 @@ function parse_body(graph, xml_link::XMLElement)
193220
r = [1, 0, 0]
194221
end
195222
"$(Symbol(linkname)) = BodyBox(; r=$(r), body.m=$(mass), body.r_cm=$(r_cm), body.I_11 = $(inertia[1,1]), body.I_22 = $(inertia[2,2]), body.I_33 = $(inertia[3,3]), body.I_21 = $(inertia[2,1]), body.I_31 = $(inertia[3,1]), body.I_32 = $(inertia[3,2]), color=$(color), length=$(length), width=$(width), height=$(height))"
223+
else
224+
error("Geometry type $type not recognized")
196225
end
197226
end
198227

@@ -209,11 +238,11 @@ urdf2multibody(joinpath(dirname(pathof(Multibody)), "..", "test", "urdf", "doubl
209238
210239
## Keyword arguments
211240
- `extras=false`: If `true`, the generated code will include package imports, a simulation of the model and a rendering of the model.
212-
- `out=nothing`: If provided, the generated code will be written to this file, otherwise the string will only be returned.
241+
- `out=nothing`: If provided, the generated code will be written to this file, otherwise the translated model is returned as a string.
213242
- `worldconnection=:rigid`: If `:rigid`, the world frame will be connected to the root link with a rigid connection. If a joint constructor is provided, this component will be instantiated and the root link is connected to the world through this, e.g., `worldconnection = FreeMotion`, `()->Prismatic(n=[0, 1, 0])` etc.
214243
- `modelname`: The name of the model, default is the name of the URDF file with the extension removed and the first letter upper case.
215244
"""
216-
function Multibody.urdf2multibody(filename::AbstractString; extras=false, out=nothing, worldconnection = :rigid, modelname = default_modelname(filename))
245+
function Multibody.urdf2multibody(filename::AbstractString; extras=false, out=nothing, worldconnection = :rigid, modelname = default_modelname(filename), solver = "FBDF", render_fixed=false, render_joints = true, min_mass=0)
217246
gravity = 9.81
218247
floating::Bool = false
219248

@@ -246,14 +275,14 @@ function Multibody.urdf2multibody(filename::AbstractString; extras=false, out=no
246275

247276
# Parse all joints and possible extra connections due to axisflanges
248277
joints_extraconnections = map(xml_joints) do l
249-
parse_joint(l)
278+
parse_joint(l, render_fixed, render_joints)
250279
end
251280
joints = first.(joints_extraconnections)
252281
extra_connections = filter(!isempty, last.(joints_extraconnections))
253282

254283
# Parse all bodies
255284
bodies = map(xml_links) do l
256-
parse_body(graph, l)
285+
parse_body(graph, l; min_mass)
257286
end
258287

259288
roots = [v for v in vertices(graph) if indegree(graph, v) == 0]
@@ -305,7 +334,7 @@ function Multibody.urdf2multibody(filename::AbstractString; extras=false, out=no
305334
model = complete(model)
306335
ssys = structural_simplify(IRSystem(model))
307336
prob = ODEProblem(ssys, [], (0.0, 10.0))
308-
sol = solve(prob, FBDF())
337+
sol = solve(prob, $(solver)())
309338
plot(sol) |> display
310339
311340
import GLMakie

src/Multibody.jl

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -251,4 +251,7 @@ include("robot/FullRobot.jl")
251251
export PlanarMechanics
252252
include("PlanarMechanics/PlanarMechanics.jl")
253253

254+
export SphereVisualizer, CylinderVisualizer, BoxVisualizer
255+
include("visualizers.jl")
256+
254257
end

src/visualizers.jl

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
@mtkmodel Visaluzable begin
2+
@components begin
3+
frame_a = Frame()
4+
end
5+
@parameters begin
6+
color[1:4] = [1.0, 0.0, 0.0, 1.0], [description = "Color of the body in animations"]
7+
render = true, [description = "Render the joint in animations"]
8+
end
9+
@equations begin
10+
frame_a.f ~ zeros(3)
11+
frame_a.tau ~ zeros(3)
12+
end
13+
end
14+
15+
@mtkmodel SphereVisualizer begin
16+
@extend () = v = Visaluzable()
17+
@parameters begin
18+
radius = 0.1, [description = "Radius of the sphere in animations"]
19+
end
20+
end
21+
22+
@mtkmodel CylinderVisualizer begin
23+
@extend () = v = Visaluzable()
24+
@parameters begin
25+
radius = 0.1, [description = "Radius of the sphere in animations"]
26+
length = 1.0, [description = "length of the cylinder"]
27+
length_direction[1:3] = [1.0, 0.0, 0.0], [description = "length direction of the cylinder, resolved in frame_a"]
28+
end
29+
end
30+
31+
@mtkmodel BoxVisualizer begin
32+
@extend () = v = Visaluzable()
33+
@parameters begin
34+
length_direction[1:3] = [1.0, 0.0, 0.0], [description = "length direction of the box, resolved in frame_a"]
35+
width_direction[1:3] = [0.0, 1.0, 0.0], [description = "width direction of the box, resolved in frame_a"]
36+
length = 1.0, [description = "length of the box"]
37+
width = 1.0, [description = "width of the box"]
38+
height = 1.0, [description = "height of the box"]
39+
r_shape[1:3] = [0,0,0]
40+
end
41+
end
42+

0 commit comments

Comments
 (0)