とりあえずCANのプロトコルはOdrive風にしてみた。しかしOdriveとSimpleFOCだと単位が違うのが少し面倒。rpsとrad/sの変換を入れようとしてるけども、まずはSTM32F103でCAN通信をやりながらSimpleFOCでベクトル制御を動かせるかを試したいので値は変換しない状態でやってみようかと思う。
#include "SPI.h"
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "encoders/MT6701/MagneticSensorMT6701SSI.h"
#include <EEPROM.h>
#include "stm32f103-can.h"
#define Protocol_Version 0x01
#define Hw_Version_Major 0x00
#define Hw_Version_Minor 0x00
#define Hw_Version_Variant 0x00
#define Fw_Version_Major 0x00
#define Fw_Version_Minor 0x00
#define Fw_Version_Revision 0x00
#define Fw_Version_Unreleased 0x00
#define NODE_ID_DEFAULT 0x000
#define NODE_BC 0x3F
uint16_t nodeID = 0x005;
#define MOTOR_POLE 7
#define CS1 PA15
#define SCK1 PB3
#define MISO1 PB4
#define MOSI1 PB5
#define DRV_EN PB12
#define TX3_SCL2 PB10
#define RX3_SDA2 PB11
#define CAN_RX PB8
#define CAN_TX PB9
#define V_CURR PA0
#define W_CURR PA1
#define U_CURR PA2
#define TEMP PA3
#define VOLTAGE PA4
#define LED_BUILTIN PC13
HardwareSerial Serial3(TX3_SCL2, RX3_SDA2);
SPIClass SPI_1(MOSI1, MISO1, SCK1);
MagneticSensorMT6701SSI sensor(CS1);
InlineCurrentSense current_sense = InlineCurrentSense(0.01, -50 * 4, W_CURR, V_CURR, U_CURR);
BLDCMotor motor = BLDCMotor(MOTOR_POLE);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15, DRV_EN); //W V U EN
typedef union { //IEEE 754 Float
uint8_t uint[8];
float value[2];
} FLOAT_BYTE_UNION;
uint8_t eepromRead(uint8_t reqID) {
uint8_t lastData = 0xFF;
for (uint16_t i = 0; i < EEPROM.length(); i += 2) {
uint8_t dataID = EEPROM.read(i);
uint8_t data = EEPROM.read(i + 1);
//Serial1.println(dataID);
if (dataID == reqID) {
lastData = data;
//Serial1.print("EEPROM Read:");
//Serial1.println(i);
}
if (dataID == 0xFF | dataID == 0x00) {
break;
}
}
//Serial1.print("EEPROM Data:");
//Serial1.println(lastData);
return lastData;
}
void eepromWrite(uint8_t reqID, uint8_t data) {
uint16_t lastID = 0xFFFF;
for (uint16_t i = 0; i < EEPROM.length(); i += 2) {
uint8_t eepromId = EEPROM.read(i);
if (eepromId == 0xFF | eepromId == 0x00) {
lastID = i;
//Serial1.print("EEPROM Write:");
//Serial1.println(i);
break;
}
}
if (lastID == EEPROM.length()) {
lastID = 0;
}
EEPROM.write(lastID, reqID);
EEPROM.write(lastID + 1, data);
}
void CANread() {
if (CANMsgAvail()) {
CAN_msg_t CAN_RX_msg;
CANReceive(&CAN_RX_msg);
uint16_t cmdID = uint16_t(CAN_RX_msg.id & 0x1F);
uint16_t nodeIDrcv = CAN_RX_msg.id >> 5;
CAN_msg_t CAN_TX_msg;
memset(&CAN_TX_msg, 0, sizeof(CAN_msg_t));
CAN_TX_msg.type = DATA_FRAME;
CAN_TX_msg.format = STANDARD_FORMAT;
CAN_TX_msg.id = ((nodeID << 5) | cmdID);
if (nodeIDrcv == nodeID) {
switch (cmdID) {
// case 0x003: //Get Motor Error
// break;
// case 0x004: //Get Encoder Error
// break;
// case 0x005: //Get Sensorless Error
// break;
case 0x006: //Set Axis Node ID
if (CAN_RX_msg.type == DATA_FRAME) {
uint32_t reqNodeID = CAN_RX_msg.data[0] | CAN_RX_msg.data[1] << 8 | CAN_RX_msg.data[2] << 16 | CAN_RX_msg.data[3] << 24;
//Serial1.println(reqNodeID,HEX);
if ((reqNodeID < 0x3F) && (reqNodeID != eepromRead(1))) {
eepromWrite(1, reqNodeID);
//Serial1.println("nodeID update");
}
}
break;
case 0x009: //Get Encoder Estimates
if (CAN_RX_msg.type == REMOTE_FRAME) {
FLOAT_BYTE_UNION output;
output.value[0] = motor.shaft_angle;
output.value[1] = motor.shaft_velocity;
memcpy(CAN_TX_msg.data, output.uint, 8);
CAN_TX_msg.len = 8;
CANSend(&CAN_TX_msg);
}
break;
case 0x00C: //Set Input Pos
if (CAN_RX_msg.type == DATA_FRAME) {
FLOAT_BYTE_UNION input;
memcpy(input.uint, CAN_RX_msg.data, 8);
motor.controller = MotionControlType::angle;
target_angle = input.value[0];
}
break;
case 0x00D: //Set Input Vel
if (CAN_RX_msg.type == DATA_FRAME) {
FLOAT_BYTE_UNION input;
memcpy(input.uint, CAN_RX_msg.data, 8);
motor.controller = MotionControlType::velocity;
target_angle = input.value[0];
}
break;
case 0x00E: //Set Input Torque
if (CAN_RX_msg.type == DATA_FRAME) {
FLOAT_BYTE_UNION input;
memcpy(input.uint, CAN_RX_msg.data, 8);
motor.controller = MotionControlType::torque;
target_angle = input.value[0];
}
break;
// case 0x014: //Get IQ
// break;
case 0x015: //Get Temperature(FET IEEE 754 Float, Motor IEEE 754 Float)
if (CAN_RX_msg.type == REMOTE_FRAME) {
FLOAT_BYTE_UNION output;
output.value[0] = (1.43 - analogRead(ATEMP) * 3.3 / 4095) / 0.0043 + 25;
output.value[1] = analogRead(AVREF);
memcpy(CAN_TX_msg.data, output.uint, 8);
CAN_TX_msg.len = 8;
CANSend(&CAN_TX_msg);
}
break;
case 0x017: //Get Bus Voltage and Current
if (CAN_RX_msg.type == REMOTE_FRAME) {
FLOAT_BYTE_UNION output;
output.value[0] = analogRead(VOLTAGE) * 3.3 / 4095.0 * 4.0;
output.value[1] = motor.current.q;
memcpy(CAN_TX_msg.data, output.uint, 8);
CAN_TX_msg.len = 8;
CANSend(&CAN_TX_msg);
}
break;
// case 0x01c: //Get ADC Voltage
// break;
default:
break;
}
}
if (CAN_RX_msg.type == REMOTE_FRAME) {
switch (cmdID) {
case 0x000: //Get Version
CAN_TX_msg.data[0] = Protocol_Version;
CAN_TX_msg.data[1] = Hw_Version_Major;
CAN_TX_msg.data[2] = Hw_Version_Minor;
CAN_TX_msg.data[3] = Hw_Version_Variant;
CAN_TX_msg.data[4] = Fw_Version_Major;
CAN_TX_msg.data[5] = Fw_Version_Minor;
CAN_TX_msg.data[6] = Fw_Version_Revision;
CAN_TX_msg.data[7] = Fw_Version_Unreleased;
CAN_TX_msg.len = 8;
CANSend(&CAN_TX_msg);
break;
case 0x001: //Heartbeat Message
CAN_TX_msg.data[1] = nodeID >> 8;
CAN_TX_msg.data[0] = nodeID;
CAN_TX_msg.len = 8;
CANSend(&CAN_TX_msg);
break;
default:
break;
}
}
}
}
float target_angle = 0;
Commander command = Commander(Serial3);
void doTarget(char* cmd) {
command.scalar(&target_angle, cmd);
}
void doMotor(char* cmd) {
command.motor(&motor, cmd);
}
void doAnalog(char* cmd) {
if (cmd[0] == 'T') Serial3.println(analogRead(TEMP));
else if (cmd[0] == 'V') {
Serial3.print("Voltage: ");
Serial3.println(analogRead(VOLTAGE) * 0.0032);
}
};
void setup() {
analogReadResolution(12);
pinMode(LED_BUILTIN, OUTPUT);
digitalWrite(LED_BUILTIN, HIGH);
Serial3.setTx(TX3_SCL2);
Serial3.setRx(RX3_SDA2);
Serial3.begin(115200);
SimpleFOCDebug::enable(&Serial3);
sensor.init(&SPI_1);
motor.linkSensor(&sensor);
driver.voltage_power_supply = 8;
driver.init();
motor.linkDriver(&driver);
current_sense.linkDriver(&driver);
// control loop type and torque mode
motor.torque_controller = TorqueControlType::foc_current;
motor.controller = MotionControlType::velocity;
motor.motion_downsample = 0.0;
// velocity loop PID
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 20.0;
motor.PID_velocity.D = 0.0;
motor.PID_velocity.output_ramp = 1000.0;
motor.PID_velocity.limit = 8.0;
// Low pass filtering time constant
motor.LPF_velocity.Tf = 0.01;
// angle loop PID
motor.P_angle.P = 20.0;
motor.P_angle.I = 0.0;
motor.P_angle.D = 0.0;
motor.P_angle.output_ramp = 0.0;
motor.P_angle.limit = 40.0;
// Low pass filtering time constant
motor.LPF_angle.Tf = 0.0;
// current q loop PID
motor.PID_current_q.P = 1.5;
motor.PID_current_q.I = 15.0;
motor.PID_current_q.D = 0.0;
motor.PID_current_q.output_ramp = 1000.0;
motor.PID_current_q.limit = 5.0;
// Low pass filtering time constant
motor.LPF_current_q.Tf = 0.005;
// current d loop PID
motor.PID_current_d.P = 1.5;
motor.PID_current_d.I = 15.0;
motor.PID_current_d.D = 0.0;
motor.PID_current_d.output_ramp = 1000.0;
motor.PID_current_d.limit = 5.0;
// Low pass filtering time constant
motor.LPF_current_d.Tf = 0.02;
// Limits
motor.velocity_limit = 200.0;
motor.voltage_limit = 5.0;
motor.current_limit = 2.0;
// sensor zero offset - home position
motor.sensor_offset = 0.0;
// general settings
// pwm modulation settings
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
motor.modulation_centered = 1.0;
motor.useMonitoring(Serial3);
motor.linkCurrentSense(¤t_sense);
current_sense.init();
motor.init();
motor.sensor_direction = Direction::CW;
motor.initFOC();
command.add('T', doTarget, "target angle");
command.add('M', doMotor, "motor");
command.add('A', doAnalog, "analog read");
motor.monitor_downsample = 0;
//motor.monitor_variables = 0;
Serial3.println(F("Motor ready."));
Serial3.println(F("Set the target angle using serial terminal:"));
bool ret = CANInit(CAN_250KBPS, 2);//PB8,PB9
nodeID = eepromRead(1);
if (nodeID >= 0x3F) {
eepromWrite(1, NODE_ID_DEFAULT);
nodeID = NODE_ID_DEFAULT;
}
CAN1->FMR |= 0x1UL;
CAN1->FMR &= 0xFFFFC0FF;
CAN1->FMR |= 0x1C << 8;
CANSetFilter(0, 1, 0, 0, ((nodeID << 5) << 21), 0xFC000004);
CANSetFilter(1, 1, 0, 0, ((NODE_BC << 5) << 21), 0xFC000004);
CAN1->FMR &= ~(0x1UL);
_delay(1000);
}
void loop() {
motor.loopFOC();
motor.move(target_angle);
motor.monitor();
command.run();
CANread();
}
Odriveのほうもバージョンによってコマンドが変わっていたりするけどとりあえず使いそうなところだけ有効にしてみた。ノードIDはEEPROMに記録するようにした。同じファームを書いてあとからCANでノードIDを書き換えられる。ODriveではモードを切り替えないと現在のモード以外でのコマンドは受け付けないけど、モード切替なしにデータを受け取ったモードに自動で変更するようにしてみた。
CANのライブラリは以前フィルタを試したときに使わせてもらったスケッチと同じように元ネタのstm32f103.inoのsetupとloopを削除して"stm32f103-can.h"として別ファイルにして使用してみた。
いちいちCANでコマンドを入力するのが面倒なので簡易的なPythonツールを作成しようかなと思う。もしくはESP32で直接やってしまったほうが早いかなぁ?
あと通信が切れたときのためにモータの動作を止められるように通信Watchdogをつけておいたほうがいいかもしれないかなぁ。モータが回りっぱなしになってしまうし。