Skip to content

Commit

Permalink
Make solimp[2] match foot radius. Fixes #45.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 639351953
Change-Id: I575cd1faf11c430fdbe17391a1cc4db386720e1b
  • Loading branch information
kevinzakka authored and copybara-github committed Jun 1, 2024
1 parent 8e6ce1a commit d82891f
Show file tree
Hide file tree
Showing 7 changed files with 9 additions and 9 deletions.
2 changes: 1 addition & 1 deletion anybotics_anymal_c/anymal_c.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<default class="collision">
<geom group="3" type="cylinder"/>
<default class="foot">
<geom type="sphere" size="0.03" pos="0 0 0.02325" priority="1" solimp="0.015 1 0.031" condim="6"
<geom type="sphere" size="0.03" pos="0 0 0.02325" priority="1" solimp="0.015 1 0.03" condim="6"
friction="0.8 0.02 0.01"/>
</default>
</default>
Expand Down
2 changes: 1 addition & 1 deletion boston_dynamics_spot/scene.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<mujoco model="spot scene">
<include file="spot_arm.xml"/>
<include file="spot.xml"/>

<statistic center="0.15 0.1 0.38" extent=".8" meansize="0.05"/>

Expand Down
4 changes: 2 additions & 2 deletions boston_dynamics_spot/spot.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<mujoco model="spot">
<compiler angle="radian" meshdir="assets"/>

<option integrator="implicitfast" cone="elliptic" impratio="10"/>
<option integrator="implicitfast" cone="elliptic" impratio="100"/>

<visual>
<global ellipsoidinertia="true"/>
Expand Down Expand Up @@ -47,7 +47,7 @@
<default class="collision">
<geom group="3" type="mesh"/>
<default class="foot">
<geom type="sphere" size="0.036" pos="0 0 -0.3365" priority="1" condim="6" solimp="0.015 1 0.031"
<geom type="sphere" size="0.036" pos="0 0 -0.3365" priority="1" condim="6" solimp="0.015 1 0.036"
friction="0.8 0.02 0.01"/>
</default>
</default>
Expand Down
4 changes: 2 additions & 2 deletions boston_dynamics_spot/spot_arm.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<mujoco model="spot">
<compiler angle="radian" meshdir="assets"/>

<option integrator="implicitfast" cone="elliptic" impratio="10"/>
<option integrator="implicitfast" cone="elliptic" impratio="100"/>

<visual>
<global ellipsoidinertia="true"/>
Expand Down Expand Up @@ -78,7 +78,7 @@
<default class="collision">
<geom group="3" type="mesh"/>
<default class="foot">
<geom type="sphere" size="0.036" pos="0 0 -0.3365" priority="1" condim="6" solimp="0.015 1 0.031"
<geom type="sphere" size="0.036" pos="0 0 -0.3365" priority="1" condim="6" solimp="0.015 1 0.036"
friction="0.8 0.02 0.01"/>
</default>
</default>
Expand Down
2 changes: 1 addition & 1 deletion unitree_a1/a1.xml
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
<geom size="0.01" fromto="0.02 0 -0.13 0 0 -0.2"/>
</default>
<default class="foot">
<geom type="sphere" size="0.02" pos="0 0 -0.2" priority="1" solimp="0.015 1 0.031" condim="6"
<geom type="sphere" size="0.02" pos="0 0 -0.2" priority="1" solimp="0.015 1 0.02" condim="6"
friction="0.8 0.02 0.01"/>
</default>
</default>
Expand Down
2 changes: 1 addition & 1 deletion unitree_go1/go1.xml
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@
<geom size="0.01" fromto="0.02 0 -0.13 0 0 -0.2"/>
</default>
<default class="foot">
<geom type="sphere" size="0.023" pos="0 0 -0.213" priority="1" solimp="0.015 1 0.031" condim="6"
<geom type="sphere" size="0.023" pos="0 0 -0.213" priority="1" solimp="0.015 1 0.023" condim="6"
friction="0.8 0.02 0.01"/>
</default>
</default>
Expand Down
2 changes: 1 addition & 1 deletion unitree_go2/go2.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
<default class="collision">
<geom group="3"/>
<default class="foot">
<geom size="0.022" pos="-0.002 0 -0.213" priority="1" solimp="0.015 1 0.031" condim="6"
<geom size="0.022" pos="-0.002 0 -0.213" priority="1" solimp="0.015 1 0.022" condim="6"
friction="0.8 0.02 0.01"/>
</default>
</default>
Expand Down

0 comments on commit d82891f

Please sign in to comment.