Is it possible to control ODrive Pro with STM32F446RE + MCP2551 using CAN communication? I tried it a little but it didn’t work at all.
Calibrated with ODriveGUi
Yep absolutely. You can see our CAN protocol here: CAN Protocol — ODrive Documentation 0.6.11 documentation
If you want to show some of your code, happy to take a look!
1 Like
thank you!! This is a part of the code. I will omit the definition of id, basic can send, receive, and filter.
#ifndef ODRIVE_H_
#define ODRIVE_H_
#include "main.h"
// ODrive CAN Command IDs
typedef enum {
ODRIVE_CMD_HEARTBEAT = 0x01,
ODRIVE_CMD_SET_AXIS_STATE = 0x07,
ODRIVE_CMD_GET_ENCODER_ESTIMATES = 0x09,
ODRIVE_CMD_SET_INPUT_VEL = 0x0D,
ODRIVE_CMD_CLEAR_ERRORS = 0x18,
ODRIVE_CMD_SET_CONTROLLER_MODES = 0x0B
} ODriveCommandID;
// ODrive Axis States
typedef enum {
ODRIVE_AXIS_STATE_IDLE = 1,
ODRIVE_AXIS_STATE_FULL_CALIBRATION_SEQUENCE = 3,
ODRIVE_AXIS_STATE_CLOSED_LOOP_CONTROL = 8
} ODriveAxisState;
// ODrive Control Modes
typedef enum {
VOLTAGE_CONTROL = 0,
TORQUE_CONTROL = 1,
VELOCITY_CONTROL = 2,
POSITION_CONTROL = 3
} ODriveControlMode;
// ODrive Input Modes
typedef enum {
INACTIVE = 0,
PASSTHROUGH = 1,
VEL_RAMP = 2,
POS_FILTER = 3,
MIX_CHANNELS = 4,
TRAP_TRAJ = 5,
TORQUE_RAMP = 6,
MIRROR = 7
} ODriveInputMode;
// ODrive feedback
typedef struct {
float pos_estimate;
float vel_estimate;
uint32_t axis_error;
uint8_t axis_state;
} ODriveFeedback_t;
// ODrive axis
typedef struct {
CAN_HandleTypeDef* CAN_INSTANCE;
uint8_t AXIS_ID;
ODriveFeedback_t feedback;
} Axis;
void ODrive_RX_CallBack(Axis* axis);
void Set_Axis_Requested_State(Axis axis, ODriveAxisState state);
void Set_Input_Vel(Axis axis, float velocity, float torque_feedforward);
void Set_Controller_Modes(Axis axis, ODriveControlMode control_mode, ODriveInputMode input_mode);
#endif /* ODRIVE_H_ */
`
odrive.c
#include "ODrive.h"
#include <string.h>
static void pack_float(uint8_t* data, float value) {
memcpy(data, &value, sizeof(float));
}
static float unpack_float(uint8_t* data) {
float value;
memcpy(&value, data, sizeof(float));
return value;
}
static void send_can_message(CAN_HandleTypeDef* hcan, uint32_t id, uint8_t* data, uint8_t len) {
CAN_TxHeaderTypeDef TxHeader;
uint32_t TxMailbox;
TxHeader.StdId = id;
TxHeader.IDE = CAN_ID_STD;
TxHeader.RTR = CAN_RTR_DATA;
TxHeader.DLC = len;
TxHeader.TransmitGlobalTime = DISABLE;
while (HAL_CAN_GetTxMailboxesFreeLevel(hcan) == 0); // wait
if (HAL_CAN_AddTxMessage(hcan, &TxHeader, data, &TxMailbox) != HAL_OK) {
Error_Handler();
}
}
// build can message id
static uint32_t build_can_id(uint8_t axis_id, uint8_t cmd_id) {
return (axis_id << 5) | cmd_id;
}
void ODrive_RX_CallBack(Axis* axis) {
CAN_RxHeaderTypeDef rx_header;
uint8_t rx_data[8];
// get message from FIFO
if (HAL_CAN_GetRxMessage(axis->CAN_INSTANCE, CAN_RX_FIFO0, &rx_header, rx_data) != HAL_OK) {
return;
}
uint8_t cmd_id = rx_header.StdId & 0x1F;
switch (cmd_id) {
case ODRIVE_CMD_HEARTBEAT:
axis->feedback.axis_error = (rx_data[3] << 24) | (rx_data[2] << 16) | (rx_data[1] << 8) | rx_data[0];
axis->feedback.axis_state = rx_data[4];
break;
case ODRIVE_CMD_GET_ENCODER_ESTIMATES:
axis->feedback.pos_estimate = unpack_float(&rx_data[0]);
axis->feedback.vel_estimate = unpack_float(&rx_data[4]);
break;
}
}
void Set_Axis_Requested_State(Axis axis, ODriveAxisState state) {
uint8_t payload[8] = {0};
payload[0] = (uint8_t)state;
uint32_t can_id = build_can_id(axis.AXIS_ID, ODRIVE_CMD_SET_AXIS_STATE);
send_can_message(axis.CAN_INSTANCE, can_id, payload, 4);
}
void Set_Input_Vel(Axis axis, float velocity, float torque_feedforward) {
uint8_t payload[8] = {0};
pack_float(&payload[0], velocity);
pack_float(&payload[4], torque_feedforward);
uint32_t can_id = build_can_id(axis.AXIS_ID, ODRIVE_CMD_SET_INPUT_VEL);
send_can_message(axis.CAN_INSTANCE, can_id, payload, 8);
}
void Set_Controller_Modes(Axis axis, ODriveControlMode control_mode, ODriveInputMode input_mode) {
uint8_t payload[8] = {0};
payload[0] = (uint8_t)control_mode;
payload[4] = (uint8_t)input_mode;
uint32_t can_id = build_can_id(axis.AXIS_ID, ODRIVE_CMD_SET_CONTROLLER_MODES);
send_can_message(axis.CAN_INSTANCE, can_id, payload, 8);
}