CAN Interface Available for Testing

Hey everyone!

It just occurred to me that I haven’t actually posted on here to let you know that I’ve finished a CAN interface for ODrive, which is ready for testing.

Branch: https://github.com/madcowswe/ODrive/tree/rc-v0.5.0
Documentation: https://github.com/madcowswe/ODrive/tree/rc-v0.5.0/docs/can-protocol.md

I’ve copied the documentation here for convenience. Let me know if you have any questions!


CAN Protocol

Hardware Setup

ODrive assumes the CAN PHY is a standard differential twisted pair in a linear bus configuration with 120 ohm termination resistance at each end. ODrive uses 3.3v as the high output, but conforms to the CAN PHY requirement of achieving a differential voltage > 1.5V to represent a “0”. As such, it is compatible with standard 5V bus architectures.

ODrive currently supports the following CAN baud rates:

  • 125 kbps
  • 250 kbps (default)
  • 500 kbps
  • 1000 kbps

Transport Protocol

We’ve implemented a very basic CAN protocol that we call “CAN Simple” to get users going with ODrive. This protocol is sufficiently abstracted that it is straightforward to add other protocols such as CANOpen, J1939, or Fibre over ISO-TP in the future. Unfortunately, implementing those protocols is a lot of work, and we wanted to give users a way to control ODrive’s basic functions via CAN sooner rather than later.

CAN Frame

At its most basic, the CAN Simple frame looks like this:

  • Upper 6 bits - Node ID - max 0x3F
  • Lower 5 bits - Command ID - max 0x1F

To understand how the Node ID and Command ID interact, let’s look at an example

odrv0.axis0.can_node_id = 0x010 - Reserves messages 0x200 through 0x21F
odrv0.axis1.can_node_id = 0x018 - Reserves messages 0x300 through 0x31F

It may not be obvious, but this allows for some compatibility with CANOpen. Although the address space 0x200 and 0x300 correspond to receive PDO base addresses, we can guarantee they will not conflict if all CANopen node IDs are >= 32. E.g.:

CANopen nodeID = 35 = 0x23
Receive PDO 0x200 + nodeID = 0x223, which does not conflict with the range [0x200 : 0x21F]

Be careful that you don’t assign too many nodeIDs per PDO group. Four CAN Simple nodes (32*4) is all of the available address space of a single PDO. If the bus is strictly ODrive CAN Simple nodes, a simple sequential Node ID assignment will work fine.

Messages

CMD ID Name Sender Signals Start byte
0x000 CANOpen NMT Message** Master - -
0x700 CANOpen Heartbeat Message** Slave - -
0x001 ODrive Heartbeat Message Axis Axis Error
Axis Current State
0
4
0x002 ODrive Estop Message Master - -
0x003 Get Motor Error* Axis Motor Error 0
0x004 Get Encoder Error* Axis Encoder Error 0
0x005 Get Sensorless Error* Axis Sensorless Error 0
0x006 Set Axis Node ID Master Axis CAN Node ID 0
0x007 Set Axis Requested State Master Axis Requested State 0
0x008 Set Axis Startup Config Master - Not yet implemented - -
0x009 Get Encoder Estimates* Master Encoder Pos Estimate
Encoder Vel Estimate
0
4
0x00A Get Encoder Count* Master Encoder Shadow Count
Encoder Count in CPR
0
4
0x00B Move To Pos Master Goal Position 0
0x00C Set Pos Setpoint Master Pos Setpoint
Vel FF
Current FF
0
4
6
0x00D Set Vel Setpoint Master Vel Setpoint
Current FF
0
4
0x00E Set Current Setpoint Master Current Setpoint 0
0x00F Set Velocity Limit Master Velocity Limit 0
0x010 Start Anticogging Master - -
0x011 Set Traj Vel Limit Master Traj Vel Limit 0
0x012 Set Traj Accel Limits Master Traj Accel Limit
Traj Decel Limit
0
4
0x013 Set Traj A per Count / s^2 Master Traj A per CSS 0
0x014 Get IQ* Axis Iq Setpoint
Iq Measured
0
4
0x015 Get Sensorless Estimates* Master Sensorless Pos Estimate
Sensorless Vel Estimate
0
4
0x016 Reboot ODrive Master***
0x017 Get Vbus Voltage Master*** Vbus Voltage 0

* Note: These messages are call & response. The Master node sends a message with the RTR bit set, and the axis responds with the same ID and specified payload.
** Note: These CANOpen messages are reserved to avoid bus collisions with CANOpen devices. They are not used by CAN Simple.
*** Note: These messages can be sent to either address on a given ODrive board.


Signals

Name Type Bits Factor Offset Byte Order
Axis Error Unsigned Int 32 1 0 Intel
Axis Current State Unsigned Int 32 1 0 Intel
Motor Error Unsigned Int 32 1 0 Intel
Encoder Error Unsigned Int 32 1 0 Intel
Sensorless Error Unsigned Int 32 1 0 Intel
Axis CAN Node ID Unsigned Int 16 1 0 Intel
Axis Requested State Unsigned Int 32 1 0 Intel
Encoder Pos Estimate IEEE 754 Float 32 1 0 Intel
Encoder Vel Estimate IEEE 754 Float 32 1 0 Intel
Encoder Shadow Count Signed Int 32 1 0 Intel
Encoder Count In CPR Signed Int 32 1 0 Intel
Goal Position Signed Int 32 1 0 Intel
Pos Setpoint Signed Int 32 1 0 Intel
Vel FF Signed Int 16 0.1 0 Intel
Current FF Signed Int 16 0.01 0 Intel
Vel Setpoint Signed Int 32 0.01 0 Intel
Current Setpoint Signed Int 32 0.01 0 Intel
Velocity Limit IEEE 754 Float 32 1 0 Intel
Traj Vel Limit IEEE 754 Float 32 1 0 Intel
Traj Accel Limit IEEE 754 Float 32 1 0 Intel
Traj Decel Limit IEEE 754 Float 32 1 0 Intel
Traj A per CSS IEEE 754 Float 32 1 0 Intel
Iq Setpoint IEEE 754 Float 32 1 0 Intel
Iq Measured IEEE 754 Float 32 1 0 Intel
Sensorless Pos Estimate IEEE 754 Float 32 1 0 Intel
Sensorless Vel Estimate IEEE 754 Float 32 1 0 Intel
Vbus Voltage IEEE 754 Float 32 1 0 Intel

Configuring ODrive for CAN

Configuration of the CAN parameters should be done via USB before putting the device on the bus.

To set the desired baud rate, use <odrv>.can.set_baud_rate(<value>). The baud rate can be done without rebooting the device. If you’d like to keep the baud rate, simply call <odrv>.save_configuration() before rebooting.

Each axis looks like a separate node on the bus. Thus, they’ve inherited a new configuration property: can_node_id. This ID can be from 0 to 63 (0x3F) inclusive.

Example Configuration

odrv0.axis0.config.can_node_id = 3
odrv0.axis1.config.can_node_id = 1
odrv0.can.set_baud_rate(500000)
odrv0.save_configuration()
odrv0.reboot()
10 Likes

It’s so great! I’ve just found the UART usually doesn’t work for my odrive3.4. I wonder if the CAN Interface is suitable for odrive3.4?

Try it! I’ve been using a 3.3 for testing

Hello! I am going to test the CAN protocol and I’ve flashed the firmware into my version3.4 Odrive.Everything is going well on my Odrive. But I’m not very familiar with CAN and don’t know how to write codes to control Odrive. Can you give some easy examples for stm32? For instance, some codes about how to control speed?

You’ll need another device that speaks CAN, like your STM32, and it will need the CAN Transceiver hardware. If you don’t have that, consider getting an Arduino or Teensy with appropriate CAN shield.

You can look at the source code for ODrive under Firmware/Communications/interface_can.cpp if you want to see how to setup an STM32F4 to send CAN messages, but you’ll still need the transceivers

Hello!I still don’t make it…

!
As you can see, I can use CAN protocol to transmit messages now and I am sure everything is OK on my two stm32 boards(The two blue boards in the picture).I can use board A to send message and board B to receive message.
On the Odrive side, I set the node_ID same as your example. I use velocity control mode and motor can spin according to odrivetool.
I am going to send vel_setpoint by CAN protocol to control the motor speed. Here is my CAN frame.
TxHeader.StdId = 0x073 ;
TxHeader.RTR = CAN_RTR_DATA;
TxHeader.IDE = CAN_ID_STD;
TxHeader.DLC = 8;
TxHeader.TransmitGlobalTime = DISABLE;
TxData[0] = 0xff;
TxData[1] = 0xff;
TxData[2] = 0xff;
TxData[3] = 0xff;
TxData[4] = 0xff;
TxData[5] = 0xff;
TxData[6] = 0xff;
TxData[7] = 0xff;

I am using odrv0.axis0, and the node_ID is 3(binary 011), the CMD_ID to set velocity setpoint is 0x013(binary 10011), so the StdId should be 0111 0011(the upper bits adds the lower bits), which is 0x73 in hex. But I don’t understand the signals so I give the signal the largest number.
BUT IT DOESN’T WORK!!!

Can you make a more detailed tutorial? Hope you can understand my English.

2 Likes

I also found I can’t use position control mode using your firmware. Anyway, thanks for your effort

I made a mistake in the list of commands, please check again.

odrv0.axis0.
odrv0.axis0.config.can_node_id = 3
odrv0.axis1.config.can_node_id = 1
odrv0.can.set_baud_rate(500000)
odrv0.save_configuration()
odrv0.reboot()

To set axis0 position to 100000:
Axis ID = 0x03
Command ID = 0x00A

CAN Message ID: = 0x03 << 5 + 0x00A = 0x6A
Data length = 8

Data Frame:
< Signal : Pos Setpoint : 32 bit signed int >
[0] = (uint32_t)100000
[1] = (uint32_t)100000 >> 8
[2] = (uint32_t)100000 >> 16
[3] = (uint32_t)100000 >> 24

< Signal : Vel FF : 16 bit signed int >
[4] = 0
[5] = 0

< Signal : Current FF : 16 bit signed int >
[6] = 0
[7] = 0

I just cloned the repository and compiled the code, but it does not look like the examples you provide here.
In odrv0.can, I get:
Out[9]:
node_id = 0 (int)
TxMailboxCompleteCallbackCnt = 0 (int)
TxMailboxAbortCallbackCnt = 0 (int)
received_msg_cnt = 0 (int)
received_ack = 0 (int)
unexpected_errors = 0 (int)
unhandled_messages = 0 (int)

and in odrv0.axis0.config, there are no CAN-settings.

Is there something I’ve missed when compiling the code?

1 Like

Sounds like you pulled the master or devel branch. You have to pull the CAN PR or my fork

I can control an odrive under position,current and velocity mode through can.It feels convenient to control my odrives through can.But how can i read the current feedback?

hello! Friends.Could you tell me how to control an odrive under position,current and velocity mode through can?

1 Like

Just added message 0x014, “Get IQ” which spits out the Iq Setpoint and Iq Measured for the requested axis.

Hi, great feature! But I have a problem with it on ODrive hardware 3.5/24V. It seems ok on 3.4.
Sometimes I get a few messages in CAN when reflash odrive, probably on start after reflash. But then silence. By the way I have some codes (my custom firmware) that uses CAN on Odrive and it seems working even on 3.5, so I believe hardware is not damaged. My setup is 500 Kbps, that I set in source code as default. I connected USB2CAN adapter and another CAN device on the same line, so I can see messages form another device but not odrive. Tried both with single ODrive and yet another device. When ODrive is only one device and I send messages from host, my CAN adapter became blinking, which means transmit/recieve error. Do you have any idea what can I do?

I’m not sure why it would work on ODrive 3.4 but not on 3.5. Do you have termination resistance? I don’t think @madcowswe made any changes to 3.5 that would cause CAN to be misconfigured.

I see, Yes I have termination resistor.

If you’re comfortable using a debugger, you could put a debugging point in the CAN handler function to see if it is triggering? Unfortunately I don’t currently have any way to test.

Hey @greenfield932, I just discovered there was a bug in the software where it was not validating the Axis IDs. Please pull the newest version of the branch and try again!

void Odrive_Control(CAN_TypeDef *CANx, u8 motor_num, int set_point, u8 control_mode)
{
CanTxMsg tx_message;
tx_message.StdId = (motor_num << 5) + (0x00B + control_mode);
tx_message.IDE = CAN_Id_Standard;
tx_message.RTR = CAN_RTR_Data;
tx_message.DLC = 0x08;

switch(control_mode)
{
	case 1: break;
	case 2: set_point *= 100;break; //cnts/s
	case 3: set_point /= 10;break; // mA
}
tx_message.Data[0] = set_point;	
tx_message.Data[1] = set_point>>8;	
tx_message.Data[2] = set_point>>16;	
tx_message.Data[3] = set_point>>24;	
tx_message.Data[4] = 0;
tx_message.Data[5] = 0;
tx_message.Data[6] = 0;
tx_message.Data[7] = 0;

CAN_Transmit(CANx,&tx_message);

}

This function works well under velocity control mode and position control mode.Under current control mode,when I send a positive number,it still works,but when i send a number smaller than -10(included),it goes wild and does not work as i expected.I have no idea how to fix it.

I checked the real current setpoint.When i send -10(10mA),Odrive received 25A.I 'm confused.