forked from pengjujin/rllab_mujoco
-
Notifications
You must be signed in to change notification settings - Fork 0
/
reacher_mod.xml
37 lines (36 loc) · 2.02 KB
/
reacher_mod.xml
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
<mujoco model="reacher">
<compiler angle="radian" inertiafromgeom="true"/>
<default>
<joint armature="1" damping="1" limited="true"/>
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
</default>
<option gravity="0 0 -9.8" integrator="RK4" timestep="0.01"/>
<worldbody>
<!-- Arena -->
<geom conaffinity="1" contype="1" name="ground" pos="0 0 0" rgba="0.8 0.8 0.8 1" size="1 1 10" type="plane"/>
<body name="body0" pos="0 0 0.23">
<geom conaffinity="1" contype="1" fromto="0 0 0 0 0 -0.1" name="link0" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
<joint axis="0 1 0" limited="false" name="joint0" pos="0 0 0" type="hinge"/>
<body name="body1" pos="0 0 -0.1">
<joint axis="0 1 0" limited="false" name="joint1" pos="0 0 0" type="hinge"/>
<geom conaffinity="1" contype="1" fromto="0 0 0 0 0 -0.1" name="link1" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
<body name="fingertip" pos="0 0 -0.11">
<geom conaffinity="1" contype="1" name="fingertip" pos="0 0 0" rgba="0.0 0.8 0.6 1" size=".01" type="sphere"/>
</body>
</body>
</body>
<!-- Target -->
<body name="target" pos="0.00 0.00 .00">
<geom conaffinity="1" contype="1" size="0.04 0.04 0.005" pos="0 0 0" name="target_bottom" rgba="0.9 0.2 0.2 1" type="box"/>
<geom conaffinity="1" contype="1" size="0.005 0.04 0.04" pos="-0.04 0 0.04" name="target_side1" rgba="0.9 0.2 0.2 1" type="box"/>
<geom conaffinity="1" contype="1" size="0.04 0.005 0.04" pos="0 0.04 0.04" name="target_side2" rgba="0.9 0.2 0.2 1" type="box"/>
<geom conaffinity="1" contype="1" size="0.005 0.04 0.04" pos="0.04 0 0.04" name="target_side3" rgba="0.9 0.2 0.2 1" type="box"/>
<geom conaffinity="1" contype="1" size="0.04 0.005 0.04" pos="0 -0.04 0.04" name="target_side4" rgba="0.9 0.2 0.2 1" type="box"/>
<joint limited="false" type="free" />
</body>
</worldbody>
<actuator>
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint0"/>
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint1"/>
</actuator>
</mujoco>