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

51 lines
1.4 KiB
YAML
Raw Normal View History

2024-10-07 11:57:32 +08:00
model_name: "model_0702.pt"
framework: "isaacgym"
rows: 4
cols: 3
use_history: True
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]
2024-10-10 21:22:58 +08:00
rl_kp: [20.1, 20.1, 20.1,
20.1, 20.1, 20.1,
20.1, 20.1, 20.1,
20.1, 20.1, 20.1]
rl_kd: [0.54, 0.54, 0.54,
0.54, 0.54, 0.54,
0.54, 0.54, 0.54,
0.54, 0.54, 0.54]
2024-10-07 11:57:32 +08:00
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]