最終調整

Dependencies:   mbed AQM0802 CRotaryEncoder TB6612FNG

Committer:
GGU
Date:
Wed Nov 20 04:41:18 2019 +0000
Revision:
21:97cc65e61580
Parent:
20:3b35311f4576
Child:
22:b40f7d0c0f12
test;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
GGU 16:017874772ea7 1 ////ライントレースサンプル
yusaku0125 3:e455433c8cae 2 #include "mbed.h"
yusaku0125 3:e455433c8cae 3 #include "CRotaryEncoder.h"
yusaku0125 4:ac9e6772ddb3 4 #include "TB6612.h"
yusaku0125 8:15b4e1d7a2c5 5 #include "AQM0802.h"
yusaku0125 4:ac9e6772ddb3 6
yusaku0125 4:ac9e6772ddb3 7
yusaku0125 4:ac9e6772ddb3 8 //☆★☆★各種パラメータ調整箇所☆★☆★☆★
GGU 16:017874772ea7 9 #define DEFAULT_SPEED 300 //1走目の基本速度[mm/sec]
GGU 21:97cc65e61580 10 #define DEFAULT_SPEED1 800
GGU 16:017874772ea7 11 #define DEFAULT_SPEED2 900
GGU 16:017874772ea7 12 #define STOP_DISTANCE 200000 //停止距離200000[um]⇒20[cm]
poritekutama 14:7ed78f52f40e 13 #define TURN_POWER 0.6 //コースアウト時の旋回力
poritekutama 14:7ed78f52f40e 14 #define PULSE_TO_UM 28 //エンコーダ1パルス当たりのタイヤ移動距離[um]
GGU 16:017874772ea7 15 #define INTERRUPT_TIME 3000 //割りこみ周期[us]
poritekutama 14:7ed78f52f40e 16 #define DEFAULT_GRAY 0.2f //フォトリフレクタデジタル入力の閾値
yusaku0125 7:cfbf8d4a4d36 17 //シリアル通信でSensor_Digital値を確認し調整する。
poritekutama 14:7ed78f52f40e 18 #define MARKER_WIDTH 10000 //マーカ幅[um](ビニルテープ幅19000[um]以内)
yusaku0125 7:cfbf8d4a4d36 19 //コースの傷によってマーカ誤検知する場合は値を大きくする。
yusaku0125 7:cfbf8d4a4d36 20 #define CROSS_JUDGE 4 //ラインセンサいくつ以上白線検知で交差点認識するか設定。
yusaku0125 5:f635f1f01d2d 21 //モータ速度のゲイン関連(むやみに調整しない)
yusaku0125 6:afd8f0d02c8d 22 #define M_KP 0.002f //P(比例)制御成分
yusaku0125 6:afd8f0d02c8d 23 #define M_KD 0.001f //D(微分)制御成分
yusaku0125 5:f635f1f01d2d 24
yusaku0125 5:f635f1f01d2d 25 //フォトリフレクタのゲイン(外側に行くにつれ値を何倍させたいか調整する。)
yusaku0125 6:afd8f0d02c8d 26 #define S_K1 1.0f //float演算させる値には必ずfを付ける
poritekutama 14:7ed78f52f40e 27 #define S_K2 2.4f //2倍
poritekutama 14:7ed78f52f40e 28 #define S_K3 4.7f //4倍
yusaku0125 5:f635f1f01d2d 29
yusaku0125 5:f635f1f01d2d 30 //ラインセンサ各種制御成分
poritekutama 14:7ed78f52f40e 31 #define S_KP 1.0f //ラインセンサ比例成分。大きいほど曲がりやすい
poritekutama 14:7ed78f52f40e 32 #define S_KD 0.5f //ラインセンサ微分成分。大きいほど急なラインずれに強くなる。
yusaku0125 4:ac9e6772ddb3 33 //////////☆★☆★☆★☆★☆★//////////////
yusaku0125 4:ac9e6772ddb3 34
yusaku0125 8:15b4e1d7a2c5 35
yusaku0125 8:15b4e1d7a2c5 36
yusaku0125 8:15b4e1d7a2c5 37 //スイッチ状態の定義
yusaku0125 8:15b4e1d7a2c5 38 #define PUSH 0 //スイッチ押したときの状態
yusaku0125 8:15b4e1d7a2c5 39 #define PULL 1 //スイッチ離したときの状態
yusaku0125 6:afd8f0d02c8d 40 //機体状態の定義
yusaku0125 6:afd8f0d02c8d 41 #define STOP 0x80 //機体停止状態
yusaku0125 6:afd8f0d02c8d 42 #define RUN_START 0x40 //スタートマーカ通過
yusaku0125 6:afd8f0d02c8d 43 #define RUN_COURSE_LOUT 0x20 //左コースアウト状態
yusaku0125 6:afd8f0d02c8d 44 #define RUN_COURSE_CENTER 0x18 //ライン中央走行状態
yusaku0125 6:afd8f0d02c8d 45 #define RUN_COURSE_ROUT 0x04 //右コースアウト状態
yusaku0125 6:afd8f0d02c8d 46 #define SECOND_RUN 0x02 //機体停止状態
yusaku0125 6:afd8f0d02c8d 47 #define TUARD_RUN 0x01 //機体設定モード
yusaku0125 6:afd8f0d02c8d 48
yusaku0125 10:e1eb10665472 49
yusaku0125 8:15b4e1d7a2c5 50 //デジタル入力オブジェクト定義
yusaku0125 8:15b4e1d7a2c5 51 DigitalIn push_sw(D13);
yusaku0125 5:f635f1f01d2d 52 /////アナログ入力オブジェクト定義//////////
GGU 20:3b35311f4576 53 /*
poritekutama 14:7ed78f52f40e 54 AnalogIn s1(D3);
poritekutama 14:7ed78f52f40e 55 AnalogIn s2(A6);
poritekutama 14:7ed78f52f40e 56 AnalogIn s3(A5);
poritekutama 14:7ed78f52f40e 57 AnalogIn s4(A4);
poritekutama 14:7ed78f52f40e 58 AnalogIn s5(A3);
poritekutama 14:7ed78f52f40e 59 AnalogIn s6(A2);
poritekutama 14:7ed78f52f40e 60 AnalogIn s7(A1);
yusaku0125 6:afd8f0d02c8d 61 AnalogIn s8(A0);
GGU 20:3b35311f4576 62 */
GGU 16:017874772ea7 63
GGU 16:017874772ea7 64 AnalogIn s1(A1);
GGU 16:017874772ea7 65 AnalogIn s2(D3);
GGU 16:017874772ea7 66 AnalogIn s3(A6);
GGU 16:017874772ea7 67 AnalogIn s4(A5);
GGU 16:017874772ea7 68 AnalogIn s5(A4);
GGU 16:017874772ea7 69 AnalogIn s6(A3);
GGU 16:017874772ea7 70 AnalogIn s7(A2);
GGU 16:017874772ea7 71 AnalogIn s8(A0);
GGU 20:3b35311f4576 72
GGU 20:3b35311f4576 73
yusaku0125 5:f635f1f01d2d 74 ///////////////////////////////////////
yusaku0125 6:afd8f0d02c8d 75 Serial PC(USBTX,USBRX);
yusaku0125 6:afd8f0d02c8d 76 CRotaryEncoder encoder_a(D1,D0); //モータAのエンコーダ
yusaku0125 6:afd8f0d02c8d 77 CRotaryEncoder encoder_b(D11,D12); //モータBのエンコーダ
yusaku0125 6:afd8f0d02c8d 78 Ticker timer; //タイマ割込み用
yusaku0125 4:ac9e6772ddb3 79 TB6612 motor_a(D2,D7,D6); //モータA制御用(pwma,ain1,ain2)
yusaku0125 6:afd8f0d02c8d 80 TB6612 motor_b(D10,D8,D9); //モータB制御用(pwmb,bin1,bin2)
yusaku0125 8:15b4e1d7a2c5 81 AQM0802 lcd(I2C_SDA,I2C_SCL); //液晶制御用
yusaku0125 4:ac9e6772ddb3 82
yusaku0125 5:f635f1f01d2d 83 //使用変数の定義
yusaku0125 8:15b4e1d7a2c5 84 int Sw_Ptn;
yusaku0125 8:15b4e1d7a2c5 85 int Old_Sw_Ptn;
poritekutama 14:7ed78f52f40e 86 int Sw=0;
GGU 16:017874772ea7 87 int Coner_c=0; //カウントを格納
poritekutama 14:7ed78f52f40e 88 char Coner_str[3];
yusaku0125 8:15b4e1d7a2c5 89 double S1_Data,S2_Data,S3_Data,S4_Data,S5_Data,S6_Data,S7_Data,S8_Data;
yusaku0125 8:15b4e1d7a2c5 90 double All_Sensor_Data; //ラインセンサ総データ量
yusaku0125 8:15b4e1d7a2c5 91 double Sensor_Diff[2]={0,0}; //ラインセンサ偏差
yusaku0125 8:15b4e1d7a2c5 92 double Sensor_P =0.0f; //ラインセンサP(比例成分)制御量
yusaku0125 8:15b4e1d7a2c5 93 double Sensor_D =0.0f; //ラインセンサD(微分成分)制御量
yusaku0125 8:15b4e1d7a2c5 94 double Sensor_PD=0.0f; //ラインセンサP,D成分の合計
yusaku0125 12:dc4c569248d7 95 char Gray_Str[5]; //LCD閾値表示用文字列
yusaku0125 12:dc4c569248d7 96 float Gray=DEFAULT_GRAY;
yusaku0125 5:f635f1f01d2d 97 long int Enc_Count_A=0,Enc_Count_B=0; //エンコーダパルス数を格納
yusaku0125 12:dc4c569248d7 98 long int Enc_A_Rotate=0,Enc_B_Rotate=0;
GGU 16:017874772ea7 99 long int Stop_Distance=STOP_DISTANCE;
yusaku0125 12:dc4c569248d7 100
GGU 16:017874772ea7 101 long int memory_A=0; //移動距離格納
GGU 16:017874772ea7 102 long int memory_B=0;
GGU 16:017874772ea7 103 char MemoryA_Str[5]; //LCD閾値表示用文字列
GGU 15:cfe79ebfcb25 104 char MemoryB_Str[5];
GGU 15:cfe79ebfcb25 105 long int Distance_A=0,Distance_B=0; //タイヤ移動距離を格納[mm]
GGU 15:cfe79ebfcb25 106 long int Distance_memory_A=0, Distance_memory_B=0;
poritekutama 14:7ed78f52f40e 107
yusaku0125 7:cfbf8d4a4d36 108 long int Marker_Run_Distance=0;
yusaku0125 5:f635f1f01d2d 109 long int Speed_A=0, Speed_B=0; //現在速度
GGU 16:017874772ea7 110
GGU 16:017874772ea7 111 long int Low_Speed=DEFAULT_SPEED;
GGU 16:017874772ea7 112 long int Medium_Speed=DEFAULT_SPEED1;
GGU 16:017874772ea7 113 long int High_Speed=DEFAULT_SPEED2;
yusaku0125 11:2cd6f8be124e 114 char Speed_Str[5]; //LCD速度表示用文字列
yusaku0125 5:f635f1f01d2d 115 long int Target_Speed_A=0,Target_Speed_B=0; //目標速度
poritekutama 14:7ed78f52f40e 116 long int Target_Speed_A1=0,Target_Speed_B1=0; //目標速度
yusaku0125 8:15b4e1d7a2c5 117 long int Motor_A_Diff[2]={0,0}; //過去の速度偏差と現在の速度偏差を格納
yusaku0125 8:15b4e1d7a2c5 118 long int Motor_B_Diff[2]={0,0}; //
yusaku0125 8:15b4e1d7a2c5 119 float Motor_A_P,Motor_B_P; //モータ速度制御P成分
yusaku0125 8:15b4e1d7a2c5 120 float Motor_A_D,Motor_B_D; //モータ速度制御D成分
yusaku0125 8:15b4e1d7a2c5 121 float Motor_A_PD,Motor_B_PD; //モータ速度制御PD合成
yusaku0125 4:ac9e6772ddb3 122 float Motor_A_Pwm,Motor_B_Pwm; //モータへの出力
yusaku0125 6:afd8f0d02c8d 123 unsigned char Sensor_Digital =0x00;
yusaku0125 6:afd8f0d02c8d 124 unsigned char Old_Sensor_Digital=0x00;
yusaku0125 7:cfbf8d4a4d36 125 int Sensor_Cnt=0;
yusaku0125 8:15b4e1d7a2c5 126 unsigned char Machine_Status =STOP; //機体状態
yusaku0125 6:afd8f0d02c8d 127 unsigned char Old_Machine_Status=0x00; //過去の機体状態
yusaku0125 7:cfbf8d4a4d36 128 int Marker_Pass_Flag = 0;
yusaku0125 7:cfbf8d4a4d36 129 int Old_Marker_Pass_Flag=0;
yusaku0125 7:cfbf8d4a4d36 130 int Corner_Flag=0;
yusaku0125 7:cfbf8d4a4d36 131 int SG_Flag=0;
yusaku0125 7:cfbf8d4a4d36 132 int SG_Cnt=0;
yusaku0125 7:cfbf8d4a4d36 133 int Cross_Flag=0;
poritekutama 19:edf765724d2d 134 long int Imaginary_Speed=0;
poritekutama 19:edf765724d2d 135
GGU 16:017874772ea7 136
GGU 16:017874772ea7 137 int Row=0; //行変数
GGU 16:017874772ea7 138 float course_data[100][3]; //記憶走行用配列
poritekutama 19:edf765724d2d 139 float curvature=0;
GGU 16:017874772ea7 140
yusaku0125 6:afd8f0d02c8d 141 void sensor_analog_read(){
yusaku0125 5:f635f1f01d2d 142 S1_Data=s1.read();
yusaku0125 5:f635f1f01d2d 143 S2_Data=s2.read();
yusaku0125 5:f635f1f01d2d 144 S3_Data=s3.read();
yusaku0125 5:f635f1f01d2d 145 S4_Data=s4.read();
yusaku0125 5:f635f1f01d2d 146 S5_Data=s5.read();
yusaku0125 5:f635f1f01d2d 147 S6_Data=s6.read();
yusaku0125 5:f635f1f01d2d 148 S7_Data=s7.read();
yusaku0125 6:afd8f0d02c8d 149 S8_Data=s8.read();
yusaku0125 6:afd8f0d02c8d 150 }
yusaku0125 7:cfbf8d4a4d36 151
yusaku0125 7:cfbf8d4a4d36 152
yusaku0125 6:afd8f0d02c8d 153 void sensor_digital_read(){//8つのフォトリフレクタの入力を8ビットのデジタルパターンに変換
yusaku0125 7:cfbf8d4a4d36 154 Sensor_Cnt=0;
yusaku0125 6:afd8f0d02c8d 155 Old_Sensor_Digital=Sensor_Digital;
yusaku0125 12:dc4c569248d7 156 if(S1_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 157 Sensor_Digital |= 0x80; //7ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 158 }else Sensor_Digital &= 0x7F; //7ビット目のみマスク(0にする。)
yusaku0125 12:dc4c569248d7 159 if(S2_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 160 Sensor_Digital |= 0x40; //6ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 161 Sensor_Cnt++;
yusaku0125 7:cfbf8d4a4d36 162 }else Sensor_Digital &= 0xBF; //6ビット目のみマスク(0にする。)
yusaku0125 12:dc4c569248d7 163 if(S3_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 164 Sensor_Digital |= 0x20; //5ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 165 Sensor_Cnt++;
yusaku0125 7:cfbf8d4a4d36 166 }else Sensor_Digital &= 0xDF; //5ビット目のみマスク(0にする。)
yusaku0125 12:dc4c569248d7 167 if(S4_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 168 Sensor_Digital |= 0x10; //4ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 169 Sensor_Cnt++;
yusaku0125 7:cfbf8d4a4d36 170 }else Sensor_Digital &= 0xEF; //4ビット目のみマスク(0にする。)
yusaku0125 12:dc4c569248d7 171 if(S5_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 172 Sensor_Digital |= 0x08; //3ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 173 Sensor_Cnt++;
yusaku0125 7:cfbf8d4a4d36 174 }else Sensor_Digital &= 0xF7; //3ビット目のみマスク(0にする。)
yusaku0125 12:dc4c569248d7 175 if(S6_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 176 Sensor_Digital |= 0x04; //2ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 177 Sensor_Cnt++;
yusaku0125 7:cfbf8d4a4d36 178 }else Sensor_Digital &= 0xFB; //2ビット目のみマスク(0にする。)
yusaku0125 12:dc4c569248d7 179 if(S7_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 180 Sensor_Digital |= 0x02; //1ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 181 Sensor_Cnt++;
yusaku0125 7:cfbf8d4a4d36 182 }else Sensor_Digital &= 0xFD; //1ビット目のみマスク(0にする。)
yusaku0125 12:dc4c569248d7 183 if(S8_Data>Gray){
yusaku0125 7:cfbf8d4a4d36 184 Sensor_Digital |= 0x01; //0ビット目のみセット (1にする。)
yusaku0125 7:cfbf8d4a4d36 185 }else Sensor_Digital &= 0xFE; //0ビット目のみマスク(0にする。)
yusaku0125 6:afd8f0d02c8d 186 }
yusaku0125 6:afd8f0d02c8d 187
yusaku0125 6:afd8f0d02c8d 188 void Machine_Status_Set(){
yusaku0125 7:cfbf8d4a4d36 189 Old_Machine_Status=Machine_Status;
yusaku0125 7:cfbf8d4a4d36 190
yusaku0125 6:afd8f0d02c8d 191 //機体がライン中央に位置するとき
yusaku0125 6:afd8f0d02c8d 192 if(Sensor_Digital&RUN_COURSE_CENTER )Machine_Status|=RUN_COURSE_CENTER;
yusaku0125 6:afd8f0d02c8d 193 else Machine_Status &= 0xE7;//ライン中央情報のマスク
yusaku0125 6:afd8f0d02c8d 194 if((Sensor_Digital==0x00)&&(Old_Sensor_Digital==0x40)){//左センサコースアウト時
yusaku0125 6:afd8f0d02c8d 195 Machine_Status|=RUN_COURSE_LOUT;//左コースアウト状態のビットをセット
yusaku0125 6:afd8f0d02c8d 196 }else if((Machine_Status&RUN_COURSE_LOUT)&&(Sensor_Digital&RUN_COURSE_CENTER)){
yusaku0125 6:afd8f0d02c8d 197 //左コースアウト状態かつ機体がライン中央に復帰したとき
yusaku0125 6:afd8f0d02c8d 198 Machine_Status &= 0xDF;//左コースアウト情報のみマスク
yusaku0125 6:afd8f0d02c8d 199 }
yusaku0125 6:afd8f0d02c8d 200 if((Sensor_Digital==0x00)&&(Old_Sensor_Digital==0x02)){//右センサコースアウト時
yusaku0125 6:afd8f0d02c8d 201 Machine_Status|=RUN_COURSE_ROUT;//右コースアウト状態のビットをセット
yusaku0125 6:afd8f0d02c8d 202 }else if((Machine_Status&RUN_COURSE_ROUT)&&(Sensor_Digital&RUN_COURSE_CENTER)){
yusaku0125 6:afd8f0d02c8d 203 //右コースアウト状態かつ機体がライン中央に復帰したとき
yusaku0125 6:afd8f0d02c8d 204 Machine_Status &= 0xFB;//右コースアウト情報のみマスク
yusaku0125 6:afd8f0d02c8d 205 }
yusaku0125 6:afd8f0d02c8d 206 }
poritekutama 19:edf765724d2d 207 void coner_curvature(){
poritekutama 19:edf765724d2d 208 if((motor_a>(motor_b*1.8)) || (motor_a<(motor_b*0.2))){//左が右より80%以上早いか20%以上遅いとき
poritekutama 19:edf765724d2d 209 Imaginary_Speed=Low_Speed;
poritekutama 19:edf765724d2d 210 Target_Speed_A=Imaginary_Speed;
poritekutama 19:edf765724d2d 211 Target_Speed_B=Imaginary_Speed;
poritekutama 19:edf765724d2d 212
poritekutama 19:edf765724d2d 213 }else if((motor_a>(motor_b*1.5)) || (motor_a<(motor_b*0.5))){//左が右より50%以上早いか50%以上遅いとき
poritekutama 19:edf765724d2d 214 Imaginary_Speed=Medium_Speed;
poritekutama 19:edf765724d2d 215 Target_Speed_A=Imaginary_Speed;
poritekutama 19:edf765724d2d 216 Target_Speed_B=Imaginary_Speed;
poritekutama 19:edf765724d2d 217 }else if((motor_a>(motor_b*1.2)) || (motor_a<(motor_b*0.8))){//左が右より20%以上早いか20%以上遅いとき⇒直線
poritekutama 19:edf765724d2d 218 Imaginary_Speed=High_Speed;
poritekutama 19:edf765724d2d 219 Target_Speed_A=Imaginary_Speed;
poritekutama 19:edf765724d2d 220 Target_Speed_B=Imaginary_Speed;
poritekutama 19:edf765724d2d 221 }
poritekutama 19:edf765724d2d 222 else{
poritekutama 19:edf765724d2d 223 Imaginary_Speed=High_Speed;
poritekutama 19:edf765724d2d 224 Target_Speed_A=Imaginary_Speed;
poritekutama 19:edf765724d2d 225 Target_Speed_B=Imaginary_Speed;
poritekutama 19:edf765724d2d 226 }
poritekutama 19:edf765724d2d 227 course_data[Row][0]=(float)Distance_memory_A;
poritekutama 19:edf765724d2d 228 course_data[Row][1]=(float)Distance_memory_B;
poritekutama 19:edf765724d2d 229 course_data[Row][2]=Imaginary_Speed;
poritekutama 19:edf765724d2d 230 PC.printf("left:%.2f\t",course_data[Row][0]);
poritekutama 19:edf765724d2d 231 PC.printf("right:%.2f\t",course_data[Row][1]);
poritekutama 19:edf765724d2d 232 PC.printf("speed:%.2f\n\r",course_data[Row][2]);
poritekutama 19:edf765724d2d 233
poritekutama 19:edf765724d2d 234 }
yusaku0125 8:15b4e1d7a2c5 235
yusaku0125 8:15b4e1d7a2c5 236 //タイマ割り込み1[ms]周期
yusaku0125 6:afd8f0d02c8d 237 void timer_interrupt(){
yusaku0125 7:cfbf8d4a4d36 238
yusaku0125 6:afd8f0d02c8d 239 //ラインセンサ情報取得
yusaku0125 6:afd8f0d02c8d 240 sensor_analog_read();
yusaku0125 6:afd8f0d02c8d 241 sensor_digital_read();
yusaku0125 7:cfbf8d4a4d36 242
yusaku0125 7:cfbf8d4a4d36 243 //機体状態の取得
yusaku0125 6:afd8f0d02c8d 244 Machine_Status_Set();
yusaku0125 7:cfbf8d4a4d36 245
yusaku0125 7:cfbf8d4a4d36 246 //交差点の認識
yusaku0125 7:cfbf8d4a4d36 247 if(Sensor_Cnt>=CROSS_JUDGE )Cross_Flag=1;//ラインセンサ4つ以上検知状態の時は交差点を示す。
yusaku0125 7:cfbf8d4a4d36 248
yusaku0125 7:cfbf8d4a4d36 249 //各種マーカの検知
yusaku0125 7:cfbf8d4a4d36 250 Old_Marker_Pass_Flag=Marker_Pass_Flag;//過去のフラグを退避
yusaku0125 7:cfbf8d4a4d36 251 if(Sensor_Digital&0x81){ //マーカセンサ検知時
yusaku0125 7:cfbf8d4a4d36 252 Marker_Pass_Flag=1; //マーカ通過中フラグをON
yusaku0125 7:cfbf8d4a4d36 253 if(Sensor_Digital&0x80)Corner_Flag=1; //コーナセンサの検知
yusaku0125 7:cfbf8d4a4d36 254 if(Sensor_Digital&0x01)SG_Flag=1; //スタートゴールセンサの検知
yusaku0125 7:cfbf8d4a4d36 255 if((Corner_Flag==1)&&(SG_Flag==1));//交差点通過中。何もしない
yusaku0125 7:cfbf8d4a4d36 256 }else Marker_Pass_Flag=0;//マーカ通過終了
yusaku0125 7:cfbf8d4a4d36 257
yusaku0125 7:cfbf8d4a4d36 258 //マーカ通過後、マーカ種類判別
yusaku0125 7:cfbf8d4a4d36 259 if((Old_Marker_Pass_Flag==1)&&(Marker_Pass_Flag==0)){//マーカ通過後
yusaku0125 7:cfbf8d4a4d36 260 if(Marker_Run_Distance>MARKER_WIDTH){//マーカ幅がもっともらしいとき
yusaku0125 7:cfbf8d4a4d36 261 if(Cross_Flag==1);//交差点の時は何もしない
yusaku0125 7:cfbf8d4a4d36 262 else if((SG_Flag==1)&&(SG_Cnt==0)){//ゴールスタートマーカの時⇒1回目
yusaku0125 7:cfbf8d4a4d36 263 SG_Cnt=1;
yusaku0125 7:cfbf8d4a4d36 264 }else if((SG_Flag==1)&&(SG_Cnt==1)){//ゴールスタートマーカの時⇒2回目
yusaku0125 7:cfbf8d4a4d36 265 Machine_Status|=STOP; //機体停止状態へ
yusaku0125 7:cfbf8d4a4d36 266 SG_Cnt=0;
poritekutama 19:edf765724d2d 267 }else if(Corner_Flag==1){//コーナマーカの時
GGU 16:017874772ea7 268 Distance_memory_A=0;
GGU 16:017874772ea7 269 Distance_memory_B=0;
GGU 16:017874772ea7 270 Enc_Count_A=encoder_a.Get(); //エンコーダパルス数を取得
GGU 16:017874772ea7 271 Enc_Count_B=-encoder_b.Get();
GGU 16:017874772ea7 272 Distance_memory_A=(Enc_Count_A*PULSE_TO_UM);
GGU 16:017874772ea7 273 Distance_memory_B=(Enc_Count_B*PULSE_TO_UM);
GGU 16:017874772ea7 274
poritekutama 19:edf765724d2d 275 /*course_data[Row][0]=Distance_memory_A;
GGU 16:017874772ea7 276 course_data[Row][1]=Distance_memory_B;
poritekutama 19:edf765724d2d 277 course_data[Row][2]=Imaginary_Speed;
GGU 16:017874772ea7 278
poritekutama 19:edf765724d2d 279 PC.printf("左:%.2f",course_data[Row][0]);
GGU 16:017874772ea7 280 PC.printf("右:%.2f",course_data[Row][1]);
GGU 16:017874772ea7 281 PC.printf("速度:%.2f",course_data[Row][2]);
GGU 16:017874772ea7 282 */
poritekutama 19:edf765724d2d 283 coner_curvature();
GGU 16:017874772ea7 284 Row++;
GGU 16:017874772ea7 285
yusaku0125 7:cfbf8d4a4d36 286 }
yusaku0125 7:cfbf8d4a4d36 287 }else{//マーカではなく、誤検知だった場合。
yusaku0125 7:cfbf8d4a4d36 288 //何もしない
yusaku0125 7:cfbf8d4a4d36 289 }
yusaku0125 7:cfbf8d4a4d36 290 Corner_Flag=0;
yusaku0125 7:cfbf8d4a4d36 291 SG_Flag=0;
yusaku0125 7:cfbf8d4a4d36 292 Cross_Flag=0;
yusaku0125 7:cfbf8d4a4d36 293 Marker_Run_Distance=0;//マーカ通過距離情報リセット
yusaku0125 7:cfbf8d4a4d36 294 }
yusaku0125 6:afd8f0d02c8d 295
yusaku0125 5:f635f1f01d2d 296 //センサ取得値の重ね合わせ(端のセンサほどモータ制御量を大きくする)
yusaku0125 5:f635f1f01d2d 297 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);
yusaku0125 6:afd8f0d02c8d 298 Sensor_Diff[1]=Sensor_Diff[0];//過去のラインセンサ偏差を退避
yusaku0125 5:f635f1f01d2d 299 Sensor_Diff[0]=All_Sensor_Data;
yusaku0125 5:f635f1f01d2d 300 Sensor_P=All_Sensor_Data*S_KP; //ラインセンサ比例成分の演算
yusaku0125 5:f635f1f01d2d 301 Sensor_D=(Sensor_Diff[0]-Sensor_Diff[1])*S_KD; //ラインセンサ微分成分の演算
yusaku0125 6:afd8f0d02c8d 302 Sensor_PD=Sensor_P+Sensor_D;
yusaku0125 6:afd8f0d02c8d 303
yusaku0125 4:ac9e6772ddb3 304 ////モータ現在速度の取得
yusaku0125 4:ac9e6772ddb3 305 Enc_Count_A=encoder_a.Get(); //エンコーダパルス数を取得
yusaku0125 4:ac9e6772ddb3 306 Enc_Count_B=-encoder_b.Get();
GGU 17:b29e2c88b3c5 307 Distance_A=(Enc_Count_A*PULSE_TO_UM); //移動距離をmm単位で格納
GGU 17:b29e2c88b3c5 308 Distance_B=(Enc_Count_B*PULSE_TO_UM);
GGU 15:cfe79ebfcb25 309
GGU 15:cfe79ebfcb25 310 Distance_memory_A=(Enc_Count_A*PULSE_TO_UM);
GGU 15:cfe79ebfcb25 311 Distance_memory_B=(Enc_Count_B*PULSE_TO_UM);
GGU 15:cfe79ebfcb25 312
GGU 16:017874772ea7 313 Speed_A=(Distance_A*1000)/INTERRUPT_TIME;//走行速度演算[mm/s]
GGU 16:017874772ea7 314 Speed_B=(Distance_B*1000)/INTERRUPT_TIME;
yusaku0125 10:e1eb10665472 315
yusaku0125 10:e1eb10665472 316 if(Machine_Status&STOP){//機体停止状態の時
yusaku0125 12:dc4c569248d7 317 Enc_A_Rotate+=Enc_Count_A;//閾値用に左エンコーダ値の蓄積
yusaku0125 12:dc4c569248d7 318 if(Enc_A_Rotate<-6400)Enc_A_Rotate=-6400;
yusaku0125 12:dc4c569248d7 319 if(Enc_A_Rotate>6400)Enc_A_Rotate=6400;
yusaku0125 12:dc4c569248d7 320 Enc_B_Rotate+=Enc_Count_B;//速度用に右エンコーダ値の蓄積
yusaku0125 11:2cd6f8be124e 321 if(Enc_B_Rotate<-6400)Enc_B_Rotate=-6400;
yusaku0125 10:e1eb10665472 322 if(Enc_B_Rotate>6400)Enc_B_Rotate=6400;
GGU 16:017874772ea7 323 if(Stop_Distance<0)Stop_Distance=0;
GGU 16:017874772ea7 324 if(Stop_Distance>STOP_DISTANCE)Stop_Distance=STOP_DISTANCE;
yusaku0125 10:e1eb10665472 325 }
yusaku0125 7:cfbf8d4a4d36 326 if(Marker_Pass_Flag==1){//マーカ通過中は通過距離情報を蓄積する。
yusaku0125 7:cfbf8d4a4d36 327 Marker_Run_Distance+=(Distance_A+Distance_B)/2;
yusaku0125 7:cfbf8d4a4d36 328 }
yusaku0125 8:15b4e1d7a2c5 329 //エンコーダ関連情報のリセット
GGU 17:b29e2c88b3c5 330 Distance_A=0;
GGU 17:b29e2c88b3c5 331 Distance_B=0;
GGU 16:017874772ea7 332
yusaku0125 3:e455433c8cae 333 encoder_a.Set(0);
yusaku0125 4:ac9e6772ddb3 334 encoder_b.Set(0);
yusaku0125 4:ac9e6772ddb3 335
GGU 15:cfe79ebfcb25 336 memory_A=Distance_memory_A;
GGU 15:cfe79ebfcb25 337 memory_B=Distance_memory_B;
GGU 15:cfe79ebfcb25 338
yusaku0125 4:ac9e6772ddb3 339 /////各モータの目標速度の設定
GGU 16:017874772ea7 340 if(Sw==0){
GGU 21:97cc65e61580 341 Target_Speed_A=Medium_Speed;
GGU 21:97cc65e61580 342 Target_Speed_B=Medium_Speed;
GGU 21:97cc65e61580 343
poritekutama 14:7ed78f52f40e 344 Motor_A_Diff[1]=Motor_A_Diff[0];
poritekutama 14:7ed78f52f40e 345 Motor_B_Diff[1]=Motor_B_Diff[0];
GGU 21:97cc65e61580 346
poritekutama 14:7ed78f52f40e 347 Motor_A_Diff[0]=(Target_Speed_A-Speed_A);
poritekutama 14:7ed78f52f40e 348 Motor_B_Diff[0]=(Target_Speed_B-Speed_B);
poritekutama 14:7ed78f52f40e 349 }
poritekutama 14:7ed78f52f40e 350 else {
GGU 21:97cc65e61580 351 Target_Speed_A1=High_Speed;
GGU 21:97cc65e61580 352 Target_Speed_B1=High_Speed;
poritekutama 14:7ed78f52f40e 353
poritekutama 14:7ed78f52f40e 354 Motor_A_Diff[1]=Motor_A_Diff[0];
poritekutama 14:7ed78f52f40e 355 Motor_B_Diff[1]=Motor_B_Diff[0];
GGU 21:97cc65e61580 356
poritekutama 14:7ed78f52f40e 357 Motor_A_Diff[0]=(Target_Speed_A1-Speed_A);
poritekutama 14:7ed78f52f40e 358 Motor_B_Diff[0]=(Target_Speed_B1-Speed_B);
poritekutama 14:7ed78f52f40e 359 }
poritekutama 19:edf765724d2d 360
poritekutama 19:edf765724d2d 361 /*
yusaku0125 4:ac9e6772ddb3 362 /////モータの速度制御
yusaku0125 4:ac9e6772ddb3 363 //過去の速度偏差を退避
GGU 16:017874772ea7 364 Motor_A_Diff[1]=Motor_A_Diff[0];
yusaku0125 6:afd8f0d02c8d 365 Motor_B_Diff[1]=Motor_B_Diff[0];
yusaku0125 4:ac9e6772ddb3 366 //現在の速度偏差を取得。
yusaku0125 4:ac9e6772ddb3 367 Motor_A_Diff[0]=(Target_Speed_A-Speed_A);
yusaku0125 4:ac9e6772ddb3 368 Motor_B_Diff[0]=(Target_Speed_B-Speed_B);
poritekutama 14:7ed78f52f40e 369
poritekutama 14:7ed78f52f40e 370 Motor_A_Diff[0]=(Target_Speed_A1-Speed_A);
poritekutama 14:7ed78f52f40e 371 Motor_B_Diff[0]=(Target_Speed_B1-Speed_B);
GGU 20:3b35311f4576 372 */
poritekutama 14:7ed78f52f40e 373
poritekutama 19:edf765724d2d 374
GGU 16:017874772ea7 375 //P成分演算
yusaku0125 4:ac9e6772ddb3 376 Motor_A_P=Motor_A_Diff[0]*M_KP;
yusaku0125 4:ac9e6772ddb3 377 Motor_B_P=Motor_B_Diff[0]*M_KP;
yusaku0125 4:ac9e6772ddb3 378 //D成分演算
yusaku0125 4:ac9e6772ddb3 379 Motor_A_D=(Motor_A_Diff[0]-Motor_A_Diff[1])*M_KD;
yusaku0125 4:ac9e6772ddb3 380 Motor_B_D=(Motor_B_Diff[0]-Motor_B_Diff[1])*M_KD;
yusaku0125 8:15b4e1d7a2c5 381 //モータ速度制御のPD合成
yusaku0125 8:15b4e1d7a2c5 382 Motor_A_PD=Motor_A_P+Motor_A_D;
yusaku0125 8:15b4e1d7a2c5 383 Motor_B_PD=Motor_B_P+Motor_B_D;
yusaku0125 8:15b4e1d7a2c5 384 //最終的なモータ制御量の合成
yusaku0125 8:15b4e1d7a2c5 385 Motor_A_Pwm=Motor_A_PD+Sensor_PD;
yusaku0125 8:15b4e1d7a2c5 386 Motor_B_Pwm=Motor_B_PD-Sensor_PD;
yusaku0125 8:15b4e1d7a2c5 387
GGU 16:017874772ea7 388 //モータ制御量の上限下限設定
yusaku0125 6:afd8f0d02c8d 389 if(Motor_A_Pwm>0.95f)Motor_A_Pwm=0.95f;
yusaku0125 6:afd8f0d02c8d 390 else if(Motor_A_Pwm<-0.95)Motor_A_Pwm=-0.95f;
yusaku0125 6:afd8f0d02c8d 391 if(Motor_B_Pwm>0.95f)Motor_B_Pwm=0.95f;
yusaku0125 6:afd8f0d02c8d 392 else if(Motor_B_Pwm<-0.95f)Motor_B_Pwm=-0.95f;
GGU 20:3b35311f4576 393
yusaku0125 8:15b4e1d7a2c5 394 //モータへの出力
yusaku0125 6:afd8f0d02c8d 395 if(!(Machine_Status&STOP)){//マシンが停止状態でなければ
yusaku0125 8:15b4e1d7a2c5 396 if(Machine_Status&RUN_COURSE_LOUT){ //左端センサ振り切れた時
yusaku0125 8:15b4e1d7a2c5 397 motor_a=-(-TURN_POWER); //左旋回
yusaku0125 6:afd8f0d02c8d 398 motor_b=-(TURN_POWER);
yusaku0125 8:15b4e1d7a2c5 399 }else if(Machine_Status&RUN_COURSE_ROUT){ //右端センサ振り切れた時
yusaku0125 8:15b4e1d7a2c5 400 motor_a=-(TURN_POWER); //右旋回
yusaku0125 6:afd8f0d02c8d 401 motor_b=-(-TURN_POWER);
yusaku0125 7:cfbf8d4a4d36 402 }else if(Cross_Flag==1){//交差点通過中
yusaku0125 7:cfbf8d4a4d36 403 motor_a=-0.3;//交差点なので控えめの速度で直進
yusaku0125 7:cfbf8d4a4d36 404 motor_b=-0.3;
yusaku0125 7:cfbf8d4a4d36 405 }
yusaku0125 7:cfbf8d4a4d36 406 else{
yusaku0125 6:afd8f0d02c8d 407 motor_a=-Motor_A_Pwm;
yusaku0125 6:afd8f0d02c8d 408 motor_b=-Motor_B_Pwm;
yusaku0125 6:afd8f0d02c8d 409 }
yusaku0125 6:afd8f0d02c8d 410 }else{//停止状態の時はモータへの出力は無効
yusaku0125 6:afd8f0d02c8d 411 motor_a=0;
yusaku0125 6:afd8f0d02c8d 412 motor_b=0;
GGU 20:3b35311f4576 413 }
yusaku0125 3:e455433c8cae 414 }
yusaku0125 3:e455433c8cae 415
yusaku0125 3:e455433c8cae 416 int main() {
yusaku0125 8:15b4e1d7a2c5 417 timer.attach_us(&timer_interrupt,INTERRUPT_TIME);//タイマ割り込みスタート
yusaku0125 8:15b4e1d7a2c5 418 lcd.cls();//表示クリア
yusaku0125 8:15b4e1d7a2c5 419 lcd.locate(0,0);
yusaku0125 10:e1eb10665472 420 lcd.print("STOP");
yusaku0125 10:e1eb10665472 421 lcd.locate(0,1);
GGU 16:017874772ea7 422 sprintf(Speed_Str,"%04d",Medium_Speed);
GGU 16:017874772ea7 423 lcd.print(Speed_Str);
GGU 15:cfe79ebfcb25 424
yusaku0125 3:e455433c8cae 425 while(1){
yusaku0125 8:15b4e1d7a2c5 426 Old_Sw_Ptn=Sw_Ptn; //過去のスイッチ入力情報を退避
yusaku0125 8:15b4e1d7a2c5 427 Sw_Ptn=push_sw; //現在のスイッチ入力情報の取得
poritekutama 14:7ed78f52f40e 428 if((!(Old_Machine_Status&STOP))&&(Machine_Status&STOP)){//走行終了時
GGU 16:017874772ea7 429 //sprintf(MemoryA_Str,"%d",memory_A);
GGU 16:017874772ea7 430 //sprintf(MemoryB_Str,"%d",memory_B);
yusaku0125 10:e1eb10665472 431 lcd.locate(0,0);
yusaku0125 10:e1eb10665472 432 lcd.print(" ");
yusaku0125 10:e1eb10665472 433 lcd.locate(0,0);
GGU 16:017874772ea7 434 lcd.print("STOP");
GGU 15:cfe79ebfcb25 435
GGU 16:017874772ea7 436 //lcd.locate(0,0);
GGU 16:017874772ea7 437 //lcd.print(MemoryA_Str);
GGU 16:017874772ea7 438 //lcd.locate(0,1);
GGU 16:017874772ea7 439 //lcd.print(MemoryB_Str);
GGU 16:017874772ea7 440 wait(5);
GGU 16:017874772ea7 441 Gray=DEFAULT_GRAY;
GGU 16:017874772ea7 442 Medium_Speed=DEFAULT_SPEED1;
GGU 16:017874772ea7 443
GGU 16:017874772ea7 444 Sw++;
yusaku0125 10:e1eb10665472 445 }
poritekutama 14:7ed78f52f40e 446
yusaku0125 10:e1eb10665472 447 if(Machine_Status&STOP){//機体停止状態の時
yusaku0125 12:dc4c569248d7 448
yusaku0125 12:dc4c569248d7 449 Gray=DEFAULT_GRAY+((float)Enc_A_Rotate/16000);//センサ閾値調整
GGU 16:017874772ea7 450 sprintf(Gray_Str,"%3.2f",Gray);//速度情報文字列変換
GGU 16:017874772ea7 451 sprintf(Coner_str,"%d",Coner_c);
GGU 20:3b35311f4576 452
GGU 20:3b35311f4576 453 lcd.locate(0,0);
GGU 16:017874772ea7 454 lcd.print(Gray_Str);
GGU 16:017874772ea7 455 lcd.print(" ");
GGU 20:3b35311f4576 456 lcd.print(Coner_str);
GGU 20:3b35311f4576 457
GGU 20:3b35311f4576 458 lcd.locate(0,1);
GGU 20:3b35311f4576 459 lcd.print(" ");
GGU 20:3b35311f4576 460 lcd.locate(0,1);
GGU 20:3b35311f4576 461 lcd.print(Speed_Str);
poritekutama 14:7ed78f52f40e 462 if(Sw==0){
GGU 16:017874772ea7 463 Medium_Speed=DEFAULT_SPEED1+(Enc_B_Rotate/16);//標準速度調整
GGU 16:017874772ea7 464 sprintf(Speed_Str,"%04d",Medium_Speed);//速度情報文字列変換
poritekutama 14:7ed78f52f40e 465 }else {
GGU 16:017874772ea7 466 High_Speed=DEFAULT_SPEED2+(Enc_B_Rotate/16);
GGU 16:017874772ea7 467 sprintf(Speed_Str,"%04d",High_Speed);//速度情報文字列変換
GGU 20:3b35311f4576 468 }
yusaku0125 10:e1eb10665472 469 }
yusaku0125 10:e1eb10665472 470
yusaku0125 8:15b4e1d7a2c5 471
yusaku0125 8:15b4e1d7a2c5 472 if((Old_Sw_Ptn==PULL)&&(Sw_Ptn==PUSH)){//スイッチが押された瞬間
yusaku0125 10:e1eb10665472 473 if(Machine_Status&STOP){//機体停止状態の時
poritekutama 14:7ed78f52f40e 474 Coner_c=0;
yusaku0125 10:e1eb10665472 475 lcd.locate(0,0);
yusaku0125 10:e1eb10665472 476 lcd.print(" ");
yusaku0125 8:15b4e1d7a2c5 477 lcd.locate(0,0);
yusaku0125 10:e1eb10665472 478 lcd.print("GO!!");
yusaku0125 10:e1eb10665472 479 wait(2);
GGU 16:017874772ea7 480 Stop_Distance=0;
GGU 20:3b35311f4576 481 Machine_Status&=0x7F;//ストップ状態解除
GGU 21:97cc65e61580 482 //Target_Speed_A=Medium_Speed;
GGU 21:97cc65e61580 483 //Target_Speed_B=Medium_Speed;
GGU 20:3b35311f4576 484
GGU 20:3b35311f4576 485
yusaku0125 10:e1eb10665472 486 }else{//機体走行中であったとき
yusaku0125 10:e1eb10665472 487 //各種フラグのクリア
yusaku0125 10:e1eb10665472 488 Corner_Flag=0;
yusaku0125 10:e1eb10665472 489 SG_Flag=0;
yusaku0125 10:e1eb10665472 490 Cross_Flag=0;
yusaku0125 10:e1eb10665472 491 Marker_Run_Distance=0;//マーカ通過距離情報リセット
yusaku0125 10:e1eb10665472 492
yusaku0125 10:e1eb10665472 493 Machine_Status |= STOP;//機体停止状態にする。
yusaku0125 8:15b4e1d7a2c5 494 lcd.locate(0,0);
yusaku0125 10:e1eb10665472 495 lcd.print(" ");
yusaku0125 8:15b4e1d7a2c5 496 lcd.locate(0,0);
yusaku0125 10:e1eb10665472 497 lcd.print("STOP");
yusaku0125 10:e1eb10665472 498 }
yusaku0125 9:1c28fcc1e9b8 499 }
yusaku0125 0:df99e50ed3fd 500 }
yusaku0125 3:e455433c8cae 501 }