OpenArm Debugging Process
Basic Process
OpenArm official website provides basic user manual for reference:
OpenArm official debugging documentation: https://docs.openarm.dev/software/setup/
Complete Process and Recommendations
This article will provide a complete debugging process and give debugging recommendations based on actual usage experience.
Single Motor Debugging
Whether debugging through OpenArm's official documentation or following this article, it's recommended to start with a single motor first, and then proceed with multi-motor combined debugging after each motor test is completed.
Through this process, you can effectively avoid situations where the entire system experiences anomalies during debugging process, making it difficult to pinpoint the issue.
1. Modify Motor ID
- Confirm the corresponding debug motor ID according to the following table.
| Node | 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 that motor power and serial cable are properly connected, run the program. Then follow the diagram process below to modify motor ID.
You can simply test whether motor is working normally through calibration.
2. Configure SocketCAN Interface
- Environment preparation, please 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 provides 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 1 Mbit/s:
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 frames.
candump -x can0- Modify motor bit rate, send temporary motor bit rate modification command (configuration disappears after power-off).
Command to set motor bit rate to 1M/5M is as follows:
openarm-can-change-baudrate --baudrate 5000000 --canid 1 --socketcan can0If you want to confirm subsequent bit rate, you can add --flash after the command to record to flash memory (⚠️ Please do not frequently record to flash memory, limit is 10000 modifications per single motor).
At this point, motor communicates in CAN FD mode by default. If parameter is modified to 1000000, then bit rate is 1 Mbit/s, and operating mode is CAN 2.0.
- Observe candump tool, it should capture data similar to figure below:
Example in the picture shows four groups of commands: CAN adapter sends bit rate configuration command, motor replies upon receiving. (If there is no response, then there is an abnormality).
The first two groups are configured for 1 Mbit/s bit rate CAN 2.0 mode, and the last two groups are configured for 1M/5M bit rate CAN FD mode.
Through the CAN frame format of the last motor's reply, you can determine whether motor is operating in FD mode.
- Use cansend command to control motor enable/disable function
By sending bit rate configuration command and following configuration commands, and observing motor response from candump as well as motor status indicator lights, you can determine whether motor communication is normal.
It is recommended to use CAN 2.0 for preliminary communication testing to eliminate failures caused by FD parameter mismatch.
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 indicator lights:
- Green light always on: Motor enabled
- Red light always on: Motor disabled
- Red light flashing: Motor error status
candump receive example:
Common Issue Troubleshooting
If communication anomalies occur during debugging process, we have provided detailed documentation for CAN communication anomaly troubleshooting methods and common communication issue handling.
Communication anomaly troubleshooting: https://mp.weixin.qq.com/s/N5zSEOQ8qPamX8igaHNg7Q
Common line issues: https://mp.weixin.qq.com/s/5dGna857x9LAaTmiI6rMAQ
Common parameter configuration issues: TODO