CAN Communication Issue Between ODrive and USB-CAN — No Frames Visible in candump - No Messages Transmitted Despite Correct Setup

Hello,

I’m working on a CAN connection between an ODrive (firmware v0.5.6) and a USB-CAN adapter (CH340) via a USB hub. The motor is functioning, but I’m not seeing any frames in candump can0

Hardware Setup:

  • ODrive v3.6-56V (firmware v0.5.6)
  • USB-CAN adapter (CH340-based, ID 1a86:7523)
  • Physical connections: GND, CAN_H, CAN_L between ODrive and USB-CAN adapter
  • Linux Ubuntu system with can-utils installed

Hardware Detection

  • The PC properly detects the USB-CAN adapter: lsusb shows the CH340 (ID 1a86:7523).
  • The serial port is /dev/ttyUSB1

ODrive Configuration (via odrivetool):
import odrive
odrv0 = odrive.find_any()

CAN configuration

odrv0.config.enable_can_a = True
odrv0.can.config.baud_rate = 250000

Node ID assignment

odrv0.axis0.config.can.node_id = 0
odrv0.axis1.config.can.node_id = 1

Periodic messages

odrv0.axis0.config.can.heartbeat_rate_ms = 100
odrv0.axis1.config.can.heartbeat_rate_ms = 100
odrv0.axis0.config.can.encoder_rate_ms = 1000
odrv0.axis1.config.can.encoder_rate_ms = 1000

Save and reboot

odrv0.save_configuration()
odrv0.reboot()

Linux CAN Interface Setup:

Load modules

sudo modprobe slcan can can-raw

Configure USB-CAN adapter

sudo slcand -o -c -s5 /dev/ttyUSB0 can0
sudo ip link set down can0
sudo ip link set can0 type can bitrate 250000
sudo ip link set up can0

Verify interface

ip -details link show can0

Shows: bitrate 250000, state UP

Status Verification:

Configuration confirmed

print(odrv0.config.enable_can_a) # True
print(odrv0.can.config.baud_rate) # 250000
print(odrv0.axis0.config.can.node_id) # 0
print(odrv0.axis1.config.can.node_id) # 1

No errors detected

print(odrv0.axis0.error) # 0
print(odrv0.axis1.error) # 0
print(odrv0.can.error) # 0

Problem:

  • candump can0 shows no messages from ODrive
  • CAN interface is functional (tested with cansend can0 123#DEADBEEF - message appears in candump)
  • Motor moves when commanded via USB, but no CAN traffic generated
  • Both axes remain in IDLE state (current_state = 1)

Questions:

  1. Does firmware v0.5.6 require specific axis states for CAN message transmission?
  2. Are there additional CAN configuration parameters I’m missing?
  3. Should I see heartbeat messages even when axes are in IDLE state?
  4. Any known compatibility issues with CH340-based USB-CAN adapters?

Additional Notes:

  • Motor calibration successful (odrv0.axis1.motor.is_calibrated = True)
  • No encoder connected (planning sensorless control)
  • Physical CAN bus may need 120Ω termination resistors

Any guidance would be greatly appreciated. The configuration appears correct based on documentation, but no CAN messages are being transmitted from the ODrive.

Thank you for your help!

.

Hi!

  • Does firmware v0.5.6 require specific axis states for CAN message transmission?

No, it should in idle.

  • Are there additional CAN configuration parameters I’m missing?

This looks correct.

  • Should I see heartbeat messages even when axes are in IDLE state?

Yes.

  • Any known compatibility issues with CH340-based USB-CAN adapters?

No known issues, however we can’t guarantee that the USB-CAN adapter you picked doesn’t have any other intrinsic issues. Could you share a link to the product page?

That being said, looking at your slcand command, I think I see a possible issue – the -c flag sends a close command. You’re also not specifying the USB serial speed. I also believe you don’t need to explicitly set the bus down, nor set the CAN bitrate (as this will be set via slcand)

Note that since you’re using SocketCAN, the CAN message will show in candump even if the USB-CAN adapter isn’t actually functional, which I think may be the issue.

You could try this command set:
sudo slcand -o -s5 -t hw -S 115200 /dev/ttyUSB0
sudo ip link set up can0

Then you can e.g. candump can0 normally.

Note that the 115200 is just a starting value, this will likely have to be the same value as used on the USB-CAN adapter’s onboard microcontroller (other common values would be 921600 and 2000000). You could also try without the -S 115200 flag and see if the defaults work.

If you can post a link to the specific USB-CAN adapter, that would help a lot!

Also:

  • Physical CAN bus may need 120Ω termination resistors

If you don’t have any 120ohm resistors, then CAN will just not function. However, the ODrive v3.6 has a DIP switch to enable an onboard 120ohm termination resistor, and most USB-CAN adapters have one built in, or selectable via a switch.