quadruped_ros2_control/descriptions/unitree/go2_description/config/issacgym/config.yaml

53 lines
1.4 KiB
YAML
Raw Normal View History

2024-10-15 22:40:15 +08:00
model_name: "policy.pt"
2024-10-10 21:22:58 +08:00
framework: "isaacgym"
rows: 4
cols: 3
decimation: 4
2024-10-15 20:17:03 +08:00
num_observations: 48
2024-10-15 22:40:15 +08:00
observations: ["lin_vel", "ang_vel", "gravity_vec", "commands", "dof_pos", "dof_vel", "actions"]
#observations_history: [6, 5, 4, 3, 2, 1, 0]
2024-10-10 21:22:58 +08:00
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]
2024-10-15 22:40:15 +08:00
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]
2024-10-15 20:17:03 +08:00
fixed_kp: [60, 60, 60,
60, 60, 60,
60, 60, 60,
60, 60, 60]
fixed_kd: [5, 5, 5,
5, 5, 5,
5, 5, 5,
5, 5, 5]
hip_scale_reduction: 1.0
2024-10-10 21:22:58 +08:00
hip_scale_reduction_indices: [0, 3, 6, 9]
num_of_dofs: 12
action_scale: 0.25
2024-10-15 22:40:15 +08:00
2024-10-10 21:22:58 +08:00
lin_vel_scale: 2.0
ang_vel_scale: 0.25
dof_pos_scale: 1.0
dof_vel_scale: 0.05
2024-10-15 22:40:15 +08:00
2024-10-15 20:17:03 +08:00
commands_scale: [2.0, 2.0, 0.25]
2024-10-15 22:40:15 +08:00
2024-10-10 21:22:58 +08:00
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,
2024-10-15 20:17:03 +08:00
-0.1000, 0.8000, -1.5000,
2024-10-10 21:22:58 +08:00
0.1000, 1.0000, -1.5000,
2024-10-15 20:17:03 +08:00
-0.1000, 1.0000, -1.5000]