Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion benchmark/example_benchmark.jl
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ for i=1:length(files)
steps = Base.OneTo(100)
storage = Storage{Float64}(steps,length(mech.bodies))

if files[i] in controlled
if files[i] controlled
control_function = eval(Meta.parse(files[i]*"_control!"))
SUITE[files[i]] = @benchmarkable simulate!($mech, $steps, $storage, $control_function) samples=2
else
Expand Down
115 changes: 115 additions & 0 deletions examples/examples_files/fourbar.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
<?xml version="1.0"?>

<robot name="Fourbar">
<link name="base_link">
</link>

<link name="link1">
<inertial>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<mass value="1" />
<inertia ixx=".0841667" ixy="0" ixz="0" iyy=".0841667" iyz="0" izz=".00166667" />
</inertial>
<visual>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<geometry>
<!-- <cylinder length="1" radius=".05" /> -->
<box size=".1 .1 1" />
</geometry>
<material name="green">
<color rgba="1 0 1 1" />
</material>
</visual>
</link>

<link name="link2">
<inertial>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<mass value="1" />
<inertia ixx=".0841667" ixy="0" ixz="0" iyy=".0841667" iyz="0" izz=".00166667" />
</inertial>
<visual>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<geometry>
<box size=".1 .1 1" />
</geometry>
<material name="green">
<color rgba="1 0 0 1" />
</material>
</visual>
</link>

<link name="link3">
<inertial>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<mass value="1" />
<inertia ixx=".0841667" ixy="0" ixz="0" iyy=".0841667" iyz="0" izz=".00166667" />
</inertial>
<visual>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<geometry>
<!-- <cylinder length="1" radius=".05" /> -->
<box size=".1 .1 1" />
</geometry>
<material name="green">
<color rgba="1 0 1 1" />
</material>
</visual>
</link>

<link name="link4">
<inertial>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<mass value="1" />
<inertia ixx=".0841667" ixy="0" ixz="0" iyy=".0841667" iyz="0" izz=".00166667" />
</inertial>
<visual>
<origin xyz="0 0 -0.5" rpy="0 0. 0." />
<geometry>
<box size=".1 .1 1" />
</geometry>
<material name="green">
<color rgba="1 0 0 1" />
</material>
</visual>
</link>



<joint name="jointb1" type="continuous">
<parent link="base_link" />
<child link="link1" />
<origin rpy="0.1 0 0" xyz="0 0 0" />
<axis xyz="1 0 0" />
</joint>

<joint name="joint12" type="continuous">
<parent link="link1" />
<child link="link2" />
<origin rpy="0.2 0 0" xyz="0 0 -1" />
<axis xyz="1 0 0" />
</joint>

<joint name="joint13" type="continuous">
<parent link="link1" />
<child link="link3" />
<origin rpy="-0.2 0 0" xyz="0 0 0" />
<axis xyz="1 0 0" />
</joint>

<joint name="joint34" type="continuous">
<parent link="link3" />
<child link="link4" />
<origin rpy="-0.4 0 0" xyz="0 0 -1" />
<axis xyz="1 0 0" />
</joint>

<loop_joint name="joint24" type="continuous">
<axis xyz="1 0 0"/>
<link1 link="link2" rpy="0 0 0" xyz="0 0 -1"/>
<link2 link="link4" rpy="0 0 0" xyz="0 0 -1"/>
</loop_joint>



</robot>
Loading