foc/arduino/main/main.ino

248 lines
7.2 KiB
Arduino
Raw Normal View History

2021-08-17 17:01:19 +00:00
/**
Deng's FOC SimpleFOC 2.1.1 FOC V1.0
T+使
10rad/s T10
使 BLDCMotor(7)
16.8V, voltage_power_supply , voltage_limit
PID GB6010 使PID
*/
#include <SimpleFOC.h>
#include <WiFi.h>
#include <AsyncUDP.h> //引用以使用异步UDP
2021-08-25 08:23:23 +00:00
#include <Kalman.h> // Source: https://github.com/TKJElectronics/KalmanFilter
Kalman kalmanZ;
#define gyroZ_OFF -0.72
/* ----IMU Data---- */
float PID_P = 8; //
float PID_I = 0; //
float PID_D = 0; //
double accX, accY, accZ;
double gyroX, gyroY, gyroZ;
int16_t tempRaw;
double gyroZangle; // Angle calculate using the gyro only
double compAngleZ; // Calculated angle using a complementary filter
double kalAngleZ; // Calculated angle using a Kalman filter
uint32_t timer;
uint8_t i2cData[14]; // Buffer for I2C data
/* ----FOC Data---- */
// driver instance
double acc2rotation(double x, double y);
2021-08-17 17:01:19 +00:00
const char *ssid = "esp32";
const char *password = "12345678";
2021-08-25 08:23:23 +00:00
2021-08-17 17:01:19 +00:00
AsyncUDP udp; //创建UDP对象
unsigned int localUdpPort = 2333; //本地端口号
2021-08-25 08:23:23 +00:00
unsigned int broadcastPort = localUdpPort;
2021-08-17 17:01:19 +00:00
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
2021-08-25 08:23:23 +00:00
TwoWire I2Ctwo = TwoWire(1);
2021-08-17 17:01:19 +00:00
2021-08-25 08:23:23 +00:00
//倒立摆参数
float LQR_K1 = 200; //摇摆到平衡
float LQR_K2 = 15; //
float LQR_K3 = 0.15; //
2021-08-17 17:01:19 +00:00
//电机参数
BLDCMotor motor = BLDCMotor(5);
BLDCDriver3PWM driver = BLDCDriver3PWM(32, 33, 25, 22);
//命令设置
int target_velocity = 0;
2021-08-25 08:23:23 +00:00
int target_angle = 149;
2021-08-17 17:01:19 +00:00
void onPacketCallBack(AsyncUDPPacket packet)
{
target_velocity = atoi((char*)(packet.data()));
Serial.print("数据内容: ");
Serial.println(target_velocity);
// packet.print("reply data");
}
void setup() {
Serial.begin(115200);
2021-08-25 08:23:23 +00:00
// kalman mpu6050 init
Wire.begin(19, 18,400000);// Set I2C frequency to 400kHz
i2cData[0] = 7; // Set the sample rate to 1000Hz - 8kHz/(7+1) = 1000Hz
i2cData[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling
i2cData[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s
i2cData[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g
while (i2cWrite(0x19, i2cData, 4, false))
; // Write to all four registers at once
while (i2cWrite(0x6B, 0x01, true))
; // PLL with X axis gyroscope reference and disable sleep mode
while (i2cRead(0x75, i2cData, 1))
;
if (i2cData[0] != 0x68)
{ // Read "WHO_AM_I" register
Serial.print(F("Error reading sensor"));
while (1)
;
}
delay(100); // Wait for sensor to stabilize
/* Set kalman and gyro starting angle */
while (i2cRead(0x3B, i2cData, 6))
;
accX = (int16_t)((i2cData[0] << 8) | i2cData[1]);
accY = (int16_t)((i2cData[2] << 8) | i2cData[3]);
accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]);
double pitch = acc2rotation(accX, accY);
kalmanZ.setAngle(pitch);
gyroZangle = pitch;
timer = micros();
Serial.println("kalman mpu6050 init");
//wifi初始化
2021-08-17 17:01:19 +00:00
WiFi.mode(WIFI_AP);
while(!WiFi.softAP(ssid, password)){}; //启动AP
Serial.println("AP启动成功");
while (!udp.listen(localUdpPort)) //等待udp监听设置成功
{
}
udp.onPacket(onPacketCallBack); //注册收到数据包事件
2021-08-25 08:23:23 +00:00
I2Ctwo.begin(23, 5, 400000); //SDA,SCL
sensor.init(&I2Ctwo);
2021-08-17 17:01:19 +00:00
//连接motor对象与传感器对象
motor.linkSensor(&sensor);
//供电电压设置 [V]
driver.voltage_power_supply = 12;
driver.init();
//连接电机和driver对象
motor.linkDriver(&driver);
//FOC模型选择
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
//运动控制模式设置
motor.controller = MotionControlType::velocity;
//速度PI环设置
motor.PID_velocity.P = 1.5;
motor.PID_velocity.I = 20;
//最大电机限制电机
motor.voltage_limit = 12;
//速度低通滤波时间常数
motor.LPF_velocity.Tf = 0.01;
//设置最大速度限制
motor.velocity_limit = 40;
motor.useMonitoring(Serial);
//初始化电机
motor.init();
//初始化 FOC
motor.initFOC();
Serial.println(F("Motor ready."));
Serial.println(F("Set the target velocity using serial terminal:"));
2021-08-25 08:23:23 +00:00
}
char s[255];
int t_v;
int lim_v = 20;
2021-08-17 17:01:19 +00:00
void loop() {
2021-08-25 08:23:23 +00:00
while (i2cRead(0x3B, i2cData, 14));
accX = (int16_t)((i2cData[0] << 8) | i2cData[1]);
accY = (int16_t)((i2cData[2] << 8) | i2cData[3]);
accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]);
tempRaw = (int16_t)((i2cData[6] << 8) | i2cData[7]);
gyroX = (int16_t)((i2cData[8] << 8) | i2cData[9]);
gyroY = (int16_t)((i2cData[10] << 8) | i2cData[11]);
gyroZ = (int16_t)((i2cData[12] << 8) | i2cData[13]);
double dt = (double)(micros() - timer) / 1000000; // Calculate delta time
timer = micros();
double pitch = acc2rotation(accX, accY);
double gyroZrate = gyroZ / 131.0; // Convert to deg/s
kalAngleZ = kalmanZ.getAngle(pitch, gyroZrate + gyroZ_OFF, dt);
gyroZangle += (gyroZrate + gyroZ_OFF) * dt;
compAngleZ = 0.93 * (compAngleZ + (gyroZrate + gyroZ_OFF) * dt) + 0.07 * pitch;
// Reset the gyro angle when it has drifted too much
if (gyroZangle < -180 || gyroZangle > 180)
gyroZangle = kalAngleZ;
sprintf(s, "%.2f",kalAngleZ); //将100转为16进制表示的字符串
// target_velocity = -angle_pid(kalAngleZ);
// if (abs(target_velocity)>lim_v)
// target_velocity = -target_velocity;
// if (target_velocity >lim_v)
// target_velocity = lim_v;
// if (target_velocity<-lim_v)
// target_velocity = -lim_v;
Serial.print(motor.shaft_velocity);Serial.print("\t");
Serial.print(target_velocity);Serial.print("\t");
Serial.print(target_angle);Serial.print("\t");
Serial.print(kalAngleZ);Serial.print("\t");
Serial.print("\r\n");
2021-08-17 17:01:19 +00:00
motor.loopFOC();
motor.move(target_velocity);
2021-08-25 08:23:23 +00:00
//可以使用该方法广播信息
IPAddress broadcastAddr((~(uint32_t)WiFi.subnetMask())|((uint32_t)WiFi.localIP())); //计算广播地址
udp.writeTo((const unsigned char*)s, strlen(s), broadcastAddr, localUdpPort); //广播数据
}
/* mpu6050加速度转换为角度
acc2rotation(ax, ay)
acc2rotation(az, ay) */
double acc2rotation(double x, double y)
{
if (y < 0)
{
return atan(x / y) / 1.570796 * 90 + 180;
}
else if (x < 0)
{
return (atan(x / y) / 1.570796 * 90 + 360);
}
else
{
return (atan(x / y) / 1.570796 * 90);
}
}
2021-08-17 17:01:19 +00:00
2021-08-25 08:23:23 +00:00
unsigned long lastTime;
double errSum, lastErr;
int angle_pid(double now_angle)
{
/*How long since we last calculated*/
unsigned long now = millis();
double timeChange = (double)(now - lastTime);
/*Compute all the working error variables*/
double error = target_angle-now_angle;
errSum += (error * timeChange);
double dErr = (error - lastErr) / timeChange;
/*Compute PID Output*/
int Output = PID_P * error + PID_I * errSum + PID_D * dErr;
/*Remember some variables for next time*/
lastErr = error;
lastTime = now;
return Output;
2021-08-17 17:01:19 +00:00
}