概述
项目介绍和功能特性
项目介绍和功能特性 Desktop-Wanderer 是一个基于视觉引导的小型机器人系统,实现了自主目标检测、导航和抓取功能。系统采用模块化设计,支持多种硬件加速方案,具备以下核心功能特性:
- 视觉感知:基于YOLO的目标检测系统,支持ONNX CPU推理和Atlas 310B、RK3588 NPU硬件加速 process.py
- 智能导航:视觉引导的移动控制,能够自动导航至目标位置 move_controller.py
- 精确操作:支持两种机械臂控制模式 - ACT学习策略和逆运动学控制 setup.py
- 状态管理:基于状态机的行为控制,实现搜索-抓取的自动化流程 setup.py
系统架构概览
Desktop-Wanderer 采用四层分层架构设计,从应用层到硬件层逐级抽象:

系统核心是位于 src/main.py 的主控制循环 main.py ,负责协调各个子系统:
- 初始化阶段:加载配置、初始化机器人连接、读取初始关节角度
- 感知阶段:获取机器人观测数据,执行YOLO目标检测
- 决策阶段:根据当前状态选择相应控制器(移动控制或机械臂控制)
- 执行阶段:发送控制指令到机器人,维持指定FPS控制频率
快速开始指南
环境准备
- 硬件要求:
- LeKiwi机器人平台
- USB串口连接舵机控制板
- 12V8A电源连接舵机控制板
- 软件依赖
pip install -r requirements.txt
- lerobot 平台安装
python 3.10环境准备
wget "https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-$(uname)-$(uname -m).sh"
bash Miniforge3-$(uname)-$(uname -m).sh
conda create -y -n lerobot python=3.10
lerobot 安装
conda activate lerobot
conda install ffmpeg -c conda-forge
git clone https://github.com/huggingface/lerobot.git
cd lerobot
pip install -e .
# 舵机驱动安装
pip install -e ".[feetech]"
详细说明可看安装与配置部分
配置设置
修改 config.yaml 配置文件:
port: /dev/tty.usbmodem5AE60581751 # 串口号
fps: 20 # 帧率
log_level: INFO # 日志级别
hardware_mode: normal # normal,310b,rk3588
control_mode: inverse # inverse, act
安装与配置 (Installation & Configuration)
环境要求和依赖
在PC上进行调试需要安装lerobot平台,具体安装方法可以参考 lerobot_Installation,下文也会给出。
安装miniforge
wget "https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-$(uname)-$(uname -m).sh"
bash Miniforge3-$(uname)-$(uname -m).sh
创建python3.10环境
conda create -y -n lerobot python=3.10
激活环境
conda activate lerobot
conda安装ffmpeg
conda install ffmpeg -c conda-forge
从源码下载安装lerobot
克隆仓库
git clone https://github.com/huggingface/lerobot.git
cd lerobot
安装
pip install -e .
安装舵机控制SDK
pip install -e ".[feetech]"
基础环境准备完毕,在代码根目录运行
python -m src.main
配置文件说明
配置文件内容
port: /dev/ttyACM0 # 在控制板上的默认端口号
fps: 20 # 每秒识别20帧
log_level: INFO # 日志级别
hardware_mode: normal # normal,310b,rk3588 支持的硬件
control_mode: inverse # inverse, act 行动模式
其中
- port:在安装lerobot后,处于lerobot环境下,将设备连接到电脑运行
lerobot-find-port,之后会出现一堆设备号,根据指示,拔掉连接线后按回车,即可获得串口号,控制板上的环境已经安装完毕,端口号为固定的 '/dev/ttyACM0' - hardware_mode: 在PC上调试的时候选择normal模式,在控制板上运行的时候,为rk3588
首次运行
机械臂初始设置
连接机械臂后首次运行代码,由于没有硬件配置文件,需要初始化机械臂
正常会看见
"Move robot to the middle of its range of motion and press ENTER...."
之后将所有电机置于中点位置,按回车,之后缓慢的转动所有电机,到每个电机的上下限位,之后按回车,即可完成配置文件的录入。
项目再次启动
如果已经生成配置文件,打开项目能看到
"Press ENTER to use provided calibration file associated with the id {self.id}, or type 'c' and press ENTER to run calibration: "
之后可以按ENTER进入项目,或者等待3秒进入项目,或者输入c + ENTER重新初始化。
配置文件路径为
~/.cache/huggingface/lerobot/calibration/robots/lekiwi/None.json
删除它后进入项目自动进入初始化模式
硬件连接设置
核心架构 (Core Architecture)
四层架构设计
模块依赖关系
初始化流程
状态机 (State Machine)
RobotStatus 枚举定义
文件: src/setup.py
class RobotStatus(Enum):
SEARCH = "search" # 找球模式
PICK = "pick" # 捡球模式
FIND_BUCKET = "find_bucket" # 找桶模式
PUT_BALL = "put_ball" # 放球模式
状态转换图
┌─────────────────────────────────────────────────────┐
│ │
▼ │
┌─────────┐ ┌─────────┐ ┌──────────────┐ ┌──────────┐ ┌─────────┐
│ SEARCH │───▶│ PICK │───▶│ FIND_BUCKET │───▶│ PUT_BALL │───▶│ SEARCH │
└─────────┘ └─────────┘ └──────────────┘ └──────────┘ └─────────┘
▲ │ │ │ │
│ │ │ │ │
└──────────────┴─────────────────┴────────────────┴──────────────┘
(reset_robot)
状态详细说明
1. SEARCH(找球模式)
进入条件:
- 系统启动后初始状态
- PUT_BALL 完成后返回
行为:
- 使用
move_controller()控制底盘移动 - 调用
yolo_infer()进行目标检测(找球) - 检测到球并在视野中央稳定 10 帧后进入 PICK 状态
目标检测区域:
┌─────────────────────────────────┐
│ │
│ ┌───────────────────┐ │
│ │ │ │
│ │ TARGET ZONE │ │ ← 球需要在这个区域内
│ │ │ │
│ └───────────────────┘ │
│ │
└─────────────────────────────────┘
2. PICK(捡球模式)
进入条件:
- SEARCH 状态下检测到球并稳定 10 帧
行为:
- 使用
p_control_loop()执行CATCH_ACTION动作序列 - 逆运动学控制机械臂移动到球的位置
- 执行夹爪动作抓住球
- 动作序列完成后进入 FIND_BUCKET 状态
动作序列:
CATCH_ACTION = [
("move_to", (0.0989, 0.125)), # 移动到初始位置
("shoulder_pan", -12), # 肩部旋转
("gripper", 60), # 张开夹爪
("wrist_flex", 80), # 腕部弯曲
("move_to", (0.140, 0.1211)), # 移动到球上方
("move_to", (0.140, -0.05)), # 下降到球位置
("gap", 0), # 停顿
("gripper", -60), # 闭合夹爪(夹住球)
("gap", 0), # 停顿
("shoulder_pan", 12), # 肩部归位
("move_to", (-0.1, 0.2)), # 举起球
("wrist_flex", -20) # 腕部配合
]
3. FIND_BUCKET(找桶模式)
进入条件:
- PICK 状态动作序列执行完成
行为:
- 检查夹爪是否仍然夹住球(
gripper_pos > 25) - 如果球丢失,返回 SEARCH 状态重新寻找
- 使用
move_controller_for_bucket()控制底盘移动 - 调用
get_black_bucket_local()或get_red_bucket_local()寻找桶 - 检测到桶并在视野中央稳定 10 帧后进入 PUT_BALL 状态
找桶策略:
- 优先检测黑色桶
- 如果找不到黑色桶,检测红色桶
4. PUT_BALL(放球模式)
进入条件:
- FIND_BUCKET 状态下检测到桶并稳定 10 帧
行为:
- 使用
p_control_loop()执行PUT_ACTION动作序列 - 逆运动学控制机械臂移动到桶上方
- 执行夹爪动作释放球
- 动作序列完成后返回 SEARCH 状态
动作序列:
PUT_ACTION = [
("shoulder_lift", 50), # 抬起机械臂
("gap", 0), # 停顿
("gripper", 60), # 张开夹爪(放球)
("gap", 0), # 停顿
("move_to", (-0.1, 0.2)), # 收回机械臂
("gripper", -60), # 闭合夹爪
]
状态转换逻辑
文件: src/main.py
SEARCH → PICK
# move_controller.py:53-56
if position > (TARGET_POSITION + 10): # 球太大(太近)
action = direction.get_action("backward", 1)
elif center_x < left or center_x > right: # 球偏离中心
action = direction.get_action("rotate_left/right")
else:
_cycle_time += 1
if _cycle_time > 10: # 稳定10帧
set_robot_status(RobotStatus.PICK)
PICK → FIND_BUCKET
# main.py:121-123
if CATCH_ACTION[command_step][0] == "move_to":
if abs(current_x - target_x) < 0.002 and abs(current_y - target_y) < 0.002:
command_step += 1
if command_step == len(CATCH_ACTION):
set_robot_status(RobotStatus.FIND_BUCKET)
FIND_BUCKET → PUT_BALL
# move_controller.py:98-102
else:
_cycle_time += 1
if _cycle_time > 10:
set_robot_status(RobotStatus.PUT_BALL)
FIND_BUCKET → SEARCH(球丢失)
# main.py:80-83
gripper_pos = current_obs.get('arm_gripper.pos', 5)
is_gripper_holding = gripper_pos > 25
if not is_gripper_holding:
set_robot_status(RobotStatus.SEARCH)
reset_robot()
PUT_BALL → SEARCH
# main.py:136-146
if command_step == len(PUT_ACTION):
set_robot_status(RobotStatus.SEARCH)
reset_robot()
command_step = 0
稳定性计数器机制
文件: src/move_controller.py
_cycle_time = 0 # 全局计数器
def move_controller(...):
if result: # 检测到目标
if 目标在视野中央:
_cycle_time += 1
if _cycle_time > 10: # 稳定10帧
触发状态转换
else:
_cycle_time = 0 # 目标偏离,重置计数器
else: # 未检测到目标
_cycle_time = 0
作用:
- 防止误触发(目标一闪而过)
- 确保机器人已稳定对准目标
- 10 帧约等于 0.5 秒(20 FPS)
控制模式
文件: src/setup.py
class RobotControlModel(Enum):
ACT = "act" # ACT 学习策略控制
INVERSE = "inverse" # 逆运动学控制
| 模式 | 说明 | 使用场景 |
|---|---|---|
inverse | 逆运动学控制机械臂 | 默认模式,精确位置控制 |
act | ACT 策略控制 | 模仿学习模式 |
目标检测区域参数
文件: src/main.py:46-53
height, width = 480, 640
_target_w = (min(height, width) // 3) - 10 # 约 150
_target_h = min(height, width) // 3 # 约 160
_left = max(0, (width - _target_w) // 2) # 约 245
_top = max(0, (height - _target_h) // 2) # 约 160
_right = min(width, _left + _target_w) # 约 395
_bottom = min(height, _top + _target_h) # 约 320
这些参数定义了摄像头画面中央的目标区域,用于判断球/桶是否在视野中央。
控制系统 (Control Systems)
移动控制器
机械臂控制器
ACT策略控制器
逆运动学控制器
控制模式选择
视觉系统 (Vision System)
YOLO推理实现
硬件加速支持 (ONNX/Atlas 310B)
目标检测和跟踪
硬件抽象层 (Hardware Abstraction)
LeKiwi机器人接口
方向控制
键盘遥操作
主控制循环 (Main Control Loop)
控制循环实现
动作-观察循环
时序控制机制
开发指南 (Development Guide)
代码结构和规范
添加新功能
调试和测试
模型优化
参看1的doc/03_Rockchip_RKNPU_API_Reference_RKNN_Toolkit2_V2.3.2_CN.pdf,这是官方的API使用文档。
把onnx模型转为rknn模型的极简脚本:
# file name: onnx2rknn.py
from rknn.api import RKNN
rknn = RKNN()
rknn.config(target_platform='rk3588')
rknn.load_onnx(model='tennis.onnx')
rknn.build(do_quantization=False)
rknn.export_rknn(export_path='tennis.rknn')
rknn.release()
连接主机
目前有adb, ssh, 调试串口三种连接方式。日常调试推荐用ssh连接。
用户名:orangepi 密码:orangepi
# 调试串口连接
minicom -D /dev/ttyUSB0 -b 1500000
# usb线adb连接
adb devices
adb shell
# ssh连接
sudo ip a add 192.168.1.2/24 dev <ethN> # 设置主机的ip地址
ssh orangepi@192.168.1.10 # 开发板上靠近电源线的网口被设置为192.168.1.10
手动运行
系统启动后本程序会自动运行,可以手动运行观察输出。如下命令都是在开发板的系统上执行。
sudo systemctl stop chenlong-robot # 停止本程序的运行,注意下次重启后本程序依然会自动运行
conda activate rknn # 切换到本程序的运行环境
cd ~/Desktop-Wanderer # 切换到本程序所在的目录
python -m src.main # 手动运行本程序
附录
https://github.com/airockchip/rknn-toolkit2.git