此代码库是从 ALOHA 存储库分叉而来的,其中包含使用 Mobile ALOHA 硬件进行远程操作和数据收集的实现。 要构建 ALOHA,请按照下面的硬件组装教程和快速入门指南进行操作。 要训练模仿学习算法,您还需要安装从 ACT 分叉而来的 ACT for Mobile ALOHA。
config
:每个机器人的配置,指定它们应该绑定到的端口,更多详细信息请参阅快速入门指南。launch
:所有 4 个相机和所有 4 个机器人的 ROS 启动文件。aloha_scripts
:用于 Teleop 和数据收集的 Python 代码
当前测试和工作配置:
- ✅ Ubuntu 18.04 + ROS 1 noetic
- ✅ Ubuntu 20.04 + ROS 1 概念
正在进行的测试(兼容性工作正在进行中):
- 🚧 ROS 2 系列
- 🚧 >= Ubuntu 22.04
- 按照 https://docs.trossenrobotics.com/interbotix_xsarms_docs/ 安装 ROS 和 interbotix 软件
- 这将创建包含 的目录。
~/interbotix_ws
src
- git clone 这个仓库
~/interbotix_ws/src
source /opt/ros/noetic/setup.sh && source ~/interbotix_ws/devel/setup.sh
sudo apt-get install ros-noetic-usb-cam && sudo apt-get install ros-noetic-cv-bridge
- run inside 中,确保构建成功
catkin_make
~/interbotix_ws
- 转到 ,查找函数 。
更改为 .
这可以防止代码在延迟远程操作的每一步都计算 FK。
~/interbotix_ws/src/interbotix_ros_toolboxes/interbotix_xs_toolbox/interbotix_xs_modules/src/interbotix_xs_modules/arm.py
publish_positions
self.T_sb = mr.FKinSpace(self.robot_des.M, self.robot_des.Slist, self.joint_commands)
self.T_sb = None
本节的目标是运行 ,它启动
与 4 个机器人和 3 个摄像头通信。完成以下步骤后,它应该可以正常工作:roslaunch aloha 4arms_teleop.launch
第 1 步:通过 USB 将 4 个机器人连接到计算机,然后开机。请勿使用延长线或 USB 集线器。
-
要检查机器人是否已连接,请在此处安装 dynamixel 向导
-
Dynamixel 向导是一个非常有用的调试工具,可以连接到机器人的各个电机。它允许 诸如重新启动电机(非常有用)、扭矩开/关和发送命令等操作。 但是,它对机器人的运动学一无所知,因此要小心碰撞。 如果电机扭矩关闭,即关节中没有自动接合的制动器,机器人就会崩溃。
-
打开 Dynamixel 向导,进入并选择:
options
- 协议 2.0
- 所有端口
- 1000000 基点
- ID 范围从 0 到 10
-
注意:每次扫描前都重复上述内容。
-
然后点击 。应该会显示 4 个设备,每个设备有 9 个电机。
Scan
-
出现的一个问题是每个机器人绑定到的端口会随着时间的推移而变化,例如机器人 最初可能会突然变为 。为了解决这个问题,我们将每个机器人绑定到一个固定的符号链接 port 的映射如下:
ttyUSB0
ttyUSB5
ttyDXL_master_right
:右主机器人(主机器人:操作员将持有的机器人)ttyDXL_puppet_right
:右 Puppet Robot(Puppet:执行任务的机器人)ttyDXL_master_left
: 左 Master RobotttyDXL_puppet_left
: 左木偶机器人
-
以 :right master robot 为例:
ttyDXL_master_right
-
找到正确的 master robot 当前绑定的端口,例如
ttyUSB0
-
运行 以获取序列号。使用显示的第一个,格式应类似于 。
udevadm info --name=/dev/ttyUSB0 --attribute-walk | grep serial
FT6S4DSP
-
sudo vim /etc/udev/rules.d/99-fixed-interbotix-udev.rules
并添加以下行:SUBSYSTEM=="tty", ATTRS{serial}=="<serial number here>", ENV{ID_MM_DEVICE_IGNORE}="1", ATTR{device/latency_timer}="1", SYMLINK+="ttyDXL_master_right"
-
这将确保正确的主机器人始终绑定到
ttyDXL_master_right
-
对其余 3 个臂重复此操作。
-
-
要应用更改,请运行
sudo udevadm control --reload && sudo udevadm trigger
-
如果成功,您应该能够在
ttyDXL*
/dev
第 2 步:设置夹爪电机的最大电流
- 打开 Dynamixel 向导,然后选择人偶手臂的手腕转动器。它的名称应该是
[ID:009] XM430-W350
- 提示:机器人底座上的 LED 在与 Dynamixel Wizard 对话时会闪烁。这将有助于确定选择了哪个机器人。
- 查找 ,输入 ,然后点击底部。
38 Current Limit
300
save
- 对两个 Puppet Robot 重复此操作。
- 这限制了通过机械手电机的最大电流,以防止过载错误。
第 3 步:设置 3 台摄像机
-
您可以在此处使用 USB 集线器,但每个集线器最多有 2 个摄像头,以实现合理的延迟。
-
为确保所有 3 台相机都绑定到一致的端口,需要执行类似的步骤。
-
默认情况下,相机会绑定到 ,而我们希望有符号链接
/dev/video{0, 1, 2...}
{CAM_RIGHT_WRIST, CAM_LEFT_WRIST, CAM_HIGH}
-
举个例子,假设它现在绑定到 。run 获取它的 serial。使用显示的第一个,格式应类似于 。
CAM_RIGHT_WRIST
/dev/video0
udevadm info --name=/dev/video0 --attribute-walk | grep serial
0E1A2B2F
-
然后添加以下行
sudo vim /etc/udev/rules.d/99-fixed-interbotix-udev.rules
SUBSYSTEM=="video4linux", ATTRS{serial}=="<serial number here>", ATTR{index}=="0", ATTRS{idProduct}=="085c", ATTR{device/latency_timer}="1", SYMLINK+="CAM_RIGHT_WRIST"
-
对
{CAM_LEFT_WRIST, CAM_HIGH}
CAM_RIGHT_WRIST
-
要应用更改,请运行
sudo udevadm control --reload && sudo udevadm trigger
-
如果成功,您应该能够在
{CAM_RIGHT_WRIST, CAM_LEFT_WRIST, CAM_HIGH}
/dev
第 4 步:设置 AgileX Tracer 基
- 通过库存的 CANBUS 转 USB 电缆将底座连接到计算机,然后开机。
- 从 AgileX 安装 SDK
pip3 install pyagxrobots
- 启用 gs_usb 内核模块
sudo modprobe gs_usb
- 启动 CAN 设备
sudo ip link set can0 up type can bitrate 500000
- 如果前面的步骤没有出现错误,您应该能够使用 command 现在看到 can 设备
ifconfig -a
- 安装和使用 can-utils 来测试硬件
sudo apt install can-utils
- 测试命令:
# receiving data from can0 candump can0
此时,有一个新的终端
conda deactivate # if conda shows up by default
source /opt/ros/noetic/setup.sh && source ~/interbotix_ws/devel/setup.sh
roslaunch aloha 4arms_teleop.launch
如果未显示错误消息,则计算机应成功连接到所有 3 个摄像头、所有 4 个机器人手臂和机器人底座。
- 确保 Dynamixel Wizard 已断开连接,并且没有应用程序正在使用网络摄像头的流。它将阻止 ROS 连接到 这些设备。
conda create -n aloha python=3.8.10
conda activate aloha
pip install torchvision
pip install torch
pip install pyquaternion
pip install pyyaml
pip install rospkg
pip install pexpect
pip install mujoco
pip install dm_control
pip install opencv-python
pip install matplotlib
pip install einops
pip install packaging
pip install h5py
pip install tqdm
pip install wandb
注意:在运行以下命令之前,请务必将所有 4 个机器人置于睡眠位置,并打开主机器人的夹持器。 所有机器人都将上升到易于远程操作的高度。
# ROS terminal conda deactivate source /opt/ros/noetic/setup.sh && source ~/interbotix_ws/devel/setup.sh roslaunch aloha 4arms_teleop.launch
conda activate aloha cd ~/interbotix_ws/src/aloha/aloha_scripts python3 one_side_teleop.py right
conda activate aloha cd ~/interbotix_ws/src/aloha/aloha_scripts python3 one_side_teleop.py left
conda activate aloha cd ~/interbotix_ws/src/aloha/aloha_scripts python3 one_side_teleop.py right
conda activate aloha cd ~/interbotix_ws/src/aloha/aloha_scripts python3 one_side_teleop.py left" tabindex="0" role="button">
当主侧机械手关闭时,遥控将开始。
要设置新终端,请运行:
conda activate aloha
cd ~/interbotix_ws/src/aloha/aloha_scripts
我们运行的是用于测试远程操作的,没有数据收集。要收集剧集的数据,请运行:one_side_teleop.py
python3 record_episodes.py --dataset_dir <data save dir> --episode_idx 0
这会在 上存储一个 hdf5 文件。
要更改剧集长度和其他参数,请直接编辑。<data save dir>
constants.py
要可视化收集的剧集,请运行:
python3 visualize_episodes.py --dataset_dir <data save dir> --episode_idx 0
要重播使用真实机器人收集的剧集,请运行:
python3 replay_episodes.py --dataset_dir <data save dir> --episode_idx 0
要在切断电源等之前降低 4 个机器人,请运行:
python3 sleep.py