跳到主要内容

强化学习案例

概述

本案例简单介绍如何使用乐聚开源的强化学习运动控制仓库kuavo-rl-opensource实现对乐聚夸父机器人的训练和部署。

效果展示

  • sim2sim
  • sim2real

部署

代码拉取和编译

git clone -b beta https://gitee.com/leju-robot/kuavo-rl-opensource.git

cd kuavo-rl-opensource/kuavo-robot-deploy/
sudo su
source installed/setup.bash
catkin build humanoid_controllers

H12遥控器控制说明

  • 启动说明
    • 实物启动
      • 启动前确保E建在最左边,F建在最右边。
      • 机器人缩腿后F键拨到最左边是站立。
      • 在机器人站立后,依次按下对应进入强化学习模式和解锁的按键。此时可以通过摇杆控制机器人。
      • E键拨到最右边是停止程序(注意此时机器人不会自动下蹲)

程序启动及控制说明

#新开终端
cd kuavo-rl-opensource
sudo su
source devel/setup.bash
# 仿真
roslaunch humanoid_controllers load_kuavo_mujoco_sim.launch joystick_type:=h12 # 启动rl控制器、wbc、仿真器。
# 实物
roslaunch humanoid_controllers load_kuavo_real.launch joystick_type:=h12 # 可以选择cali:=true和cali_arm:=true进行校准启动,但校准启动不会自动缩腿,需要把F键拨到最左边两次,第一次是执行缩腿,第二次是执行站立 。

注意:仿真和实物选择一个启动即可。也可通过键盘控制,joystick_type参数指定为sim即可,终端有按键功能提示。

启动说明

  • 强化学习H12遥控器建位说明: 跳转

  • 实物启动

    • 启动前确保E建在最左边,F建在最右边。
    • 机器人缩腿后F键拨到最左边是站立。
    • 在机器人站立后,依次按下对应进入强化学习模式和解锁的按键。此时可以通过摇杆控制机器人。
    • E键拨到最右边是停止程序(注意此时机器人不会自动下蹲)

电机控制话题说明

  • 电机控制指令通过ROS话题/joint_cmd发布,消息类型为kuavo_msgs::jointCmd。控制方式根据control_modes字段决定是力矩控制(力控)还是位置控制(位控),具体实现如下:

1. 控制指令输出方式

  • 消息结构jointCmd消息包含以下字段:
字段类型描述
joint_qfloat64[]目标关节位置(弧度)
joint_vfloat64[]目标关节速度(弧度/秒)
taufloat64[]目标关节力矩(Nm)
tau_maxfloat64[]最大关节扭矩
tau_ratiofloat64[]扭矩系数
joint_kpfloat64[]kp参数
joint_kdfloat64[]kd参数
control_modesint32[]控制模式(0-力矩,1-速度,2-位置)
  • 发布逻辑:在update()函数中,根据控制模式填充消息并发布到/joint_cmd

2. 控制模式选择

  • 力矩控制(CST)control_modes=0
  • 直接发送tau值到底层驱动器。
  • 示例代码段:
jointCmdMsg.control_modes.push_back(0); // CST模式
jointCmdMsg.tau.push_back(calculated_torque);
  • 位置控制(CSP)control_modes=2
  • 发送目标位置joint_q和PID参数kp/kd,由底层驱动器闭环控制。
  • 示例代码段:
jointCmdMsg.control_modes.push_back(2); // CSP模式
jointCmdMsg.joint_q.push_back(target_position);
jointCmdMsg.joint_kp.push_back(kp_value);

3. 混合控制实现

  • 模式切换:通过JointControlMode_数组配置每个关节的控制模式。
  • RL控制器:根据策略输出选择力矩或位置指令,例如:
if (JointControlMode_(i) == 0) { // 力矩控制
cmd[i] = kp*(目标位置 - 当前位置) - kd*速度;
} else if (JointControlMode_(i) == 2) { // 位置控制
发送目标位置和PID参数;
}

4. 底层硬件交互

  • 接口处理KuavoHardwareInterface类实际将jointCmd转换为CAN指令,发送给电机驱动器。
  • 驱动器配置:驱动器需根据control_modes切换控制模式(如CSP/CST),并应用对应的PD参数。

总结

  • 力控:直接发送关节力矩值,驱动器闭环控制电流。
  • 位控:发送目标位置和PD参数,驱动器闭环控制位置。
  • 混合控制:通过每个关节独立的control_modes实现不同关节的力控/位控混合。

PD 控制实现分析

1. 参数配置模块

1.1 关节参数加载
// 从referenceFile加载主关节参数
loadData::loadEigenMatrix(referenceFile, "jointKp", jointKp_);
loadData::loadEigenMatrix(referenceFile, "jointKd", jointKd_);

// 头部关节特殊配置
if (headNum_ > 0) {
loadData::loadEigenMatrix(referenceFile, "head_kp_", head_kp_);
loadData::loadEigenMatrix(referenceFile, "head_kd_", head_kd_);
}
  • 参数维度:(jointNum + jointArmNum),支持不同关节独立配置
  • ​头部特殊处理:单独加载 headkp 和 headkd
1.2 滤波器参数
// 关节指令滤波器配置
Eigen::VectorXd jointCmdFilterCutoffFreq_(jointNum_ + jointArmNum_);
loadData::loadEigenMatrix(rlParamFile, "jointCmdFilterCutoffFreq", jointCmdFilterCutoffFreq_);
jointCmdFilter_.setParams(dt, jointCmdFilterCutoffFreq_);
  • 平滑RL输出动作,防止力矩突变

2.1 RL 控制器关节力矩计算

RL 控制器中的 PD 力矩计算
// updateRLcmd() 函数中的 PD 计算
jointTor_(i) = jointKp_(i) * (local_action[i] * actionScale_ - jointPos_[i] + defalutJointPos_[i]) - jointKd_(i) * jointVel_[i];

//其中(local_action[i] * actionScale_ - jointPos_[i] + defalutJointPos_[i])是关节位置误差,-jointVel_[i]是速度误差
  • 公式: PD公式

  • actionScale_ 缩放 RL 输出动作值

  • clipActions_ 限制动作范围,防止过大

头部关节的独立 PD 控制
// 头部力矩计算
vector_t head_feedback_tau = head_kp_.cwiseProduct(desire_head_pos_ - sensor_data_head_.jointPos_)
+ head_kd_.cwiseProduct(-sensor_data_head_.jointVel_);
  • 公式: 头部PD公式

  • 独立于身体控制回路,直接使用传感器反馈数据

程序参阅

  • 路径:<kuavo-rl-opensource>/src/humanoid-control/humanoid_controllers/src/humanoidController.cpp

主要控制流程

  1. 启动控制器
    • 初始化硬件接口、WBC、状态估计器等。
    • 启动键盘控制线程和推理线程。
  2. 状态估计
    • 从传感器数据缓冲区获取最新的传感器数据。
    • 使用状态估计器更新机器人状态。
  3. 控制模式选择
    • 根据当前状态和用户输入选择控制模式(WBC 或 RL)。
  4. 控制计算
    • 如果选择 WBC 模式,调用 wbc_->update 计算关节扭矩。
    • 如果选择 RL 模式,调用神经网络模型生成控制命令。
  5. 命令发布
    • 将控制命令发布到硬件接口。
  6. 循环更新
    • 不断重复状态估计、控制计算和命令发布的过程。

训练

安装

isaacgym

wget https://developer.nvidia.com/isaac-gym-preview-4
tar -xvzf isaac-gym-preview-4 #将名字改为 isaacgym 并存放在'kuavo-robot-train'同级目录下

conda

推荐使用MiniConda,轻量化使用更灵活。

#安装
mkdir -p ~/miniconda3
wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh
bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3
rm ~/miniconda3/miniconda.sh
#初始化
~/miniconda3/bin/conda init --all
source ~/.bashrc

配置环境

conda create -n humanoid-gym-op python=3.8
conda activate humanoid-gym-op
cd kuavo-rl-opensource/kuavo-robot-train
pip install -e ../isaacgym/python
pip install -e .

Training and Playing

示例

python scripts/train.py --task=kuavo_s42_sk_ppo --run_name v1 --headless --num_envs 4096
python scripts/play.py --task=kuavo_s42_sk_ppo --run_name v1

按照指定的pt文件继续训练

python scripts/train.py --task=kuavo_s42_sk_ppo --run_name v1 --headless --num_envs 4096 --resume --load_run Feb07_11-27-10_v1 --checkpoint 0 #该例子表示文件保存在'kuavo-robot-train/logs/Kuavo_s42_sk_ppo/Feb07_11-27-10_v1'目录下,选择了model_0.pt文件进行继续训练,headless选项关闭了GUI显示。
python scripts/play.py --task=kuavo_s42_sk_ppo --run_name v1 --load_run Feb07_11-27-10_v1 --checkpoint 0

参数说明

自定义参数详解

1. 训练任务控制
参数名类型默认值关键作用使用场景示例
--taskstrXBotL_free定义训练任务类型切换机器人型号(如XBotL_walking
--max_iterationsint-最大训练迭代次数限制训练时长
--resumeflagFalse从检查点恢复训练训练意外中断后继续
2. 实验版本管理
参数名类型关键作用数据存储逻辑
--experiment_namestr标识实验项目对应 experiments/ 下的文件夹
--run_namestr单次运行标识同一实验的不同参数对比
--load_runstr加载历史运行记录-1 表示加载最新运行
--checkpointint指定模型检查点-1 加载最新检查点
3. 硬件资源配置
参数名类型默认值技术细节典型配置
--rl_devicestrcuda:0RL算法运行的设备cuda:1 指定第二块GPU
--num_envsint-并行环境数4096(需根据显存调整)
--horovodflagFalse启用分布式训练多GPU训练时使用
4. 可视化与调试
参数名类型关键作用典型使用场景
--headlessflag禁用图形渲染服务器无显示器环境
--seedint固定随机种子实验可复现性保障
5. 参数优先级逻辑
  • 命令行参数 > 配置文件 > 代码默认值