|
/***********************************************************************
// 兩輪自平衡車最終版控制程序(6軸MPU6050+互補濾波+PWM電機)
// 單片機STC12C5A60S2
// 晶振:20M
// 日期:2014.11.26 - ?
***********************************************************************/
#include <REG52.H>
#include <math.h>
#include <stdio.h>
#include <INTRINS.H>
typedef unsigned char uchar;
typedef unsigned short ushort;
typedef unsigned int uint;
//******功能模塊頭文件*******
#include "DELAY.H" //延時頭文件
//--------------------------------------------
#include "STC_ISP.H" //程序燒錄頭文件
#include "SET_SERIAL.H"//串口頭文件
#include "SET_PWM.H"//PWM頭文件
#include "MOTOR.H"//電機控制頭文件
#include "MPU6050.H"//MPU6050頭文件
//-----------------這些文件---------------------------
//******角度參數************
float Gyro_y; //Y軸陀螺儀數據暫存
//--------------加速度和角度的轉化------------------
float Angle_gy; //由角速度計算的傾斜角度
//陀螺儀直接反應角度
float Accel_x; //X軸加速度值暫存
float Angle_ax; //由加速度計算的傾斜角度 、
float Angle; //小車最終傾斜角度
uchar value; //角度正負極性標記
//******PWM參數*************
int speed_mr; //右電機 轉速//這個的測量---------轉盤
int speed_ml; //左電機 轉速
int PWM_R; //右輪PWM值計算
int PWM_L; //左輪PWM值計算
float PWM; //綜合PWM計算
float PWMI; //PWM積分值
//******電機參數*************
float speed_r_l;//電機轉速
float speed; //電機轉速濾波
float position; //位移
//******藍牙遙控參數*************
uchar remote_char;
char turn_need;
char speed_need;
//*********************************************************
//定時器100Hz數據更新中斷 T1定時器
//*********************************************************
void Init_Timer1(void)//10毫秒@20MHz,100Hz刷新頻率
{
AUXR &= 0xBF;//定時器時鐘12T模式
TMOD &= 0x0F;//設置定時器模式
TMOD |= 0x10;//設置定時器模式
TL1 = 0xE5; //設置定時初值
TH1 = 0xBE; //設置定時初值
TF1 = 0; //清除TF1標志
TR1 = 1; //定時器1開始計時
}
//*********************************************************
//中斷控制初始化
//*********************************************************
void Init_Interr(void)
{
EA = 1; //開總中斷
EX0 = 1; //開外部中斷INT0
EX1 = 1; //開外部中斷INT1
IT0 = 1; //下降沿觸發
IT1 = 1; //下降沿觸發
ET1 = 1; //開定時器1中斷
}
//******卡爾曼參數************
float code Q_angle=0.001;
float code Q_gyro=0.003;
float code R_angle=0.5;
float code dt=0.01; //dt為kalman濾波器采樣時間;
char code C_0 = 1;
float xdata Q_bias, Angle_err;
float xdata PCt_0, PCt_1, E;
float xdata K_0, K_1, t_0, t_1;
float xdata Pdot[4] ={0,0,0,0};
float xdata PP[2][2] = { { 1, 0 },{ 0, 1 } };
//*********************************************************
// 卡爾曼濾波
//*********************************************************
//Kalman濾波,20MHz的處理時間約0.77ms;
void Kalman_Filter(float Accel,float Gyro) // 濾波,輸出標準的方波驅動電機
{
Angle+=(Gyro - Q_bias) * dt; //先驗估計陀螺角度
Pdot[0]=Q_angle - PP[0][1] - PP[1][0]; // Pk-先驗估計誤差協方差的微分
Pdot[1]=- PP[1][1];
Pdot[2]=- PP[1][1];
Pdot[3]=Q_gyro;
PP[0][0] += Pdot[0] * dt; // Pk-先驗估計誤差協方差微分的積分
PP[0][1] += Pdot[1] * dt; // =先驗估計誤差協方差
PP[1][0] += Pdot[2] * dt;
PP[1][1] += Pdot[3] * dt;
Angle_err = Accel - Angle;//zk-先驗估計
PCt_0 = C_0 * PP[0][0];
PCt_1 = C_0 * PP[1][0];
E = R_angle + C_0 * PCt_0;
K_0 = PCt_0 / E;
K_1 = PCt_1 / E;
t_0 = PCt_0;
t_1 = C_0 * PP[0][1];
PP[0][0] -= K_0 * t_0; //后驗估計誤差協方差
PP[0][1] -= K_0 * t_1;
PP[1][0] -= K_1 * t_0;
PP[1][1] -= K_1 * t_1;
Angle+= K_0 * Angle_err; //后驗估計
Q_bias+= K_1 * Angle_err; //后驗估計
Gyro_y = Gyro - Q_bias; //輸出值(后驗估計)的微分=角速度
}
//*********************************************************
// 傾角計算(卡爾曼融合)
//*********************************************************
void Angle_Calcu(void)
{
//------加速度--------------------------
//范圍為2g時,換算關系:16384 LSB/g
//角度較小時,x=sinx得到角度(弧度), deg = rad*180/3.14
//因為x>=sinx,故乘以1.3適當放大
Accel_x = GetData(ACCEL_XOUT_H); //讀取X軸加速度 存在ACCEL_XOUT_H 寄存器
Angle_ax = (Accel_x - 1100) /16384; //去除零點偏移,計算得到角度(弧度)
Angle_ax = Angle_ax*1.2*180/3.14; //弧度轉換為度,
//-------角速度-------------------------
//范圍為2000deg/s時,換算關系:16.4 LSB/(deg/s)
Gyro_y = GetData(GYRO_YOUT_H); //靜止時角速度Y軸輸出為 【-30】 左右
Gyro_y = -(Gyro_y + 30)/16.4; //去除零點偏移,計算角速度值, 【負號為方向處理】
//Angle_gy = Angle_gy + Gyro_y*0.01; //角速度積分得到傾斜角度.
//-------卡爾曼濾波融合-----------------------
Kalman_Filter(Angle_ax,Gyro_y); //卡爾曼濾波計算傾角
/*//-------互補濾波-----------------------
//補償原理是取當前傾角和加速度獲得傾角差值進行放大,然后與
//陀螺儀角速度疊加后再積分,從而使傾角最跟蹤為加速度獲得的角度
//0.5為放大倍數,可調節補償度;0.01為系統周期10ms
Angle = Angle + (((Angle_ax-Angle)*0.5 + Gyro_y)*0.01);*/
}
//*********************************************************
//電機轉速和位移值計算
//*********************************************************
void Psn_Calcu(void)
{
speed_r_l =(speed_mr + speed_ml)*0.5;
speed *= 0.7;//上一次的 //車輪速度濾波
speed += speed_r_l*0.3;
position += speed; //積分得到位移
position += speed_need;//加上藍牙位移,等于總的移動
if(position<-6000) position = -6000;
if(position> 6000) position = 6000;
}
static float code Kp = 9.0; //PID參數
static float code Kd = 2.6; //PID參數
static float code Kpn = 0.01; //PID參數
static float code Ksp = 2.0; //PID參數
//*********************************************************
//電機PWM值計算
//*********************************************************
void PWM_Calcu(void)
{
if(Angle<-40||Angle>40) //角度過大,關閉電機
{
CCAP0H = 0;
CCAP1H = 0;
return;
}
PWM = Kp*Angle + Kd*Gyro_y; //PID:角速度和角度
PWM += Kpn*position + Ksp*speed; //PID:速度和位置
PWM_R = PWM + turn_need;
PWM_L = PWM - turn_need; //藍牙的傾斜,
PWM_Motor(PWM_L,PWM_R);
}
//*********************************************************
//手機藍牙遙控
//*********************************************************
void Bluetooth_Remote(void)
{
remote_char = receive_char(); //接收藍牙串口數據
if(remote_char ==0x02) speed_need = -80; //前進
else if(remote_char ==0x01) speed_need = 80; //后退
else speed_need = 0; //不動
if(remote_char ==0x03) turn_need = 15; //左轉
else if(remote_char ==0x04) turn_need = -15; //右轉
else turn_need = 0; //不轉
}
/*=================================================================================*/
//*********************************************************
//main
//*********************************************************
void main()
{
delaynms(500); //上電延時
Init_PWM(); //PWM初始化
Init_Timer0(); //初始化定時器0,作為PWM時鐘源
Init_Timer1(); //初始化定時器1
Init_Interr(); //中斷初始化
Init_Motor(); //電機控制初始化
Init_BRT(); //串口初始化(獨立波特率)
InitMPU6050(); //初始化MPU6050
delaynms(500);
while(1)
{
Bluetooth_Remote();
}
}
/*=================================================================================*/
//********timer1中斷***********************
void Timer1_Update(void) interrupt 3
{
TL1 = 0xE5; //設置定時初值10MS
TH1 = 0xBE;
//STC_ISP(); //程序下載
Angle_Calcu(); //傾角計算
Psn_Calcu(); //電機位移計算
PWM_Calcu(); //計算PWM值
speed_mr = speed_ml = 0;
}
//********右電機中斷***********************
void INT_L(void) interrupt 0
{
if(SPDL == 1) { speed_ml++; } //左電機前進
else { speed_ml--; } //左電機后退
LED = ~LED;
}
//********左電機中斷***********************
void INT_R(void) interrupt 2
{
if(SPDR == 1) { speed_mr++; } //右電機前進
else { speed_mr--; } //右電機后退
LED = ~LED;
}
|
|