OpenArm Debugging Workflow
Basic Workflow
OpenArm official documentation provides basic usage manuals for reference:
OpenArm official debugging documentation: https://docs.openarm.dev/software/setup/
Complete Workflow and Recommendations
This document provides a complete debugging workflow, combined with practical usage experience, and gives debugging recommendations.
Single Motor Debugging
Whether following OpenArm debugging documentation or this guide, it is recommended to start with a single motor. After testing each motor individually, proceed to multi-motor combined debugging.
Following this workflow effectively avoids situations where the entire system behaves abnormally during debugging, making it difficult to pinpoint the issue.
1. Modify Motor ID
- Confirm the debugging motor ID according to the following table:
| Joint | Transmitter | Receiver |
|---|---|---|
| J1 | 0x01 | 0x11 |
| J2 | 0x02 | 0x12 |
| J3 | 0x03 | 0x13 |
| J4 | 0x04 | 0x14 |
| J5 | 0x05 | 0x15 |
| J6 | 0x06 | 0x16 |
| J7 | 0x07 | 0x17 |
| J8 | 0x08 | 0x18 |
Prepare Damiao debugging tool
Windows download link: https://files.seeedstudio.com/wiki/robotics/Actuator/damiao/Debugging_Tools_v.1.6.8.8.exe
Check motor power supply and serial cable connections, then run the program. Follow the illustrated workflow to modify motor ID.
Simple motor functionality testing can be performed through calibration.
2. Configure SocketCAN Interface
- Environment preparation, ensure the following tools are installed:
sudo apt install -y software-properties-common
sudo add-apt-repository -y ppa:openarm/main
sudo apt update
sudo apt install -y \
can-utils \
iproute2 \
libopenarm-can-dev \
openarm-can-utils- CAN adapter bit rate configuration
OpenArm provided configuration commands:
# CAN 2.0
openarm-can-configure-socketcan can0
# CAN FD 1M/5M (recommended)
openarm-can-configure-socketcan can0 -fd -b 1000000 -d 5000000Manual configuration:
Configure CAN 2.0, bit rate 1M:
sudo ip link set can0 down
sudo ip link set can0 type can bitrate 1000000
sudo ip link set can0 upConfigure CAN FD, bit rate 1M/5M:
sudo ip link set can0 down
sudo ip link set can0 type can bitrate 1000000 dbitrate 5000000 fd on
sudo ip link set can0 up3. Manual Motor Control
- First start candump tool to record channel messages.
candump -x can0- Modify motor bit rate, send temporary motor bit rate modification command (configuration disappears after power loss).
Command to set motor bit rate to 1M/5M:
openarm-can-change-baudrate --baudrate 5000000 --canid 1 --socketcan can0If confirming the bit rate for future use, add --flash to save to flash memory (⚠ Do not write to flash frequently; each motor is limited to 10,000 modifications.)
At this point, the motor defaults to CAN FD mode communication. If parameter is modified to 1000000, the bit rate is 1 Mbit/s and working mode is CAN 2.0.
- Observe candump tool, should capture data similar to the figure below:
The example image shows four sets of commands. The CAN adapter sends bit rate configuration commands, and the motor responds after receiving them. (If there is no response, an anomaly exists.)
The first two sets configure 1 Mbit/s CAN 2.0 mode, while the last two sets configure 1M/5M bit rate CAN FD mode.
Through the CAN frame format of the last motor response, you can determine that the motor is in FD working mode.
- Use cansend command to control motor enable/disable
By sending bit rate configuration and the following configuration commands, observing candump for motor responses and motor status indicators, you can determine if motor communication is normal.
It is recommended to use CAN 2.0 for preliminary communication testing to eliminate failures caused by FD parameter mismatches.
CAN 2.0 mode:
cansend can0 001#FFFFFFFFFFFFFFFB # Error clear
cansend can0 001#FFFFFFFFFFFFFFFC # Enable
cansend can0 001#FFFFFFFFFFFFFFFD # DisableCAN FD mode:
cansend can0 001##1FFFFFFFFFFFFFFFB # Error clear
cansend can0 001##1FFFFFFFFFFFFFFFC # Enable
cansend can0 001##1FFFFFFFFFFFFFFFD # DisableMotor indicators:
- Green light steady on: Motor enabled
- Red light steady on: Motor disabled
- Red light flashing: Motor error state
candump reception example:
Common Troubleshooting
If communication anomalies occur during debugging, we have provided detailed documentation for CAN communication anomaly troubleshooting and common communication issue handling.
Communication anomaly troubleshooting: https://mp.weixin.qq.com/s/N5zSEOQ8qPamX8igaHNg7Q Common wiring issues: https://mp.weixin.qq.com/s/5dGna857x9LAaTmiI6rMAQ Common parameter configuration issues: TODO