Software Setup
LeRobot installation, SO-101 robot config, servo calibration, leader–follower teleop setup, Python API, and troubleshooting. Everything from a fresh Python install to a running arm.
Jump to a section:
LeRobot Installation
LeRobot is the only software package you need for the SO-101. It handles servo communication, calibration, teleop, and data recording.
Create a virtual environment
python -m venv ~/.venvs/so101
source ~/.venvs/so101/bin/activate # Windows: .venvs\so101\Scripts\activate
Install LeRobot
pip install lerobot
Verify installation
python -c "import lerobot; print(lerobot.__version__)"
Install from source (optional — for latest features)
git clone https://github.com/huggingface/lerobot.git
cd lerobot
pip install -e ".[so101]"
SO-101 Robot Configuration
LeRobot includes a built-in SO-101 robot config. You specify the USB port for the follower arm (and leader arm if using two-arm teleop).
Find your USB port
# Linux / macOS
ls /dev/ttyUSB* # typical: /dev/ttyUSB0, /dev/ttyUSB1
ls /dev/tty.usbserial* # macOS alternative
# Windows — check Device Manager → Ports → COMx
SO-101 config YAML
LeRobot uses an inline config on the command line or a YAML file. For a single-arm setup:
# ~/.lerobot/robots/so101_follower.yaml
robot_type: so101
port: /dev/ttyUSB0 # update to your port
cameras:
wrist_cam:
type: opencv
index_or_path: 0
fps: 30
width: 640
height: 480
Two-arm (leader–follower) config
# ~/.lerobot/robots/so101_bimanual.yaml
robot_type: so101
port: /dev/ttyUSB1 # follower arm
leader_arms:
main:
type: so101
port: /dev/ttyUSB0 # leader arm
cameras:
top_cam:
type: opencv
index_or_path: 0
fps: 30
width: 640
height: 480
Test connection
python -m lerobot.scripts.control_robot \
--robot.type=so101 \
--robot.port=/dev/ttyUSB0 \
--control.type=none # just connects and reads state
You should see joint position readings printed. If you get a port error, check Troubleshooting.
Servo Calibration
Unlike CAN-bus arms that use absolute encoders, the Feetech STS3215 servos need calibration to define their zero positions. LeRobot handles this automatically.
Run calibration
python -m lerobot.scripts.control_robot \
--robot.type=so101 \
--robot.port=/dev/ttyUSB0 \
--control.type=calibrate
The script will prompt you to move the arm to specific positions (home, min, max for each joint) and press Enter at each position. It saves calibration data to ~/.cache/huggingface/lerobot/calibration/so101/.
Calibration positions
LeRobot will ask you to position each joint at three poses:
- Home position: arm fully extended, end-effector pointing forward
- Zero torque position: arm hanging naturally under gravity
- 90-degree reference: each joint at its midpoint
Verify calibration
python -m lerobot.scripts.control_robot \
--robot.type=so101 \
--robot.port=/dev/ttyUSB0 \
--control.type=teleoperate # move arm by hand to verify joint readout
Move the arm manually (compliance mode). Joint positions should read near zero at home and increase/decrease smoothly as you move each joint.
Recalibration tip: Run calibration again any time you disassemble a joint, replace a servo, or find that joint positions drift. Calibration files are stored per-arm serial number and reloaded automatically.
Leader–Follower Teleoperation
The SO-101 is designed for leader–follower teleoperation: one arm (leader) captures your hand movements, and the second arm (follower) mirrors them in real time. This produces the highest quality training demonstrations.
Start leader–follower teleop
python -m lerobot.scripts.control_robot \
--robot.type=so101 \
--robot.port=/dev/ttyUSB1 \
--robot.leader_arms.main.type=so101 \
--robot.leader_arms.main.port=/dev/ttyUSB0 \
--control.type=teleoperate
Single-arm keyboard teleop (no second arm)
If you only have one arm, use keyboard control mode:
python -m lerobot.scripts.control_robot \
--robot.type=so101 \
--robot.port=/dev/ttyUSB0 \
--control.type=teleoperate \
--control.teleop_keys=true
Compliance / gravity compensation mode
Put the leader arm into low-torque mode so you can move it freely with your hand:
python -c "
from lerobot.common.robot_devices.robots.so101 import SO101Robot
robot = SO101Robot(port='/dev/ttyUSB0')
robot.connect()
robot.set_compliance_mode(True) # arm moves freely under hand guidance
"
Python API Quickstart
You can control the SO-101 directly via the LeRobot robot API without the CLI scripts.
Basic joint control
from lerobot.common.robot_devices.robots.so101 import SO101Robot
import torch
robot = SO101Robot(port="/dev/ttyUSB0")
robot.connect()
# Read current joint positions (6 DOF)
obs = robot.capture_observation()
print("Joint positions:", obs["observation.state"])
# Send joint position command (in degrees, normalized to [-1, 1] range)
action = torch.zeros(6) # all joints to zero position
robot.send_action(action)
robot.disconnect()
Gravity compensation (backdrivable mode)
from lerobot.common.robot_devices.robots.so101 import SO101Robot
robot = SO101Robot(port="/dev/ttyUSB0")
robot.connect()
# Enable backdrive — arm can be moved freely by hand
robot.set_compliance_mode(True)
import time
for _ in range(100):
obs = robot.capture_observation()
print(obs["observation.state"]) # prints live joint positions as you move arm
time.sleep(0.02)
robot.disconnect()
Reading servo status
from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus
bus = FeetechMotorsBus(port="/dev/ttyUSB0",
motors={"joint1": (1, "sts3215"),
"joint2": (2, "sts3215"),
"joint3": (3, "sts3215"),
"joint4": (4, "sts3215"),
"joint5": (5, "sts3215"),
"gripper": (6, "sts3215")})
bus.connect()
positions = bus.read("Present_Position", ["joint1", "joint2", "joint3"])
print("Positions:", positions)
bus.disconnect()
Top 3 Common Issues
FileNotFoundError: /dev/ttyUSB0
The USB servo controller is not detected. Usually a missing driver or the cable is unplugged.
Fix:
# Check if the device is listed
ls /dev/ttyUSB* # Linux
ls /dev/tty.usbserial* # macOS
# Linux: add yourself to the dialout group (requires logout)
sudo usermod -aG dialout $USER
# Windows: install CP2102 or CH340 USB driver,
# then check Device Manager for COM port number
Servos are physically connected but LeRobot cannot read their positions. Usually a power issue or wrong baud rate.
Fix:
# 1. Verify 5V power supply is connected and LED on servo board is on
# 2. Check all servo daisy-chain cables are fully seated
# 3. Try scanning for servos directly:
python -c "
from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus
bus = FeetechMotorsBus('/dev/ttyUSB0', motors={})
bus.connect()
ids = bus.find_motor_ids()
print('Found motor IDs:', ids)
bus.disconnect()
"
LeRobot saves calibration per arm serial number. If it cannot find the calibration file, it will warn and use raw encoder values.
Fix:
# Check calibration file location
ls ~/.cache/huggingface/lerobot/calibration/so101/
# Re-run calibration if the file is missing
python -m lerobot.scripts.control_robot \
--robot.type=so101 \
--robot.port=/dev/ttyUSB0 \
--control.type=calibrate
# Pass explicit calibration path if needed
python -m lerobot.scripts.control_robot \
--robot.type=so101 \
--robot.port=/dev/ttyUSB0 \
--robot.calibration_dir=/path/to/calibration \
--control.type=teleoperate
Still stuck? Ask on the SO-101 Forum or check the LeRobot GitHub issues.