forked from YikaiFu-cart/acAubo
Compare commits
5 Commits
7eee2e07c1
...
v1.0.0
| Author | SHA1 | Date | |
|---|---|---|---|
| b9888055eb | |||
| 20a0013cbd | |||
| 4768d809e1 | |||
| 0d0b398552 | |||
| 8636099a52 |
213
README.md
213
README.md
@ -1,8 +1,12 @@
|
||||
# TomatoPick 番茄采摘系统
|
||||
|
||||
TomatoPick 是一个面向番茄自动采摘实验的 Python 项目,集成了 Tkinter 参数界面、Intel RealSense RGB-D 相机、YOLO pose 目标检测、AUBO 机械臂控制和 AGV 移动平台控制。
|
||||
TomatoPick 是一个面向番茄自动采摘实验的 Python 运行端项目。项目集成 Tkinter 参数界面、Intel RealSense RGB-D 相机、YOLO pose 检测、AUBO 机械臂控制和 AGV 移动平台控制,用于完成“巡检、发现番茄、停车、定位、抓取、放置、继续巡检”的闭环流程。
|
||||
|
||||
当前仓库是运行端工程,核心代码集中在 `main.py`、`control.py` 和 `control_core.py`,辅助脚本位于 `tools/`。
|
||||
当前仓库的主要入口是:
|
||||
|
||||
- `main.py`:图形界面入口,推荐日常调试和运行使用。
|
||||
- `control.py`:兼容入口和配置桥接层,负责把 UI 或外部脚本设置的参数同步给核心逻辑。
|
||||
- `control_core.py`:设备连接、视觉检测、坐标转换、机械臂动作、AGV 控制和采摘状态机。
|
||||
|
||||
## 项目结构
|
||||
|
||||
@ -10,121 +14,84 @@ TomatoPick 是一个面向番茄自动采摘实验的 Python 项目,集成了
|
||||
TomatoPick/
|
||||
├── main.py # Tkinter 图形界面入口
|
||||
├── control.py # UI 与核心逻辑之间的配置转发/兼容入口
|
||||
├── control_core.py # 相机、YOLO、机械臂、AGV 与采摘状态机
|
||||
├── ui_settings.json # UI 参数缓存,运行后自动保存/更新
|
||||
├── control_core.py # RealSense、YOLO、机械臂、AGV 与采摘状态机
|
||||
├── start_tomatopick.bat # Windows 双击启动脚本
|
||||
├── ui_settings.json # UI 参数缓存,运行后会保存/更新
|
||||
├── models/ # YOLO 模型文件
|
||||
│ ├── best.pt
|
||||
│ ├── V1.0_s.pt
|
||||
│ ├── V2.0_s.pt
|
||||
│ ├── V2.1_s.pt
|
||||
│ └── yolo11n-pose.pt
|
||||
├── tools/
|
||||
│ ├── pip_install.txt # 依赖安装命令参考
|
||||
│ ├── realsense_record_video.py # RealSense 录制辅助脚本
|
||||
│ ├── video_to_rgb_frames.py # 视频抽帧辅助脚本
|
||||
│ ├── aubo_joint_position.py # AUBO 关节位置辅助脚本
|
||||
│ └── 1.png # UI 相机区域背景图
|
||||
│ ├── aubo_joint_position.py # AUBO 关节位置读取辅助脚本
|
||||
│ └── 1.png # UI 相机区域默认背景图
|
||||
└── README.md
|
||||
```
|
||||
|
||||
## 功能概览
|
||||
|
||||
- 通过图形界面配置机械臂 IP、AGV IP、运行时长、YOLO 模型路径、放置位置等参数。
|
||||
- 支持完整采摘流程:AGV 巡检、视觉检测、停车、精确定位、机械臂抓取、放置、回 Home、AGV 继续前进。
|
||||
- 支持“视觉测试”模式,只启动 RealSense 和 YOLO 推理,不启动机械臂和 AGV,适合先调试模型与相机画面。
|
||||
- 将运行日志、终端输出和相机检测画面实时显示在 UI 中。
|
||||
- 通过 `ui_settings.json` 保存上一次 UI 参数,方便下次启动恢复。
|
||||
- 通过图形界面配置机械臂 IP、AGV IP、运行时长、YOLO 模型路径、放置位姿、末端剪刀开关等参数。
|
||||
- 支持完整采摘流程:AGV 巡检、视觉检测、AGV 停车、深度定位、机械臂抓取、放置、回 Home、AGV 继续前进。
|
||||
- 支持“视觉测试”模式,只启动 RealSense 和 YOLO 推理,不连接机械臂和 AGV,适合先调试模型与相机画面。
|
||||
- 在 UI 中实时显示运行日志、终端输出和相机检测画面。
|
||||
- 通过 `ui_settings.json` 保存上一次 UI 参数,便于下次启动恢复。
|
||||
|
||||
## 核心文件说明
|
||||
## 核心流程
|
||||
|
||||
### `main.py`
|
||||
完整流程由 `control_core.main()` 启动,内部会依次完成:
|
||||
|
||||
图形界面入口,直接运行即可打开参数配置界面。
|
||||
```text
|
||||
连接机械臂
|
||||
-> 机械臂尽量回到 Home
|
||||
-> 连接 AGV 并获取控制权
|
||||
-> 初始化 RealSense
|
||||
-> 加载 YOLO pose 模型
|
||||
-> 启动视觉线程和 AGV 线程
|
||||
-> AGV 前进巡检
|
||||
-> 视觉发现候选番茄后通知 AGV 停车
|
||||
-> 视觉计算采摘点、深度和抓取角度
|
||||
-> 机械臂抓取并放置
|
||||
-> 机械臂返回 Home
|
||||
-> AGV 继续巡检
|
||||
```
|
||||
|
||||
主要职责:
|
||||
|
||||
- 构建 Tkinter 主界面,包括参数区、运行日志、相机画面和终端输出。
|
||||
- 读取和保存 `ui_settings.json`。
|
||||
- 选择 YOLO `.pt` 模型文件和相机背景图。
|
||||
- 启动完整采摘流程,内部调用 `control.main()`。
|
||||
- 启动视觉测试流程,只初始化 RealSense 与 YOLO。
|
||||
- 接收 `control_core.py` 推送的相机帧并叠加检测信息。
|
||||
|
||||
### `control.py`
|
||||
|
||||
兼容入口和配置桥接层。UI 或外部脚本会先修改这里的模块级参数,然后由 `_sync_config()` 同步到 `control_core.configure()`。
|
||||
|
||||
常用参数包括:
|
||||
|
||||
| 参数 | 说明 |
|
||||
| --- | --- |
|
||||
| `ROBOT_IP` / `ROBOT_PORT` | AUBO 机械臂连接地址 |
|
||||
| `AGV_IP` / `AGV_PORT` | AGV 连接地址 |
|
||||
| `AGV_SPEED_FORWARD` | AGV 前进速度 |
|
||||
| `TOTAL_DURATION` | 系统总运行时长,单位秒 |
|
||||
| `AGV_STOP_TIMEOUT` | AGV 停车后等待采摘的超时时间 |
|
||||
| `YOLO_MODEL_PATH` | YOLO pose 模型路径,默认 `best.pt` |
|
||||
| `YOLO_DETECT_CONF` | YOLO 推理置信度阈值 |
|
||||
| `PICK_CONFIDENCE_THRESHOLD` | 进入采摘逻辑的目标置信度阈值 |
|
||||
| `HOME_JOINTS` | 机械臂 Home 关节位 |
|
||||
| `place_positions` | 番茄放置位 |
|
||||
| `SCISSORS_ENABLED` | 是否启用末端剪刀/夹爪动作 |
|
||||
|
||||
### `control_core.py`
|
||||
|
||||
核心业务逻辑,负责设备连接、视觉检测、坐标转换、机械臂动作、AGV 控制和资源释放。
|
||||
|
||||
主要模块:
|
||||
|
||||
- `PlacementManager`:管理放置位。
|
||||
- `DetectedTomato` / `TomatoCandidate`:保存检测目标、关键点、深度和坐标信息。
|
||||
- `RobotArmController`:封装机械臂回 Home、移动到预抓取点、抓取点和放置点等动作。
|
||||
- `VisionController`:封装 RealSense 采集、YOLO pose 检测、关键点筛选、深度读取、坐标转换和抓取触发。
|
||||
- `AgvController`:封装 AGV 获取控制权、前进、停止和清理。
|
||||
|
||||
核心状态由 3 个 `threading.Event` 协调:
|
||||
线程间主要通过 3 个事件协作:
|
||||
|
||||
| 状态 | 说明 |
|
||||
| --- | --- |
|
||||
| `running` | 系统总运行开关 |
|
||||
| `has_tomato` | 视觉线程发现候选番茄后置位,通知 AGV 停车 |
|
||||
| `picking_done` | 本轮抓取放置完成后置位,允许 AGV 继续前进 |
|
||||
|
||||
简化流程:
|
||||
|
||||
```text
|
||||
连接机械臂
|
||||
-> 连接 AGV 并获取控制权
|
||||
-> 初始化 RealSense
|
||||
-> 加载 YOLO 模型
|
||||
-> 启动视觉线程和 AGV 线程
|
||||
-> AGV 前进巡检
|
||||
-> 视觉发现成熟番茄
|
||||
-> AGV 停止
|
||||
-> 视觉计算采摘点和抓取角度
|
||||
-> 机械臂抓取并放置
|
||||
-> 机械臂返回 Home
|
||||
-> AGV 继续前进
|
||||
```
|
||||
| `picking_done` | 本轮抓取放置完成后置位,允许系统进入下一轮巡检 |
|
||||
|
||||
## 环境依赖
|
||||
|
||||
建议在 Windows 环境下运行,并提前安装设备 SDK。
|
||||
建议在 Windows 环境下运行,并提前安装 RealSense、AUBO 机械臂和 AGV 所需 SDK。
|
||||
|
||||
主要 Python 依赖:
|
||||
主要 Python 依赖包括:
|
||||
|
||||
```text
|
||||
Pillow
|
||||
opencv-python
|
||||
numpy
|
||||
Pillow
|
||||
ultralytics
|
||||
pyrealsense2
|
||||
pyaubo_sdk
|
||||
pyaubo_agvc_sdk
|
||||
ultralytics
|
||||
```
|
||||
|
||||
`tkinter`、`threading`、`ctypes`、`signal` 等为 Python 标准库或随 Python 发行版提供。
|
||||
|
||||
可参考安装方式:
|
||||
可以参考 `tools/pip_install.txt` 安装依赖。CPU 环境示例:
|
||||
|
||||
```bash
|
||||
pip install opencv-python numpy Pillow ultralytics pyrealsense2
|
||||
python -m pip install pillow==11.2.1 opencv-python==4.10.0.84 numpy==2.0.0 pyrealsense2==2.55.1.6486 pyaubo_agvc_sdk==0.2.0 pyaubo_sdk==0.24.1 ultralytics==8.3.112 -i https://pypi.tuna.tsinghua.edu.cn/simple
|
||||
```
|
||||
|
||||
`pyaubo_sdk` 和 `pyaubo_agvc_sdk` 通常需要按设备厂商提供的 SDK 包安装。
|
||||
如需 GPU 版本 PyTorch,请先按本机 CUDA 版本安装 `torch`、`torchvision` 和 `torchaudio`,再安装其余依赖。
|
||||
|
||||
## 启动方式
|
||||
|
||||
@ -136,12 +103,23 @@ pip install opencv-python numpy Pillow ultralytics pyrealsense2
|
||||
python main.py
|
||||
```
|
||||
|
||||
界面中可执行:
|
||||
Windows 下也可以直接双击项目根目录中的:
|
||||
|
||||
```text
|
||||
start_tomatopick.bat
|
||||
```
|
||||
|
||||
该脚本会先自动切换到脚本所在目录,再执行 `python main.py`。因此把整个项目移动到其他目录或其他电脑后,只要 `start_tomatopick.bat` 仍和 `main.py` 在同一目录,就不需要手动修改项目路径。
|
||||
|
||||
如果需要桌面入口,可以自行在桌面创建快捷方式,并把目标指向 `start_tomatopick.bat`。
|
||||
|
||||
界面中主要按钮:
|
||||
|
||||
- `启动程序`:运行完整采摘流程,会连接机械臂、AGV、RealSense 并加载 YOLO。
|
||||
- `视觉测试`:只测试相机采集和 YOLO 检测,不启动机械臂与 AGV。
|
||||
- `视觉测试`:只测试相机采集和 YOLO 检测,不启动机械臂和 AGV。
|
||||
- `停止程序`:停止当前任务并释放资源。
|
||||
- `保存参数`:将当前 UI 参数写入 `ui_settings.json`。
|
||||
- `保存参数`:将当前 UI 参数写入 `ui_settings.json`,并同步到运行中的配置入口。
|
||||
- `保存位置`:保存当前放置位姿 `[x, y, z, roll, pitch, yaw]`。
|
||||
|
||||
### 2. 直接启动核心流程
|
||||
|
||||
@ -151,23 +129,28 @@ python main.py
|
||||
python control.py
|
||||
```
|
||||
|
||||
这种方式会使用 `control.py` 顶部定义的默认参数,不读取 UI 输入。
|
||||
这种方式使用 `control.py` 顶部定义的默认参数,不读取 UI 输入。
|
||||
|
||||
## 模型文件
|
||||
## 参数说明
|
||||
|
||||
默认模型路径为:
|
||||
`control.py` 是当前项目的主要可调参数入口。常用参数如下:
|
||||
|
||||
```text
|
||||
best.pt
|
||||
```
|
||||
| 参数 | 说明 |
|
||||
| --- | --- |
|
||||
| `ROBOT_IP` / `ROBOT_PORT` | AUBO 机械臂连接地址 |
|
||||
| `AGV_IP` / `AGV_PORT` | AGV 连接地址 |
|
||||
| `AGV_SPEED_FORWARD` | AGV 前进速度 |
|
||||
| `AGV_SPEED_STOP` | AGV 停止速度 |
|
||||
| `TOTAL_DURATION` | 系统总运行时长,单位秒 |
|
||||
| `AGV_STOP_TIMEOUT` | AGV 停车后等待采摘完成的超时时间 |
|
||||
| `YOLO_MODEL_PATH` | YOLO pose 模型路径,默认 `best.pt` |
|
||||
| `YOLO_DETECT_CONF` | YOLO 推理置信度阈值 |
|
||||
| `PICK_CONFIDENCE_THRESHOLD` | 进入采摘逻辑的目标置信度阈值 |
|
||||
| `HOME_JOINTS` | 机械臂 Home 关节位 |
|
||||
| `place_positions` | 番茄放置位姿列表,当前 UI 使用第一个放置位 |
|
||||
| `SCISSORS_ENABLED` | 是否启用末端剪刀/夹爪动作 |
|
||||
|
||||
可以将模型文件放在项目根目录,也可以在 UI 中选择任意 `.pt` 文件。使用绝对路径时,请确认路径在当前机器上存在。
|
||||
|
||||
当前 `ui_settings.json` 中保存的模型路径和背景图路径可能来自其他电脑或旧目录,首次运行前建议在 UI 中重新选择。
|
||||
|
||||
## 参数保存与传递
|
||||
|
||||
UI 参数传递流程:
|
||||
UI 参数传递链路:
|
||||
|
||||
```text
|
||||
main.py
|
||||
@ -181,25 +164,41 @@ main.py
|
||||
因此:
|
||||
|
||||
- 从 UI 启动时,以界面中的参数为准。
|
||||
- 直接运行 `control.py` 时,以 `control.py` 中写死的默认参数为准。
|
||||
- 如果修改了 `control.py` 的默认值,需要重新启动程序才会生效。
|
||||
- 直接运行 `control.py` 时,以 `control.py` 中的默认参数为准。
|
||||
- `ui_settings.json` 中的模型路径和背景图路径可能来自其他电脑或旧目录,首次运行前建议在 UI 中重新选择。
|
||||
|
||||
## 模型文件
|
||||
|
||||
项目默认模型路径为:
|
||||
|
||||
```text
|
||||
best.pt
|
||||
```
|
||||
|
||||
仓库中的 `models/` 目录已包含多份 `.pt` 模型。可以将目标模型放在项目根目录并使用 `best.pt`,也可以在 UI 中选择 `models/` 下或其他位置的 `.pt` 文件。
|
||||
|
||||
当前视觉逻辑使用 YOLO pose 的关键点:
|
||||
|
||||
- 第 0 个关键点:采摘点 `cutpoint`。
|
||||
- 第 1 个关键点:方向端点 `endpoint`。
|
||||
|
||||
模型类别、关键点顺序和训练定义需要与上述逻辑一致。
|
||||
|
||||
## 运行前检查
|
||||
|
||||
完整流程会控制真实硬件,启动前请确认:
|
||||
完整采摘流程会控制真实硬件。启动前请确认:
|
||||
|
||||
- AUBO 机械臂、AGV、RealSense 相机均已连接,并能被对应 SDK 访问。
|
||||
- `ROBOT_IP`、`AGV_IP`、端口号与现场设备一致。
|
||||
- `ROBOT_IP`、`AGV_IP` 和端口号与现场设备一致。
|
||||
- `HOME_JOINTS`、手眼标定矩阵 `R_tc` / `T_tc`、放置位 `place_positions` 已按现场设备校准。
|
||||
- YOLO 模型路径正确,且模型类别与关键点定义符合当前采摘逻辑。
|
||||
- 调试视觉效果时优先使用 `视觉测试`,确认画面和检测结果稳定后再运行完整采摘流程。
|
||||
- YOLO 模型路径正确,模型类别和关键点定义符合当前采摘逻辑。
|
||||
- 首次调试时优先使用 `视觉测试`,确认相机画面、检测框、关键点和深度结果稳定后,再运行完整采摘流程。
|
||||
|
||||
## 辅助脚本
|
||||
|
||||
`tools/` 目录提供了一些调试脚本:
|
||||
`tools/` 目录提供以下调试脚本:
|
||||
|
||||
- `realsense_record_video.py`:录制 RealSense 视频。
|
||||
- `video_to_rgb_frames.py`:从视频中导出 RGB 图片帧。
|
||||
- `aubo_joint_position.py`:辅助读取/查看 AUBO 机械臂关节位置。
|
||||
|
||||
这些脚本主要用于采集数据、调试相机和校准机械臂位姿。
|
||||
- `aubo_joint_position.py`:读取/查看 AUBO 机械臂关节位置。
|
||||
- `pip_install.txt`:依赖安装命令参考。
|
||||
|
||||
12
control.py
12
control.py
@ -26,7 +26,7 @@ AGV_RUN_DISTANCE = 5.0
|
||||
# -------------------- 运行时长与检测参数 --------------------
|
||||
TOTAL_DURATION = 300
|
||||
AGV_STOP_TIMEOUT = 10
|
||||
AGV_PICK_SETTLE_DELAY = 1.0
|
||||
AGV_PICK_SETTLE_DELAY = 1.5
|
||||
YOLO_MODEL_PATH = "best.pt"
|
||||
YOLO_DETECT_CONF = 0.5
|
||||
PICK_CONFIDENCE_THRESHOLD = 0.7
|
||||
@ -42,24 +42,25 @@ HOME_JOINTS = [-1.5247, 1.0899, 2.4671, 1.2761, 1.5113, 0.0001]
|
||||
APPROACH_Y_OFFSET = 0.15
|
||||
LIFT_Z_OFFSET = 0.035
|
||||
PICKUP_X_OFFSET = 0.0
|
||||
PICKUP_Y_OFFSET = -0.015
|
||||
PICKUP_Y_OFFSET = -0.013
|
||||
PICK_ANGLE_ORIENTATION_INDEX = 4
|
||||
PICK_ANGLE_SIGN = 1.0
|
||||
MAX_PICK_ANGLE_DEG = 30.0
|
||||
|
||||
# 当前项目只使用一个放置位,仍保留列表结构以兼容 control_core。
|
||||
place_positions = [[-0.6283, 0.0354, -0.0889, 2.8798, 0.02, -1.4346]]
|
||||
place_positions = [[-0.6203, 0.026, 0.1078, 2.9923, 0.0366, -1.4157]]
|
||||
|
||||
|
||||
# -------------------- 夹爪与机械臂运动参数 --------------------
|
||||
GRIPPER_CLOSE_IO = 1
|
||||
GRIPPER_OPEN_IO = 0
|
||||
GRIPPER_ACTION_DELAY = 2.0
|
||||
PICK_POINT_ARRIVAL_DELAY = 1.0
|
||||
SCISSORS_ENABLED = True
|
||||
|
||||
# 这里沿用底层 SDK 的弧度制。
|
||||
ARM_SPEED = 100 * (M_PI / 180)
|
||||
ARM_ACCEL = 100 * (M_PI / 180)
|
||||
ARM_SPEED = 150 * (M_PI / 180)
|
||||
ARM_ACCEL = 120 * (M_PI / 180)
|
||||
|
||||
|
||||
# -------------------- 参数同步清单 --------------------
|
||||
@ -88,6 +89,7 @@ _CONFIG_NAMES = (
|
||||
"GRIPPER_CLOSE_IO",
|
||||
"GRIPPER_OPEN_IO",
|
||||
"GRIPPER_ACTION_DELAY",
|
||||
"PICK_POINT_ARRIVAL_DELAY",
|
||||
"SCISSORS_ENABLED",
|
||||
"ARM_SPEED",
|
||||
"ARM_ACCEL",
|
||||
|
||||
@ -32,7 +32,7 @@ _runtime_config: Dict[str, Any] = {}
|
||||
|
||||
|
||||
PICK_ZONE_LEFT_RATIO = 1.0 / 3.0
|
||||
PICK_ZONE_RIGHT_RATIO = 2.0 / 3.0
|
||||
PICK_ZONE_RIGHT_RATIO = 7.0 / 10.0
|
||||
PICK_KEYPOINT_CONF_THRESHOLD = 0.8 # 关键点置信度低于该值时不参与采摘。
|
||||
PICK_CUTPOINT_KEYPOINT_INDEX = 0 # YOLO pose 第 0 个点为采摘点 cutpoint。
|
||||
PICK_ENDPOINT_KEYPOINT_INDEX = 1 # YOLO pose 第 1 个点为方向端点 endpoint。
|
||||
@ -741,6 +741,11 @@ class RobotArmController:
|
||||
self.return_home()
|
||||
return False
|
||||
|
||||
pick_point_delay = float(_cfg("PICK_POINT_ARRIVAL_DELAY"))
|
||||
if pick_point_delay > 0:
|
||||
print(f"机械臂:已到达抓取点,等待 {pick_point_delay:.1f} 秒后执行夹爪动作")
|
||||
time.sleep(pick_point_delay)
|
||||
|
||||
self.close_scissors_for_pick()
|
||||
|
||||
retreat_joints = self.move_pose(approach_pose, pickup_joints, description="采摘后返回预抓取点")
|
||||
|
||||
BIN
models/V1.0_s.pt
Normal file
BIN
models/V1.0_s.pt
Normal file
Binary file not shown.
BIN
models/V2.0_s.pt
Normal file
BIN
models/V2.0_s.pt
Normal file
Binary file not shown.
BIN
models/V2.1_s.pt
Normal file
BIN
models/V2.1_s.pt
Normal file
Binary file not shown.
BIN
models/best.pt
Normal file
BIN
models/best.pt
Normal file
Binary file not shown.
BIN
models/yolo11n-pose.pt
Normal file
BIN
models/yolo11n-pose.pt
Normal file
Binary file not shown.
13
start_tomatopick.bat
Normal file
13
start_tomatopick.bat
Normal file
@ -0,0 +1,13 @@
|
||||
@echo off
|
||||
setlocal
|
||||
|
||||
cd /d "%~dp0"
|
||||
python main.py
|
||||
|
||||
if errorlevel 1 (
|
||||
echo.
|
||||
echo TomatoPick failed to start or exited with an error.
|
||||
echo Working directory: %CD%
|
||||
echo.
|
||||
pause
|
||||
)
|
||||
BIN
tools/robot_tomato_harvest_icon.ico
Normal file
BIN
tools/robot_tomato_harvest_icon.ico
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 218 KiB |
Reference in New Issue
Block a user