走行1回目デフォルト 走行2回目記憶走行
Dependencies: mbed AQM0802 CRotaryEncoder TB6612FNG
main.cpp@10:e1eb10665472, 2019-08-28 (annotated)
- Committer:
- yusaku0125
- Date:
- Wed Aug 28 09:44:41 2019 +0000
- Revision:
- 10:e1eb10665472
- Parent:
- 9:1c28fcc1e9b8
- Child:
- 11:2cd6f8be124e
test;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
yusaku0125 | 10:e1eb10665472 | 1 | ////ライントレースサンプルver7 |
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 | //☆★☆★各種パラメータ調整箇所☆★☆★☆★ |
yusaku0125 | 8:15b4e1d7a2c5 | 9 | #define FIRST_SPEED 500 //1走目の基本速度[mm/sec] |
yusaku0125 | 8:15b4e1d7a2c5 | 10 | #define SECOND_SPEED 750 //2走目の基本速度[mm/sec] |
yusaku0125 | 8:15b4e1d7a2c5 | 11 | #define THIRD_SPEED 1000 //3走目の基本速度[mm/sec] |
yusaku0125 | 6:afd8f0d02c8d | 12 | #define TURN_POWER 0.5 //コースアウト時の旋回力 |
yusaku0125 | 6:afd8f0d02c8d | 13 | #define PULSE_TO_UM 30 //エンコーダ1パルス当たりのタイヤ移動距離[um] |
yusaku0125 | 6:afd8f0d02c8d | 14 | #define INTERRUPT_TIME 1000 //割りこみ周期[us] |
yusaku0125 | 10:e1eb10665472 | 15 | #define GRAY 0.6f //フォトリフレクタデジタル入力の閾値 |
yusaku0125 | 7:cfbf8d4a4d36 | 16 | //シリアル通信でSensor_Digital値を確認し調整する。 |
yusaku0125 | 10:e1eb10665472 | 17 | #define MARKER_WIDTH 15 //マーカ幅[mm](ビニルテープ幅19[mm]以内) |
yusaku0125 | 7:cfbf8d4a4d36 | 18 | //コースの傷によってマーカ誤検知する場合は値を大きくする。 |
yusaku0125 | 7:cfbf8d4a4d36 | 19 | #define CROSS_JUDGE 4 //ラインセンサいくつ以上白線検知で交差点認識するか設定。 |
yusaku0125 | 5:f635f1f01d2d | 20 | //モータ速度のゲイン関連(むやみに調整しない) |
yusaku0125 | 6:afd8f0d02c8d | 21 | #define M_KP 0.002f //P(比例)制御成分 |
yusaku0125 | 6:afd8f0d02c8d | 22 | #define M_KD 0.001f //D(微分)制御成分 |
yusaku0125 | 5:f635f1f01d2d | 23 | |
yusaku0125 | 5:f635f1f01d2d | 24 | //フォトリフレクタのゲイン(外側に行くにつれ値を何倍させたいか調整する。) |
yusaku0125 | 6:afd8f0d02c8d | 25 | #define S_K1 1.0f //float演算させる値には必ずfを付ける |
yusaku0125 | 6:afd8f0d02c8d | 26 | #define S_K2 2.0f //2倍 |
yusaku0125 | 6:afd8f0d02c8d | 27 | #define S_K3 4.0f //4倍 |
yusaku0125 | 5:f635f1f01d2d | 28 | |
yusaku0125 | 5:f635f1f01d2d | 29 | //ラインセンサ各種制御成分 |
yusaku0125 | 6:afd8f0d02c8d | 30 | #define S_KP 0.5f //ラインセンサ比例成分。大きいほど曲がりやすい |
yusaku0125 | 6:afd8f0d02c8d | 31 | #define S_KD 0.3f //ラインセンサ微分成分。大きいほど急なラインずれに強くなる。 |
yusaku0125 | 4:ac9e6772ddb3 | 32 | //////////☆★☆★☆★☆★☆★////////////// |
yusaku0125 | 4:ac9e6772ddb3 | 33 | |
yusaku0125 | 8:15b4e1d7a2c5 | 34 | |
yusaku0125 | 8:15b4e1d7a2c5 | 35 | |
yusaku0125 | 8:15b4e1d7a2c5 | 36 | //スイッチ状態の定義 |
yusaku0125 | 8:15b4e1d7a2c5 | 37 | #define PUSH 0 //スイッチ押したときの状態 |
yusaku0125 | 8:15b4e1d7a2c5 | 38 | #define PULL 1 //スイッチ離したときの状態 |
yusaku0125 | 6:afd8f0d02c8d | 39 | //機体状態の定義 |
yusaku0125 | 6:afd8f0d02c8d | 40 | #define STOP 0x80 //機体停止状態 |
yusaku0125 | 6:afd8f0d02c8d | 41 | #define RUN_START 0x40 //スタートマーカ通過 |
yusaku0125 | 6:afd8f0d02c8d | 42 | #define RUN_COURSE_LOUT 0x20 //左コースアウト状態 |
yusaku0125 | 6:afd8f0d02c8d | 43 | #define RUN_COURSE_CENTER 0x18 //ライン中央走行状態 |
yusaku0125 | 6:afd8f0d02c8d | 44 | #define RUN_COURSE_ROUT 0x04 //右コースアウト状態 |
yusaku0125 | 6:afd8f0d02c8d | 45 | #define SECOND_RUN 0x02 //機体停止状態 |
yusaku0125 | 6:afd8f0d02c8d | 46 | #define TUARD_RUN 0x01 //機体設定モード |
yusaku0125 | 6:afd8f0d02c8d | 47 | |
yusaku0125 | 10:e1eb10665472 | 48 | #define FIRST 1 |
yusaku0125 | 10:e1eb10665472 | 49 | #define SECOND 2 |
yusaku0125 | 10:e1eb10665472 | 50 | #define THIRD 3 |
yusaku0125 | 10:e1eb10665472 | 51 | |
yusaku0125 | 8:15b4e1d7a2c5 | 52 | //デジタル入力オブジェクト定義 |
yusaku0125 | 8:15b4e1d7a2c5 | 53 | DigitalIn push_sw(D13); |
yusaku0125 | 5:f635f1f01d2d | 54 | /////アナログ入力オブジェクト定義////////// |
yusaku0125 | 6:afd8f0d02c8d | 55 | AnalogIn s1(D3); |
yusaku0125 | 6:afd8f0d02c8d | 56 | AnalogIn s2(A6); |
yusaku0125 | 6:afd8f0d02c8d | 57 | AnalogIn s3(A5); |
yusaku0125 | 6:afd8f0d02c8d | 58 | AnalogIn s4(A4); |
yusaku0125 | 6:afd8f0d02c8d | 59 | AnalogIn s5(A3); |
yusaku0125 | 6:afd8f0d02c8d | 60 | AnalogIn s6(A2); |
yusaku0125 | 6:afd8f0d02c8d | 61 | AnalogIn s7(A1); |
yusaku0125 | 6:afd8f0d02c8d | 62 | AnalogIn s8(A0); |
yusaku0125 | 5:f635f1f01d2d | 63 | /////////////////////////////////////// |
yusaku0125 | 6:afd8f0d02c8d | 64 | Serial PC(USBTX,USBRX); |
yusaku0125 | 6:afd8f0d02c8d | 65 | CRotaryEncoder encoder_a(D1,D0); //モータAのエンコーダ |
yusaku0125 | 6:afd8f0d02c8d | 66 | CRotaryEncoder encoder_b(D11,D12); //モータBのエンコーダ |
yusaku0125 | 6:afd8f0d02c8d | 67 | Ticker timer; //タイマ割込み用 |
yusaku0125 | 4:ac9e6772ddb3 | 68 | TB6612 motor_a(D2,D7,D6); //モータA制御用(pwma,ain1,ain2) |
yusaku0125 | 6:afd8f0d02c8d | 69 | TB6612 motor_b(D10,D8,D9); //モータB制御用(pwmb,bin1,bin2) |
yusaku0125 | 8:15b4e1d7a2c5 | 70 | AQM0802 lcd(I2C_SDA,I2C_SCL); //液晶制御用 |
yusaku0125 | 4:ac9e6772ddb3 | 71 | |
yusaku0125 | 5:f635f1f01d2d | 72 | //使用変数の定義 |
yusaku0125 | 8:15b4e1d7a2c5 | 73 | int Sw_Ptn; |
yusaku0125 | 8:15b4e1d7a2c5 | 74 | int Old_Sw_Ptn; |
yusaku0125 | 10:e1eb10665472 | 75 | int Run_Mode=FIRST; |
yusaku0125 | 8:15b4e1d7a2c5 | 76 | double S1_Data,S2_Data,S3_Data,S4_Data,S5_Data,S6_Data,S7_Data,S8_Data; |
yusaku0125 | 8:15b4e1d7a2c5 | 77 | double All_Sensor_Data; //ラインセンサ総データ量 |
yusaku0125 | 8:15b4e1d7a2c5 | 78 | double Sensor_Diff[2]={0,0}; //ラインセンサ偏差 |
yusaku0125 | 8:15b4e1d7a2c5 | 79 | double Sensor_P =0.0f; //ラインセンサP(比例成分)制御量 |
yusaku0125 | 8:15b4e1d7a2c5 | 80 | double Sensor_D =0.0f; //ラインセンサD(微分成分)制御量 |
yusaku0125 | 8:15b4e1d7a2c5 | 81 | double Sensor_PD=0.0f; //ラインセンサP,D成分の合計 |
yusaku0125 | 5:f635f1f01d2d | 82 | long int Enc_Count_A=0,Enc_Count_B=0; //エンコーダパルス数を格納 |
yusaku0125 | 10:e1eb10665472 | 83 | long int Enc_B_Rotate=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 84 | long int Distance_A=0,Distance_B=0; //タイヤ移動距離を格納[mm] |
yusaku0125 | 7:cfbf8d4a4d36 | 85 | long int Marker_Run_Distance=0; |
yusaku0125 | 5:f635f1f01d2d | 86 | long int Speed_A=0, Speed_B=0; //現在速度 |
yusaku0125 | 10:e1eb10665472 | 87 | long int Default_Speed=FIRST_SPEED; |
yusaku0125 | 5:f635f1f01d2d | 88 | long int Target_Speed_A=0,Target_Speed_B=0; //目標速度 |
yusaku0125 | 8:15b4e1d7a2c5 | 89 | long int Motor_A_Diff[2]={0,0}; //過去の速度偏差と現在の速度偏差を格納 |
yusaku0125 | 8:15b4e1d7a2c5 | 90 | long int Motor_B_Diff[2]={0,0}; // |
yusaku0125 | 8:15b4e1d7a2c5 | 91 | float Motor_A_P,Motor_B_P; //モータ速度制御P成分 |
yusaku0125 | 8:15b4e1d7a2c5 | 92 | float Motor_A_D,Motor_B_D; //モータ速度制御D成分 |
yusaku0125 | 8:15b4e1d7a2c5 | 93 | float Motor_A_PD,Motor_B_PD; //モータ速度制御PD合成 |
yusaku0125 | 4:ac9e6772ddb3 | 94 | float Motor_A_Pwm,Motor_B_Pwm; //モータへの出力 |
yusaku0125 | 6:afd8f0d02c8d | 95 | unsigned char Sensor_Digital =0x00; |
yusaku0125 | 6:afd8f0d02c8d | 96 | unsigned char Old_Sensor_Digital=0x00; |
yusaku0125 | 7:cfbf8d4a4d36 | 97 | int Sensor_Cnt=0; |
yusaku0125 | 8:15b4e1d7a2c5 | 98 | unsigned char Machine_Status =STOP; //機体状態 |
yusaku0125 | 6:afd8f0d02c8d | 99 | unsigned char Old_Machine_Status=0x00; //過去の機体状態 |
yusaku0125 | 7:cfbf8d4a4d36 | 100 | int Marker_Pass_Flag = 0; |
yusaku0125 | 7:cfbf8d4a4d36 | 101 | int Old_Marker_Pass_Flag=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 102 | int Corner_Flag=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 103 | int SG_Flag=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 104 | int SG_Cnt=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 105 | int Cross_Flag=0; |
yusaku0125 | 6:afd8f0d02c8d | 106 | void sensor_analog_read(){ |
yusaku0125 | 5:f635f1f01d2d | 107 | S1_Data=s1.read(); |
yusaku0125 | 5:f635f1f01d2d | 108 | S2_Data=s2.read(); |
yusaku0125 | 5:f635f1f01d2d | 109 | S3_Data=s3.read(); |
yusaku0125 | 5:f635f1f01d2d | 110 | S4_Data=s4.read(); |
yusaku0125 | 5:f635f1f01d2d | 111 | S5_Data=s5.read(); |
yusaku0125 | 5:f635f1f01d2d | 112 | S6_Data=s6.read(); |
yusaku0125 | 5:f635f1f01d2d | 113 | S7_Data=s7.read(); |
yusaku0125 | 6:afd8f0d02c8d | 114 | S8_Data=s8.read(); |
yusaku0125 | 6:afd8f0d02c8d | 115 | } |
yusaku0125 | 7:cfbf8d4a4d36 | 116 | |
yusaku0125 | 7:cfbf8d4a4d36 | 117 | |
yusaku0125 | 6:afd8f0d02c8d | 118 | void sensor_digital_read(){//8つのフォトリフレクタの入力を8ビットのデジタルパターンに変換 |
yusaku0125 | 7:cfbf8d4a4d36 | 119 | Sensor_Cnt=0; |
yusaku0125 | 6:afd8f0d02c8d | 120 | Old_Sensor_Digital=Sensor_Digital; |
yusaku0125 | 7:cfbf8d4a4d36 | 121 | if(S1_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 122 | Sensor_Digital |= 0x80; //7ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 123 | }else Sensor_Digital &= 0x7F; //7ビット目のみマスク(0にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 124 | if(S2_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 125 | Sensor_Digital |= 0x40; //6ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 126 | Sensor_Cnt++; |
yusaku0125 | 7:cfbf8d4a4d36 | 127 | }else Sensor_Digital &= 0xBF; //6ビット目のみマスク(0にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 128 | if(S3_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 129 | Sensor_Digital |= 0x20; //5ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 130 | Sensor_Cnt++; |
yusaku0125 | 7:cfbf8d4a4d36 | 131 | }else Sensor_Digital &= 0xDF; //5ビット目のみマスク(0にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 132 | if(S4_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 133 | Sensor_Digital |= 0x10; //4ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 134 | Sensor_Cnt++; |
yusaku0125 | 7:cfbf8d4a4d36 | 135 | }else Sensor_Digital &= 0xEF; //4ビット目のみマスク(0にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 136 | if(S5_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 137 | Sensor_Digital |= 0x08; //3ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 138 | Sensor_Cnt++; |
yusaku0125 | 7:cfbf8d4a4d36 | 139 | }else Sensor_Digital &= 0xF7; //3ビット目のみマスク(0にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 140 | if(S6_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 141 | Sensor_Digital |= 0x04; //2ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 142 | Sensor_Cnt++; |
yusaku0125 | 7:cfbf8d4a4d36 | 143 | }else Sensor_Digital &= 0xFB; //2ビット目のみマスク(0にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 144 | if(S7_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 145 | Sensor_Digital |= 0x02; //1ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 146 | Sensor_Cnt++; |
yusaku0125 | 7:cfbf8d4a4d36 | 147 | }else Sensor_Digital &= 0xFD; //1ビット目のみマスク(0にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 148 | if(S8_Data>GRAY){ |
yusaku0125 | 7:cfbf8d4a4d36 | 149 | Sensor_Digital |= 0x01; //0ビット目のみセット (1にする。) |
yusaku0125 | 7:cfbf8d4a4d36 | 150 | }else Sensor_Digital &= 0xFE; //0ビット目のみマスク(0にする。) |
yusaku0125 | 6:afd8f0d02c8d | 151 | } |
yusaku0125 | 6:afd8f0d02c8d | 152 | |
yusaku0125 | 6:afd8f0d02c8d | 153 | void Machine_Status_Set(){ |
yusaku0125 | 7:cfbf8d4a4d36 | 154 | Old_Machine_Status=Machine_Status; |
yusaku0125 | 7:cfbf8d4a4d36 | 155 | |
yusaku0125 | 6:afd8f0d02c8d | 156 | //機体がライン中央に位置するとき |
yusaku0125 | 6:afd8f0d02c8d | 157 | if(Sensor_Digital&RUN_COURSE_CENTER )Machine_Status|=RUN_COURSE_CENTER; |
yusaku0125 | 6:afd8f0d02c8d | 158 | else Machine_Status &= 0xE7;//ライン中央情報のマスク |
yusaku0125 | 6:afd8f0d02c8d | 159 | if((Sensor_Digital==0x00)&&(Old_Sensor_Digital==0x40)){//左センサコースアウト時 |
yusaku0125 | 6:afd8f0d02c8d | 160 | Machine_Status|=RUN_COURSE_LOUT;//左コースアウト状態のビットをセット |
yusaku0125 | 6:afd8f0d02c8d | 161 | }else if((Machine_Status&RUN_COURSE_LOUT)&&(Sensor_Digital&RUN_COURSE_CENTER)){ |
yusaku0125 | 6:afd8f0d02c8d | 162 | //左コースアウト状態かつ機体がライン中央に復帰したとき |
yusaku0125 | 6:afd8f0d02c8d | 163 | Machine_Status &= 0xDF;//左コースアウト情報のみマスク |
yusaku0125 | 6:afd8f0d02c8d | 164 | } |
yusaku0125 | 6:afd8f0d02c8d | 165 | if((Sensor_Digital==0x00)&&(Old_Sensor_Digital==0x02)){//右センサコースアウト時 |
yusaku0125 | 6:afd8f0d02c8d | 166 | Machine_Status|=RUN_COURSE_ROUT;//右コースアウト状態のビットをセット |
yusaku0125 | 6:afd8f0d02c8d | 167 | }else if((Machine_Status&RUN_COURSE_ROUT)&&(Sensor_Digital&RUN_COURSE_CENTER)){ |
yusaku0125 | 6:afd8f0d02c8d | 168 | //右コースアウト状態かつ機体がライン中央に復帰したとき |
yusaku0125 | 6:afd8f0d02c8d | 169 | Machine_Status &= 0xFB;//右コースアウト情報のみマスク |
yusaku0125 | 6:afd8f0d02c8d | 170 | } |
yusaku0125 | 6:afd8f0d02c8d | 171 | } |
yusaku0125 | 6:afd8f0d02c8d | 172 | |
yusaku0125 | 8:15b4e1d7a2c5 | 173 | |
yusaku0125 | 8:15b4e1d7a2c5 | 174 | //タイマ割り込み1[ms]周期 |
yusaku0125 | 6:afd8f0d02c8d | 175 | void timer_interrupt(){ |
yusaku0125 | 7:cfbf8d4a4d36 | 176 | |
yusaku0125 | 6:afd8f0d02c8d | 177 | //ラインセンサ情報取得 |
yusaku0125 | 6:afd8f0d02c8d | 178 | sensor_analog_read(); |
yusaku0125 | 6:afd8f0d02c8d | 179 | sensor_digital_read(); |
yusaku0125 | 7:cfbf8d4a4d36 | 180 | |
yusaku0125 | 7:cfbf8d4a4d36 | 181 | //機体状態の取得 |
yusaku0125 | 6:afd8f0d02c8d | 182 | Machine_Status_Set(); |
yusaku0125 | 7:cfbf8d4a4d36 | 183 | |
yusaku0125 | 7:cfbf8d4a4d36 | 184 | //交差点の認識 |
yusaku0125 | 7:cfbf8d4a4d36 | 185 | if(Sensor_Cnt>=CROSS_JUDGE )Cross_Flag=1;//ラインセンサ4つ以上検知状態の時は交差点を示す。 |
yusaku0125 | 7:cfbf8d4a4d36 | 186 | |
yusaku0125 | 7:cfbf8d4a4d36 | 187 | //各種マーカの検知 |
yusaku0125 | 7:cfbf8d4a4d36 | 188 | Old_Marker_Pass_Flag=Marker_Pass_Flag;//過去のフラグを退避 |
yusaku0125 | 7:cfbf8d4a4d36 | 189 | if(Sensor_Digital&0x81){ //マーカセンサ検知時 |
yusaku0125 | 7:cfbf8d4a4d36 | 190 | Marker_Pass_Flag=1; //マーカ通過中フラグをON |
yusaku0125 | 7:cfbf8d4a4d36 | 191 | if(Sensor_Digital&0x80)Corner_Flag=1; //コーナセンサの検知 |
yusaku0125 | 7:cfbf8d4a4d36 | 192 | if(Sensor_Digital&0x01)SG_Flag=1; //スタートゴールセンサの検知 |
yusaku0125 | 7:cfbf8d4a4d36 | 193 | if((Corner_Flag==1)&&(SG_Flag==1));//交差点通過中。何もしない |
yusaku0125 | 7:cfbf8d4a4d36 | 194 | }else Marker_Pass_Flag=0;//マーカ通過終了 |
yusaku0125 | 7:cfbf8d4a4d36 | 195 | |
yusaku0125 | 7:cfbf8d4a4d36 | 196 | //マーカ通過後、マーカ種類判別 |
yusaku0125 | 7:cfbf8d4a4d36 | 197 | if((Old_Marker_Pass_Flag==1)&&(Marker_Pass_Flag==0)){//マーカ通過後 |
yusaku0125 | 7:cfbf8d4a4d36 | 198 | if(Marker_Run_Distance>MARKER_WIDTH){//マーカ幅がもっともらしいとき |
yusaku0125 | 7:cfbf8d4a4d36 | 199 | if(Cross_Flag==1);//交差点の時は何もしない |
yusaku0125 | 7:cfbf8d4a4d36 | 200 | else if((SG_Flag==1)&&(SG_Cnt==0)){//ゴールスタートマーカの時⇒1回目 |
yusaku0125 | 7:cfbf8d4a4d36 | 201 | SG_Cnt=1; |
yusaku0125 | 7:cfbf8d4a4d36 | 202 | }else if((SG_Flag==1)&&(SG_Cnt==1)){//ゴールスタートマーカの時⇒2回目 |
yusaku0125 | 7:cfbf8d4a4d36 | 203 | Machine_Status|=STOP; //機体停止状態へ |
yusaku0125 | 7:cfbf8d4a4d36 | 204 | SG_Cnt=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 205 | }else if(Corner_Flag==1){//コーナマーカの時 |
yusaku0125 | 7:cfbf8d4a4d36 | 206 | //地区大会では何もしない |
yusaku0125 | 7:cfbf8d4a4d36 | 207 | } |
yusaku0125 | 7:cfbf8d4a4d36 | 208 | }else{//マーカではなく、誤検知だった場合。 |
yusaku0125 | 7:cfbf8d4a4d36 | 209 | //何もしない |
yusaku0125 | 7:cfbf8d4a4d36 | 210 | } |
yusaku0125 | 7:cfbf8d4a4d36 | 211 | Corner_Flag=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 212 | SG_Flag=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 213 | Cross_Flag=0; |
yusaku0125 | 7:cfbf8d4a4d36 | 214 | Marker_Run_Distance=0;//マーカ通過距離情報リセット |
yusaku0125 | 7:cfbf8d4a4d36 | 215 | } |
yusaku0125 | 6:afd8f0d02c8d | 216 | |
yusaku0125 | 5:f635f1f01d2d | 217 | //センサ取得値の重ね合わせ(端のセンサほどモータ制御量を大きくする) |
yusaku0125 | 5:f635f1f01d2d | 218 | 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 | 219 | Sensor_Diff[1]=Sensor_Diff[0];//過去のラインセンサ偏差を退避 |
yusaku0125 | 5:f635f1f01d2d | 220 | Sensor_Diff[0]=All_Sensor_Data; |
yusaku0125 | 5:f635f1f01d2d | 221 | Sensor_P=All_Sensor_Data*S_KP; //ラインセンサ比例成分の演算 |
yusaku0125 | 5:f635f1f01d2d | 222 | Sensor_D=(Sensor_Diff[0]-Sensor_Diff[1])*S_KD; //ラインセンサ微分成分の演算 |
yusaku0125 | 6:afd8f0d02c8d | 223 | Sensor_PD=Sensor_P+Sensor_D; |
yusaku0125 | 6:afd8f0d02c8d | 224 | |
yusaku0125 | 6:afd8f0d02c8d | 225 | |
yusaku0125 | 4:ac9e6772ddb3 | 226 | ////モータ現在速度の取得 |
yusaku0125 | 4:ac9e6772ddb3 | 227 | Enc_Count_A=encoder_a.Get(); //エンコーダパルス数を取得 |
yusaku0125 | 4:ac9e6772ddb3 | 228 | Enc_Count_B=-encoder_b.Get(); |
yusaku0125 | 4:ac9e6772ddb3 | 229 | Distance_A=(Enc_Count_A*PULSE_TO_UM); //移動距離をmm単位で格納 |
yusaku0125 | 4:ac9e6772ddb3 | 230 | Distance_B=(Enc_Count_B*PULSE_TO_UM); |
yusaku0125 | 4:ac9e6772ddb3 | 231 | Speed_A=(Distance_A*1000)/INTERRUPT_TIME;//走行速度演算[mm/s] |
yusaku0125 | 10:e1eb10665472 | 232 | Speed_B=(Distance_B*1000)/INTERRUPT_TIME; |
yusaku0125 | 10:e1eb10665472 | 233 | |
yusaku0125 | 10:e1eb10665472 | 234 | if(Machine_Status&STOP){//機体停止状態の時 |
yusaku0125 | 10:e1eb10665472 | 235 | Enc_B_Rotate+=Enc_Count_B;//モード設定用に右エンコーダ値の蓄積 |
yusaku0125 | 10:e1eb10665472 | 236 | if(Enc_B_Rotate<0)Enc_B_Rotate=0; |
yusaku0125 | 10:e1eb10665472 | 237 | if(Enc_B_Rotate>6400)Enc_B_Rotate=6400; |
yusaku0125 | 10:e1eb10665472 | 238 | } |
yusaku0125 | 7:cfbf8d4a4d36 | 239 | if(Marker_Pass_Flag==1){//マーカ通過中は通過距離情報を蓄積する。 |
yusaku0125 | 7:cfbf8d4a4d36 | 240 | Marker_Run_Distance+=(Distance_A+Distance_B)/2; |
yusaku0125 | 7:cfbf8d4a4d36 | 241 | } |
yusaku0125 | 8:15b4e1d7a2c5 | 242 | //エンコーダ関連情報のリセット |
yusaku0125 | 4:ac9e6772ddb3 | 243 | Distance_A=0; |
yusaku0125 | 4:ac9e6772ddb3 | 244 | Distance_B=0; |
yusaku0125 | 3:e455433c8cae | 245 | encoder_a.Set(0); |
yusaku0125 | 4:ac9e6772ddb3 | 246 | encoder_b.Set(0); |
yusaku0125 | 4:ac9e6772ddb3 | 247 | |
yusaku0125 | 4:ac9e6772ddb3 | 248 | /////各モータの目標速度の設定 |
yusaku0125 | 8:15b4e1d7a2c5 | 249 | Target_Speed_A=Default_Speed; |
yusaku0125 | 8:15b4e1d7a2c5 | 250 | Target_Speed_B=Default_Speed; |
yusaku0125 | 4:ac9e6772ddb3 | 251 | |
yusaku0125 | 4:ac9e6772ddb3 | 252 | /////モータの速度制御 |
yusaku0125 | 4:ac9e6772ddb3 | 253 | //過去の速度偏差を退避 |
yusaku0125 | 4:ac9e6772ddb3 | 254 | Motor_A_Diff[1]=Motor_A_Diff[0]; |
yusaku0125 | 6:afd8f0d02c8d | 255 | Motor_B_Diff[1]=Motor_B_Diff[0]; |
yusaku0125 | 4:ac9e6772ddb3 | 256 | //現在の速度偏差を取得。 |
yusaku0125 | 4:ac9e6772ddb3 | 257 | Motor_A_Diff[0]=(Target_Speed_A-Speed_A); |
yusaku0125 | 4:ac9e6772ddb3 | 258 | Motor_B_Diff[0]=(Target_Speed_B-Speed_B); |
yusaku0125 | 4:ac9e6772ddb3 | 259 | //P成分演算 |
yusaku0125 | 4:ac9e6772ddb3 | 260 | Motor_A_P=Motor_A_Diff[0]*M_KP; |
yusaku0125 | 4:ac9e6772ddb3 | 261 | Motor_B_P=Motor_B_Diff[0]*M_KP; |
yusaku0125 | 4:ac9e6772ddb3 | 262 | //D成分演算 |
yusaku0125 | 4:ac9e6772ddb3 | 263 | Motor_A_D=(Motor_A_Diff[0]-Motor_A_Diff[1])*M_KD; |
yusaku0125 | 4:ac9e6772ddb3 | 264 | Motor_B_D=(Motor_B_Diff[0]-Motor_B_Diff[1])*M_KD; |
yusaku0125 | 8:15b4e1d7a2c5 | 265 | //モータ速度制御のPD合成 |
yusaku0125 | 8:15b4e1d7a2c5 | 266 | Motor_A_PD=Motor_A_P+Motor_A_D; |
yusaku0125 | 8:15b4e1d7a2c5 | 267 | Motor_B_PD=Motor_B_P+Motor_B_D; |
yusaku0125 | 8:15b4e1d7a2c5 | 268 | //最終的なモータ制御量の合成 |
yusaku0125 | 8:15b4e1d7a2c5 | 269 | Motor_A_Pwm=Motor_A_PD+Sensor_PD; |
yusaku0125 | 8:15b4e1d7a2c5 | 270 | Motor_B_Pwm=Motor_B_PD-Sensor_PD; |
yusaku0125 | 8:15b4e1d7a2c5 | 271 | |
yusaku0125 | 8:15b4e1d7a2c5 | 272 | //モータ制御量の上限下限設定 |
yusaku0125 | 6:afd8f0d02c8d | 273 | if(Motor_A_Pwm>0.95f)Motor_A_Pwm=0.95f; |
yusaku0125 | 6:afd8f0d02c8d | 274 | else if(Motor_A_Pwm<-0.95)Motor_A_Pwm=-0.95f; |
yusaku0125 | 6:afd8f0d02c8d | 275 | if(Motor_B_Pwm>0.95f)Motor_B_Pwm=0.95f; |
yusaku0125 | 6:afd8f0d02c8d | 276 | else if(Motor_B_Pwm<-0.95f)Motor_B_Pwm=-0.95f; |
yusaku0125 | 6:afd8f0d02c8d | 277 | |
yusaku0125 | 8:15b4e1d7a2c5 | 278 | //モータへの出力 |
yusaku0125 | 6:afd8f0d02c8d | 279 | if(!(Machine_Status&STOP)){//マシンが停止状態でなければ |
yusaku0125 | 8:15b4e1d7a2c5 | 280 | if(Machine_Status&RUN_COURSE_LOUT){ //左端センサ振り切れた時 |
yusaku0125 | 8:15b4e1d7a2c5 | 281 | motor_a=-(-TURN_POWER); //左旋回 |
yusaku0125 | 6:afd8f0d02c8d | 282 | motor_b=-(TURN_POWER); |
yusaku0125 | 8:15b4e1d7a2c5 | 283 | }else if(Machine_Status&RUN_COURSE_ROUT){ //右端センサ振り切れた時 |
yusaku0125 | 8:15b4e1d7a2c5 | 284 | motor_a=-(TURN_POWER); //右旋回 |
yusaku0125 | 6:afd8f0d02c8d | 285 | motor_b=-(-TURN_POWER); |
yusaku0125 | 7:cfbf8d4a4d36 | 286 | }else if(Cross_Flag==1){//交差点通過中 |
yusaku0125 | 7:cfbf8d4a4d36 | 287 | motor_a=-0.3;//交差点なので控えめの速度で直進 |
yusaku0125 | 7:cfbf8d4a4d36 | 288 | motor_b=-0.3; |
yusaku0125 | 7:cfbf8d4a4d36 | 289 | } |
yusaku0125 | 7:cfbf8d4a4d36 | 290 | else{ |
yusaku0125 | 6:afd8f0d02c8d | 291 | motor_a=-Motor_A_Pwm; |
yusaku0125 | 6:afd8f0d02c8d | 292 | motor_b=-Motor_B_Pwm; |
yusaku0125 | 6:afd8f0d02c8d | 293 | } |
yusaku0125 | 6:afd8f0d02c8d | 294 | }else{//停止状態の時はモータへの出力は無効 |
yusaku0125 | 6:afd8f0d02c8d | 295 | motor_a=0; |
yusaku0125 | 6:afd8f0d02c8d | 296 | motor_b=0; |
yusaku0125 | 6:afd8f0d02c8d | 297 | } |
yusaku0125 | 3:e455433c8cae | 298 | } |
yusaku0125 | 3:e455433c8cae | 299 | |
yusaku0125 | 8:15b4e1d7a2c5 | 300 | |
yusaku0125 | 8:15b4e1d7a2c5 | 301 | |
yusaku0125 | 3:e455433c8cae | 302 | int main() { |
yusaku0125 | 8:15b4e1d7a2c5 | 303 | timer.attach_us(&timer_interrupt,INTERRUPT_TIME);//タイマ割り込みスタート |
yusaku0125 | 8:15b4e1d7a2c5 | 304 | lcd.cls();//表示クリア |
yusaku0125 | 8:15b4e1d7a2c5 | 305 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 306 | lcd.print("STOP"); |
yusaku0125 | 10:e1eb10665472 | 307 | lcd.locate(0,1); |
yusaku0125 | 10:e1eb10665472 | 308 | lcd.print("FIRST"); |
yusaku0125 | 3:e455433c8cae | 309 | while(1){ |
yusaku0125 | 8:15b4e1d7a2c5 | 310 | Old_Sw_Ptn=Sw_Ptn; //過去のスイッチ入力情報を退避 |
yusaku0125 | 8:15b4e1d7a2c5 | 311 | Sw_Ptn=push_sw; //現在のスイッチ入力情報の取得 |
yusaku0125 | 10:e1eb10665472 | 312 | if((!(Old_Machine_Status&=STOP))&&(Machine_Status&=STOP)){//走行終了時 |
yusaku0125 | 10:e1eb10665472 | 313 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 314 | lcd.print(" "); |
yusaku0125 | 10:e1eb10665472 | 315 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 316 | lcd.print("STOP"); |
yusaku0125 | 10:e1eb10665472 | 317 | } |
yusaku0125 | 10:e1eb10665472 | 318 | if(Machine_Status&STOP){//機体停止状態の時 |
yusaku0125 | 10:e1eb10665472 | 319 | if((Enc_B_Rotate/1600)<1){//右エンコーダが1回転未満であったら |
yusaku0125 | 10:e1eb10665472 | 320 | if(Run_Mode!=FIRST){ |
yusaku0125 | 10:e1eb10665472 | 321 | lcd.cls();//表示クリア |
yusaku0125 | 10:e1eb10665472 | 322 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 323 | lcd.print("STOP"); |
yusaku0125 | 10:e1eb10665472 | 324 | lcd.locate(0,1); |
yusaku0125 | 10:e1eb10665472 | 325 | lcd.print("FIRST"); |
yusaku0125 | 10:e1eb10665472 | 326 | Run_Mode=FIRST; |
yusaku0125 | 10:e1eb10665472 | 327 | Default_Speed=FIRST_SPEED; |
yusaku0125 | 10:e1eb10665472 | 328 | } |
yusaku0125 | 10:e1eb10665472 | 329 | }else if(((Enc_B_Rotate/1600)>=1)&&((Enc_B_Rotate/1600)<2)){//右エンコーダが1回転以上、2回転未満であったら |
yusaku0125 | 10:e1eb10665472 | 330 | if(Run_Mode!=SECOND){ |
yusaku0125 | 10:e1eb10665472 | 331 | lcd.cls();//表示クリア |
yusaku0125 | 10:e1eb10665472 | 332 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 333 | lcd.print("STOP"); |
yusaku0125 | 10:e1eb10665472 | 334 | lcd.locate(0,1); |
yusaku0125 | 10:e1eb10665472 | 335 | lcd.print("SECOND");//2走目のモードであることを示す。 |
yusaku0125 | 10:e1eb10665472 | 336 | Run_Mode=SECOND; |
yusaku0125 | 10:e1eb10665472 | 337 | Default_Speed=SECOND_SPEED; |
yusaku0125 | 10:e1eb10665472 | 338 | } |
yusaku0125 | 10:e1eb10665472 | 339 | }else if(((Enc_B_Rotate/1600)>=2)&&((Enc_B_Rotate/1600)<3)){//右エンコーダが2回転以上、3回転未満であったら |
yusaku0125 | 10:e1eb10665472 | 340 | if(Run_Mode!=THIRD){ |
yusaku0125 | 10:e1eb10665472 | 341 | lcd.cls();//表示クリア |
yusaku0125 | 10:e1eb10665472 | 342 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 343 | lcd.print("STOP"); |
yusaku0125 | 10:e1eb10665472 | 344 | lcd.locate(0,1); |
yusaku0125 | 10:e1eb10665472 | 345 | lcd.print("THIRD");//2走目のモードであることを示す。 |
yusaku0125 | 10:e1eb10665472 | 346 | Run_Mode=THIRD; |
yusaku0125 | 10:e1eb10665472 | 347 | Default_Speed=THIRD_SPEED; |
yusaku0125 | 10:e1eb10665472 | 348 | } |
yusaku0125 | 10:e1eb10665472 | 349 | } |
yusaku0125 | 10:e1eb10665472 | 350 | |
yusaku0125 | 10:e1eb10665472 | 351 | } |
yusaku0125 | 10:e1eb10665472 | 352 | |
yusaku0125 | 8:15b4e1d7a2c5 | 353 | |
yusaku0125 | 8:15b4e1d7a2c5 | 354 | if((Old_Sw_Ptn==PULL)&&(Sw_Ptn==PUSH)){//スイッチが押された瞬間 |
yusaku0125 | 10:e1eb10665472 | 355 | if(Machine_Status&STOP){//機体停止状態の時 |
yusaku0125 | 10:e1eb10665472 | 356 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 357 | lcd.print(" "); |
yusaku0125 | 8:15b4e1d7a2c5 | 358 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 359 | lcd.print("GO!!"); |
yusaku0125 | 10:e1eb10665472 | 360 | wait(2); |
yusaku0125 | 10:e1eb10665472 | 361 | Machine_Status&=0x7F;//ストップ状態解除 |
yusaku0125 | 10:e1eb10665472 | 362 | }else{//機体走行中であったとき |
yusaku0125 | 10:e1eb10665472 | 363 | //各種フラグのクリア |
yusaku0125 | 10:e1eb10665472 | 364 | Corner_Flag=0; |
yusaku0125 | 10:e1eb10665472 | 365 | SG_Flag=0; |
yusaku0125 | 10:e1eb10665472 | 366 | Cross_Flag=0; |
yusaku0125 | 10:e1eb10665472 | 367 | Marker_Run_Distance=0;//マーカ通過距離情報リセット |
yusaku0125 | 10:e1eb10665472 | 368 | |
yusaku0125 | 10:e1eb10665472 | 369 | Machine_Status |= STOP;//機体停止状態にする。 |
yusaku0125 | 8:15b4e1d7a2c5 | 370 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 371 | lcd.print(" "); |
yusaku0125 | 8:15b4e1d7a2c5 | 372 | lcd.locate(0,0); |
yusaku0125 | 10:e1eb10665472 | 373 | lcd.print("STOP"); |
yusaku0125 | 10:e1eb10665472 | 374 | } |
yusaku0125 | 9:1c28fcc1e9b8 | 375 | } |
yusaku0125 | 0:df99e50ed3fd | 376 | } |
yusaku0125 | 3:e455433c8cae | 377 | } |