配列を使用し記憶走行を行う

Dependencies:   mbed AQM0802 CRotaryEncoder TB6612FNG

main.cpp

Committer:
1817106
Date:
2019-11-08
Revision:
15:9e234fb2d07a
Parent:
14:584e778a20ea

File content as of revision 15:9e234fb2d07a:

////ライントレースサンプルver7_1
#include "mbed.h"
#include "CRotaryEncoder.h"
#include "TB6612.h"
#include "AQM0802.h"


//☆★☆★各種パラメータ調整箇所☆★☆★☆★
#define     DEFAULT_SPEED   800     //1走目の基本速度[mm/sec]
#define     STOP_DISTANCE   200000  //停止距離200000[um]⇒20[cm]
#define     TURN_POWER      0.3     //コースアウト時の旋回力
#define     PULSE_TO_UM     29      //エンコーダ1パルス当たりのタイヤ移動距離[um]
#define     INTERRUPT_TIME  1000    //割りこみ周期[us]
#define     DEFAULT_GRAY    0.3f    //フォトリフレクタデジタル入力の閾値
                                    //シリアル通信でSensor_Digital値を確認し調整する。
#define     MARKER_WIDTH    13000      //マーカ幅[um](ビニルテープ幅19[um]以内)
                                    //コースの傷によってマーカ誤検知する場合は値を大きくする。
#define     CROSS_JUDGE     4       //ラインセンサいくつ以上白線検知で交差点認識するか設定。
//モータ速度のゲイン関連(むやみに調整しない)
#define     M_KP            0.002f  //P(比例)制御成分
#define     M_KD            0.001f  //D(微分)制御成分

//フォトリフレクタのゲイン(外側に行くにつれ値を何倍させたいか調整する。)
#define     S_K1            1.0f    //float演算させる値には必ずfを付ける
#define     S_K2            2.0f    //2倍
#define     S_K3            2.8f    //4倍

//ラインセンサ各種制御成分
#define     S_KP            0.53f    //ラインセンサ比例成分。大きいほど曲がりやすい
#define     S_KD            0.8f    //ラインセンサ微分成分。大きいほど急なラインずれに強くなる。
//////////☆★☆★☆★☆★☆★//////////////



//スイッチ状態の定義
#define PUSH    0       //スイッチ押したときの状態
#define PULL    1       //スイッチ離したときの状態
//機体状態の定義
#define STOP                0x80   //機体停止状態
#define RUN_START           0x40   //スタートマーカ通過
#define RUN_COURSE_LOUT     0x20   //左コースアウト状態
#define RUN_COURSE_CENTER   0x18   //ライン中央走行状態
#define RUN_COURSE_ROUT     0x04   //右コースアウト状態
#define SECOND_RUN          0x02   //機体停止状態
#define TUARD_RUN           0x01   //機体設定モード


//デジタル入力オブジェクト定義
DigitalIn   push_sw(D13);
/////アナログ入力オブジェクト定義//////////
AnalogIn    s1(A1);
AnalogIn    s2(D3);
AnalogIn    s3(A6);
AnalogIn    s4(A5);
AnalogIn    s5(A4);
AnalogIn    s6(A3);
AnalogIn    s7(A2);
AnalogIn    s8(A0);
///////////////////////////////////////  
Serial      PC(USBTX,USBRX);
CRotaryEncoder encoder_a(D1,D0);    //モータAのエンコーダ
CRotaryEncoder encoder_b(D11,D12);  //モータBのエンコーダ
Ticker      timer;              //タイマ割込み用 
TB6612      motor_a(D2,D7,D6);  //モータA制御用(pwma,ain1,ain2)
TB6612      motor_b(D10,D8,D9); //モータB制御用(pwmb,bin1,bin2)
AQM0802     lcd(I2C_SDA,I2C_SCL);       //液晶制御用

//使用変数の定義
int    Sw_Ptn;
int    Old_Sw_Ptn;
double S1_Data,S2_Data,S3_Data,S4_Data,S5_Data,S6_Data,S7_Data,S8_Data; 
double  All_Sensor_Data;      //ラインセンサ総データ量
double Sensor_Diff[2]={0,0}; //ラインセンサ偏差
double Sensor_P =0.0f;        //ラインセンサP(比例成分)制御量
double Sensor_D =0.0f;        //ラインセンサD(微分成分)制御量
double Sensor_PD=0.0f;       //ラインセンサP,D成分の合計
char    Gray_Str[5];        //LCD閾値表示用文字列
float   Gray=DEFAULT_GRAY;
long int Enc_Count_A=0,Enc_Count_B=0;        //エンコーダパルス数を格納
long int Enc_A_Rotate=0,Enc_B_Rotate=0;
long int Stop_Distance=STOP_DISTANCE;
long int Distance_A=0,Distance_B=0;          //タイヤ移動距離を格納[mm]
long int Marker_Run_Distance=0; 
long int Speed_A=0,  Speed_B=0;              //現在速度
long int Machine_Speed=DEFAULT_SPEED;
char     Speed_Str[5];                  //LCD速度表示用文字列
long int Target_Speed_A=0,Target_Speed_B=0;  //目標速度
long int Motor_A_Diff[2]={0,0};         //過去の速度偏差と現在の速度偏差を格納
long int Motor_B_Diff[2]={0,0};         //
float Motor_A_P,Motor_B_P;              //モータ速度制御P成分
float Motor_A_D,Motor_B_D;              //モータ速度制御D成分
float Motor_A_PD,Motor_B_PD;            //モータ速度制御PD合成
float Motor_A_Pwm,Motor_B_Pwm;          //モータへの出力
unsigned char Sensor_Digital    =0x00;
unsigned char Old_Sensor_Digital=0x00;
int   Sensor_Cnt=0;
unsigned char Machine_Status    =STOP;                 //機体状態
unsigned char Old_Machine_Status=0x00;             //過去の機体状態
int Marker_Pass_Flag = 0;
int Old_Marker_Pass_Flag=0;
int Corner_Flag=0;
int SG_Flag=0;
int SG_Cnt=0;
int Cross_Flag=0;
void sensor_analog_read(){
    S1_Data=s1.read();
    S2_Data=s2.read();
    S3_Data=s3.read();
    S4_Data=s4.read();
    S5_Data=s5.read();
    S6_Data=s6.read();
    S7_Data=s7.read();
    S8_Data=s8.read();    
}


void sensor_digital_read(){//8つのフォトリフレクタの入力を8ビットのデジタルパターンに変換
    Sensor_Cnt=0;
    Old_Sensor_Digital=Sensor_Digital;
    if(S1_Data>Gray){
            Sensor_Digital |= 0x80;   //7ビット目のみセット (1にする。)
    }else   Sensor_Digital &= 0x7F;   //7ビット目のみマスク(0にする。)
    if(S2_Data>Gray){
            Sensor_Digital |= 0x40;   //6ビット目のみセット (1にする。)
            Sensor_Cnt++;
    }else   Sensor_Digital &= 0xBF;   //6ビット目のみマスク(0にする。)
    if(S3_Data>Gray){
            Sensor_Digital |= 0x20;   //5ビット目のみセット (1にする。)
            Sensor_Cnt++;
    }else    Sensor_Digital &= 0xDF;   //5ビット目のみマスク(0にする。)
    if(S4_Data>Gray){
            Sensor_Digital |= 0x10;   //4ビット目のみセット (1にする。)
            Sensor_Cnt++;
    }else    Sensor_Digital &= 0xEF;   //4ビット目のみマスク(0にする。)
    if(S5_Data>Gray){
            Sensor_Digital |= 0x08;   //3ビット目のみセット (1にする。)
            Sensor_Cnt++;
    }else   Sensor_Digital &= 0xF7;   //3ビット目のみマスク(0にする。)
    if(S6_Data>Gray){
            Sensor_Digital |= 0x04;   //2ビット目のみセット (1にする。)
            Sensor_Cnt++;
    }else   Sensor_Digital &= 0xFB;   //2ビット目のみマスク(0にする。)
    if(S7_Data>Gray){
            Sensor_Digital |= 0x02;   //1ビット目のみセット (1にする。)
            Sensor_Cnt++;
    }else   Sensor_Digital &= 0xFD;   //1ビット目のみマスク(0にする。)
    if(S8_Data>Gray){
            Sensor_Digital |= 0x01;   //0ビット目のみセット (1にする。)
    }else   Sensor_Digital &= 0xFE;   //0ビット目のみマスク(0にする。)    
}

void Machine_Status_Set(){
    Old_Machine_Status=Machine_Status; 
       
    //機体がライン中央に位置するとき
    if(Sensor_Digital&RUN_COURSE_CENTER )Machine_Status|=RUN_COURSE_CENTER;
    else Machine_Status &= 0xE7;//ライン中央情報のマスク
    if((Sensor_Digital==0x00)&&(Old_Sensor_Digital==0x40)){//左センサコースアウト時
        Machine_Status|=RUN_COURSE_LOUT;//左コースアウト状態のビットをセット
    }else if((Machine_Status&RUN_COURSE_LOUT)&&(Sensor_Digital&RUN_COURSE_CENTER)){
        //左コースアウト状態かつ機体がライン中央に復帰したとき
        Machine_Status &= 0xDF;//左コースアウト情報のみマスク    
    }
    if((Sensor_Digital==0x00)&&(Old_Sensor_Digital==0x02)){//右センサコースアウト時
        Machine_Status|=RUN_COURSE_ROUT;//右コースアウト状態のビットをセット
    }else if((Machine_Status&RUN_COURSE_ROUT)&&(Sensor_Digital&RUN_COURSE_CENTER)){
        //右コースアウト状態かつ機体がライン中央に復帰したとき
        Machine_Status &= 0xFB;//右コースアウト情報のみマスク    
    }     
}


//タイマ割り込み1[ms]周期
void timer_interrupt(){
    
    //ラインセンサ情報取得
    sensor_analog_read();
    sensor_digital_read();
    
    //機体状態の取得
    Machine_Status_Set();
  
    //各種マーカの検知
    Old_Marker_Pass_Flag=Marker_Pass_Flag;//過去のフラグを退避
    if(Sensor_Digital&0x81){                   //マーカセンサ検知時
        Marker_Pass_Flag=1;                     //マーカ通過中フラグをON
        if(Sensor_Digital&0x80)Corner_Flag=1;  //コーナセンサの検知
        if(Sensor_Digital&0x01)SG_Flag=1;      //スタートゴールセンサの検知
        if((Corner_Flag==1)&&(SG_Flag==1))Cross_Flag=1;//交差点通過中。何もしない    
    }else Marker_Pass_Flag=0;//マーカ通過終了       

    //マーカ通過後、マーカ種類判別    
    if((Old_Marker_Pass_Flag==1)&&(Marker_Pass_Flag==0)){//マーカ通過後
        if(Marker_Run_Distance>MARKER_WIDTH){//マーカ幅がもっともらしいとき
            if(Cross_Flag==1);//交差点の時は何もしない
            else if((SG_Flag==1)&&(SG_Cnt==0)){//ゴールスタートマーカの時⇒1回目
                SG_Cnt=1;
            }else if((SG_Flag==1)&&(SG_Cnt==1)){//ゴールスタートマーカの時⇒2回目
                Machine_Status|=STOP;           //機体停止状態へ
                SG_Cnt=0;    
            }else if(Corner_Flag==1){//コーナマーカの時
                //地区大会では何もしない                
            }
        }else{//マーカではなく、誤検知だった場合。
            //何もしない
        }
        Corner_Flag=0;
        SG_Flag=0;
        Cross_Flag=0;
        Marker_Run_Distance=0;//マーカ通過距離情報リセット
    }
    
    //センサ取得値の重ね合わせ(端のセンサほどモータ制御量を大きくする)
    All_Sensor_Data=-(S2_Data*S_K3+S3_Data*S_K2+S4_Data*S_K1)+(S5_Data*S_K1+S6_Data*S_K2+S7_Data*S_K3);
    Sensor_Diff[1]=Sensor_Diff[0];//過去のラインセンサ偏差を退避
    Sensor_Diff[0]=All_Sensor_Data;
    Sensor_P=All_Sensor_Data*S_KP;                  //ラインセンサ比例成分の演算       
    Sensor_D=(Sensor_Diff[0]-Sensor_Diff[1])*S_KD;  //ラインセンサ微分成分の演算
    Sensor_PD=Sensor_P+Sensor_D; 
    
          
    ////モータ現在速度の取得            
    Enc_Count_A=encoder_a.Get();   //エンコーダパルス数を取得
    Enc_Count_B=-encoder_b.Get();
    Distance_A=(Enc_Count_A*PULSE_TO_UM);  //移動距離をum単位で格納
    Distance_B=(Enc_Count_B*PULSE_TO_UM);
    Speed_A=(Distance_A*1000)/INTERRUPT_TIME;//走行速度演算[mm/s]
    Speed_B=(Distance_B*1000)/INTERRUPT_TIME;
    
    if(Machine_Status&STOP){//機体停止状態の時
        if(Stop_Distance>=STOP_DISTANCE){
         Enc_A_Rotate+=Enc_Count_A;//閾値用に左エンコーダ値の蓄積 
         Enc_B_Rotate+=Enc_Count_B;//速度用に右エンコーダ値の蓄積                   
        }
        if(Enc_A_Rotate<-6400)Enc_A_Rotate=-6400;
        if(Enc_A_Rotate>6400)Enc_A_Rotate=6400;        
        if(Enc_B_Rotate<-6400)Enc_B_Rotate=-6400;
        if(Enc_B_Rotate>6400)Enc_B_Rotate=6400;
        if((Distance_A>=0)&&(Distance_B>=0))Stop_Distance+=(Distance_A+Distance_B)/2;
        if(Stop_Distance<0)Stop_Distance=0;
        if(Stop_Distance>STOP_DISTANCE)Stop_Distance=STOP_DISTANCE;
    }
    if(Marker_Pass_Flag==1){//マーカ通過中は通過距離情報を蓄積する。
        Marker_Run_Distance+=(Distance_A+Distance_B)/2;
    }
    
    
    //エンコーダ関連情報のリセット
    Distance_A=0;
    Distance_B=0;
    encoder_a.Set(0);
    encoder_b.Set(0);
    
    /////各モータの目標速度の設定
    Target_Speed_A=Machine_Speed;
    Target_Speed_B=Machine_Speed;
    
    /////モータの速度制御
    //過去の速度偏差を退避
    Motor_A_Diff[1]=Motor_A_Diff[0];
    Motor_B_Diff[1]=Motor_B_Diff[0];
    //現在の速度偏差を取得。    
    Motor_A_Diff[0]=(Target_Speed_A-Speed_A);
    Motor_B_Diff[0]=(Target_Speed_B-Speed_B);
    //P成分演算
    Motor_A_P=Motor_A_Diff[0]*M_KP;
    Motor_B_P=Motor_B_Diff[0]*M_KP;
    //D成分演算
    Motor_A_D=(Motor_A_Diff[0]-Motor_A_Diff[1])*M_KD;
    Motor_B_D=(Motor_B_Diff[0]-Motor_B_Diff[1])*M_KD;
    //モータ速度制御のPD合成
    Motor_A_PD=Motor_A_P+Motor_A_D;
    Motor_B_PD=Motor_B_P+Motor_B_D;
    //最終的なモータ制御量の合成    
    Motor_A_Pwm=Motor_A_PD+Sensor_PD;
    Motor_B_Pwm=Motor_B_PD-Sensor_PD;

    //モータ制御量の上限下限設定
    if(Motor_A_Pwm>0.95f)Motor_A_Pwm=0.95f;
    else if(Motor_A_Pwm<-0.95)Motor_A_Pwm=-0.95f;
    if(Motor_B_Pwm>0.95f)Motor_B_Pwm=0.95f;
    else if(Motor_B_Pwm<-0.95f)Motor_B_Pwm=-0.95f;
        
    //モータへの出力    
    if(!(Machine_Status&STOP)){//マシンが停止状態でなければ
        if(Machine_Status&RUN_COURSE_LOUT){         //左端センサ振り切れた時
            motor_a=-(-TURN_POWER); //左旋回
            motor_b=-(TURN_POWER);    
        }else if(Machine_Status&RUN_COURSE_ROUT){   //右端センサ振り切れた時
            motor_a=-(TURN_POWER);  //右旋回    
            motor_b=-(-TURN_POWER);
        }else if(Sensor_Cnt>=CROSS_JUDGE){//交差点通過中
            motor_a=-0.3;//交差点なので控えめの速度で直進
            motor_b=-0.3;
        }
        else{
            motor_a=-Motor_A_Pwm;
            motor_b=-Motor_B_Pwm;
        }
    }else{//停止状態の時はモータへの出力は無効
        if(Stop_Distance<STOP_DISTANCE){
            motor_a=-Motor_A_Pwm/4;
            motor_b=-Motor_B_Pwm/4;

        }else{
            motor_a=0;
            motor_b=0;
        }        
    }                       
}



int main() { 
    timer.attach_us(&timer_interrupt,INTERRUPT_TIME);//タイマ割り込みスタート 
    lcd.cls();//表示クリア
    lcd.locate(0,0);
    lcd.print("STOP");
    lcd.locate(0,1);
    sprintf(Speed_Str,"%04d",Machine_Speed);
    lcd.print(Speed_Str);        
    while(1){
        Old_Sw_Ptn=Sw_Ptn;  //過去のスイッチ入力情報を退避
        Sw_Ptn=push_sw;     //現在のスイッチ入力情報の取得
        PC.printf("Sensor_Digital:%02x\tMachine_Status:%02x\tSG_Cnt:%d\r\n",Sensor_Digital,Machine_Status,SG_Cnt);
        if((!(Old_Machine_Status&STOP))&&(Machine_Status&STOP)){//走行終了時
            lcd.locate(0,0);
            lcd.print("     ");
            lcd.locate(0,0);
            lcd.print("STOP");
            wait(5);
            Gray=DEFAULT_GRAY;
            Machine_Speed=DEFAULT_SPEED;                            
        }
        if(Machine_Status&STOP){//機体停止状態の時
          
            Gray=DEFAULT_GRAY+((float)Enc_A_Rotate/16000);//センサ閾値調整
            sprintf(Gray_Str,"%3.2f",Gray);//速度情報文字列変換
            lcd.locate(0,0);
            lcd.print("      ");
            lcd.locate(0,0);
            lcd.print(Gray_Str);             
            Machine_Speed=DEFAULT_SPEED+(Enc_B_Rotate/16);//標準速度調整
            sprintf(Speed_Str,"%04d",Machine_Speed);//速度情報文字列変換                
            lcd.locate(0,1);
            lcd.print("      ");
            lcd.locate(0,1);
            lcd.print(Speed_Str);            
        }
        
                 
        if((Old_Sw_Ptn==PULL)&&(Sw_Ptn==PUSH)){//スイッチが押された瞬間
            if(Machine_Status&STOP){//機体停止状態の時
                lcd.locate(0,0);
                lcd.print("     ");
                lcd.locate(0,0);
                lcd.print("GO!!");
                wait(2);
                Stop_Distance=0;
                Machine_Status&=0x7F;//ストップ状態解除
            }else{//機体走行中であったとき
                //各種フラグのクリア
                Corner_Flag=0;
                SG_Flag=0;
                Cross_Flag=0;
                Marker_Run_Distance=0;//マーカ通過距離情報リセット
                                
                Machine_Status |= STOP;//機体停止状態にする。
                lcd.locate(0,0);
                lcd.print("     ");
                lcd.locate(0,0);
                lcd.print("STOP");                  
            }
        }               
    }
}