CAN Bus Guide

Both ODrive Pro and ODrive S1 use a custom protocol called CANSimple. This currently supports CAN 2.0b and will support CAN-FD soon, at 12mbps for Pro, and 8mbps for S1. For more information, please refer to the CAN protocol page.

Note

This guide is intended for beginners to set up CAN on the ODrive and on their host device. We will be working in Python, on a Raspberry Pi with an MCP2515 CAN Controller Hat as our host device, but most of the content can be applied to any other systems.

Hardware Setup

ODrive assumes the physical layer is a standard differential twisted pair in a linear bus configuration with 120 ohm termination resistance at each end. The CANH (High) and CANL (Low) pins are used for CAN communication. Connect CANH to CANH and CANL to CANL (found on the datasheet pinout (Pro, S1)) for all devices on the bus, and ensure you have a good ground between each node.

  • Semi-isolated CAN FD network

    • CAN transceiver is powered by the onboard power

    • CAN GND should be connected to the system star ground point

Important

Make sure to connect CAN GND to DC- at the system ground star point.

CAN picture

Note

Many devices make use of a DE-9 (commonly mistakenly called DB-9) connector for CAN. The typical pinout is CANL on pin 2 and CANH on pin 7.

Important

If your ODrive is the “last” (furthest) device on the bus, you can use the on-board 120 Ohm termination resistor by switching the DIP switch to “CAN 120R”. Otherwise, add an external resistor. The nominal bus resistance should be 60 ohms between CANH and CANL.

Setting up the ODrive

  1. Enable the CAN interface a by setting <odrv>.config.enable_can_a to True

  2. Set the Node ID with <odrv>.axis0.config.can.node_id

    By default, ODrive supports a value up to 63 (0x3F). See can-protocol for more information.

  3. Specify the baud rate with odrv0.can.config.baud_rate

    Speed

    value

    125 kbps

    125000

    250 kbps

    250000

    500 kbps

    500000

    1000 kbps

    1000000

  4. Save the configuration with <odrv>.save_configuration()

Setting up the Host

Important

For this demonstration we will working on a Raspberry Pi with the MCP2515 CAN Controller Hat. Please be aware that specific instructions for different hosts or different CAN Hats/adapters may vary.

Enable CAN Hat

  1. The Raspberry Pi does not support CAN internally, so we need to use some external hardware to connect to the CAN bus. The MCP2515 CAN Hat we are using communicates with the Raspberry Pi via SPI.

  1. To enable this we need to modify the boot configuration file by running:

    sudo nano /boot/config.txt
    
  2. In this file, local and uncomment the line

    dtparam=spi=on
    
  3. Directly below this, we want to add the lines

dtoverlay=mcp2515-can0,oscillator=12000000,interrupt=25
dtoverlay=spi0-hw-cs

Important

Some SPI CAN hat variants have different oscillator crystals, make sure the value for oscillator (12MHz here) matches the hardware you are using. If you’re not sure what value to use, the top of the oscillator will have the value printed on it in MHz.

  1. Save the changes and reboot

  1. Install can-utils with sudo apt-get install can-utils

  2. Creating a connection between your application and the can0 socket

sudo ip link set can0 up type can bitrate 250000

Important

Make sure this value matches the ODrive baud_rate, by default the ODrive uses 250 kbps (250000)

Note

For more details regarding this process, checkout this in depth tutorial and this forum post

Verifying Communcation

By default, each ODrive axis will send a heartbeat message at 10Hz. We can confirm our ODrive communication is working by starting the can0 interface, and then reading from it:

sudo ip link set can0 up type can bitrate 250000
candump can0 -xct z -n 10

This will read the first 10 messages from the ODrive and stop. If you’d like to see all messages, remove the -n 10 part (hit CTRL+C to exit). The other flags (x, c, t) are adding extra information, colouring, and a timestamp, respectively.

candump can0 -xct z -n 10
(000.000000)  can0  RX - -  001   [8]  00 00 00 00 01 00 00 00
(000.001995)  can0  RX - -  021   [8]  00 00 00 00 08 00 00 00
(000.099978)  can0  RX - -  001   [8]  00 00 00 00 01 00 00 00
(000.101963)  can0  RX - -  021   [8]  00 00 00 00 08 00 00 00
(000.199988)  can0  RX - -  001   [8]  00 00 00 00 01 00 00 00
(000.201980)  can0  RX - -  021   [8]  00 00 00 00 08 00 00 00
(000.299986)  can0  RX - -  001   [8]  00 00 00 00 01 00 00 00
(000.301976)  can0  RX - -  021   [8]  00 00 00 00 08 00 00 00
(000.399986)  can0  RX - -  001   [8]  00 00 00 00 01 00 00 00
(000.401972)  can0  RX - -  021   [8]  00 00 00 00 08 00 00 00

Alternatively, if you have python can installed (pip3 install python-can), you can use the can.viewer script:

python3 -m can.viewer -c "can0" -i "socketcan" which will give you a nice readout.

Examples (Python)

Intro: Read Heartbeat

  1. Make sure all dependancies are install

    pip3 install python-can
    
  2. Create a CAN bus object and flush old messages

    import can
    
    bus = can.interface.Bus("can0", bustype="socketcan")
    
    # Flush CAN RX buffer so there are no more old pending messages
    while not (bus.recv(timeout=0) is None): pass
    
  3. Define the heartbeat message ID

    node_id = 0 # must match `<odrv>.axis0.config.can.node_id`. The default is 0.
    cmd_id = 0x01 # heartbeat command ID
    message_id = (node_id << 5 | cmd_id)
    

    Note

    CANSimple separates the CAN message ID into two parts: An axis ID and a command ID. Please refer to the CANSimple page for more information.

  4. Wait for the heartbeat, and print results

    import struct
    
    for msg in bus:
      if msg.arbitration_id == message_id
          error, state, result, traj_done = struct.unpack('<IBBB', bytes(msg.data[:7]))
          break
    print(error, state, result, traj_done)
    

Closed Loop Control

Important

Make sure your ODrive is fully connected and configured for closed loop control before continuing (this will require a USB connection). If you haven’t already, please see the Getting Started guide or the GUI Wizard to complete this step. Once finished, the USB connect is no longer required.

  1. Make sure all dependancies are install

    pip3 install python-can
    
  2. Create a CAN bus object and flush old messages

    import can
    
    bus = can.interface.Bus("can0", bustype="socketcan")
    
    # Flush CAN RX buffer so there are no more old pending messages
    while not (bus.recv(timeout=0) is None): pass
    
  3. Put axis into closed loop control state

    import struct
    
    bus.send(can.Message(
        arbitration_id=(node_id << 5 | 0x07), # 0x07: Set_Axis_State
        data=struct.pack('<I', 8), # 8: AxisState.CLOSED_LOOP_CONTROL
        is_extended_id=False
    ))
    
  4. Wait for axis to enter closed loop control by scanning heartbeat messages

    for msg in bus:
        if msg.arbitration_id == (node_id << 5 | 0x01): # 0x01: Heartbeat
            error, state, result, traj_done = struct.unpack('<IBBB', bytes(msg.data[:7]))
            if state == 8: # 8: AxisState.CLOSED_LOOP_CONTROL
                break
    
  5. Set velocity to 1.0 turns/s

    bus.send(can.Message(
        arbitration_id=(node_id << 5 | 0x0d), # 0x0d: Set_Input_Vel
        data=struct.pack('<ff', 1.0, 0.0), # 1.0: velocity, 0.0: torque feedforward
        is_extended_id=False
    ))
    
  6. Print encoder feedback

    for msg in bus:
        if msg.arbitration_id == (node_id << 5 | 0x09): # 0x09: Get_Encoder_Estimates
            pos, vel = struct.unpack('<ff', bytes(msg.data))
            print(f"pos: {pos:.3f} [turns], vel: {vel:.3f} [turns/s]")
    

Download Full Example Here.