DamiaoMotorsBus class. Damiao motors are high-performance actuators that communicate via CAN bus, offering precise torque control, high bandwidth, and excellent dynamic response.
Overview
Damiao motors use CAN bus communication with MIT-style impedance control, making them ideal for dynamic robot applications. LeRobot provides a high-level interface for motor control, state reading, and calibration. Key Features:- CAN bus communication (CAN FD supported)
- MIT impedance control (position, velocity, torque)
- High control bandwidth (>1kHz)
- Real-time state feedback (position, velocity, torque, temperature)
- Hardware zero-position setting
- Batch operations for multi-motor control
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:76
Supported Models
LeRobot supports various Damiao motor models:- DM-J4310 series
- DM-J6006 series
- DM-J8009 series
- And other MIT-mode compatible Damiao motors
/home/daytona/workspace/source/src/lerobot/motors/damiao/tables.py
Hardware Requirements
CAN Interface
Linux (recommended):- SocketCAN-compatible adapter (e.g., PEAK PCAN-USB, Kvaser)
- USB-to-CAN adapter with socketcan support
- SLCAN-compatible adapter (serial-based CAN)
- USB-to-CAN adapter with SLCAN firmware
Wiring
- Use 120Ω termination resistors at both ends of the CAN bus
- Keep CAN_H and CAN_L twisted pairs
- Maximum cable length: 40m @ 1 Mbps, 500m @ 125 kbps
- Ensure adequate 24V power supply (motors draw significant current)
Installation
Linux Setup (SocketCAN)
CAN FD Support (for OpenArms and high-speed applications)
macOS Setup (SLCAN)
Testing CAN Connection
Configuration
Motor Configuration
Define your motors with CAN IDs:/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:92
CAN ID Configuration
Damiao motors require proper CAN ID configuration:- Send ID (
id): The ID used to send commands to the motor (e.g., 1, 2, 3) - Receive ID (
recv_id): The ID the motor uses to respond (typically0x100 + id)
Motor Types
Specify the exact motor model for proper limit calculations:motor_type_str.
Basic Usage
Connecting to Motors
ConnectionError is raised with diagnostic information.
From /home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:158
Reading Motor State
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:585
Synchronized Reading (High-Speed)
For high-frequency control, use synchronized reads:/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:638
Writing Motor Commands
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:617
Torque Control
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:295
Setting Zero Position
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:334
Disconnecting
MIT Impedance Control
Damiao motors use MIT-style impedance control, which combines position, velocity, and torque control:Control Parameters
-
Kp (Stiffness): Position error gain (0-500)
- Higher = stiffer, tracks position better
- Lower = more compliant, absorbs impacts
- Default: 10.0
-
Kd (Damping): Velocity error gain (0-5)
- Higher = more damping, reduces oscillations
- Lower = faster response, may oscillate
- Default: 0.5
- Goal Position: Target position in degrees
- Goal Velocity: Target velocity in degrees/second (usually 0)
- Feedforward Torque: Direct torque command in N⋅m (usually 0)
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:463
Tuning Gains
Motor Calibration
Recording Range of Motion
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:759
Saving Calibration
Advanced Usage
High-Frequency Control Loop
Gravity Compensation
Emergency Stop
Troubleshooting
Connection Issues
“No response from motor” error:- Verify 24V power is connected and adequate
- Check CAN wiring: CAN_H, CAN_L, GND
- Verify motor CAN IDs match configuration
- Ensure CAN interface is up:
ip link show can0 - Try lower bitrate:
bitrate=500000 - Check termination resistors (120Ω at both ends)
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:585
“Failed to connect to CAN bus” error:
Linux:
Motor Behavior Issues
Motor oscillates or vibrates:- Reduce Kp gain
- Increase Kd gain for damping
- Check for mechanical binding
- Verify adequate power supply
- Increase Kp gain
- Check position limits
- Verify motor is enabled
- Check for external load exceeding motor torque capacity
- Reduce duty cycle
- Improve cooling (heatsinks, airflow)
- Check for mechanical friction
- Reduce Kp/Kd if causing constant torque
- Monitor continuously:
Performance Issues
Low control rate / packet drops:- Use CAN FD:
use_can_fd=True - Increase data bitrate:
data_bitrate=5000000 - Use batch operations:
sync_write(),sync_read_all_states() - Reduce number of read operations per cycle
- Check CAN bus load:
canbusload can0@1000000
- Ensure real-time Linux kernel (PREEMPT_RT)
- Set process priority:
- Disable CPU frequency scaling
- Use dedicated CAN interface (not shared with other devices)
CAN Bus Monitoring
Monitoring Traffic
Bus Statistics
Best Practices
- Always use synchronized operations (
sync_write,sync_read_all_states) for multi-motor control - Start with low gains (Kp=5, Kd=0.5) and increase gradually
- Monitor temperatures during extended operation
- Use CAN FD for high-frequency control (>500 Hz)
- Implement emergency stop (catch Ctrl+C, disable torque)
- Set zero positions after mechanical assembly
- Check CAN statistics regularly for packet loss
- Use proper termination to prevent signal reflections
- Limit current if needed to protect mechanics
- Log all motor errors for debugging
References
- Source code:
/home/daytona/workspace/source/src/lerobot/motors/damiao/damiao.py:1 - Motor limits:
/home/daytona/workspace/source/src/lerobot/motors/damiao/tables.py - Damiao Motors (Seedstudio)
- python-can Documentation
- SocketCAN Documentation