@@ -55,7 +55,7 @@ function parse_pose(xml_pose::XMLElement)
55
55
rot, trans
56
56
end
57
57
58
- function parse_joint (xml_joint:: XMLElement )
58
+ function parse_joint (xml_joint:: XMLElement , render_fixed, render_joints )
59
59
urdf_joint_type = attribute (xml_joint, " type" )
60
60
name = getname (xml_joint)
61
61
@@ -69,7 +69,7 @@ function parse_joint(xml_joint::XMLElement)
69
69
components = " $name = URDFRevolute(; r=$r , R=$R , n=$axis )"
70
70
else
71
71
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 )
73
73
$(name) _damper = Rotational.Damper(; d=$damping )
74
74
"""
75
75
connections = """
@@ -81,7 +81,7 @@ function parse_joint(xml_joint::XMLElement)
81
81
axis = parse_vector (T, find_element (xml_joint, " axis" ), " xyz" , " 1 0 0" )
82
82
damping = parse_scalar (Float64, find_element (xml_joint, " dynamics" ), " damping" , " 0" )
83
83
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 )"
85
85
else
86
86
components = """
87
87
$name = URDFPrismatic(; r=$r , R=$R , n=$axis , axisflange=true)
@@ -99,9 +99,9 @@ function parse_joint(xml_joint::XMLElement)
99
99
if norm (r) == 0 && R == I
100
100
components = " $name = NullJoint()" # Null joint
101
101
elseif R == I (3 )
102
- components = " $name = FixedTranslation(; r=$r )"
102
+ components = " $name = FixedTranslation(; r=$r , render= $render_fixed )"
103
103
else
104
- components = " $name = FixedTranslation(; r=$r )"
104
+ components = " $name = FixedTranslation(; r=$r , render= $render_fixed )"
105
105
@warn " Ignoring rotation of joint $name "
106
106
# R = RotMatrix3(R)
107
107
# components = "$name = FixedRotation(; r=$r, n = $(rotation_axis(R)), angle = $(rotation_angle(R)))"
@@ -130,6 +130,7 @@ function parse_inertia(xml_inertial::XMLElement)
130
130
moment = R * moment * R'
131
131
# TODO : Double-check and test inertia transform, rotation convention RotXYZ? Transformation RIR' or R'IR?
132
132
end
133
+
133
134
mass, moment, r_cm
134
135
end
135
136
@@ -138,7 +139,8 @@ getname(xml_link::XMLElement) = attribute(xml_link, "name")
138
139
function parse_geometry (xml_link:: XMLElement )
139
140
xml_geometry = find_element (xml_link, " visual" , " geometry" )
140
141
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
142
144
elseif (cylinder = find_element (xml_geometry, " cylinder" )) != = nothing
143
145
radius = parse_scalar (Float64, cylinder, " radius" , " 0.1" )
144
146
length = parse_scalar (Float64, cylinder, " length" , " 1" )
@@ -166,22 +168,47 @@ function parse_geometry(xml_link::XMLElement)
166
168
return geometry, type
167
169
end
168
170
169
- function parse_body (graph, xml_link:: XMLElement )
171
+ function parse_body (graph, xml_link:: XMLElement ; min_mass )
170
172
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
172
180
linkname = getname (xml_link)
173
181
174
182
R, r = parse_pose (find_element (xml_link, " visual" , " origin" ))
175
183
color = parse_color (xml_link, " 1 0 0 1" )
176
184
geometry, type = parse_geometry (xml_link)
185
+ if geometry === nothing
186
+ error (" No geometry found for link $linkname " )
187
+ end
177
188
if R != I
178
189
@warn " Ignoring rotation of link $linkname "
179
190
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
181
205
radius = geometry. radius
182
206
" $(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)"
183
207
elseif type === :cylinder
184
208
(; radius, length) = geometry
209
+ if iszero (r)
210
+ r = [1 , 0 , 0 ]
211
+ end
185
212
r = normalize (r)* length
186
213
" $(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)"
187
214
elseif type === :box
@@ -193,6 +220,8 @@ function parse_body(graph, xml_link::XMLElement)
193
220
r = [1 , 0 , 0 ]
194
221
end
195
222
" $(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" )
196
225
end
197
226
end
198
227
@@ -209,11 +238,11 @@ urdf2multibody(joinpath(dirname(pathof(Multibody)), "..", "test", "urdf", "doubl
209
238
210
239
## Keyword arguments
211
240
- `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 .
213
242
- `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.
214
243
- `modelname`: The name of the model, default is the name of the URDF file with the extension removed and the first letter upper case.
215
244
"""
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 )
217
246
gravity = 9.81
218
247
floating:: Bool = false
219
248
@@ -246,14 +275,14 @@ function Multibody.urdf2multibody(filename::AbstractString; extras=false, out=no
246
275
247
276
# Parse all joints and possible extra connections due to axisflanges
248
277
joints_extraconnections = map (xml_joints) do l
249
- parse_joint (l)
278
+ parse_joint (l, render_fixed, render_joints )
250
279
end
251
280
joints = first .(joints_extraconnections)
252
281
extra_connections = filter (! isempty, last .(joints_extraconnections))
253
282
254
283
# Parse all bodies
255
284
bodies = map (xml_links) do l
256
- parse_body (graph, l)
285
+ parse_body (graph, l; min_mass )
257
286
end
258
287
259
288
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
305
334
model = complete(model)
306
335
ssys = structural_simplify(IRSystem(model))
307
336
prob = ODEProblem(ssys, [], (0.0, 10.0))
308
- sol = solve(prob, FBDF ())
337
+ sol = solve(prob, $(solver) ())
309
338
plot(sol) |> display
310
339
311
340
import GLMakie
0 commit comments