Skip to main content
OpenArm is a 7-DOF robotic arm that uses high-performance Damiao motors with CAN-FD communication. It’s designed for research and development with precise control and modular design.

Overview

OpenArm features:
  • 7 degrees of freedom + gripper
  • Damiao motors (DM8009, DM4340, DM4310)
  • CAN-FD communication
  • MIT control mode (position, velocity, torque)
  • Left and right arm configurations
  • High-performance manipulation

Features

  • Motors: 4 different Damiao motor types for optimal joint performance
  • Communication: CAN-FD (up to 5 Mbps data rate)
  • Control: MIT mode with configurable KP/KD gains
  • Side-specific: Pre-configured joint limits for left/right arms
  • Modular: Expandable hardware design
  • High-bandwidth: Fast control loops enabled by CAN-FD

Hardware Specifications

Motor Configuration

OpenArm uses different Damiao motor models optimized for each joint:
JointCAN ID (Send/Recv)Motor ModelUse Case
joint_10x01 / 0x11DM8009Shoulder pan (high torque)
joint_20x02 / 0x12DM8009Shoulder lift (high torque)
joint_30x03 / 0x13DM4340Shoulder rotation
joint_40x04 / 0x14DM4340Elbow flex
joint_50x05 / 0x15DM4310Wrist roll
joint_60x06 / 0x16DM4310Wrist pitch
joint_70x07 / 0x17DM4310Wrist rotation
gripper0x08 / 0x18DM4310Gripper

Motor Models

  • DM8009 (DM-J8009P-2EC): High-torque motors for shoulders
  • DM4340 / DM4340P: Mid-torque for shoulder rotation and elbow
  • DM4310 (DM-J4310-2EC V1.1): Precise control for wrist and gripper

CAN-FD Configuration

  • Interface: SocketCAN (Linux), SLCAN (serial), or auto-detect
  • Nominal bitrate: 1 Mbps
  • Data bitrate: 5 Mbps (CAN-FD)
  • Protocol: CAN-FD enabled by default

Installation

Hardware Setup

  1. Connect CAN interface to your computer
    • Linux: Use USB-to-CAN adapter (e.g., PEAK, Kvaser)
    • Set up SocketCAN interface
  2. Configure CAN interface:
# Linux: Set up CAN interface
sudo ip link set can0 type can bitrate 1000000 dbitrate 5000000 fd on
sudo ip link set can0 up

# Verify interface
ip link show can0
  1. Install CAN utilities:
sudo apt-get install can-utils

Software Installation

pip install lerobot
Python-CAN library is installed automatically for CAN communication.

Configuration

Left Arm Configuration

from lerobot.robots.openarm_follower import (
    OpenArmFollower,
    OpenArmFollowerConfig
)

config = OpenArmFollowerConfig(
    robot_type="openarm_follower",
    id="openarm_left",
    port="can0",        # CAN interface
    side="left",        # Use left arm joint limits
    can_interface="socketcan",
    use_can_fd=True
)

Right Arm Configuration

config = OpenArmFollowerConfig(
    robot_type="openarm_follower",
    id="openarm_right",
    port="can1",
    side="right",       # Use right arm joint limits
    can_interface="socketcan",
    use_can_fd=True
)

Custom Configuration

from lerobot.cameras.opencv import OpenCVCameraConfig

config = OpenArmFollowerConfig(
    robot_type="openarm_follower",
    id="openarm_custom",
    port="can0",
    side=None,  # Use custom joint limits (see below)
    
    # CAN settings
    can_interface="socketcan",
    use_can_fd=True,
    can_bitrate=1000000,      # 1 Mbps nominal
    can_data_bitrate=5000000, # 5 Mbps data
    
    # MIT control gains
    position_kp=[240.0, 240.0, 240.0, 240.0, 24.0, 31.0, 25.0, 25.0],
    position_kd=[5.0, 5.0, 3.0, 5.0, 0.3, 0.3, 0.3, 0.3],
    
    # Custom joint limits
    joint_limits={
        "joint_1": (-75.0, 75.0),
        "joint_2": (-90.0, 90.0),
        # ... etc
    },
    
    # Cameras
    cameras={
        "wrist": OpenCVCameraConfig(
            index_or_path=0,
            fps=30,
            width=640,
            height=480
        )
    }
)

Configuration Parameters

port
str
required
CAN interface name (e.g., "can0", "can1" on Linux)
side
str | None
Arm side: "left", "right", or None for custom limits. When set, uses pre-configured joint limits.
can_interface
str
default:"socketcan"
CAN interface type: "socketcan" (Linux), "slcan" (serial), or "auto"
use_can_fd
bool
default:"true"
Enable CAN-FD (required for OpenArm)
can_bitrate
int
default:"1000000"
Nominal CAN bitrate (1 Mbps)
can_data_bitrate
int
default:"5000000"
CAN-FD data bitrate (5 Mbps)
position_kp
list[float]
Position gains for 8 motors [j1-j7, gripper]. Defaults: [240, 240, 240, 240, 24, 31, 25, 25]
position_kd
list[float]
Velocity gains for 8 motors. Defaults: [5, 5, 3, 5, 0.3, 0.3, 0.3, 0.3]
joint_limits
dict[str, tuple[float, float]]
Joint limits in degrees. Auto-set when side is specified. Defaults to small safe values if side=None.
max_relative_target
float | dict[str, float]
Safety limit for maximum position change per action
disable_torque_on_disconnect
bool
default:"true"
Disable motor torque on disconnect

Usage

Basic Connection

from lerobot.robots.openarm_follower import (
    OpenArmFollower,
    OpenArmFollowerConfig
)

config = OpenArmFollowerConfig(
    robot_type="openarm_follower",
    id="openarm_left",
    port="can0",
    side="left"
)

with OpenArmFollower(config) as robot:
    # Get current state
    obs = robot.get_observation()
    print(f"Positions: {[obs[k] for k in obs if k.endswith('.pos')]}")
    
    # Send action
    action = {
        "joint_1.pos": 0.0,
        "joint_2.pos": -30.0,
        "joint_3.pos": 0.0,
        "joint_4.pos": 60.0,
        "joint_5.pos": 0.0,
        "joint_6.pos": -20.0,
        "joint_7.pos": 0.0,
        "gripper.pos": -30.0  # Negative = closed
    }
    robot.send_action(action)

Observation Format

OpenArm provides comprehensive motor feedback:
obs = robot.get_observation()
# Returns:
{
    # Positions (degrees)
    "joint_1.pos": 0.0,
    "joint_2.pos": -30.0,
    # ... all 8 joints ...
    
    # Velocities (degrees/s)
    "joint_1.vel": 0.0,
    "joint_2.vel": 0.0,
    # ... all 8 joints ...
    
    # Torques (Nm)
    "joint_1.torque": 0.0,
    "joint_2.torque": 0.0,
    # ... all 8 joints ...
    
    # Camera images (if configured)
    "wrist": np.ndarray
}

Action Format

action = {
    "joint_1.pos": 10.0,   # degrees
    "joint_2.pos": -25.0,
    "joint_3.pos": 5.0,
    "joint_4.pos": 55.0,
    "joint_5.pos": 0.0,
    "joint_6.pos": -15.0,
    "joint_7.pos": 0.0,
    "gripper.pos": -50.0  # -65 to 0 (closed to open)
}

robot.send_action(action)

Joint Limits

Left Arm Limits

LEFT_DEFAULT_JOINTS_LIMITS = {
    "joint_1": (-75.0, 75.0),
    "joint_2": (-90.0, 9.0),   # Different from right
    "joint_3": (-85.0, 85.0),
    "joint_4": (0.0, 135.0),
    "joint_5": (-85.0, 85.0),
    "joint_6": (-40.0, 40.0),
    "joint_7": (-80.0, 80.0),
    "gripper": (-65.0, 0.0)     # Negative = closed
}

Right Arm Limits

RIGHT_DEFAULT_JOINTS_LIMITS = {
    "joint_1": (-75.0, 75.0),
    "joint_2": (-9.0, 90.0),    # Different from left
    "joint_3": (-85.0, 85.0),
    "joint_4": (0.0, 135.0),
    "joint_5": (-85.0, 85.0),
    "joint_6": (-40.0, 40.0),
    "joint_7": (-80.0, 80.0),
    "gripper": (-65.0, 0.0)
}
Note that joint_2 has different limits for left and right arms. Always specify side or provide custom limits.

MIT Control Mode

OpenArm uses MIT (torque-based) control mode:
# Control equation: τ = Kp(q_desired - q) + Kd(dq_desired - dq) + τ_feedforward

# Configure gains
config = OpenArmFollowerConfig(
    port="can0",
    # Position gains (8 values for 8 motors)
    position_kp=[240.0, 240.0, 240.0, 240.0, 24.0, 31.0, 25.0, 25.0],
    # Velocity gains
    position_kd=[5.0, 5.0, 3.0, 5.0, 0.3, 0.3, 0.3, 0.3]
)
Gain Guidelines:
  • Higher Kp: Stiffer position control (shoulders: 240)
  • Lower Kp: Compliant control (wrists: 24-31)
  • Higher Kd: More damping (shoulders: 5.0)
  • Lower Kd: Less damping (wrists: 0.3)

Calibration

OpenArm requires calibration on first use:
robot = OpenArmFollower(config)
robot.connect(calibrate=True)

# Calibration procedure:
# 1. Move arm to neutral/zero position
# 2. Follow prompts to record zero positions
# 3. Calibration saved automatically

# Saved to: ~/.cache/lerobot/calibration/robots/openarm_follower/{id}.json

Dual Arm Setup

from lerobot.robots.openarm_follower import (
    OpenArmFollower,
    OpenArmFollowerConfig
)

left_config = OpenArmFollowerConfig(
    robot_type="openarm_follower",
    id="openarm_left",
    port="can0",
    side="left"
)

right_config = OpenArmFollowerConfig(
    robot_type="openarm_follower",
    id="openarm_right",
    port="can1",
    side="right"
)

with OpenArmFollower(left_config) as left_arm, \
     OpenArmFollower(right_config) as right_arm:
    
    # Coordinated bimanual control
    left_obs = left_arm.get_observation()
    right_obs = right_arm.get_observation()
    
    left_arm.send_action(left_action)
    right_arm.send_action(right_action)

Troubleshooting

CAN Interface Not Found

# Check if interface exists
ip link show can0

# Set up interface
sudo ip link set can0 type can bitrate 1000000 dbitrate 5000000 fd on
sudo ip link set can0 up

# Verify
ip -details link show can0

CAN-FD Not Enabled

# Enable CAN-FD when bringing up interface
sudo ip link set can0 type can bitrate 1000000 dbitrate 5000000 fd on
#                                                                 ^^^^^
# Make sure 'fd on' is included

Motors Not Responding

# Check CAN bus traffic
candump can0

# Should see CAN frames when robot is active
# If no frames: check power, cables, CAN termination

Permission Denied

# Add user to necessary groups
sudo usermod -a -G dialout $USER

# For CAN access, may need additional permissions
sudo chmod 666 /dev/can0

Wrong Side Configuration

# If joint_2 hits limits unexpectedly:
config = OpenArmFollowerConfig(
    port="can0",
    side="left"  # Make sure this matches your physical arm
)

# Or use custom limits:
config = OpenArmFollowerConfig(
    port="can0",
    side=None,
    joint_limits={...}  # Provide your own limits
)

Implementation Details

  • Motor bus: DamiaoMotorsBus
  • Protocol: CAN-FD with MIT control
  • Normalization: Always uses degrees
  • Control mode: Position with KP/KD gains
  • Source: /home/daytona/workspace/source/src/lerobot/robots/openarm_follower/openarm_follower.py
  • Config: /home/daytona/workspace/source/src/lerobot/robots/openarm_follower/config_openarm_follower.py

Robot Overview

See all supported robots

Damiao Motors

Damiao motor bus API

CAN Communication

CAN-FD setup and configuration

Recording Data

Record manipulation data

External Resources

Build docs developers (and LLMs) love