forked from google-deepmind/mujoco_mpc
-
Notifications
You must be signed in to change notification settings - Fork 0
/
task.xml
55 lines (48 loc) · 1.98 KB
/
task.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
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
<mujoco model="Swimmer">
<include file="../common.xml" />
<!-- modified from: https://github.com/google-deepmind/dm_control/blob/main/dm_control/suite/swimmer.xml -->
<include file="swimmer_modified.xml" />
<custom>
<!-- agent -->
<numeric name="agent_planner" data="2" />
<numeric name="agent_horizon" data="2" />
<numeric name="agent_timestep" data="0.01" />
<numeric name="agent_integrator" data="2" />
<numeric name="agent_policy_width" data="0.0015" />
<numeric name="sampling_spline_points" data="10" />
<numeric name="sampling_exploration" data="0.05" />
<numeric name="gradient_spline_points" data="10" />
<!-- estimator -->
<numeric name="estimator" data="0" />
<numeric name="estimator_sensor_start" data="2" />
<numeric name="estimator_number_sensor" data="8" />
<numeric name="estimator_timestep" data="0.0075" />
<numeric name="batch_configuration_length" data="3" />
<numeric name="batch_scale_prior" data="1.0e-3" />
</custom>
<worldbody>
<body name="target" mocap="true" pos="1 1 .05">
<geom name="target" type="sphere" size="0.05" material="target"/>
<light name="target_light" diffuse=".7 .7 .7" pos="0 0 0.5"/>
</body>
</worldbody>
<sensor>
<!-- cost -->
<user name="Control" dim="5" user="0 0.1 0 1" />
<user name="Distance" dim="2" user="2 10 0 10 0.04" />
<!-- estimator -->
<jointpos name="rootx" joint="rootx" />
<jointpos name="rooty" joint="rooty" />
<jointpos name="rootz" joint="rootz" />
<jointpos name="joint0" joint="joint_0" />
<jointpos name="joint1" joint="joint_1" />
<jointpos name="joint2" joint="joint_2" />
<jointpos name="joint3" joint="joint_3" />
<jointpos name="joint4" joint="joint_4" />
<!-- trace -->
<framepos name="trace0" objtype="geom" objname="nose"/>
<!-- residual -->
<framepos name="nose" objtype="geom" objname="nose"/>
<framepos name="target" objtype="body" objname="target"/>
</sensor>
</mujoco>