56 lines
1.7 KiB
YAML
56 lines
1.7 KiB
YAML
model_name: "model_0702.pt"
|
|
framework: "isaacgym"
|
|
rows: 4
|
|
cols: 3
|
|
use_history: True
|
|
dt: 0.005
|
|
decimation: 4
|
|
num_observations: 45
|
|
observations: ["ang_vel", "gravity_vec", "commands", "dof_pos", "dof_vel", "actions"]
|
|
clip_obs: 100.0
|
|
clip_actions_lower: [-100, -100, -100,
|
|
-100, -100, -100,
|
|
-100, -100, -100,
|
|
-100, -100, -100]
|
|
clip_actions_upper: [100, 100, 100,
|
|
100, 100, 100,
|
|
100, 100, 100,
|
|
100, 100, 100]
|
|
rl_kp: [20, 20, 20,
|
|
20, 20, 20,
|
|
20, 20, 20,
|
|
20, 20, 20]
|
|
rl_kd: [0.5, 0.5, 0.5,
|
|
0.5, 0.5, 0.5,
|
|
0.5, 0.5, 0.5,
|
|
0.5, 0.5, 0.5]
|
|
fixed_kp: [80, 80, 80,
|
|
80, 80, 80,
|
|
80, 80, 80,
|
|
80, 80, 80]
|
|
fixed_kd: [3, 3, 3,
|
|
3, 3, 3,
|
|
3, 3, 3,
|
|
3, 3, 3]
|
|
hip_scale_reduction: 0.5
|
|
hip_scale_reduction_indices: [0, 3, 6, 9]
|
|
num_of_dofs: 12
|
|
action_scale: 0.25
|
|
lin_vel_scale: 2.0
|
|
ang_vel_scale: 0.25
|
|
dof_pos_scale: 1.0
|
|
dof_vel_scale: 0.05
|
|
commands_scale: [2.0, 2.0, 1.0]
|
|
torque_limits: [33.5, 33.5, 33.5,
|
|
33.5, 33.5, 33.5,
|
|
33.5, 33.5, 33.5,
|
|
33.5, 33.5, 33.5]
|
|
default_dof_pos: [ 0.1000, 0.8000, -1.5000,
|
|
-0.1000, 0.8000, -1.5000,
|
|
0.1000, 1.0000, -1.5000,
|
|
-0.1000, 1.0000, -1.5000]
|
|
joint_controller_names: ["FL_hip_controller", "FL_thigh_controller", "FL_calf_controller",
|
|
"FR_hip_controller", "FR_thigh_controller", "FR_calf_controller",
|
|
"RL_hip_controller", "RL_thigh_controller", "RL_calf_controller",
|
|
"RR_hip_controller", "RR_thigh_controller", "RR_calf_controller"]
|