forked from google-deepmind/mujoco_mpc
-
Notifications
You must be signed in to change notification settings - Fork 0
/
task_flat.xml
163 lines (144 loc) · 6.57 KB
/
task_flat.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
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
<mujoco model="Quadruped">
<include file="../common.xml"/>
<size memory="1M"/>
<custom>
<!-- agent -->
<text name="task_transition" data="Quadruped|Biped|Walk|Scramble|Flip" />
<numeric name="agent_planner" data="2 " />
<numeric name="agent_horizon" data="0.35" />
<numeric name="agent_timestep" data="0.01" />
<numeric name="sampling_spline_points" data="3" />
<numeric name="sampling_trajectories" data="60"/>
<numeric name="sampling_exploration" data="0.04" />
<numeric name="gradient_spline_points" data="5" />
<!-- residual -->
<numeric name="residual_select_Gait" data="0"/>
<text name="residual_list_Gait" data="Stand|Walk|Trot|Canter|Gallop"/>
<numeric name="residual_select_Gait switch" data="1"/>
<text name="residual_list_Gait switch" data="Manual|Automatic"/>
<numeric name="residual_Cadence" data="2 0 4" />
<numeric name="residual_Amplitude" data=".06 0 0.2" />
<numeric name="residual_Duty ratio" data="0 0 1"/>
<numeric name="residual_Walk speed" data="0 0 4"/>
<numeric name="residual_Walk turn" data="0 -2 2"/>
<numeric name="residual_select_Flip dir" data="0"/>
<text name="residual_list_Flip dir" data="Back Flip|Front Flip"/>
<numeric name="residual_select_Biped type" data="0"/>
<text name="residual_list_Biped type" data="Foot Stand|Hand Stand"/>
<numeric name="residual_Heading" data="0 -3.14 3.14" />
<!-- estimator -->
<numeric name="estimator" data="0" />
<numeric name="estimator_sensor_start" data="9" />
<numeric name="estimator_number_sensor" data="21" />
<numeric name="estimator_timestep" data="0.005" />
<numeric name="batch_configuration_length" data="3" />
<numeric name="batch_scale_prior" data="1.0e-3" />
</custom>
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
<global azimuth="-90"/>
</visual>
<statistic extent="1" center="0 0 .3"/>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" diffuse="0.5 0.5 0.5" specular="0.3 0.3 0.3"
directional="true" castshadow="false"/>
<geom name="floor" size="0 0 0.1" pos="0 0 -0.01" type="plane" material="blue_grid"/>
<body name="goal" mocap="true" pos=".3 0 0.26">
<geom size="0.12" contype="0" conaffinity="0" rgba="0 1 0 .5" group="2"/>
</body>
<body name="box" mocap="true" pos="-2.5 0 0">
<geom name="box" class="prop" size="1 1 0.3"/>
</body>
<geom name="ramp" class="prop" pos="3.13 2.5 -.18" size="1.6 1 .5" euler="0 -0.2 0"/>
<geom name="hill" class="prop" pos="6 6 -5.5" size="6" type="sphere"/>
</worldbody>
<default>
<default class="torque">
<general gainprm="40" ctrllimited="true" ctrlrange="-1 1"/>
</default>
<default class="task">
<site rgba="1 0 0 1" size=".02" group="5"/>
<default class="flight">
<site rgba="1 .3 .3 1" size="0.019" group="5"/>
</default>
<default class="stance">
<site rgba=".3 1 .3 1" size=".018" group="4"/>
</default>
</default>
<default class="prop">
<geom type="box" rgba="0 0.4 1 1"/>
</default>
</default>
<!-- modified from: https://github.com/google-deepmind/mujoco_menagerie/tree/main/unitree_a1 -->
<include file="a1_modified.xml" />
<actuator>
<general class="torque" name="FR_hip" joint="FR_hip_joint"/>
<general class="torque" name="FR_thigh" joint="FR_thigh_joint"/>
<general class="torque" name="FR_calf" joint="FR_calf_joint"/>
<general class="torque" name="FL_hip" joint="FL_hip_joint"/>
<general class="torque" name="FL_thigh" joint="FL_thigh_joint"/>
<general class="torque" name="FL_calf" joint="FL_calf_joint"/>
<general class="torque" name="RR_hip" joint="RR_hip_joint"/>
<general class="torque" name="RR_thigh" joint="RR_thigh_joint"/>
<general class="torque" name="RR_calf" joint="RR_calf_joint"/>
<general class="torque" name="RL_hip" joint="RL_hip_joint"/>
<general class="torque" name="RL_thigh" joint="RL_thigh_joint"/>
<general class="torque" name="RL_calf" joint="RL_calf_joint"/>
</actuator>
<sensor>
<!-- cost -->
<user name="Upright" dim="3" user="6 1 0 3 0.05" />
<user name="Height" dim="1" user="6 1 0 3 0.04" />
<user name="Position" dim="3" user="2 0.2 0 0.5 0.1" />
<user name="Gait" dim="4" user="6 2 0 10 0.03" />
<user name="Balance" dim="2" user="2 0.2 0 0.3 0.1" />
<user name="Effort" dim="12" user="0 0.03 0.0 0.1" />
<user name="Posture" dim="12" user="0 0.02 0.0 0.1" />
<user name="Orientation" dim="2" user="0 0 0 .03" />
<user name="Angmom" dim="3" user="0 0 0 .03" />
<!-- estimator measurements -->
<framepos name="torso_pos" objtype="site" objname="torso" />
<framepos name="FR_pos" objtype="site" objname="FR" />
<framepos name="FL_pos" objtype="site" objname="FL" />
<framepos name="RR_pos" objtype="site" objname="RR" />
<framepos name="RL_pos" objtype="site" objname="RL" />
<jointpos name="pos_FR_hip_joint" joint="FR_hip_joint" />
<jointpos name="pos_FR_thigh_joint" joint="FR_thigh_joint" />
<jointpos name="pos_FR_calf_joint" joint="FR_calf_joint" />
<jointpos name="pos_FL_hip_joint" joint="FL_hip_joint" />
<jointpos name="pos_FL_thigh_joint" joint="FL_thigh_joint" />
<jointpos name="pos_FL_calf_joint" joint="FL_calf_joint" />
<jointpos name="pos_RR_hip_joint" joint="RR_hip_joint" />
<jointpos name="pos_RR_thigh_joint" joint="RR_thigh_joint" />
<jointpos name="pos_RR_calf_joint" joint="RR_calf_joint" />
<jointpos name="pos_RL_hip_joint" joint="RL_hip_joint" />
<jointpos name="pos_RL_thigh_joint" joint="RL_thigh_joint" />
<jointpos name="pos_RL_calf_joint" joint="RL_calf_joint" />
<touch name="FR_touch" site="FR"/>
<touch name="FL_touch" site="FL"/>
<touch name="RR_touch" site="RR"/>
<touch name="RL_touch" site="RL"/>
<!-- trace -->
<framepos name="trace0" objtype="site" objname="head"/>
<!-- residual -->
<subtreecom name="torso_subtreecom" body="trunk"/>
<subtreelinvel name="torso_subtreelinvel" body="trunk"/>
<subtreelinvel name="torso_angmom" body="trunk"/>
</sensor>
<keyframe>
<key name="home"
qpos="0 0 0.26
1 0 0 0
-0.000341931 0.0181576 -0.0268335
0.00160968 0.0247957 -0.0270045
0.00191398 -0.033048 -0.0675298
-0.00199489 -0.0374747 -0.0681862"/>
<key name="crouch"
qpos="-0.0501827 0.00107117 0.143925
1 0 0 0
0 0 -0.5
0 0 -0.5
0 0 -0.5
0 0 -0.5"/>
</keyframe>
</mujoco>