This codebase is forked from the ALOHA repo, and contains implementation for teleoperation and data collection with the Mobile ALOHA hardware. To build ALOHA, follow the Hardware Assembly Tutorial and the quick start guide below. To train imitation learning algorithms, you would also need to install ACT for Mobile ALOHA which is forked from ACT.
config
: a config for each robot, designating the port they should bind to, more details in quick start guide.launch
: a ROS launch file for all 4 cameras and all 4 robots.aloha_scripts
: python code for teleop and data collectionCurrently tested and working configurations:
Ongoing testing (compatibility effort underway):
~/interbotix_ws
which contains src
.~/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
catkin_make
inside ~/interbotix_ws
, make sure the build is successful~/interbotix_ws/src/interbotix_ros_toolboxes/interbotix_xs_toolbox/interbotix_xs_modules/src/interbotix_xs_modules/arm.py
, find function publish_positions
.
Change self.T_sb = mr.FKinSpace(self.robot_des.M, self.robot_des.Slist, self.joint_commands)
to self.T_sb = None
.
This prevents the code from calculating FK at every step which delays teleoperation.
The goal of this section is to run roslaunch aloha 4arms_teleop.launch
, which starts
communication with 4 robots and 3 cameras. It should work after finishing the following steps:
Step 1: Connect 4 robots to the computer via USB, and power on. Do not use extension cable or usb hub.
To check if the robot is connected, install dynamixel wizard here
Dynamixel wizard is a very helpful debugging tool that connects to individual motors of the robot. It allows things such as rebooting the motor (very useful!), torque on/off, and sending commands. However, it has no knowledge about the kinematics of the robot, so be careful about collisions. The robot will collapse if motors are torque off i.e. there is no automatically engaged brakes in joints.
Open Dynamixel wizard, go into options
and select:
Note: repeat above everytime before you scan.
Then hit Scan
. There should be 4 devices showing up, each with 9 motors.
One issue that arises is the port each robot binds to can change over time, e.g. a robot that
is initially ttyUSB0
might suddenly become ttyUSB5
. To resolve this, we bind each robot to a fixed symlink
port with the following mapping:
ttyDXL_master_right
: right master robot (master: the robot that the operator would be holding)ttyDXL_puppet_right
: right puppet robot (puppet: the robot that performs the task)ttyDXL_master_left
: left master robotttyDXL_puppet_left
: left puppet robotTake ttyDXL_master_right
: right master robot as an example:
Find the port that the right master robot is currently binding to, e.g. ttyUSB0
run udevadm info --name=/dev/ttyUSB0 --attribute-walk | grep serial
to obtain the serial number. Use the first one that shows up, the format should look similar to FT6S4DSP
.
sudo vim /etc/udev/rules.d/99-fixed-interbotix-udev.rules
and add the following line:
SUBSYSTEM=="tty", ATTRS{serial}=="
This will make sure the right master robot is always binding to ttyDXL_master_right
Repeat with the rest of 3 arms.
To apply the changes, run sudo udevadm control --reload && sudo udevadm trigger
If successful, you should be able to find ttyDXL*
in your /dev
Step 2: Set max current for gripper motors
[ID:009] XM430-W350
38 Current Limit
, enter 300
, then hit save
at the bottom.Step 3: Setup 3 cameras
You may use usb hub here, but maximum 2 cameras per hub for reasonable latency.
To make sure all 3 cameras are binding to a consistent port, similar steps are needed.
Cameras are by default binding to /dev/video{0, 1, 2...}
, while we want to have symlinks {CAM_RIGHT_WRIST, CAM_LEFT_WRIST, CAM_HIGH}
Take CAM_RIGHT_WRIST
as an example, and let's say it is now binding to /dev/video0
. run udevadm info --name=/dev/video0 --attribute-walk | grep serial
to obtain it's serial. Use the first one that shows up, the format should look similar to 0E1A2B2F
.
Then sudo vim /etc/udev/rules.d/99-fixed-interbotix-udev.rules
and add the following line
SUBSYSTEM=="video4linux", ATTRS{serial}=="
Repeat this for {CAM_LEFT_WRIST, CAM_HIGH}
in additional to CAM_RIGHT_WRIST
To apply the changes, run sudo udevadm control --reload && sudo udevadm trigger
If successful, you should be able to find {CAM_RIGHT_WRIST, CAM_LEFT_WRIST, CAM_HIGH}
in your /dev
Step 4: Setup the AgileX Tracer base
pip3 install pyagxrobots
sudo modprobe gs_usb
sudo ip link set can0 up type can bitrate 500000
ifconfig -a
sudo apt install can-utils
# receiving data from can0
candump can0
At this point, have a new terminal
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
If no error message is showing up, the computer should be successfully connected to all 3 cameras, all 4 robot arms and the robot base.
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
Notice: Before running the commands below, be sure to place all 4 robots in their sleep positions, and open master robot's gripper. All robots will rise to a height that is easy for teleoperation.
# ROS terminal
conda deactivate
source /opt/ros/noetic/setup.sh && source ~/interbotix_ws/devel/setup.sh
roslaunch aloha 4arms_teleop.launch
# Right hand terminal
conda activate aloha
cd ~/interbotix_ws/src/aloha/aloha_scripts
python3 one_side_teleop.py right
# Left hand terminal
conda activate aloha
cd ~/interbotix_ws/src/aloha/aloha_scripts
python3 one_side_teleop.py left
The teleoperation will start when the master side gripper is closed.
To set up a new terminal, run:
conda activate aloha
cd ~/interbotix_ws/src/aloha/aloha_scripts
The one_side_teleop.py
we ran is for testing teleoperation and has no data collection. To collect data for an episode, run:
python3 record_episodes.py --dataset_dir <data save dir> --episode_idx 0
This will store a hdf5 file at <data save dir>
.
To change episode length and other params, edit constants.py
directly.
To visualize the episode collected, run:
python3 visualize_episodes.py --dataset_dir <data save dir> --episode_idx 0
To replay the episode collected with real robot, run:
python3 replay_episodes.py --dataset_dir <data save dir> --episode_idx 0
To lower 4 robots before e.g. cutting off power, run:
python3 sleep.py