Настройка программного обеспечения

Установка плагина, настройка ведущего/ведомого рычага, двуручное управление ROS2, интеграция LeRobot DK1, Python API и устранение неполадок. От новой установки Ubuntu до переносимой бимануальной системы.

Перейти в раздел:

Шаг 1 — Установка SDK

Установка SDK

DK1 SDK распространяется как плагин LeRobot через trlc-dk1 хранилище. Он регистрирует четыре типа устройств: dk1_leader, dk1_follower, bi_dk1_leader, и bi_dk1_follower.

Сначала установите LeRobot

pip install lerobot

Клонируйте и установите плагин DK1.

git clone https://github.com/TRLC-AI/trlc-dk1.git
cd trlc-dk1
uv pip install -e .

Проверьте установку

python3 -c "from lerobot.common.robots import make_robot; print('DK1 plugin OK')"

# Check that DK1 device types are registered
python3 -c "
from lerobot.common.robots.factory import get_robot_types
types = get_robot_types()
for t in types:
    if 'dk1' in t:
        print(t)
"

Вы должны увидеть dk1_leader, dk1_follower, bi_dk1_leader, bi_dk1_follower распечатано. Если нет, убедитесь, что плагин установлен правильно с помощью uv pip show trlc-dk1.

Установить из определенного коммита (для воспроизводимости)

cd trlc-dk1
git checkout v0.3.0
uv pip install -e .
Шаг 2 — Конфигурация лидера/последователя

Конфигурация рычага ведущего/ведомого

Бимануальная система DK1 основана на назначении портов, чтобы отличить ведущий рычаг (Dynamixel XL330) от ведомого рычага (DM4340 + DM4310). Неправильное назначение портов является наиболее распространенной ошибкой настройки.

Обнаружение последовательных портов USB

Запустите утилиту обнаружения портов LeRobot, поочередно подключая только одну руку:

# Connect ONLY the leader arm (Dynamixel XL330)
python -m lerobot.scripts.find_motors_bus_port
# Note the reported port, e.g. /dev/ttyACM0

# Disconnect leader, connect ONLY the follower arm (DM series)
python -m lerobot.scripts.find_motors_bus_port
# Note the reported port, e.g. /dev/ttyACM1

Создайте конфигурацию бимануального робота

Создайте файл конфигурации YAML для биручной пары. LeRobot использует это для направления команд нужной руке:

# ~/.lerobot/robots/dk1_bimanual.yaml
robot_type: bi_dk1_follower
leader_arms:
  left:
    port: /dev/ttyACM0
    motors: [shoulder_pan, shoulder_lift, elbow_flex, wrist_flex, wrist_roll, gripper_left, gripper_right]
follower_arms:
  left:
    port: /dev/ttyACM1
    motors: [shoulder_pan, shoulder_lift, elbow_flex, wrist_flex, wrist_roll, gripper_left, gripper_right]
cameras:
  wrist_left:
    type: opencv
    index: 0
    fps: 30
    width: 640
    height: 480
  overhead:
    type: opencv
    index: 2
    fps: 30
    width: 640
    height: 480

Проверьте конфигурацию

python -m lerobot.scripts.control_robot \
  --robot.type=bi_dk1_follower \
  --robot.config=~/.lerobot/robots/dk1_bimanual.yaml \
  --control.type=none

Это соединяется с обеими руками, не перемещая их. Проверьте наличие ошибок подключения. Если ни один из рычагов не может подключиться, повторно запустите обнаружение порта или поменяйте местами назначения портов.

Постоянство порта: Последовательные порты USB могут меняться между перезагрузками. Используйте правила udev для привязки порта к определенному рычагу по серийному номеру USB. См. Руководство по установке для шаблона правила udev.

Шаг 3 — Бимануальная настройка ROS2

Бимануальное управление ROS2

ROS2 Humble обеспечивает уровень управления более высокого уровня для DK1 с полной поддержкой двуручного планирования MoveIt2. Это необязательно для рабочих процессов сбора данных только с помощью LeRobot.

Установите пакеты ROS2 Humble и бимануальные пакеты.

sudo apt update && sudo apt install ros-humble-desktop \
  ros-humble-ros2-control ros-humble-ros2-controllers \
  ros-humble-moveit ros-humble-joint-state-publisher-gui -y

Клонируйте и создайте пакет DK1 ROS2.

mkdir -p ~/dk1_ws/src && cd ~/dk1_ws/src
git clone https://github.com/TRLC-AI/trlc-dk1-ros2.git
cd ~/dk1_ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install

Запуск в биручном режиме

source ~/dk1_ws/install/setup.bash

# Launch both arms (use_fake_hardware for testing without hardware)
ros2 launch trlc_dk1_ros2 dk1_bimanual.launch.py \
  use_fake_hardware:=false \
  leader_port:=/dev/ttyACM0 \
  follower_port:=/dev/ttyACM1

Тестирование с использованием поддельного оборудования (манипуляторы не требуются)

ros2 launch trlc_dk1_ros2 dk1_bimanual.launch.py \
  use_fake_hardware:=true

Отправить бимануальную траекторию

ros2 topic pub /follower_left/joint_trajectory_controller/joint_trajectory \
  trajectory_msgs/msg/JointTrajectory \
  '{joint_names: ["shoulder_pan"], points: [{positions: [0.3], time_from_start: {sec: 2}}]}'
Шаг 4 — Конфигурация LeRobot DK1

Конфигурация LeRobot DK1

LeRobot с плагином DK1 изначально поддерживает двуручную запись телеопераций. bi_dk1_follower Тип устройства записывает с обеих рук и всех камер одновременно.

Калибровка обоих рычагов

# Calibrate the leader arm
python -m lerobot.scripts.control_robot \
  --robot.type=dk1_leader \
  --robot.port=/dev/ttyACM0 \
  --control.type=calibrate

# Calibrate the follower arm
python -m lerobot.scripts.control_robot \
  --robot.type=dk1_follower \
  --robot.port=/dev/ttyACM1 \
  --control.type=calibrate

Начать бимануальную телеоперацию

python -m lerobot.scripts.control_robot \
  --robot.type=bi_dk1_follower \
  --robot.config=~/.lerobot/robots/dk1_bimanual.yaml \
  --control.type=teleoperate

Запишите бимануальный набор данных

python -m lerobot.scripts.control_robot \
  --robot.type=bi_dk1_follower \
  --robot.config=~/.lerobot/robots/dk1_bimanual.yaml \
  --control.type=record \
  --control.fps=30 \
  --control.repo_id=your-username/dk1-bimanual-pick-place-v1 \
  --control.num_episodes=50 \
  --control.single_task="Bimanual: pick up the block with left arm, transfer to right arm" \
  --control.warmup_time_s=5 \
  --control.reset_time_s=10

Нажмите на HuggingFace Hub

huggingface-cli login
python -m lerobot.scripts.push_dataset_to_hub \
  --repo_id=your-username/dk1-bimanual-pick-place-v1
Шаг 5 — API Python

API Python для бимануального управления

API-интерфейс DK1 Python обеспечивает прямой доступ к обоим плечам через последовательный порт. Для базового управления и регистрации данных не требуется ROS2.

Соедините обе руки

from trlc_dk1 import DK1Leader, DK1Follower, BimanualDK1

# Connect individually
leader = DK1Leader(port="/dev/ttyACM0")
follower = DK1Follower(port="/dev/ttyACM1")
leader.connect()
follower.connect()

# Or use the bimanual controller (recommended)
robot = BimanualDK1(
    leader_port="/dev/ttyACM0",
    follower_port="/dev/ttyACM1"
)
robot.connect()

Считайте совместные состояния обеих рук

import time
from trlc_dk1 import BimanualDK1

robot = BimanualDK1(leader_port="/dev/ttyACM0", follower_port="/dev/ttyACM1")
robot.connect()

for _ in range(100):
    leader_state = robot.get_leader_state()
    follower_state = robot.get_follower_state()
    print(f"Leader:   {leader_state.positions}")
    print(f"Follower: {follower_state.positions}")
    time.sleep(0.033)  # 30 Hz

robot.disconnect()

Запуск цикла лидер-последователь вручную

from trlc_dk1 import BimanualDK1
import time

robot = BimanualDK1(leader_port="/dev/ttyACM0", follower_port="/dev/ttyACM1")
robot.connect()
robot.enable_follower()

try:
    while True:
        leader_state = robot.get_leader_state()
        # Apply leader positions to follower (scaled if needed)
        robot.set_follower_positions(leader_state.positions)
        time.sleep(0.01)  # 100 Hz control loop
finally:
    robot.disable_follower()
    robot.disconnect()
Дополнительно — моделирование

Поддержка моделирования

DK1 поддерживает бимануальное моделирование MuJoCo с калиброванной моделью, которая отражает кинематику реального оборудования. Обучите политики в моделировании перед развертыванием на оборудовании.

Бимануальное моделирование MuJoCo

pip install mujoco
git clone https://github.com/TRLC-AI/trlc-dk1-mujoco.git
cd trlc-dk1-mujoco

# Run the bimanual simulation with leader/follower
python examples/bimanual_sim.py

# Run with keyboard teleop
python examples/bimanual_sim.py --teleop keyboard

Тренируйте политику в отношении среды MuJoCo

python -m lerobot.scripts.train \
  --policy.type=act \
  --env.type=dk1_bimanual_sim \
  --policy.chunk_size=100 \
  --training.num_epochs=5000 \
  --output_dir=outputs/dk1-act-sim

Сим-реальная переписка: Модель DK1 MuJoCo использует геометрию файла STEP TRLC-DK1-Follower_v0.3.0 и измеренные кривые крутящего момента двигателя DM4340/DM4310. Политики, обученные на симуляционном переносе на реальное оборудование с минимальной настройкой для структурированных задач по сбору и размещению.

Поиск неисправностей

3 основные проблемы, специфичные для бимануалов

Ошибка 1 Руки назначены на один и тот же порт — ведомый копирует лидера, но сильно отстает

Обе руки соединены с одним и тем же /dev/ttyACM* порт или назначения портов поменялись местами. Ведущий рычаг (Dynamixel XL330) и ведомый рычаг (серия DM) используют разные протоколы; неправильное назначение приводит к немедленному сбою управления.

Исправить:

# 1. Unplug both arms
# 2. Connect ONLY the leader arm (XL330 servos)
python -m lerobot.scripts.find_motors_bus_port
# Note: leader_port = /dev/ttyACM?

# 3. Disconnect leader, connect ONLY the follower arm (DM servos)
python -m lerobot.scripts.find_motors_bus_port
# Note: follower_port = /dev/ttyACM?

# 4. Update your YAML config with the correct ports
# 5. Create udev rules to make assignments permanent
Ошибка 2 Следящий рычаг колеблется или выходит за пределы диапазона во время телеуправления

Коэффициент усиления частичного разряда ведомого рычага слишком высок для текущей конфигурации полезной нагрузки или рычага. Это особенно часто случается, когда руки нагружены концевыми рабочими органами или при работе с полным выпрямлением.

Исправить:

# Reduce follower PD gains in the DK1 config
# Edit trlc-dk1/configs/follower_gains.yaml:
joint_gains:
  default:
    kp: 30   # reduce from default 50
    kd: 0.5  # reduce from default 1.0
  wrist:
    kp: 15   # wrist joints need lower gains
    kd: 0.3

# Apply and restart teleoperation
python -m lerobot.scripts.control_robot \
  --robot.type=bi_dk1_follower \
  --control.type=teleoperate
Ошибка 3 Кадры камеры пропадают или не синхронизируются во время двуручной записи.

Конкуренция за полосу пропускания USB с двумя камерами и двумя последовательными портами USB на одном контроллере шины. Расхождение временных меток LeRobot между потоками камер и показаниями общего состояния превышает допустимые пределы.

Исправить:

# 1. Check which USB bus each device is on
lsusb -t

# 2. Spread devices across separate USB bus controllers
#    - Cameras: use a powered USB hub on one controller
#    - Arms: connect directly on a different controller

# 3. Reduce camera resolution if bandwidth is still tight
# In dk1_bimanual.yaml:
cameras:
  wrist_left:
    width: 480
    height: 320   # lower resolution reduces USB bandwidth

# 4. Verify timestamp skew is acceptable
python -m trlc_dk1.tools.check_sync \
  --config ~/.lerobot/robots/dk1_bimanual.yaml
# Target: < 5ms skew between all streams

Все еще застрял? Спросите на Форум ДК1 или проверьте существующие Проблемы с GitHub.

Программное обеспечение работает? Начните сбор бимануальных данных.

Как только обе руки начнут двигаться, следующим шагом будет телеоперация и двуручная запись набора данных.