跳转至

快速上手

1237 个字 112 行代码 预计阅读时间 6 分钟

目标:先让机器人跑起来,再逐步调参适配不同地形

基于 F:\ROS\ocs2_ros2\ocs2_ros2,使用 ANYmal C 模型 + OCS2 MPC 框架


总体路线图

阶段一:环境编译 & 首次运行(平地站立/行走)
    ↓
阶段二:切换步态,熟悉交互方式
    ↓
阶段三:修改配置文件,调整运动参数
    ↓
阶段四:适配不同地形(坡地、楼梯)
    ↓
阶段五:接入感知模块(elevation map)

阶段一:编译与首次运行

1.1 编译整个工作空间

# 进入 ROS2 工作空间(ocs2_ros2 的上级)
cd /home/<your_ws>    # 或 WSL 中对应路径

# 编译(第一次会很慢,CppAD 代码生成需要 15-30 分钟)
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo

# source 环境
source install/setup.bash

⚠️ 首次编译注意task.inforecompileLibrariesCppAd = true,会在 /tmp/ocs2/ 生成自动微分代码,这是正常的,等待即可。第二次启动前可改为 false 加速启动。

1.2 首次运行(DDP 求解器,最稳定)

# 终端 1:启动完整仿真(MPC + Dummy仿真器 + RViz + 步态命令终端)
ros2 launch ocs2_legged_robot_ros legged_robot_ddp.launch.py

这个 launch 文件会自动启动 4 个节点:

节点 作用 源文件
robot_state_publisher 发布 ANYmal URDF basic.launch.py
rviz2 可视化 legged_robot.rviz
legged_robot_mpc DDP MPC 求解器 LeggedRobotDdpMpcNode.cpp
legged_robot_dummy 仿真执行器(模拟物理) LeggedRobotDummyNode.cpp
legged_robot_gait_command 步态命令交互终端 LeggedRobotGaitCommandNode.cpp

1.3 首次运行预期效果

  • RViz 中出现 ANYmal C 四足机器人,四腿接触地面,STANCE(站立)状态
  • 命令终端提示输入步态命令
  • MPC 求解器开始打印 solver statistics

阶段二:发送命令,让机器人动起来

步态命令终端的使用

legged_robot_gait_command 终端中按如下格式输入:

# 格式:[步态名]  [前进速度 m/s]  [侧移速度 m/s]  [旋转速度 rad/s]
trot  0.5  0.0  0.0       # trot步态,前进0.5m/s

2.2 推荐练习顺序

# 第1步:原地站立(确认系统正常)
stance  0.0  0.0  0.0

# 第2步:trot 慢速前进(最常用步态,对角腿交替)
trot  0.3  0.0  0.0

# 第3步:trot 正常速度
trot  0.5  0.0  0.0

# 第4步:原地旋转
trot  0.0  0.0  0.3

# 第5步:static_walk(三腿支撑,稳定性最好,后续上楼梯用这个)
static_walk  0.2  0.0  0.0

# 第6步:dynamic_walk(动态行走,中等速度)
dynamic_walk  0.3  0.0  0.0

2.3 gait.info 中所有步态一览

步态名           | 腿序列               | 周期   | 适用场景
-----------------|---------------------|--------|----------
stance           | 四腿同时支撑         | 0.5s   | 静止站立
trot             | LF+RH / RF+LH 交替  | 0.70s  | 平地快速行走 ★常用
standing_trot    | trot + 短暂全支撑    | 0.70s  | 平地稳定行走
dynamic_walk     | 三腿支撑轮流抬腿     | 1.0s   | 中速稳定
static_walk      | 三腿支撑,每腿独立   | 1.2s   | 慢速/不平地形 ★楼梯首选
amble            | 同侧腿前后序         | 0.80s  | 侧向稳定好
pawup            | 三腿支撑(单腿抬起) | 2.0s   | 特殊动作

阶段三:关键配置文件修改

这是 " 先跑起来,再调参 " 的核心,所有参数修改都在这三个文件里完成,不需要重新编译

3.1 文件 1task.infoMPC 核心参数

路径:

F:\ROS\ocs2_ros2\ocs2_ros2\basic examples\ocs2_legged_robot\config\mpc\task.info

关键参数说明与调整建议:

# ━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━
# 模型类型(一般不改)
centroidalModelType  1   # 1=单刚体动力学 SRBD(快), 0=全质心动力学(精确但慢)

# ━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━
# 摆腿轨迹参数(最常调)
swing_trajectory_config
{
  liftOffVelocity    0.2    # 抬腿初速度(正值向上),增大→起步更快
  touchDownVelocity  -0.4   # 落腿速度(负值向下),增大绝对值→落地更快
  swingHeight        0.1    # 摆腿最大高度 [m]
                            # ★ 平地: 0.10  | 坡地: 0.12 | 楼梯: 0.15~0.20
  touchdownAfterHorizon  0.2  # 超出时域后的落脚预测时间
  swingTimeScale     0.15   # 摆腿时间比例系数
}

# ━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━
# MPC 时域(适当增大可以看更远)
mpc
{
  timeHorizon       1.0    # 预测时域 [s],楼梯建议改为 1.5
  mpcDesiredFrequency  50  # MPC 求解频率 [Hz]
  mrtDesiredFrequency  400 # 控制执行频率 [Hz]
}

# ━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━
# 状态权重 Q(越大该状态越被严格跟踪)
Q
{
  (8,8)   500.0   # p_base_z:机身高度,控楼梯时可提高到 800
  (10,10) 200.0   # theta_base_y:俯仰角,楼梯时可提高到 400
  (11,11) 200.0   # theta_base_x:横滚角
}

# ━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━
# 加速提示:第二次运行前改为 false,节省启动时间
model_settings
{
  recompileLibrariesCppAd   false  # 第一次运行后改成 false!
}

3.2 文件 2gait.info — 步态定义

路径:

F:\ROS\ocs2_ros2\ocs2_ros2\basic examples\ocs2_legged_robot\config\command\gait.info

添加楼梯专用步态(在文件末尾追加

# 把 list 里也加上 stair_walk
list
{
  [0]  stance
  ...
  [12] stair_walk     # ← 新增
}

# 楼梯步态:超慢速 static_walk,每步留出足够时间
stair_walk
{
  modeSequence
  {
    [0]  LF_RF_RH    # 抬左前腿
    [1]  RF_LH_RH    # 抬左后腿
    [2]  LF_RF_LH    # 抬右前腿
    [3]  LF_LH_RH    # 抬右后腿
  }
  switchingTimes
  {
    [0]  0.0
    [1]  0.4          # 比 static_walk 的 0.3 更慢,每步0.4s
    [2]  0.8
    [3]  1.2
    [4]  1.6
  }
}

3.3 文件 3reference.info — 参考轨迹参数

路径:

F:\ROS\ocs2_ros2\ocs2_ros2\basic examples\ocs2_legged_robot\config\command\reference.info
# 运动速度限制
targetDisplacementVelocity   0.5    # 目标位移速度 [m/s],楼梯建议改 0.2
targetRotationVelocity       0.3    # 目标旋转速度 [rad/s]

# 机身默认高度(离地距离)
comHeight  0.575    # ANYmal C 标准高度
             # 坡地/楼梯:考虑改为 0.60 给腿留更多空间

# 默认关节姿态(不需要改)
defaultJointState { ... }

阶段四:不同地形调参速查表

修改 task.info 中对应参数后重启 launch 文件即可(无需重新编译

地形 swingHeight timeHorizon comHeight 推荐步态 Q(10,10) 俯仰
平地 0.10 1.0 0.575 trot 200
轻微坡地 (<15°) 0.12 1.0 0.58 dynamic_walk 300
陡坡 (15-30°) 0.15 1.5 0.60 static_walk 400
低台阶楼梯 (<15cm) 0.15 1.5 0.60 static_walk 400
标准楼梯 (~20cm) 0.20 1.5 0.62 stair_walk 500

阶段五:三种求解器对比与切换

OCS2 提供三种求解器,直接换 launch 文件即可:

# DDP(默认推荐,最稳定)
ros2 launch ocs2_legged_robot_ros legged_robot_ddp.launch.py

# SQP(基于 HPIPM,更适合有约束的复杂地形)
ros2 launch ocs2_legged_robot_ros legged_robot_sqp.launch.py

# IPM(内点法,处理不等式约束更精确)
ros2 launch ocs2_legged_robot_ros legged_robot_ipm.launch.py

建议: - 初期调试用 DDP(启动快、稳定) - 接入感知/楼梯后换 SQP(处理接触约束更好)


核心文件索引(快速查找)

F:\ROS\ocs2_ros2\ocs2_ros2\
│
├── basic examples\
│   ├── ocs2_legged_robot\
│   │   └── config\
│   │       ├── mpc\
│   │       │   └── task.info          ★★★ MPC核心参数(最常改)
│   │       └── command\
│   │           ├── gait.info          ★★★ 步态定义(添加新步态)
│   │           └── reference.info     ★★  速度/高度参考
│   │
│   └── ocs2_legged_robot_ros\
│       ├── launch\
│       │   ├── legged_robot_ddp.launch.py   ★ 主入口(DDP)
│       │   ├── legged_robot_sqp.launch.py   ★ 主入口(SQP)
│       │   ├── legged_robot_ipm.launch.py   ★ 主入口(IPM)
│       │   ├── basic.launch.py              RViz + robot_state_publisher
│       │   ├── dummy.launch.py              仿真执行节点
│       │   ├── gait_command.launch.py       步态命令终端
│       │   └── mpc_ddp.launch.py            MPC求解器节点
│       ├── src\
│       │   ├── LeggedRobotDdpMpcNode.cpp    MPC求解器主程序
│       │   ├── LeggedRobotDummyNode.cpp     ★ 仿真主程序(理解系统看这里)
│       │   └── LeggedRobotGaitCommandNode.cpp  步态命令接收
│       └── rviz\
│           └── legged_robot.rviz            RViz配置(可按需修改显示)
│
└── advance examples\
    └── ocs2_perceptive_anymal\
        ├── ocs2_switched_model_interface\
        │   └── include\...\terrain\
        │       └── TerrainModel.h      ★★ 地形接口(感知阶段使用)
        └── segmented_planes_terrain_model\  感知地形模型(接入elevation map用)

常见问题排查

问题 原因 解决
启动很慢(等 10 分钟) 首次 CppAD 编译 正常,等待完成后将 recompileLibrariesCppAd 改为 false
机器人倒下 Q 权重太小 / swingHeight 太小 增大Q(10,10) , Q(11,11);减小前进速度
步态命令无响应 步态名拼写错误 检查 gait.info 中的 list 列表
RViz 中机器人乱晃 MPC 求解失败 降低速度命令;检查 task.info dt nThreads
找不到 /tmp/ocs2 未生成 CppAD 代码 recompileLibrariesCppAd = true 重新运行一次
上楼梯腿打到台阶 swingHeight 不够 0.1 逐步调到 0.20

快速启动 Checklist

□ 1. colcon build 完成(绿色)
□ 2. source install/setup.bash
□ 3. task.info:recompileLibrariesCppAd = true(首次),之后改 false
□ 4. ros2 launch ocs2_legged_robot_ros legged_robot_ddp.launch.py
□ 5. RViz 中看到机器人站立
□ 6. 在 gait_command 终端输入:trot 0.3 0.0 0.0
□ 7. 机器人开始 trot 行走 ✓
□ 8. 尝试 static_walk 0.2 0.0 0.0(更稳定)
□ 9. 修改 swingHeight 观察效果
□ 10. 切换 SQP 求解器测试