walk_ppo.yaml 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149
  1. experiment:
  2. name: walk_ppo
  3. robot:
  4. model_name: guguji
  5. urdf_path: guguji_ros2_ws/src/guguji_ros2/urdf/guguji.urdf
  6. joint_names:
  7. - left_hip_pitch_joint
  8. - left_knee_pitch_joint
  9. - left_ankle_pitch_joint
  10. - left_ankle_joint
  11. - right_hip_pitch_joint
  12. - right_knee_pitch_joint
  13. - right_ankle_pitch_joint
  14. - right_ankle_joint
  15. command_topic_prefix: /guguji/command
  16. # 这一轮先把名义站姿改成“轻微屈膝 + 踝关节回正”的准备姿态,
  17. # 这样双腿更容易迈起来,而不是笔直站住后原地小幅摆动。
  18. nominal_joint_positions:
  19. left_hip_pitch_joint: 0.04
  20. left_knee_pitch_joint: 0.18
  21. left_ankle_pitch_joint: -0.10
  22. left_ankle_joint: 0.0
  23. right_hip_pitch_joint: 0.04
  24. right_knee_pitch_joint: 0.18
  25. right_ankle_pitch_joint: -0.10
  26. right_ankle_joint: 0.0
  27. # 这一轮继续保留“参考步态 + 残差动作”,
  28. # 但把残差动作再压小一点,让参考步态主导迈腿,PPO 主要负责微调。
  29. reference_gait:
  30. enabled: true
  31. period: 0.72
  32. # 支撑期稍长,保证落脚稳定;摆动期稍快,用于保持清晰的迈腿节奏。
  33. stance_ratio: 0.60
  34. hip_pitch_amplitude: 0.34
  35. hip_pitch_bias: 0.04
  36. knee_pitch_amplitude: 0.46
  37. knee_pitch_bias: 0.12
  38. swing_knee_scale: 1.10
  39. ankle_pitch_amplitude: 0.22
  40. ankle_pitch_bias: -0.05
  41. push_off_ankle_scale: 0.22
  42. # 把残差动作进一步收小,这样就算旧策略权重带来偏置,也不容易把机器人直接打翻。
  43. action_scale: 0.08
  44. action_smoothing: 0.82
  45. ros:
  46. joint_state_topic: /joint_states
  47. tf_topic: /tf
  48. clock_topic: /clock
  49. world_control_service: /world/default/control
  50. sim:
  51. world_name: default
  52. # walking 训练继续使用 service_step,便于一步动作对应一步奖励。
  53. step_mode: service_step
  54. control_dt: 0.05
  55. # 这一版把一步动作在 Gazebo 中的作用时间略微收回一点,优先保稳定。
  56. service_step_iterations: 22
  57. reset_settle_seconds: 1.0
  58. reset_hold_steps: 6
  59. # reset 时会直接删掉并重生模型,这里就是重生时使用的初始位姿。
  60. spawn_x: 0.0
  61. spawn_y: 0.0
  62. spawn_z: 0.35
  63. spawn_roll: 0.0
  64. spawn_pitch: 0.0
  65. spawn_yaw: 0.0
  66. action_publish_delay: 0.01
  67. post_step_wait_seconds: 0.01
  68. # 如果你想实时看画面,建议像现在这样开着 GUI 并使用 pause:=true。
  69. launch_hint: ros2 launch guguji_ros2 gazebo.launch.py pause:=true
  70. task:
  71. # 这里保留最终阶段的目标速度;真正训练时会由下面的 curriculum_stages
  72. # 先走 0.18 -> 0.22,再抬到 0.26,避免一开始就把 walking 强度顶太高。
  73. target_forward_velocity: 0.26
  74. target_base_height: null
  75. # 允许稍大一点机体摆动,为迈步时的动态平衡留空间。
  76. max_roll_rad: 0.90
  77. max_pitch_rad: 0.90
  78. min_base_height: 0.21
  79. termination_grace_steps: 18
  80. rewards:
  81. # 奖励函数这轮更偏向“真正前进”,同时保留基础稳定性约束。
  82. alive_bonus: 0.6
  83. velocity_tracking_scale: 4.8
  84. velocity_tracking_sigma: 0.10
  85. forward_progress_scale: 6.0
  86. hip_alternation_scale: 0.5
  87. hip_target_separation: 0.36
  88. hip_antiphase_sigma: 0.18
  89. knee_flexion_scale: 0.35
  90. knee_target: 0.28
  91. knee_flexion_sigma: 0.15
  92. upright_scale: 1.6
  93. height_scale: 0.9
  94. action_rate_penalty_scale: 0.004
  95. joint_limit_penalty_scale: 0.05
  96. lateral_velocity_penalty_scale: 0.08
  97. backward_velocity_penalty_scale: 2.8
  98. stall_penalty_scale: 4.6
  99. stall_velocity_threshold: 0.10
  100. fall_penalty: -15.0
  101. training:
  102. algorithm: ppo
  103. # 这里的 total_timesteps 是“无课程模式”的兜底值;
  104. # 只要 curriculum_stages 非空,train.py 就会按阶段自己的 timesteps 顺序训练。
  105. total_timesteps: 10000
  106. max_episode_steps: 500
  107. seed: 42
  108. device: cuda
  109. # 从当前最新的 walking 模型继续训,避免把已经学到的基础摆腿能力丢掉。
  110. init_model_path: outputs/walk_ppo_20260412_183147/final_model.zip
  111. # 课程学习的这一步不希望探索噪声太大,否则旧策略刚学到的迈腿节奏会被打散。
  112. initial_log_std: -2.2
  113. # walking 改成三段式课程:
  114. # 先让机器人适应 0.18 的低速稳定前进,再逐步爬到 0.22 和 0.26。
  115. curriculum_stages:
  116. - name: walk_v018
  117. target_forward_velocity: 0.18
  118. total_timesteps: 3000
  119. initial_log_std: -2.3
  120. - name: walk_v022
  121. target_forward_velocity: 0.22
  122. total_timesteps: 3000
  123. initial_log_std: -2.25
  124. - name: walk_v026
  125. target_forward_velocity: 0.26
  126. total_timesteps: 4000
  127. initial_log_std: -2.2
  128. # 学习率再收一点,避免在新步态逻辑下前几轮就把稳定性学坏。
  129. learning_rate: 0.00006
  130. n_steps: 256
  131. batch_size: 128
  132. gamma: 0.99
  133. gae_lambda: 0.95
  134. clip_range: 0.15
  135. ent_coef: 0.0
  136. vf_coef: 0.5
  137. policy_net_arch: [256, 256]
  138. checkpoint_freq: 5000
  139. output_root: guguji_rl/outputs
  140. evaluation:
  141. episodes: 3
  142. deterministic: true