Fix the slider name from 'slider_left' to 'slider_right'
When I tried to load the URDF file on MuJoCo, it failed with the
following error message:
Duplicated slider name "slider_left"
It turned out that the issue was the right slider being wrongly
tagged as 'slider_left' (not 'slider_right'). Fix it thusly.
Signed-off-by: Fujimoto Seiji <fujimoto@ceptord.net>
This commit is contained in:
parent
c8793e08ae
commit
5809be6d15
@ -422,7 +422,7 @@
|
|||||||
<axis xyz="-1.0 0.0 -0.0"/>
|
<axis xyz="-1.0 0.0 -0.0"/>
|
||||||
<limit acceleration="0.5" effort="100" lower="-0.0455" upper="0.0" velocity="1.0"/>
|
<limit acceleration="0.5" effort="100" lower="-0.0455" upper="0.0" velocity="1.0"/>
|
||||||
</joint>
|
</joint>
|
||||||
<joint name="slider_left" type="prismatic">
|
<joint name="slider_right" type="prismatic">
|
||||||
<origin rpy="0 0 0" xyz="0.0775 -0.121655 0.012086"/>
|
<origin rpy="0 0 0" xyz="0.0775 -0.121655 0.012086"/>
|
||||||
<parent link="grip_attach_1"/>
|
<parent link="grip_attach_1"/>
|
||||||
<child link="right_jaw_1"/>
|
<child link="right_jaw_1"/>
|
||||||
|
|||||||
@ -285,7 +285,7 @@
|
|||||||
<limit upper="0.0" lower="-0.0455" effort="100" velocity="1.0" acceleration="0.5"/>
|
<limit upper="0.0" lower="-0.0455" effort="100" velocity="1.0" acceleration="0.5"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="slider_left" type="prismatic">
|
<joint name="slider_right" type="prismatic">
|
||||||
<origin xyz="0.0775 -0.121655 0.012086" rpy="0 0 0"/>
|
<origin xyz="0.0775 -0.121655 0.012086" rpy="0 0 0"/>
|
||||||
<parent link="grip_attach_1"/>
|
<parent link="grip_attach_1"/>
|
||||||
<child link="right_jaw_1"/>
|
<child link="right_jaw_1"/>
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user