File: refsite.xml

package info (click to toggle)
mujoco 2.2.2-3.2
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid
  • size: 39,796 kB
  • sloc: ansic: 28,947; cpp: 28,897; cs: 14,241; python: 10,465; xml: 5,104; sh: 93; makefile: 34
file content (62 lines) | stat: -rw-r--r-- 2,569 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
<mujoco>
  <compiler autolimits="true"/>
  <!--
  Adding a high fluid viscosity and using implicit integration for extra stabillity.
  Extra stabillity is required because the abstract "arm" model is not very realistic.
  (e.g. 4 consecutive ball joints is not a realistic kinematic design)
  -->
  <option viscosity="10" integrator="implicit">
    <flag gravity="disable" contact="disable"/>
  </option>

  <statistic meansize=".05"/>

  <default>
    <default class="translation">
      <position kp="100" ctrlrange="-.25 .25"/>
    </default>
    <default class="rotation">
      <!--
      Note that the rotational control range is purposefully limited to (-pi/2, pi/2) to avoid the
      documented instabillity near pi, which is due to taking quaternion differences.
      Increase this range to pi or bigger in order to see the instabillity.
      See here for more details https://mujoco.readthedocs.io/en/latest/XMLreference.html#actuator
      -->
      <position kp=".2" ctrlrange="-1.571 1.571"/>
    </default>
    <joint damping=".01" stiffness=".0001"/>
    <site type="box" size=".012 .012 .012" rgba=".7 .7 .8 1"/>
  </default>

  <worldbody>
    <light pos="0 0 2"/>
    <geom type="box" size=".25 .25 .01" pos="0 0 -.01"/>
    <site name="reference" pos="0 0 .25"/>
    <body name="arm" pos="-.25 .25 0">
      <joint type="ball"/>
      <geom type="box" size=".01" fromto="0 0 0 0 0 .25"/>
      <body pos="0 0 .25">
        <joint type="ball"/>
        <geom type="box" size=".01" fromto="0 0 0 .25 0 0"/>
        <body pos=".25 0 0">
          <joint type="ball"/>
          <geom type="box" size=".01" fromto="0 0 0 0 -.2 0"/>
          <body pos="0 -.2 0">
            <joint type="ball"/>
            <geom type="box" size=".01" fromto="0 0 0 0 -.05 0"/>
            <site name="end_effector" pos="0 -.05 0"/>
          </body>
        </body>
      </body>
    </body>
  </worldbody>

  <actuator>
    <position name="x"  site="end_effector" refsite="reference" gear="1 0 0 0 0 0" class="translation"/>
    <position name="y"  site="end_effector" refsite="reference" gear="0 1 0 0 0 0" class="translation"/>
    <position name="z"  site="end_effector" refsite="reference" gear="0 0 1 0 0 0" class="translation"/>
    <position name="rx" site="end_effector" refsite="reference" gear="0 0 0 1 0 0" class="rotation"/>
    <position name="ry" site="end_effector" refsite="reference" gear="0 0 0 0 1 0" class="rotation"/>
    <position name="rz" site="end_effector" refsite="reference" gear="0 0 0 0 0 1" class="rotation"/>
  </actuator>
</mujoco>