The VESC firmware supports CAN bus communication for controlling multiple VESC-based devices on a shared bus. The CAN mode can be selected in VESC Tool under App Settings -> General -> CAN Mode.Documentation Index
Fetch the complete documentation index at: https://mintlify.com/vedderb/bldc/llms.txt
Use this file to discover all available pages before exploring further.
CAN modes
VESC
Default VESC CAN bus. Required for CAN forwarding and configuring multiple VESC-based devices using VESC Tool.
UAVCAN
Basic implementation of
uavcan.equipment.esc. See the DroneCAN documentation for details.Comm Bridge
Bridges the CAN bus to commands. Useful for using VESC Tool as a generic CAN interface and debugger.
Unused
CAN frames are not processed and are ignored. Custom applications and scripts can still process CAN frames. Similar to Comm Bridge, but received frames are not forwarded using commands.
VESC ID configuration
Each VESC-based device on the bus must have a unique ID. You can set the VESC ID in VESC Tool under App Settings -> General -> VESC ID. A device only accepts incoming CAN frames that match its configured ID.Timeout
By default, the VESC stops the motor when nothing has been received on the CAN bus for more than 0.5 seconds. You can change the timeout value in VESC Tool under App Settings -> General. Setting it to0 disables the timeout entirely.
A timeout brake current can also be configured. When timeout occurs, the VESC applies this current to brake the motor. The default is 0, which simply releases the motor with no braking force.
Frame format
All VESC CAN frames use 29-bit extended IDs. The receiver ID and command ID are both embedded in the extended frame ID:| Bits | Field | Description |
|---|---|---|
| B28 – B16 | Unused | Always zero |
| B15 – B8 | Command ID | The CAN_PACKET_ID value |
| B7 – B0 | VESC ID | Target device ID |
Single-frame commands
Simple CAN commands each fit in a single CAN frame. The data payload is always a 32-bit big-endian signed integer representing the command argument, multiplied by the scaling factor for that command. Example: Setting 51 A of current (CAN_PACKET_SET_CURRENT, command ID 1, scaling 1000) on VESC ID 23:
| Field | Value |
|---|---|
| Extended ID | 0x0117 |
| B0 | 0x00 |
| B1 | 0x00 |
| B2 | 0xC7 |
| B3 | 0x38 |
51 * 1000 = 51000 = 0x0000C738
Available simple commands
| Command | ID | Scaling | Unit | Range | Description |
|---|---|---|---|---|---|
CAN_PACKET_SET_DUTY | 0 | 100000 | % / 100 | -1.0 to 1.0 | Duty cycle |
CAN_PACKET_SET_CURRENT | 1 | 1000 | A | -MOTOR_MAX to MOTOR_MAX | Motor current |
CAN_PACKET_SET_CURRENT_BRAKE | 2 | 1000 | A | -MOTOR_MAX to MOTOR_MAX | Braking current |
CAN_PACKET_SET_RPM | 3 | 1 | RPM | -MAX_RPM to MAX_RPM | Motor RPM |
CAN_PACKET_SET_POS | 4 | 1000000 | Degrees | 0 to 360 | Position |
CAN_PACKET_SET_CURRENT_REL | 10 | 100000 | % / 100 | -1.0 to 1.0 | Relative current |
CAN_PACKET_SET_CURRENT_BRAKE_REL | 11 | 100000 | % / 100 | -1.0 to 1.0 | Relative braking current |
CAN_PACKET_SET_CURRENT_HANDBRAKE | 12 | 1000 | A | -MOTOR_MAX to MOTOR_MAX | Handbrake current |
CAN_PACKET_SET_CURRENT_HANDBRAKE_REL | 13 | 100000 | % / 100 | -1.0 to 1.0 | Relative handbrake current |
Commands sent outside the valid range are clamped at the limit. For example, if the maximum braking current is configured to 50 A and you send 60 A with
CAN_PACKET_SET_CURRENT_BRAKE, the firmware will use 50 A.C code example
The following implementation shows how to construct and send all simple CAN commands. Provide your owncan_transmit_eid function that writes an extended-ID frame to the bus.
Status messages
The VESC can broadcast periodic status messages on the CAN bus. Enable them in VESC Tool under App Settings -> General -> CAN Status Messages Rate x. Two independent rate groups are available. Each group can carry any combination of the six status message types. Using two rates lets you transmit high-priority telemetry frequently and lower-priority data at a reduced rate, keeping bus utilization in check.Available status messages
| Command | ID | Data |
|---|---|---|
CAN_PACKET_STATUS | 9 | ERPM, Current, Duty Cycle |
CAN_PACKET_STATUS_2 | 14 | Ah Used, Ah Charged |
CAN_PACKET_STATUS_3 | 15 | Wh Used, Wh Charged |
CAN_PACKET_STATUS_4 | 16 | Temp FET, Temp Motor, Current In, PID position |
CAN_PACKET_STATUS_5 | 27 | Tachometer, Voltage In |
CAN_PACKET_STATUS_6 | 58 | ADC1, ADC2, ADC3, PPM |
Status message encoding
CAN_PACKET_STATUS (ID 9)
CAN_PACKET_STATUS (ID 9)
| Bytes | Data | Unit | Scale |
|---|---|---|---|
| B0 – B3 | ERPM | RPM | 1 |
| B4 – B5 | Current | A | 10 |
| B6 – B7 | Duty Cycle | % / 100 | 1000 |
CAN_PACKET_STATUS_2 (ID 14)
CAN_PACKET_STATUS_2 (ID 14)
| Bytes | Data | Unit | Scale |
|---|---|---|---|
| B0 – B3 | Amp Hours Used | Ah | 10000 |
| B4 – B7 | Amp Hours Charged | Ah | 10000 |
CAN_PACKET_STATUS_3 (ID 15)
CAN_PACKET_STATUS_3 (ID 15)
| Bytes | Data | Unit | Scale |
|---|---|---|---|
| B0 – B3 | Watt Hours Used | Wh | 10000 |
| B4 – B7 | Watt Hours Charged | Wh | 10000 |
CAN_PACKET_STATUS_4 (ID 16)
CAN_PACKET_STATUS_4 (ID 16)
| Bytes | Data | Unit | Scale |
|---|---|---|---|
| B0 – B1 | FET Temperature | °C | 10 |
| B2 – B3 | Motor Temperature | °C | 10 |
| B4 – B5 | Input Current | A | 10 |
| B6 – B7 | PID Position | Degrees | 50 |
CAN_PACKET_STATUS_5 (ID 27)
CAN_PACKET_STATUS_5 (ID 27)
| Bytes | Data | Unit | Scale |
|---|---|---|---|
| B0 – B3 | Tachometer | EREV | 6 |
| B4 – B5 | Input Voltage | V | 10 |
CAN_PACKET_STATUS_6 (ID 58)
CAN_PACKET_STATUS_6 (ID 58)
| Bytes | Data | Unit | Scale |
|---|---|---|---|
| B0 – B1 | ADC1 | V | 1000 |
| B2 – B3 | ADC2 | V | 1000 |
| B4 – B5 | ADC3 | V | 1000 |
| B6 – B7 | PPM | % / 100 | 1000 |
Full CAN packet ID reference
The completeCAN_PACKET_ID enum is defined in datatypes.h. Multi-frame commands (IDs 5–8) are used internally for tunneling full VESC serial protocol packets over CAN.
| ID | Name | Description |
|---|---|---|
| 0 | CAN_PACKET_SET_DUTY | Set duty cycle |
| 1 | CAN_PACKET_SET_CURRENT | Set motor current |
| 2 | CAN_PACKET_SET_CURRENT_BRAKE | Set braking current |
| 3 | CAN_PACKET_SET_RPM | Set RPM |
| 4 | CAN_PACKET_SET_POS | Set position |
| 5 | CAN_PACKET_FILL_RX_BUFFER | Multi-frame: fill receive buffer |
| 6 | CAN_PACKET_FILL_RX_BUFFER_LONG | Multi-frame: fill receive buffer (long) |
| 7 | CAN_PACKET_PROCESS_RX_BUFFER | Multi-frame: process receive buffer |
| 8 | CAN_PACKET_PROCESS_SHORT_BUFFER | Multi-frame: process short buffer |
| 9 | CAN_PACKET_STATUS | Status message 1 |
| 10 | CAN_PACKET_SET_CURRENT_REL | Set relative current |
| 11 | CAN_PACKET_SET_CURRENT_BRAKE_REL | Set relative braking current |
| 12 | CAN_PACKET_SET_CURRENT_HANDBRAKE | Set handbrake current |
| 13 | CAN_PACKET_SET_CURRENT_HANDBRAKE_REL | Set relative handbrake current |
| 14 | CAN_PACKET_STATUS_2 | Status message 2 |
| 15 | CAN_PACKET_STATUS_3 | Status message 3 |
| 16 | CAN_PACKET_STATUS_4 | Status message 4 |
| 17 | CAN_PACKET_PING | Ping device |
| 18 | CAN_PACKET_PONG | Ping response |
| 27 | CAN_PACKET_STATUS_5 | Status message 5 |
| 31 | CAN_PACKET_SHUTDOWN | Shutdown device |
| 58 | CAN_PACKET_STATUS_6 | Status message 6 |
| 63 | CAN_PACKET_UPDATE_BAUD | Update CAN baud rate |
datatypes.h and the implementation in comm/comm_can.c.