generated from SysCV/project-template
-
Notifications
You must be signed in to change notification settings - Fork 1
/
CaDribble.yaml
341 lines (287 loc) · 7.28 KB
/
CaDribble.yaml
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
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
# used to create the object
name: CaDribble
physics_engine: ${..physics_engine}
env:
numEnvs: ${resolve_default:8000,${...num_envs}}
envSpacing: 2. # [m]
wandb_extra_log: false
wandb_extra_log_period: 8000
cameraSensorPlt: false
obs_history: true
history_length: 25
action_lag_step: 0
vision_lag_step: 0 # 100ms - 133ms
pid_delta: true
gait_condition:
# trotting [0.5,0,0] pacing [0,0,0.5]
phases: 0.0
offsets: 0.5
bounds: 0.0
kappa: 0.07
frequency: 3.0
duration: 0.5
vision_receive_prob: 1.0
state_observations:
projected_gravity: 3
dof_pos: 12
dof_vel: 12
last_actions: 12
gait_sin_indict: 2
body_yaw: 1
ball_states_p: 3
command: 2
add_noise: false
obs_noise:
projected_gravity: 0.05
dof_pos: 0.01
dof_vel: 0.1
last_actions: 0
gait_sin_indict: 0
body_yaw: 0.03
ball_states_p: 0.05
command: 0
pixel_observations:
enable: false
height: 360
width: 360
cam_range: 110
history: 1
head_cam_pose: [0.3, 0.0, 0.0]
cam_heading_rad: 0.0
# bot_cam_pose: [0.25, 0.0, -0.1]
obs_privilege: true
empty_privilege: false
priviledgeStates:
base_lin_vel: 3
base_ang_vel: 3
base_height: 1
ball_states_v_0: 3
ball_states_p_0: 3
# ball_states_v_1: 3
# ball_states_p_1: 3
# ball_states_v_2: 3
# ball_states_p_2: 3
# ball_states_v_3: 3
# ball_states_p_3: 3
# ball_states_v_6: 3
# ball_states_p_6: 3
dof_stiff: 12
dof_damp: 12
dof_calib: 12
payload: 1
com: 3
friction: 4
restitution: 4
ball_mass: 1
ball_restitution: 1
# gravity_offset: 3
ball_drag: 1
# total: 12
actions_num: 12
randomCommandVelocityRanges:
linear_x: [-1.5, 1.5] # min max [m/s]
linear_x_init: [-1.5, 1.5] # [-0.3, 0.3] # min max [m/s]
num_bins_x: 1 # 20
linear_y: [-1.5, 1.5] # min max [m/s]
linear_y_init: [-1.5, 1.5] # [-0.3, 0.3] # min max [m/s]
num_bins_y: 1 # 20
clipObservations: 5.0
clipActions: 1.0
random_params:
dof_calib:
enable: true
range_low: -0.01
range_high: 0.01
stiffness:
enable: true
range_low: 95.
range_high: 100.
damping:
enable: true
range_low: 0.9
range_high: 0.9
friction:
enable: false
range_low: 2.0
range_high: 2.0
restitution:
enable: false
range_low: 0.2
range_high: 0.2
com:
enable: true
range_low: 0.0
range_high: 0.0
x_offset: 0.00
payload:
enable: true
range_low: -0.0
range_high: 0.0
push:
enable: false
interval_s: 7
max_vel: 0.5
ball_mass:
enable: true
range_low: 0.20
range_high: 0.2
ball_restitution:
enable: true
range_low: 0.5
range_high: 1.5
ball_drag:
enable: true
range_low: -0.1
range_high: 0.5 # 0.5
interval_s: 19
ball_reset:
enable: false
vel: 0.3
prob_vel: 2e-4
pos: 1.0
prob_pos: 1e-4
gravity:
enable: false
range_low: -0.8
range_high: 0.8
interval_s: 9
randomization: true
randomization_freq: 10000 # 1s = 50 steps
terminateCondition:
robot_ball_max: 3.0
ball_speed_max: 3.0
terrain:
type: 'plane' #plane trimesh
plane:
staticFriction: 0.5 # [-]
dynamicFriction: 0.0 # [-]
restitution: 0.01 # [-]
baseInitState:
pos: [0.0, 0.0, 0.9] # x,y,z [m]
rot: [0.00, 0.0, 0.0, 1.0] # x,y,z,w [quat]
vLinear: [0.0, 0.0, 0.0] # x,y,z [m/s]
vAngular: [0.0, 0.0, 0.0] # x,y,z [rad/s]
ballInitState:
pos: [0.0, 0.0, 0.1] # x,y,z [m]
randomPosRange: [1.5, 1.5, 0.0]
# ballInitSpeed: -1.0 # [m/s]
mass: 0.4 # [kg]
control:
# PD Drive parameters:
stiffness: 100.0 # [N*m/rad]
damping: 0.9 # [N*m*s/rad]
actionScale: 0.5
hipAddtionalScale: 0.5
controlFrequencyInv: 1 # 60 Hz
# todo: change to a1 param?
defaultJointAngles: # = target angles when action = 0.0
hip_abduction_left: 0.1
hip_rotation_left: 0.
hip_flexion_left: 1.
thigh_joint_left: -1.8
ankle_joint_left: 1.57
toe_joint_left: -1.57
hip_abduction_right: -0.1
hip_rotation_right: 0.
hip_flexion_right: 1.
thigh_joint_right: -1.8
ankle_joint_right: 1.57
toe_joint_right: -1.57
rewards:
only_positive_rewards_ji22_style: True
sigma_rew_neg: 0.02 # is important!!
rewardScales:
collision: -5.0
orientation: -5.0
lin_vel_z: -0.02
torque: -0.0001
dof_pos: -0.05
dof_acc: -2.5e-7
dof_vel: -0.0001
action_rate: -0.01 # when have lag, it will be different with smoothness
action_smoothness_1: -0.1
action_smoothness_2: -0.1
# base_height: -0.001
# walk this way, this replace the feet air time
tracking_contacts_shaped_force: 4.0
tracking_contacts_shaped_vel: 4.0
# raibert_heuristic_self: -10.0
raibert_heuristic_PID: -10.0
# feet_clearance: -30.0
tracking_lin_vel_PID: 2.0 # make sure it is after raibert_heuristic_PID
# dribbling ball
dribbling_robot_ball_vel: 0.5
dribbling_robot_ball_pos: 4.0
dribbling_ball_vel: 4.0
dribbling_robot_ball_yaw: 4.0
dribbling_ball_vel_norm: 4.0
dribbling_ball_vel_angle: 4.0
rewardParams:
tracking_contacts_shaped_force:
sigma: 100.
tracking_contacts_shaped_vel:
sigma: 10.
dribbling_ball_vel:
sigma: 0.25
raibert_heuristic_PID:
k1: 1.0
k2: 4.0
k3: 0.5
feet_clearance:
height: 0.04
tracking_lin_vel_PID:
sigma: 0.25
# for a1
urdfAsset:
collapseFixedJoints: True
fixBaseLink: False
defaultDofDriveMode: 4 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 4 effort)
learn:
# normalization
linearVelocityScale: 1.0
angularVelocityScale: 0.25
dofPositionScale: 1.0
dofVelocityScale: 0.05
# episode length in seconds
episodeLength_s: 40
curriculum:
resample_s: 10
success_threshold:
dribbling_ball_vel: 0.8
tracking_contacts_shaped_force: 0.9
tracking_contacts_shaped_vel: 0.9
local_range: [0.4, 0.4]
# viewer cam:
viewer:
refEnv: 0
pos: [0, 0, 4] # [m]
lookat: [1., 1, 3.3] # [m]
# set to True if you use camera sensors in the environment
enableCameraSensors: False
sim:
dt: 0.02
substeps: 2
up_axis: "z"
use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
gravity: [0.0, 0.0, -9.81]
physx:
num_threads: ${....num_threads}
solver_type: ${....solver_type}
use_gpu: ${contains:"cuda",${....sim_device}} # set to False to run on CPU
num_position_iterations: 4
num_velocity_iterations: 1
contact_offset: 0.02
rest_offset: 0.0
bounce_threshold_velocity: 0.1
max_depenetration_velocity: 100.0
default_buffer_size_multiplier: 5.0
max_gpu_contact_pairs: 8388608 # 8*1024*1024
num_subscenes: ${....num_subscenes}
contact_collection: 1 # 0: CC_NEVER (don't collect contact info), 1: CC_LAST_SUBSTEP (collect only contacts on last substep), 2: CC_ALL_SUBSTEPS (broken - do not use!)
task:
target_ball: True
target_goal: True
have_wall: False
actor_per_environment: 4
randomize: False
randomization_params: []