航空研究会 / Mbed 2 deprecated Autoflight2018_47

Dependencies:   HCSR04_2 MPU6050_2 mbed SDFileSystem3

Fork of Autoflight2018_46 by 航空研究会

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers main.cpp Source File

main.cpp

00001 //mbed
00002 #include "mbed.h"
00003 #include "FATFileSystem.h"
00004 #include "SDFileSystem.h"
00005 //C
00006 #include "math.h"
00007 //sensor
00008 #include "MPU6050_DMP6.h"
00009 //#include "MPU9250.h"
00010 //#include "BMP280.h"
00011 #include "hcsr04.h"
00012 //device
00013 #include "sbus.h"
00014 //config
00015 #include "SkipperSv2.h"
00016 #include "falfalla.h"
00017 //other
00018 #include "pid.h"
00019 
00020 #define DEBUG_SEMIAUTO 0
00021 #define DEBUG_PRINT_INLOOP 1
00022 
00023 #define KP_ELE 15.0  //2.0
00024 #define KI_ELE 0.0
00025 #define KD_ELE 0.0  //0/0
00026 #define KP_RUD 3.0
00027 #define KI_RUD 0.0
00028 #define KD_RUD 0.0
00029 #define KP_AIL 0.1
00030 #define KI_AIL 0.2
00031 #define KD_AIL 0.2
00032 
00033 //#define g_AIL_L_Ratio_rightloop 0.5
00034 
00035 #define GAIN_CONTROLVALUE_TO_PWM 3.0
00036 
00037 #define RIGHT_ROLL -12.0
00038 #define RIGHT_PITCH -10.0  //5.0
00039 #define LEFT_ROLL 12.0
00040 #define LEFT_PITCH -5.0
00041 #define STRAIGHT_ROLL 4.0
00042 #define STRAIGHT_PITCH 3.0
00043 #define TAKEOFF_THR 0.8
00044 #define LOOP_THR 0.6
00045 
00046 //#define g_rightloopRUD 1500 
00047 
00048 #define RIGHT_ROLL_SHORT -12.0
00049 #define RIGHT_PITCH_SHORT -5.0
00050 #define LEFT_ROLL_SHORT 12.0
00051 #define LEFT_PITCH_SHORT -5.0
00052 
00053 #define rightloopROLL2 -10.0
00054 
00055 /*#define rightloopRUD 1300  //1250
00056 #define rightloopshortRUD 1250 
00057 #define leftloopRUD  1500
00058 #define leftloopshortRUD 1500 
00059 #define glideloopRUD 1300
00060 */
00061 #define AIL_R_correctionrightloop 0
00062 #define AIL_L_correctionrightloop 0
00063 #define AIL_L_correctionrightloopshort 0
00064 #define AIL_L_correctionleftloop -0
00065 #define AIL_L_correctionleftloopshort 0
00066 
00067 
00068 #define RIGHTLOOP_RUD 1250 
00069 #define RIGHTLOOPSHORT_RUD 1250 
00070 #define LEFTLOOP_RUD 1500 
00071 #define LEFTLOOPSHORT_RUD 1500
00072 #define GLIDELOOP_RUD 1300  
00073 #define AIL_L_CORRECTION_RIGHTLOOP 0
00074 #define AIL_L_CORRECTION_RIGHTLOOPSHORT 0
00075 #define AIL_L_CORRECTION_LEFTLOOP 0
00076 #define AIL_L_CORRECTION_LEFTLOOPSHORT 0
00077 
00078 #define GLIDE_ROLL -12.0
00079 #define GLIDE_PITCH -3.0
00080 
00081 
00082 #define AIL_L_RatioRising 0.5
00083 #define AIL_L_RatioDescent 2
00084 
00085 //コンパスキャリブレーション
00086 //SkipperS2基板
00087 /*
00088 #define MAGBIAS_X -35.0
00089 #define MAGBIAS_Y 535.0
00090 #define MAGBIAS_Z -50.0
00091 */
00092 //S2v2 1番基板
00093 #define MAGBIAS_X 395.0
00094 #define MAGBIAS_Y 505.0
00095 #define MAGBIAS_Z -725.0
00096 //S2v2 2番基板
00097 /*
00098 #define MAGBIAS_X 185.0
00099 #define MAGBIAS_Y 220.0
00100 #define MAGBIAS_Z -350.0
00101 */
00102 
00103 #define ELEMENT 1
00104 #define LIMIT_STRAIGHT_YAW 5.0 
00105 #define THRESHOLD_TURNINGRADIUS_YAW 60.0 
00106 #define ALLOWHEIGHT 15
00107 
00108 #ifndef PI
00109 #define PI 3.14159265358979
00110 #endif
00111 
00112 const int16_t lengthdivpwm = 320; 
00113 const int16_t changeModeCount = 6;
00114 
00115 
00116 SBUS sbus(PA_9, PA_10); //SBUS
00117 
00118 PwmOut servo1(PC_6); // TIM3_CH1  //old echo
00119 PwmOut servo2(PC_7); // TIM3_CH2    //PC_7
00120 PwmOut servo3(PB_0); // TIM3_CH3
00121 PwmOut servo4(PB_1); // TIM3_CH4
00122 PwmOut servo5(PB_6); // TIM4_CH1
00123 PwmOut servo6(PB_7); // TIM4_CH2  //old trigger
00124 //PwmOut servo7(PB_8); // TIM4_CH3    //PB_8 new echo
00125 //PwmOut servo8(PB_9); // TIM4_CH4   //new trigger
00126 
00127 RawSerial pc(PA_2,PA_3, 115200);    //tx,rx.baudrate pin;PA_2=UART2_TX, PA_3=UART2_RX
00128 //RawSerial pc2(PB_6,PB_7, 115200);   //sbus確認用
00129 SDFileSystem sd(PB_15, PB_14, PB_13, PB_12, "sd");
00130 
00131 DigitalOut led1(PA_0);  //黄色のコネクタ
00132 DigitalOut led2(PA_1);
00133 DigitalOut led3(PB_4); 
00134 DigitalOut led4(PB_5);
00135 
00136 //InterruptIn switch2(PC_14);
00137 MPU6050DMP6 mpu6050(PC_0,&pc); //割り込みピン,シリアルポインタ i2cのピン指定は MPU6050>>I2Cdev.h 内のdefine
00138 HCSR04 usensor(PB_9,PB_8); //trig,echo  9,8 
00139 
00140 PID pid_AIL(g_kpAIL,g_kiAIL,g_kdAIL);
00141 PID pid_ELE(g_kpELE,g_kiELE,g_kdELE);
00142 PID pid_RUD(g_kpRUD,g_kiRUD,g_kdRUD);
00143 
00144 enum Channel{AIL_R, ELE, THR, RUD, DROP, AIL_L, Ch7, Ch8};
00145 enum Angle{ROLL, PITCH, YAW};   //yaw:北を0とした絶対角度
00146 enum OperationMode{StartUp, SemiAuto, RightLoop, LeftLoop, GoStraight, BombwithPC, ZERO, Moebius, Glide};
00147 enum BombingMode{Takeoff, Chicken, Transition, Approach};
00148 enum OutputStatus{Manual, Auto};
00149 
00150 static OutputStatus output_status = Manual;
00151 OperationMode operation_mode = StartUp;
00152 BombingMode bombing_mode = Takeoff;
00153 
00154 static int16_t autopwm[8] = {1455,1450,1176,1628,1512,1452};
00155 /*
00156 //1号機
00157 static int16_t trimpwm[6] = {1580,1600,1176,1404,1440,1448};
00158 int16_t maxpwm[6] = {1796,1936,1848,1740,1820,1856};
00159 int16_t minpwm[6] = {1182,1265,1176,1068,1180,1176};
00160 const int16_t reverce[4] = {Reverce_falfalla[0],Reverce_falfalla[1],Reverce_falfalla[2],Reverce_falfalla[3]};
00161 */
00162 
00163 //2号機
00164 
00165 static int16_t trimpwm[6] = {1455,1450,1176,1628,1512,1452};
00166 int16_t maxpwm[6] = {1672,1786,1848,1964,1820,1860};
00167 int16_t minpwm[6] = {1057,1115,1176,1292,1180,1180};
00168 const int16_t reverce[4] = {Reverce_falfalla[0],Reverce_falfalla[1],Reverce_falfalla[2],Reverce_falfalla[3]};
00169 
00170 
00171 int16_t oldTHR = 1000;
00172 
00173 int16_t g_AIL_L_Ratio_rightloop = 0.5;
00174 
00175 
00176 static float nowAngle[3] = {0,0,0};
00177 const float trimAngle[3] = {0.0, 0.0, 0.0};
00178 const float maxAngle[2] = {90, 90};
00179 const float minAngle[2] = {-90, -90};
00180 
00181 float FirstROLL = 0.0, FirstPITCH = 0.0 ,FirstYAW = 0.0;
00182 
00183 unsigned int g_distance;
00184 Ticker USsensor;
00185 static char g_buf[16];
00186 char g_landingcommand='Z';
00187 float g_SerialTargetYAW;
00188 
00189 Timer t;
00190 Timer t2;
00191 Timeout RerurnChickenServo1;
00192 Timeout RerurnChickenServo2;
00193 
00194 /*-----関数のプロトタイプ宣言-----*/
00195 void setup();
00196 void loop();
00197 
00198 void Init_PWM();
00199 void Init_servo();              //サーボ初期化
00200 void Init_sbus();               //SBUS初期化
00201 void Init_sensors();
00202 void DisplayClock();            //クロック状態確認
00203 
00204 //センサの値取得
00205 void SensingMPU();
00206 void UpdateDist();
00207 
00208 //void offsetRollPitch(float FirstROLL, float FirstPITCH);
00209 //void TransYaw(float FirstYAW);
00210 float TranslateNewYaw(float beforeYaw,  float newzeroYaw);
00211 void UpdateTargetAngle(float targetAngle[3]);
00212 void CalculateControlValue(float targetAngle[3], float controlValue[3]);
00213 void UpdateAutoPWM(float controlValue[3]);
00214 void ConvertPWMintoRAD(float targetAngle[3]);
00215 inline float CalcRatio(float value, float trim, float limit);
00216 bool CheckSW_Up(Channel ch);
00217 int16_t ThresholdMaxMin(int16_t value, int16_t max, int16_t min);
00218 inline int16_t SetTHRinRatio(float ratio);
00219 
00220 //sbus割り込み
00221 void Update_PWM();              //マニュアル・自動モードのpwmデータを整形しpwm変数に入力
00222 void Output_PWM(int16_t pwm[6]);    //pwmをサーボへ出力
00223 
00224 //シリアル割り込み
00225 void getSF_Serial();
00226 float ConvertByteintoFloat(char high, char low);
00227 
00228 
00229 //SD設定
00230 int GetParameter(FILE *fp, const char *paramName,char parameter[]);
00231 int SetOptions(float *g_kpELE, float *g_kiELE, float *g_kdELE,
00232                float *g_kpRUD, float *g_kiRUD, float *g_kdRUD,
00233                float *g_rightloopROLL, float *g_rightloopPITCH,
00234                float *g_leftloopROLL, float *g_leftloopPITCH,
00235                float *g_gostraightROLL, float *g_gostraightPITCH,
00236                float *g_takeoffTHR, float *g_loopTHR,
00237                float *g_rightloopROLLshort, float *g_rightloopPITCHshort,
00238                float *g_leftloopROLLshort, float *g_leftloopPITCHshort,
00239                float *g_glideloopROLL, float *g_glideloopPITCH,
00240                float *g_kpAIL, float *g_kiAIL, float *g_kdAIL,
00241                int *g_rightloopRUD, int *g_rightloopshortRUD,
00242                int *g_leftloopRUD, int *g_leftloopshortRUD,
00243                int *g_glideRUD,
00244                int *g_AIL_L_correctionrightloop,int *g_AIL_L_correctionrightloopshort,
00245                int *g_AIL_L_correctionlefttloop,int *g_AIL_L_correctionleftloopshort
00246                );
00247 //switch2割り込み
00248 void ResetTrim();
00249 
00250 //自動操縦
00251 void UpdateTargetAngle_GoStraight(float targetAngle[3]);
00252 void UpdateTargetAngle_GoStraight_zero(float targetAngle[3]);       //着陸時にスロットルが0の時の直進
00253 void UpdateTargetAngle_Rightloop(float targetAngle[3]);
00254 void UpdateTargetAngle_Rightloop_short(float targetAngle[3]);
00255 void UpdateTargetAngle_Rightloop_zero(float targetAngle[3]);      //着陸時にスロットルが0の時の右旋回
00256 void UpdateTargetAngle_Leftloop(float targetAngle[3]);
00257 void UpdateTargetAngle_Leftloop_short(float targetAngle[3]);
00258 void UpdateTargetAngle_Leftloop_zero(float targetAngle[3]);     //着陸時にスロットルが0の時の左旋回
00259 void UpdateTargetAngle_Moebius(float targetAngle[3]);
00260 void UpdateTargetAngle_Glide(float targetAngle[3]);
00261 void UpdateTargetAngle_Takeoff(float targetAngle[3]);
00262 void UpdateTargetAngle_Approach(float targetAngle[3]);
00263 void Take_off_and_landing(float targetAngle[3]);
00264 
00265 int Rotate(float targetAngle[3], float TargetYAW);
00266 
00267 //投下
00268 void Chicken_Drop();
00269 void ReturnChickenServo1();
00270 void ReturnChickenServo2();
00271 
00272 //超音波による高度補正
00273 void checkHeight(float targetAngle[3]);
00274 void UpdateTargetAngle_NoseUP(float targetAngle[3]);
00275 void UpdateTargetAngle_NoseDOWN(float targetAngle[3]);
00276 
00277 //デバッグ用
00278 void Sbusprintf();
00279 void DebugPrint();
00280 
00281 /*---関数のプロトタイプ宣言終わり---*/
00282 
00283 int main()
00284 {   
00285     setup();
00286     
00287     
00288     while(1){
00289         
00290         loop();
00291         
00292         
00293         NVIC_DisableIRQ(USART1_IRQn);
00294         if(!CheckSW_Up(Ch7)){
00295             led3=0;
00296         }else{
00297             led3=1;
00298         }
00299         NVIC_EnableIRQ(USART1_IRQn);
00300     }
00301     
00302 }
00303 
00304 void setup(){
00305     //buzzer = 0;
00306     led1 = 1;
00307     led2 = 1;
00308     led3 = 1;
00309     led4 = 1;
00310     
00311     SetOptions(&g_kpELE, &g_kiELE, &g_kdELE,
00312                &g_kpRUD, &g_kiRUD, &g_kdRUD,
00313                &g_rightloopROLL, &g_rightloopPITCH,
00314                &g_leftloopROLL, &g_leftloopPITCH,
00315                &g_gostraightROLL, &g_gostraightPITCH,
00316                &g_takeoffTHR, &g_loopTHR,
00317                &g_rightloopROLLshort, &g_rightloopPITCHshort,
00318                &g_leftloopROLLshort, &g_leftloopPITCHshort,
00319                &g_glideloopROLL, &g_glideloopPITCH,
00320                &g_kpAIL, &g_kiAIL,&g_kdAIL,
00321                &g_rightloopRUD, &g_rightloopshortRUD,
00322                &g_leftloopRUD, &g_leftloopshortRUD,
00323                &g_glideloopRUD,
00324                &g_AIL_L_correctionrightloop,&g_AIL_L_correctionrightloopshort,
00325                &g_AIL_L_correctionleftloop,&g_AIL_L_correctionleftloopshort
00326                );    
00327     
00328         
00329     Init_PWM();
00330     Init_servo();
00331     Init_sbus();    
00332     Init_sensors();
00333     //switch2.rise(ResetTrim);
00334    
00335     USsensor.attach(&UpdateDist, 0.05);
00336     
00337     NVIC_SetPriority(USART1_IRQn,0);
00338     NVIC_SetPriority(EXTI0_IRQn,1);
00339     NVIC_SetPriority(TIM5_IRQn,2);
00340     NVIC_SetPriority(EXTI9_5_IRQn,3);
00341     DisplayClock();
00342     t.start();
00343     
00344     
00345     pc.printf("MPU calibration start\r\n");
00346     
00347     float offsetstart = t.read();
00348     while(t.read() - offsetstart < 26){
00349         SensingMPU();
00350         for(uint8_t i=0; i<3; i++) pc.printf("%3.2f\t",nowAngle[i]);
00351         pc.printf("\r\n");
00352         led1 = !led1;
00353         led2 = !led2;
00354         led3 = !led3;
00355         led4 = !led4;
00356     }
00357     
00358      pc.attach(getSF_Serial, Serial::RxIrq);
00359      NVIC_SetPriority(USART2_IRQn,4);
00360     
00361     FirstROLL = nowAngle[ROLL];
00362     FirstPITCH = nowAngle[PITCH];
00363     nowAngle[ROLL] -=FirstROLL;
00364     nowAngle[PITCH] -=FirstPITCH;
00365     
00366     led1 = 0;
00367     led2 = 0;
00368     led3 = 0;
00369     led4 = 0;
00370     wait(0.2);
00371     
00372     
00373     pc.printf("All initialized\r\n");
00374 }
00375 
00376 void loop(){
00377     static float targetAngle[3] = {0.0, 0.0, 0.0}, controlValue[2] = {0.0, 0.0};
00378     SensingMPU();
00379     UpdateTargetAngle(targetAngle);
00380     CalculateControlValue(targetAngle, controlValue);
00381     UpdateAutoPWM(controlValue);
00382    
00383     
00384     //NVIC_SetPriority(TIM5_IRQn,4);
00385     //NVIC_SetPriority(USART2_IRQn,2);
00386     
00387     wait_ms(23);
00388     
00389     //NVIC_SetPriority(TIM5_IRQn,2);
00390     //NVIC_SetPriority(USART2_IRQn,4);
00391     
00392     
00393    // pc.printf("6\r\n");
00394     //NVIC_DisableIRQ(USART2_IRQn);
00395     //pc.printf("%c",g_landingcommand);
00396     //NVIC_EnableIRQ(USART2_IRQn);
00397 #if DEBUG_PRINT_INLOOP
00398     //Sbusprintf();
00399     DebugPrint();
00400 #endif
00401 }
00402 
00403 //サーボ初期化関数
00404 void Init_servo(){
00405     
00406     servo1.period_ms(14);
00407     servo1.pulsewidth_us(trimpwm[AIL_R]);
00408     
00409     servo2.period_ms(14);
00410     servo2.pulsewidth_us(trimpwm[ELE]);
00411     
00412     servo3.period_ms(14);
00413     servo3.pulsewidth_us(trimpwm[THR]);
00414     
00415     servo4.period_ms(14);
00416     servo4.pulsewidth_us(trimpwm[RUD]);
00417     
00418     servo5.period_ms(14);
00419     servo5.pulsewidth_us(trimpwm[DROP]);
00420 
00421     servo6.period_ms(14);
00422     servo6.pulsewidth_us(trimpwm[AIL_L]);
00423 
00424     pc.printf("servo initialized\r\n");
00425 }
00426 
00427 //Sbus初期化
00428 void Init_sbus(){
00429     sbus.initialize();
00430     sbus.setLastfuncPoint(Update_PWM);
00431     sbus.startInterrupt();
00432 }
00433 
00434 void Init_sensors(){
00435     if(mpu6050.setup() == -1){
00436         pc.printf("failed initialize\r\n");
00437         while(1){
00438             led1 = 1; led2 = 0; led3 = 1; led4 = 0;
00439             wait(1);
00440             led1 = 0; led2 = 1; led3 = 0; led4 = 1;
00441             wait(1);
00442         }
00443     }
00444 }
00445 
00446 void Init_PWM(){
00447     pc.printf("PWM initialized\r\n");
00448 }
00449 
00450 void DisplayClock(){
00451     pc.printf("System Clock = %d[MHz]\r\n", HAL_RCC_GetSysClockFreq()/1000000);
00452     pc.printf("HCLK Clock   = %d[MHz]\r\n", HAL_RCC_GetHCLKFreq()/1000000);
00453     pc.printf("PCLK1 Clock  = %d[MHz]\r\n", HAL_RCC_GetPCLK1Freq()/1000000);
00454     pc.printf("PCLK2 Clock  = %d[MHz]\r\n", HAL_RCC_GetPCLK2Freq()/1000000);
00455     pc.printf("\r\n");
00456 }
00457 
00458 void UpdateTargetAngle(float targetAngle[3]){
00459     
00460     
00461     static int16_t count_op = 0;
00462 #if DEBUG_SEMIAUTO    
00463     switch(operation_mode){
00464         case StartUp:
00465             if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)){
00466                 count_op++;
00467                 if(count_op > changeModeCount){
00468                     operation_mode = SemiAuto;
00469                     pc.printf("Goto SemiAuto mode\r\n");
00470                     count_op = 0;
00471                 }
00472             }else count_op = 0;
00473             break;
00474 
00475         case SemiAuto:
00476         /*  大会用では以下のif文を入れてoperation_modeを変える
00477             if(CheckSW_Up(Ch6)){
00478                 count_op++;
00479                 if(count_op>changeModeCount){
00480                     output_status = XXX;
00481                     led2 = 0;
00482                     pc.printf("Goto XXX mode\r\n");
00483                     count_op = 0;
00484                 }else count_op = 0;
00485                 ConvertPWMintoRAD(targetAngle);
00486             }
00487         */
00488             ConvertPWMintoRAD(targetAngle);
00489             break;
00490 
00491         default:
00492             operation_mode = SemiAuto;
00493             break;
00494     }
00495 
00496 #else
00497 
00498     switch(operation_mode){
00499         case StartUp:
00500             if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)){        //ch7;自動・手動切り替え ch8;自動操縦モード切替
00501                 count_op++;
00502                 if(count_op > changeModeCount){
00503                     operation_mode = RightLoop;
00504                     pc.printf("Goto RightLoop mode\r\n");
00505                     count_op = 0;
00506                 }
00507             }else count_op = 0;
00508             break;
00509 
00510         case RightLoop:
00511             if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)){
00512                 count_op++;
00513                 if(count_op > changeModeCount){
00514                     operation_mode = LeftLoop;
00515                     pc.printf("Goto LeftLoop mode\r\n");
00516                     count_op = 0;
00517                 }
00518             }else count_op = 0;
00519             UpdateTargetAngle_Rightloop(targetAngle);
00520             
00521             break;
00522 
00523         case LeftLoop:
00524             if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)){
00525                 count_op++;
00526                 if(count_op > changeModeCount){
00527                     operation_mode = GoStraight;
00528                     pc.printf("Goto GoStraight mode\r\n");
00529                     count_op = 0;
00530                 }
00531             }else count_op = 0;
00532             UpdateTargetAngle_Leftloop(targetAngle);
00533             break;
00534         
00535         case GoStraight:
00536             if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)){
00537                 count_op++;
00538                 if(count_op > changeModeCount){
00539                     operation_mode = Moebius;
00540                     pc.printf("Goto Moebius mode\r\n");
00541                     count_op = 0;
00542                 }
00543             }else count_op = 0;
00544             UpdateTargetAngle_GoStraight(targetAngle);
00545             break;
00546 
00547         case Moebius:
00548             if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)){
00549                 count_op++;
00550                 if(count_op > changeModeCount){
00551                     operation_mode = Glide;
00552                     pc.printf("Goto Glide mode\r\n");
00553                     count_op = 0;
00554                 }
00555             }else count_op = 0;
00556             UpdateTargetAngle_Moebius(targetAngle);
00557             break;
00558 
00559         case Glide:
00560             if(!CheckSW_Up(Ch7) && CheckSW_Up(Ch8)){
00561                 count_op++;
00562                 if(count_op > changeModeCount){
00563                     operation_mode = BombwithPC;
00564                     pc.printf("Goto Bombing mode\r\n");
00565                     pc.attach(getSF_Serial, Serial::RxIrq);
00566                     count_op = 0;
00567                 }
00568             }else count_op = 0;
00569             UpdateTargetAngle_Glide(targetAngle);
00570             break;
00571 
00572         case BombwithPC:
00573             if(!CheckSW_Up(Ch7) && !CheckSW_Up(Ch8)){
00574                 count_op++;
00575                 if(count_op > changeModeCount){
00576                     operation_mode = RightLoop;
00577                     pc.printf("Goto RightLoop mode\r\n");
00578                     pc.attach(NULL, Serial::RxIrq);
00579                     count_op = 0;
00580                 }
00581             }else count_op = 0;
00582             Take_off_and_landing(targetAngle);
00583             break;
00584 
00585         default:
00586             operation_mode = StartUp;
00587             break;
00588     }
00589 #endif
00590 
00591     if(CheckSW_Up(Ch7)){
00592             output_status = Auto;
00593             led1 = 1;
00594         }else{
00595             output_status = Manual;
00596             led1 = 0;
00597         }
00598 
00599    
00600 }
00601 
00602 int GetParameter(FILE *fp, const char *paramName,char parameter[]){
00603     int i=0, j=0;
00604     int strmax = 200;
00605     char str[strmax];
00606 
00607     rewind(fp); //ファイル位置を先頭に
00608     while(1){
00609         if (fgets(str, strmax, fp) == NULL) {
00610             return 0;
00611         }
00612         if (!strncmp(str, paramName, strlen(paramName))) {
00613             while (str[i++] != '=') {}
00614             while (str[i] != '\n') {
00615                     parameter[j++] = str[i++];
00616             }
00617             parameter[j] = '\0';
00618             return 1;
00619         }
00620     }
00621 }
00622 
00623 
00624 //sdによる設定
00625 int SetOptions(float *g_kpELE, float *g_kiELE, float *g_kdELE,
00626                float *g_kpRUD, float *g_kiRUD, float *g_kdRUD,
00627                float *g_rightloopROLL, float *g_rightloopPITCH,
00628                float *g_leftloopROLL, float *g_leftloopPITCH,
00629                float *g_gostraightROLL, float *g_gostraightPITCH,
00630                float *g_takeoffTHR, float *g_loopTHR,
00631                float *g_rightloopROLLshort, float *g_rightloopPITCHshort,
00632                float *g_leftloopROLLshort, float *g_leftloopPITCHshort,
00633                float *g_glideloopROLL, float *g_glideloopPITCH,
00634                float *g_kpAIL, float *g_kiAIL, float *g_kdAIL,
00635                int *g_rightloopRUD, int *g_rightloopshortRUD,
00636                int *g_leftloopRUD, int *g_leftloopshortRUD,
00637                int *g_glideloopRUD,
00638                int *g_AIL_L_correctionrightloop,int *g_AIL_L_correctionrightloopshort,
00639                int *g_AIL_L_correctionleftloop,int *g_AIL_L_correctionleftloopshort
00640                ){
00641 
00642     pc.printf("SDsetup start.\r\n");    
00643     
00644     FILE *fp;
00645     char parameter[40]; //文字列渡す用の配列
00646     int SDerrorcount = 0;  //取得できなかった数を返す
00647     const char *paramNames[] = { 
00648         "KP_ELEVATOR",
00649         "KI_ELEVATOR",
00650         "KD_ELEVATOR",
00651         "KP_RUDDER",
00652         "KI_RUDDER",
00653         "KD_RUDDER",
00654         "RIGHTLOOP_ROLL",
00655         "RIGHTLOOP_PITCH",
00656         "LEFTLOOP_ROLL",
00657         "LEFTLOOP_PITCH",
00658         "GOSTRAIGHT_ROLL",
00659         "GOSTRAIGHT_PITCH",
00660         "TAKEOFF_THR_RATE",
00661         "LOOP_THR_RATE",
00662         "RIGHTLOOP_ROLL_SHORT",
00663         "RIGHTLOOP_PITCH_SHORT",
00664         "LEFTLOOP_ROLL_SHORT",
00665         "LEFTLOOP_PITCH_SHORT",
00666         "AUTOGLIDE_ROLL",
00667         "AUTOGLIDE PITCH",
00668         "KP_AILERON",
00669         "KI_AILERON",
00670         "KD_AILERON",
00671         "RIGHTLOOP_RUDDER",
00672         "RIGHTLOOPSHORT_RUDDER",
00673         "LEFTLOOP_RUDDER",
00674         "LEFTLOOPSHORT_RUDDER",
00675         "GLIDELOOP_RUDDER",
00676         "AILERON_LEFT_CORRECTION_RIGHTLOOP",        
00677         "AILERON_LEFT_CORRECTION_RIGHTLOOPSHORT",        
00678         "AILERON_LEFT_CORRECTION_LEFTLOOP",        
00679         "AILERON_LEFT_CORRECTION_LEFTLOOPSHORT"            
00680     };
00681 
00682     fp = fopen("/sd/option.txt","r");
00683     
00684     if(fp != NULL){ //開けたら
00685         pc.printf("File was openned.\r\n");
00686         if(GetParameter(fp,paramNames[0],parameter)) *g_kpELE = atof(parameter);
00687         else{                                        *g_kpELE = KP_ELE;
00688                                                      SDerrorcount++;
00689         }
00690         if(GetParameter(fp,paramNames[1],parameter)) *g_kiELE = atof(parameter);
00691         else{                                        *g_kiELE = KI_ELE;
00692                                                       SDerrorcount++;
00693         }
00694         if(GetParameter(fp,paramNames[2],parameter)) *g_kdELE = atof(parameter);
00695         else{                                        *g_kdELE = KD_ELE;
00696                                                      SDerrorcount++;
00697         }
00698         if(GetParameter(fp,paramNames[3],parameter)) *g_kpRUD = atof(parameter);
00699         else{                                        *g_kpRUD = KP_RUD;
00700                                                       SDerrorcount++;
00701         }
00702         if(GetParameter(fp,paramNames[4],parameter)) *g_kiRUD = atof(parameter);
00703         else{                                        *g_kiRUD = KI_RUD;
00704                                                       SDerrorcount++;
00705         }
00706         if(GetParameter(fp,paramNames[5],parameter)) *g_kdRUD = atof(parameter);
00707         else{                                        *g_kdRUD = KD_RUD;
00708                                                       SDerrorcount++;
00709         }
00710         if(GetParameter(fp,paramNames[6],parameter)) *g_rightloopROLL = atof(parameter);
00711         else{                                        *g_rightloopROLL = RIGHT_ROLL;
00712                                                       SDerrorcount++;
00713         }
00714         if(GetParameter(fp,paramNames[7],parameter)) *g_rightloopPITCH = atof(parameter);
00715         else{                                        *g_rightloopPITCH = RIGHT_PITCH;
00716                                                       SDerrorcount++;
00717         }
00718         if(GetParameter(fp,paramNames[8],parameter)) *g_leftloopROLL = atof(parameter);
00719         else{                                        *g_leftloopROLL = LEFT_ROLL;
00720                                                       SDerrorcount++;
00721         }
00722         if(GetParameter(fp,paramNames[9],parameter)) *g_leftloopPITCH = atof(parameter);
00723         else{                                         *g_leftloopPITCH = LEFT_PITCH;
00724                                                       SDerrorcount++;
00725         }
00726         if(GetParameter(fp,paramNames[10],parameter)) *g_gostraightROLL = atof(parameter);
00727         else{                                         *g_gostraightROLL = STRAIGHT_ROLL;
00728                                                       SDerrorcount++;
00729         }
00730         if(GetParameter(fp,paramNames[11],parameter)) *g_gostraightPITCH = atof(parameter);
00731         else{                                         *g_gostraightPITCH = STRAIGHT_PITCH;
00732                                                       SDerrorcount++;
00733         }
00734         if(GetParameter(fp,paramNames[12],parameter)) *g_takeoffTHR = atof(parameter);
00735         else{                                         *g_takeoffTHR = TAKEOFF_THR;
00736                                                       SDerrorcount++;
00737         }
00738         if(GetParameter(fp,paramNames[13],parameter)) *g_loopTHR = atof(parameter);
00739         else{                                         *g_loopTHR = LOOP_THR;
00740                                                       SDerrorcount++;
00741         }
00742         if(GetParameter(fp,paramNames[14],parameter)) *g_rightloopROLLshort = atof(parameter);
00743         else{                                         *g_rightloopROLLshort = RIGHT_ROLL_SHORT;
00744                                                       SDerrorcount++;
00745         }
00746         if(GetParameter(fp,paramNames[15],parameter)) *g_rightloopPITCHshort = atof(parameter);
00747         else{                                         *g_rightloopPITCHshort = RIGHT_PITCH_SHORT;
00748                                                       SDerrorcount++;
00749         }
00750         if(GetParameter(fp,paramNames[16],parameter)) *g_leftloopROLLshort = atof(parameter);
00751         else{                                         *g_leftloopROLLshort = LEFT_ROLL_SHORT;
00752                                                       SDerrorcount++;
00753         }
00754         if(GetParameter(fp,paramNames[17],parameter)) *g_leftloopPITCHshort = atof(parameter);
00755         else{                                         *g_leftloopPITCHshort = LEFT_PITCH_SHORT;
00756                                                       SDerrorcount++;
00757         }
00758         if(GetParameter(fp,paramNames[18],parameter)) *g_glideloopROLL = atof(parameter);
00759         else{                                         *g_glideloopROLL = GLIDE_ROLL;
00760                                                       SDerrorcount++;
00761         }
00762         if(GetParameter(fp,paramNames[19],parameter)) *g_glideloopPITCH = atof(parameter);
00763         else{                                         *g_glideloopPITCH = GLIDE_PITCH;
00764                                                       SDerrorcount++;
00765         }
00766         if(GetParameter(fp,paramNames[20],parameter)) *g_kpAIL = atof(parameter);
00767         else{                                         *g_kpAIL = KP_AIL;
00768                                                       SDerrorcount++;
00769         }
00770         if(GetParameter(fp,paramNames[21],parameter)) *g_kiAIL = atof(parameter);
00771         else{                                         *g_kiAIL = KI_AIL;
00772                                                       SDerrorcount++;
00773         }
00774         if(GetParameter(fp,paramNames[22],parameter)) *g_kdAIL = atof(parameter);
00775         else{                                         *g_kdAIL = KP_AIL;
00776                                                       SDerrorcount++;
00777         }
00778         if(GetParameter(fp,paramNames[23],parameter)) *g_rightloopRUD = atof(parameter);
00779         else{                                         *g_rightloopRUD = RIGHTLOOP_RUD;
00780                                                       SDerrorcount++;
00781         }
00782         if(GetParameter(fp,paramNames[24],parameter)) *g_rightloopshortRUD = atof(parameter);
00783         else{                                         *g_rightloopshortRUD = RIGHTLOOPSHORT_RUD;
00784                                                       SDerrorcount++;
00785         }
00786         if(GetParameter(fp,paramNames[25],parameter)) *g_leftloopRUD = atof(parameter);
00787         else{                                         *g_leftloopshortRUD = LEFTLOOP_RUD;
00788                                                       SDerrorcount++;
00789         }
00790         if(GetParameter(fp,paramNames[26],parameter)) *g_leftloopshortRUD = atof(parameter);
00791         else{                                         *g_leftloopshortRUD = LEFTLOOPSHORT_RUD;
00792                                                       SDerrorcount++;
00793         }
00794         if(GetParameter(fp,paramNames[27],parameter)) *g_glideloopRUD = atof(parameter);
00795         else{                                         *g_glideloopRUD = GLIDELOOP_RUD;
00796                                                       SDerrorcount++;
00797         }
00798         if(GetParameter(fp,paramNames[28],parameter)) *g_AIL_L_correctionrightloop = atof(parameter);
00799         else{                                         *g_AIL_L_correctionrightloop = AIL_L_CORRECTION_RIGHTLOOP;
00800                                                       SDerrorcount++;
00801         }
00802         if(GetParameter(fp,paramNames[29],parameter)) *g_AIL_L_correctionrightloopshort = atof(parameter);
00803         else{                                         *g_AIL_L_correctionrightloopshort = AIL_L_CORRECTION_RIGHTLOOPSHORT;
00804                                                       SDerrorcount++;
00805         }
00806         if(GetParameter(fp,paramNames[30],parameter)) *g_AIL_L_correctionleftloop = atof(parameter);
00807         else{                                         *g_AIL_L_correctionleftloop = AIL_L_CORRECTION_LEFTLOOP;
00808                                                       SDerrorcount++;
00809         }
00810         if(GetParameter(fp,paramNames[31],parameter)) *g_AIL_L_correctionleftloopshort = atof(parameter);
00811         else{                                         *g_AIL_L_correctionleftloopshort = AIL_L_CORRECTION_LEFTLOOPSHORT;
00812                                                       SDerrorcount++;
00813         }
00814         
00815         fclose(fp);
00816 
00817     }else{  //ファイルがなかったら
00818         pc.printf("fp was null.\r\n");
00819         *g_kpELE = KP_ELE;
00820         *g_kiELE = KI_ELE;
00821         *g_kdELE = KD_ELE;
00822         *g_kpRUD = KP_RUD;
00823         *g_kiRUD = KI_RUD;
00824         *g_kdRUD = KD_RUD;
00825         *g_rightloopROLL = RIGHT_ROLL;
00826         *g_rightloopPITCH = RIGHT_PITCH;
00827         *g_leftloopROLL = LEFT_ROLL;
00828         *g_leftloopPITCH = LEFT_PITCH;
00829         *g_gostraightROLL = STRAIGHT_ROLL;
00830         *g_gostraightPITCH = STRAIGHT_PITCH;
00831         *g_takeoffTHR = TAKEOFF_THR;
00832         *g_loopTHR = LOOP_THR;
00833         *g_kpAIL = KP_AIL; //パラメータ変えるのお忘れなく!!
00834         *g_kiAIL = KI_AIL;
00835         *g_kdAIL = KD_AIL;
00836         *g_rightloopRUD = RIGHTLOOP_RUD;
00837         *g_rightloopshortRUD = RIGHTLOOPSHORT_RUD;
00838         *g_leftloopRUD = LEFTLOOP_RUD;
00839         *g_leftloopshortRUD = LEFTLOOPSHORT_RUD;
00840         *g_glideloopRUD = GLIDELOOP_RUD;
00841         *g_AIL_L_correctionrightloop = AIL_L_CORRECTION_RIGHTLOOP;
00842         *g_AIL_L_correctionrightloopshort = AIL_L_CORRECTION_RIGHTLOOPSHORT;
00843         *g_AIL_L_correctionleftloop = AIL_L_CORRECTION_LEFTLOOP;
00844         *g_AIL_L_correctionleftloopshort = AIL_L_CORRECTION_LEFTLOOPSHORT;
00845         
00846         
00847         SDerrorcount = -1;
00848     }
00849     pc.printf("SDsetup finished.\r\n");
00850     if(SDerrorcount == 0)  pc.printf("setting option is success\r\n");
00851     else if(SDerrorcount == -1) pc.printf("ERROR 1. cannot open option\r\n");
00852     else if(SDerrorcount > 0)  pc.printf("ERROR 2. reading parameter is failed[%d]\r\n",SDerrorcount); 
00853     
00854     pc.printf("kpELE = %f, kiELE = %f, kdELE = %f\r\n", *g_kpRUD, *g_kiRUD, *g_kdRUD);
00855     pc.printf("kpRUD = %f, kiRUD = %f, kdRUD = %f\r\n", *g_kpELE, *g_kiELE, *g_kdELE);
00856     pc.printf("rightloopROLL = %f, rightloopPITCH = %f\r\n", *g_rightloopROLL, *g_rightloopPITCH);
00857     pc.printf("leftloopROLL = %f, g_leftloopPITCH =  %f\r\n", *g_leftloopROLL, *g_leftloopPITCH);
00858     pc.printf("gostraightROLL = %f, g_gostraightPITCH = %f\r\n", *g_gostraightROLL, *g_gostraightPITCH);
00859     pc.printf("g_takeoffTHR = %f, g_loopTHR = %f\r\n", *g_takeoffTHR, *g_loopTHR);
00860     pc.printf("rightloopROLLshort = %f, rightloopPITCHshort = %f\r\n", *g_rightloopROLLshort, *g_rightloopPITCHshort);
00861     pc.printf("leftloopROLLshort = %f, g_leftloopPITCHshort =  %f\r\n", *g_leftloopROLLshort, *g_leftloopPITCHshort);
00862     pc.printf("glideROLL = %f, glidePITCH = %f\r\n", *g_glideloopROLL, *g_glideloopPITCH);
00863     pc.printf("kpAIL = %f,kiAIL = %f,kdAIL = %f\r\n ",*g_kpAIL,*g_kiAIL,*g_kdAIL);
00864     pc.printf("RIGHTLOOPRUD = %d,RIGHTLOOPSHORTRUD = %d\r\n",*g_rightloopRUD,*g_rightloopshortRUD);
00865     pc.printf("LEFTTLOOPRUD = %d,LEFTLOOPSHORTRUD = %d\r\n",*g_leftloopRUD,*g_leftloopshortRUD);
00866     pc.printf("GLIDELOOPRUD = %d\r\n",*g_glideloopRUD);
00867     pc.printf("AIL_L_CORRECTION_RIGHTLOOP = %d, AIL_L_CORRECTION_RIGHTLOOPSHORT = %d\r\n",*g_AIL_L_correctionrightloop,*g_AIL_L_correctionrightloopshort);
00868     pc.printf("AIL_L_CORRECTION_LEFTLOOP = %d, AIL_L_CORRECTION_LEFTLOOPSHORT = %d\r\n",*g_AIL_L_correctionleftloop,*g_AIL_L_correctionleftloopshort);
00869     return SDerrorcount;
00870 }                  
00871 
00872 void CalculateControlValue(float targetAngle[3], float controlValue[3]){
00873     
00874     static int t_last;
00875     int t_now;
00876     float dt;
00877 
00878     t_now = t.read_us();
00879     dt = (float)((t_now - t_last)/1000000.0f) ;
00880     t_last = t_now;
00881 
00882 
00883     //controlValue[ROLL] = pid_RUD.calcPID(nowAngle[ROLL], targetAngle[ROLL], dt);
00884     controlValue[ROLL] = pid_AIL.calcPID(nowAngle[ROLL], targetAngle[ROLL], dt);       //エルロンでロール制御   
00885     controlValue[PITCH] = pid_ELE.calcPID(nowAngle[PITCH], targetAngle[PITCH], dt);
00886     
00887 }
00888 
00889 void UpdateAutoPWM(float controlValue[3]){ 
00890     NVIC_DisableIRQ(USART1_IRQn);   
00891     int16_t addpwm[2]; //-500~500
00892     addpwm[PITCH] = (float)GAIN_CONTROLVALUE_TO_PWM * controlValue[PITCH];    //センサ:機首下げ正    レバー:機首上げ正
00893     addpwm[ROLL] = (float)GAIN_CONTROLVALUE_TO_PWM * controlValue[ROLL];           //センサ:右回転正(8月13日時点;左回転が正!)     レバー:右回転正
00894     
00895     autopwm[ELE] = trimpwm[ELE] + reverce[ELE] * addpwm[PITCH];                 //rewrite
00896     autopwm[AIL_R] = trimpwm[AIL_R] - reverce[AIL_R] * addpwm[ROLL];
00897     //autopwm[THR] = oldTHR;
00898 
00899     autopwm[ELE] = ThresholdMaxMin(autopwm[ELE], maxpwm[ELE], minpwm[ELE]);
00900     autopwm[AIL_R] = ThresholdMaxMin(autopwm[AIL_R], maxpwm[AIL_R], minpwm[AIL_R]);
00901     
00902     NVIC_EnableIRQ(USART1_IRQn);
00903 }
00904 
00905 inline float CalcRatio(float value, float trim, float limit){
00906     return  (value - trim) / (limit - trim);
00907 }
00908 
00909 bool CheckSW_Up(Channel ch){
00910     
00911     if(SWITCH_CHECK < sbus.manualpwm[ch]){
00912         return true;
00913     }else{
00914         return false;
00915     }
00916     
00917 }
00918 
00919 int16_t ThresholdMaxMin(int16_t value, int16_t max, int16_t min){
00920     if(value > max) return max;
00921     if(value < min) return min;
00922     return value;
00923 }
00924 
00925 inline int16_t SetTHRinRatio(float ratio){
00926     return minpwm[THR] + (int16_t)(2 * lengthdivpwm * ratio);
00927 }
00928 
00929 
00930 
00931 /*---SBUS割り込み処理---*/
00932 
00933 //udate_Inputで抽出したpwmデータを整形して各変数に代入する。(マニュアルモード)
00934 //各stabiGylo関数で算出したpwmを各変数に代入する(自動モード)
00935 void Update_PWM()
00936 {   
00937     NVIC_DisableIRQ(USART1_IRQn); 
00938     static int16_t pwm[6];
00939     static int16_t temppwm[6]={trimpwm[0],trimpwm[1],trimpwm[2],trimpwm[3],trimpwm[4],trimpwm[5]};
00940     static int16_t FailsafeCounter=0;
00941     static int16_t OKCounter=0;
00942     
00943     if(sbus.flg_ch_update == true && sbus.failsafe_status==SBUS_SIGNAL_OK){
00944     
00945         switch(output_status){    //マニュアルモード,自動モード,自動着陸もモードを切替
00946             case Manual:
00947         if(OKCounter!=0) break;
00948                 for(uint8_t i=0;i<6;i++){
00949                     pwm[i] = sbus.manualpwm[i];  
00950                 }
00951                 oldTHR = sbus.manualpwm[THR];
00952                 //pc.printf("update_manual\r\n");
00953                 NVIC_EnableIRQ(USART1_IRQn);
00954                 break;
00955         
00956             case Auto:
00957         if(OKCounter!=0) break;
00958                 pwm[AIL_R] = autopwm[AIL_R];               //sbus.manualpwm[AIL];
00959                 pwm[ELE] = autopwm[ELE];
00960                 pwm[THR] = autopwm[THR];
00961                 pwm[RUD] = autopwm[RUD];
00962                 pwm[DROP] = autopwm[DROP];
00963                 pwm[AIL_L] = autopwm[AIL_L];
00964  
00965                 NVIC_EnableIRQ(USART1_IRQn);
00966                 break;
00967                 
00968             default:
00969         if(OKCounter!=0) break;
00970                 for(uint8_t i=0;i<6;i++){
00971                     pwm[i] = sbus.manualpwm[i];
00972                 } //pc.printf("update_manual\r\n");
00973                 NVIC_EnableIRQ(USART1_IRQn);
00974                 break;
00975         }
00976         
00977         for(uint8_t i=0;i<6;i++){
00978             if(pwm[i]<1000 || pwm[i]>2000) pwm[i]=temppwm[i];
00979             temppwm[i]=pwm[i];
00980         }
00981         
00982     }
00983     //else(sbus.flg_ch_update == false) pc.printf("0\r\n");
00984    /* if(sbus.failsafe_status==SBUS_SIGNAL_OK){
00985         pc.printf("OK\r\n");
00986         }
00987     */
00988     //pc.printf("%d\r\n",sbus.failsafe_status);
00989                     
00990     if(sbus.failsafe_status==SBUS_SIGNAL_LOST||sbus.failsafe_status==SBUS_SIGNAL_FAILSAFE) FailsafeCounter++;
00991     else FailsafeCounter=0;
00992         
00993         if(FailsafeCounter>10){
00994             for(uint8_t i=0;i<6;i++) pwm[i] = trimpwm[i];
00995             
00996         if(sbus.failsafe_status==SBUS_SIGNAL_OK) OKCounter++;
00997         if(OKCounter>10) {
00998                 OKCounter=0;
00999                 }
01000                 
01001             //pc.printf("%d\r\n",sbus.failsafe_status);
01002             //if(sbus.failsafe_status!=SBUS_SIGNAL_FAILSAFE)break;
01003             
01004         }
01005     //if(sbus.failsafe_status==SBUS_SIGNAL_OK){FailsafeCounter=0;}
01006     
01007     
01008     sbus.flg_ch_update = false;   
01009     Output_PWM(pwm);  
01010 }
01011  
01012  
01013 //pwmをサーボに出力。
01014 void Output_PWM(int16_t pwm[5])
01015 {
01016     NVIC_DisableIRQ(USART1_IRQn);
01017     servo1.pulsewidth_us(pwm[0]);
01018     servo2.pulsewidth_us(pwm[1]);
01019     servo3.pulsewidth_us(pwm[2]);
01020     servo4.pulsewidth_us(pwm[3]);
01021     servo5.pulsewidth_us(pwm[4]);
01022     servo6.pulsewidth_us(pwm[5]);
01023     NVIC_EnableIRQ(USART1_IRQn);
01024 
01025 }
01026 
01027 void ResetTrim(){
01028     for(uint8_t i=0; i<6; i++){            //i=4から書き換え_投下サーボは入ってない模様
01029         trimpwm[i] = sbus.manualpwm[i];
01030     }
01031     pc.printf("reset PWM trim\r\n");
01032 }
01033 
01034 
01035 void SensingMPU(){
01036     //static int16_t deltaT = 0, t_start = 0;
01037     //t_start = t.read_us();
01038     
01039     float rpy[3] = {0}, oldrpy[3] = {0};
01040     static uint16_t count_changeRPY = 0;
01041     static bool flg_checkoutlier = false;
01042     NVIC_DisableIRQ(USART1_IRQn);
01043     NVIC_DisableIRQ(USART2_IRQn);
01044     NVIC_DisableIRQ(TIM5_IRQn);
01045     NVIC_DisableIRQ(EXTI0_IRQn);//MPU割り込み禁止
01046     NVIC_DisableIRQ(EXTI9_5_IRQn);//超音波割り込み禁止
01047 
01048     mpu6050.getRollPitchYaw_Skipper(rpy);
01049  
01050     NVIC_EnableIRQ(USART1_IRQn);
01051     NVIC_EnableIRQ(USART2_IRQn);
01052     NVIC_EnableIRQ(TIM5_IRQn);
01053     NVIC_EnableIRQ(EXTI0_IRQn);
01054     NVIC_EnableIRQ(EXTI9_5_IRQn);
01055     
01056     
01057     //外れ値対策
01058     for(uint8_t i=0; i<3; i++) rpy[i] *= 180.0f/PI;
01059     rpy[ROLL] -= FirstROLL;
01060     rpy[PITCH] -= FirstPITCH;
01061     rpy[YAW] -= FirstYAW;
01062     
01063     for(uint8_t i=0; i<3; i++) {if(rpy[i] < nowAngle[i]-10 || rpy[i] > nowAngle[i]+10) {flg_checkoutlier = true;}}
01064     if(!flg_checkoutlier || count_changeRPY >= 2){
01065         for(uint8_t i=0; i<3; i++){
01066             nowAngle[i] = (rpy[i] + nowAngle[i])/2.0f;  //2つの移動平均
01067         }
01068         count_changeRPY = 0;
01069     }else   count_changeRPY++;
01070     flg_checkoutlier = false;
01071     
01072 }
01073 
01074 float TranslateNewYaw(float beforeYaw,  float newzeroYaw){
01075     float newYaw = beforeYaw - newzeroYaw;
01076     
01077     if(newYaw<-180.0f) newYaw += 360.0f;
01078     else if(newYaw>180.0f) newYaw -= 360.0f;
01079     return newYaw;
01080 }
01081 
01082 
01083 void getSF_Serial(){
01084     //NVIC_DisableIRQ(USART1_IRQn);
01085     //NVIC_DisableIRQ(EXTI0_IRQn);
01086     //NVIC_DisableIRQ(TIM5_IRQn);
01087 
01088 
01089         static char SFbuf[16]={'Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q','Q'};
01090 
01091         static int bufcounter=0;
01092         
01093        
01094         
01095         if(pc.readable()) {    // 受信確認
01096             
01097             SFbuf[bufcounter] = pc.getc();    // 1文字取り出し
01098           if(SFbuf[0]!='S'){
01099                  //pc.printf("x");
01100                  return;
01101           }  
01102         
01103                 
01104         
01105             //pc.printf("%c",SFbuf[bufcounter]);
01106             
01107             if(SFbuf[0]=='S'&&bufcounter<5)bufcounter++;
01108                 
01109             if(bufcounter==5 && SFbuf[4]=='F'){
01110                 
01111                 g_landingcommand = SFbuf[1];
01112                 //wait_ms(20);
01113                 //if(g_landingcommand=='Y')g_SerialTargetYAW = ConvertByteintoFloat(SFbuf[2], SFbuf[3]);
01114                 if(g_landingcommand=='Y')g_SerialTargetYAW =0.0f;
01115                 bufcounter = 0;
01116                 memset(SFbuf, 0, strlen(SFbuf));
01117                 NVIC_ClearPendingIRQ(USART2_IRQn);
01118                 //pc.printf("command = %c, commandYAW = %f\r\n", g_landingcommand, g_SerialTargetYAW); 
01119             }
01120             
01121             else if(bufcounter>=5){
01122                 //pc.printf("Communication Falsed.\r\n");
01123                 memset(SFbuf, 0, strlen(SFbuf));
01124                 bufcounter = 0;
01125                 NVIC_ClearPendingIRQ(USART2_IRQn);
01126             }
01127         }
01128                     
01129             //NVIC_EnableIRQ(TIM5_IRQn);
01130             //NVIC_EnableIRQ(EXTI0_IRQn);
01131             //NVIC_EnableIRQ(USART1_IRQn); 
01132     }
01133     
01134 float ConvertByteintoFloat(char high, char low){
01135 
01136         //int16_t intvalue = (int16_t)high*256 + (int16_t)low;
01137         int16_t intvalue = (int16_t)(((int16_t)high << 8) | low);  // Turn the MSB and LSB into a signed 16-bit value
01138         float floatvalue = (float)intvalue;
01139         return floatvalue;
01140 }
01141 
01142 
01143 //超音波割り込み
01144 void UpdateDist(){
01145     g_distance = usensor.get_dist_cm();
01146     usensor.start();
01147 }
01148 
01149 //8の字旋回
01150 void UpdateTargetAngle_Moebius(float targetAngle[3]){
01151     static uint8_t RotateCounter=0;
01152     static bool flg_setInStartAuto = false;
01153     static float FirstYAW_Moebius = 0.0;
01154     float newYaw_Moebius;
01155 
01156     if(!flg_setInStartAuto && CheckSW_Up(Ch7)){
01157         FirstYAW_Moebius = nowAngle[YAW];
01158         RotateCounter = 0;
01159         flg_setInStartAuto = true;
01160     }else if(!CheckSW_Up(Ch7)){
01161         flg_setInStartAuto = false;
01162         led2 = 0;
01163     }
01164     autopwm[THR]=oldTHR;
01165 
01166     newYaw_Moebius = TranslateNewYaw(nowAngle[YAW], FirstYAW_Moebius);
01167 
01168     if(RotateCounter == 0 && newYaw_Moebius >90.0 && newYaw_Moebius < 180.0)    {RotateCounter++; led2 = 1; pc.printf("Rotate 90\r\n");}
01169     if(RotateCounter == 1 && newYaw_Moebius >-180.0 && newYaw_Moebius < -90.0)  {RotateCounter++; led2 = 0; pc.printf("Rotate 180\r\n");}
01170     if(RotateCounter == 2 && newYaw_Moebius >-90.0 && newYaw_Moebius <-10.0)   {RotateCounter++; led2 = 1; pc.printf("Rotate 270\r\n");}
01171     if(RotateCounter == 3 && newYaw_Moebius >0.0 && newYaw_Moebius < 90.0)     {RotateCounter++; led2 = 0; pc.printf("Change Rotate direction\r\n");}
01172 
01173 
01174     if(RotateCounter <= 3) UpdateTargetAngle_Rightloop_short(targetAngle);    
01175     else UpdateTargetAngle_Leftloop_short(targetAngle);   //左旋回
01176 
01177 }
01178 
01179 //自動滑空
01180 void UpdateTargetAngle_Glide(float targetAngle[3]){
01181     static int THRcount = 0;
01182     static int t_start = 0;
01183     static bool flg_tstart = false;
01184     static bool flg_ground = false;
01185     int t_diff = 0;
01186     static int groundcount = 0;
01187     
01188     targetAngle[ROLL] = g_glideloopROLL;
01189     targetAngle[PITCH] = g_glideloopPITCH;
01190     
01191     autopwm[RUD]=g_glideloopRUD;
01192    // autopwm[THR]=oldTHR;
01193 
01194     
01195     
01196     //時間計測開始設定
01197     if(!flg_tstart && CheckSW_Up(Ch7)){
01198         t_start = t.read();
01199         flg_tstart = true;
01200         pc.printf("timer start\r\n");
01201     }else if(!CheckSW_Up(Ch7)){
01202         t_start = 0;
01203         flg_tstart = false;
01204     }
01205 
01206 
01207     //フラグが偽であれば計測は行わない    
01208     if(flg_tstart){
01209         t_diff = t.read() - t_start;
01210         //一定高度or15秒でled点灯
01211         NVIC_DisableIRQ(EXTI9_5_IRQn);
01212         if((groundcount>5 && g_distance>0) || t_diff > 15){
01213             led2 = 1;
01214             //pc.printf("Call [Stop!] calling!\r\n");
01215         }
01216         
01217         if(g_distance<180 && g_distance > 0) {
01218             groundcount++;
01219         }
01220         NVIC_EnableIRQ(EXTI9_5_IRQn);
01221     }else{
01222         t_diff = 0;
01223         groundcount = 0;
01224         led2 = 0;
01225     }
01226     
01227         NVIC_DisableIRQ(EXTI9_5_IRQn);
01228         if(t_diff > 17) autopwm[THR] = SetTHRinRatio(0.5);
01229         
01230         else if(g_distance<150 && g_distance>0 ){
01231             NVIC_DisableIRQ(EXTI9_5_IRQn);
01232             THRcount++;
01233             if(THRcount>5) flg_ground = true;
01234         }
01235         else THRcount = 0;
01236         NVIC_EnableIRQ(EXTI9_5_IRQn);
01237         
01238         if(flg_ground == true) autopwm[THR] = SetTHRinRatio(0.6);
01239         else autopwm[THR] = minpwm[THR];
01240         
01241         NVIC_DisableIRQ(USART1_IRQn);
01242         if(!CheckSW_Up(Ch7)){
01243             flg_ground = false;
01244             }
01245         NVIC_EnableIRQ(USART1_IRQn);
01246 }
01247 
01248 //離陸-投下-着陸一連
01249 void Take_off_and_landing(float targetAngle[3]){
01250     
01251     if(!CheckSW_Up(Ch7)) bombing_mode = Takeoff;
01252     
01253     switch(bombing_mode){
01254         case Takeoff:
01255             static bool flg_setFirstYaw = false;
01256             static int TakeoffCount = 0;
01257 
01258             if(!flg_setFirstYaw && CheckSW_Up(Ch7)){
01259                 FirstYAW = nowAngle[YAW];
01260                 flg_setFirstYaw = true;
01261             }else if(flg_setFirstYaw && !CheckSW_Up(Ch7)){
01262                 flg_setFirstYaw = false;
01263             }
01264             
01265             UpdateTargetAngle_Takeoff(targetAngle);
01266             NVIC_DisableIRQ(EXTI9_5_IRQn);
01267             if(g_distance>150) TakeoffCount++;
01268             else TakeoffCount = 0;
01269             NVIC_EnableIRQ(EXTI9_5_IRQn);
01270             if(TakeoffCount>5){
01271                 autopwm[THR] = 1180+320*2*0.5;
01272                 targetAngle[PITCH]=g_gostraightPITCH;
01273                 //pc.printf("Now go to Approach mode!!");
01274                 bombing_mode = Approach;
01275             }
01276             break;
01277            
01278         //case Chicken:    
01279             //break;
01280         /*    
01281         case Transition:
01282             static int ApproachCount = 0;
01283             targetAngle[YAW]=180.0;
01284             int Judge = Rotate(targetAngle, g_SerialTargetYAW);
01285             
01286             if(Judge==0) ApproachCount++;
01287             if(ApproachCount>5) bombing_mode = Approach;
01288             break;
01289             */
01290         case Approach:
01291         
01292             autopwm[THR] = SetTHRinRatio(g_loopTHR); //0.7;スロットルの割合
01293             UpdateTargetAngle_Approach(targetAngle);
01294             
01295             break;
01296             
01297         default:
01298             bombing_mode = Takeoff;
01299             break;    
01300     }
01301     
01302 }
01303 
01304 //離陸モード
01305 void UpdateTargetAngle_Takeoff(float targetAngle[3]){
01306     //pc.printf("%d \r\n",g_distance);
01307     static int tELE_start = 0;
01308     static bool flg_ELEup = false;
01309     int t_def = 0;
01310     
01311     autopwm[RUD] = trimpwm[RUD];
01312     
01313     
01314     if(!flg_ELEup && CheckSW_Up(Ch7)){
01315         tELE_start = t.read_ms();
01316         flg_ELEup = true;
01317         pc.printf("timer start\r\n");
01318     }else if(!CheckSW_Up(Ch7)){
01319         tELE_start = 0;
01320         flg_ELEup = false;
01321     }
01322     if(flg_ELEup){
01323         t_def = t.read_ms() - tELE_start;
01324         
01325         //1.5秒経過すればELE上げ舵へ
01326         if(t_def>500) targetAngle[PITCH]=-35.0;
01327         else{
01328             t_def = 0;
01329             targetAngle[PITCH]=g_gostraightPITCH;
01330         }
01331     }
01332     targetAngle[ROLL] = g_gostraightROLL;
01333     //targetAngle[PITCH] = g_loopTHR;
01334     autopwm[THR] = SetTHRinRatio(g_takeoffTHR); //0.7;スロットルの割合
01335 }
01336 
01337 
01338 //ヨーを目標値にして許容角度になるまで水平旋回
01339 int Rotate(float targetAngle[3], float TargetYAW){
01340     float diffYaw = TranslateNewYaw(TargetYAW, nowAngle[YAW]);
01341 
01342     if(diffYaw > LIMIT_STRAIGHT_YAW){
01343         /*
01344         if(diffYaw > THRESHOLD_TURNINGRADIUS_YAW) UpdateTargetAngle_Rightloop_short(targetAngle);
01345         else UpdateTargetAngle_Rightloop(targetAngle);
01346         */
01347         UpdateTargetAngle_Rightloop_short(targetAngle);
01348         return 1;
01349     }else if(diffYaw < -LIMIT_STRAIGHT_YAW){
01350         UpdateTargetAngle_Leftloop_short(targetAngle);
01351         /*
01352         if(diffYaw < -THRESHOLD_TURNINGRADIUS_YAW) UpdateTargetAngle_Leftloop_short(targetAngle);
01353         else UpdateTargetAngle_Leftloop(targetAngle);
01354         */
01355         return 1;
01356     }else{
01357         UpdateTargetAngle_GoStraight(targetAngle);
01358         return 0;
01359     }
01360 }
01361 
01362 //チキラー投下
01363 void Chicken_Drop(){
01364     if(CheckSW_Up(Ch7)){
01365         autopwm[DROP] = 1911;
01366         pc.printf("Bombed!\r\n");
01367         //RerurnChickenServo1.attach(&ReturnChickenServo1, 3);
01368         //operation_mode = Approach;
01369         //buzzer = 0;
01370         pc.printf("Goto LeftLoop mode\r\n");
01371     }
01372 }
01373 
01374 void ReturnChickenServo1(){
01375     autopwm[DROP] = 1344;
01376     pc.printf("first reverse\r\n");
01377     RerurnChickenServo2.attach(&ReturnChickenServo2, 1);
01378 }
01379 
01380 void ReturnChickenServo2(){
01381     autopwm[DROP] = 1392;
01382     pc.printf("second reverse\r\n");
01383     }
01384     
01385     //着陸モード(PCからの指令に従う)
01386 void UpdateTargetAngle_Approach(float targetAngle[3]){
01387        
01388        static bool zeroTHR=true;//着陸時のスロットル動作確認用
01389        
01390        if(CheckSW_Up(Ch7)){
01391             output_status = Auto;
01392             led1 = 1;
01393         }else{
01394             output_status = Manual;
01395             led1 = 0;
01396             zeroTHR=true;
01397         }
01398     
01399     
01400        NVIC_DisableIRQ(USART2_IRQn);
01401         switch(g_landingcommand){
01402             case 'R':   //右旋回セヨ
01403             if(zeroTHR==false){
01404                 UpdateTargetAngle_Rightloop_zero(targetAngle);
01405                 }
01406                 else{
01407                 targetAngle[ROLL] = g_rightloopROLL;
01408         targetAngle[PITCH] = g_rightloopPITCH ;
01409         autopwm[RUD]=g_rightloopRUD;              //RUD固定
01410             if(autopwm[AIL_R]<trimpwm[AIL_R]){                                                                                  //エルロン上がりやすさ調節
01411                 autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01412                 }
01413             else {autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01414             autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
01415             }
01416         }
01417         NVIC_EnableIRQ(USART2_IRQn);
01418                 break;
01419                 
01420                 case 'L':   //左旋回セヨ
01421                 if(zeroTHR==false){
01422                     UpdateTargetAngle_Leftloop_zero(targetAngle);
01423                 }
01424                     else{
01425                         targetAngle[ROLL] = g_leftloopROLL;
01426                         targetAngle[PITCH] = g_leftloopPITCH;
01427                         autopwm[RUD]=g_leftloopRUD;
01428                         if(autopwm[AIL_R]<trimpwm[AIL_R]){
01429                             autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01430                         }
01431                         else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01432                     }
01433                 NVIC_EnableIRQ(USART2_IRQn);
01434                 break;
01435                     
01436                 case 'G':   //直進セヨ
01437                 if(zeroTHR==false){
01438                     UpdateTargetAngle_GoStraight_zero(targetAngle);
01439                     }
01440                     else{
01441                     targetAngle[ROLL] = g_gostraightROLL;
01442                     targetAngle[PITCH] = g_gostraightPITCH;
01443     }
01444                     NVIC_EnableIRQ(USART2_IRQn);
01445                     break;
01446                 
01447                 case 'Y':   //指定ノヨー方向ニ移動セヨ
01448                     Rotate(targetAngle, g_SerialTargetYAW);
01449                     NVIC_EnableIRQ(USART2_IRQn);
01450                     break;
01451                 
01452                 /*case 'B':   //ブザーヲ鳴ラセ
01453                     //buzzer = 1;
01454                     NVIC_EnableIRQ(USART2_IRQn);
01455                     break;*/
01456                     
01457                 case 'B':   //物資ヲ落トセ
01458                     Chicken_Drop();
01459                     NVIC_EnableIRQ(USART2_IRQn);
01460                     break;
01461                             
01462                 case 'C':   //停止セヨ
01463                     targetAngle[ROLL] = 0.0;
01464                     targetAngle[PITCH] = -3.0;
01465                     autopwm[THR] = minpwm[THR];
01466                     zeroTHR=false;
01467                     NVIC_EnableIRQ(USART2_IRQn);
01468                     break;
01469                     
01470                 default :
01471                 NVIC_EnableIRQ(USART2_IRQn);
01472                 break;
01473                 
01474             
01475             }
01476             
01477 }
01478         
01479 void checkHeight(float targetAngle[3]){
01480         
01481         static int targetHeight = 200; 
01482        
01483         NVIC_DisableIRQ(EXTI9_5_IRQn);
01484         if(g_distance < targetHeight + ALLOWHEIGHT){
01485             UpdateTargetAngle_NoseUP(targetAngle);
01486             if(CheckSW_Up(Ch7)) led2 = 1;
01487         }
01488         else if(g_distance > targetHeight - ALLOWHEIGHT){
01489             UpdateTargetAngle_NoseDOWN(targetAngle);
01490             if(CheckSW_Up(Ch7)) led2 = 1;
01491         }
01492         else led2=0;
01493         NVIC_EnableIRQ(EXTI9_5_IRQn);
01494     }
01495     
01496     void UpdateTargetAngle_NoseUP(float targetAngle[3]){
01497     
01498     //targetAngle[PITCH] += 2.0f;
01499     //if(nowAngle[PITCH]<targetAngle[PITCH]) autopwm[THR] = SetTHRinRatio(0.6);
01500     autopwm[THR] = SetTHRinRatio(g_loopTHR+0.05);
01501     //pc.printf("nose UP");
01502 }
01503 
01504 void UpdateTargetAngle_NoseDOWN(float targetAngle[3]){
01505     
01506     //targetAngle[PITCH] -= 2.0f;
01507     autopwm[THR] = SetTHRinRatio(g_loopTHR-0.05);
01508     //pc.printf("nose DOWN");
01509 }
01510 
01511 //直進
01512 void UpdateTargetAngle_GoStraight(float targetAngle[3]){
01513 
01514     autopwm[RUD] = trimpwm[RUD];
01515     targetAngle[ROLL] = g_gostraightROLL;
01516     targetAngle[PITCH] = g_gostraightPITCH;
01517     autopwm[THR] = SetTHRinRatio(g_loopTHR);
01518     
01519     //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
01520 }
01521 
01522 //直進(着陸時スロットル0のとき)
01523 void UpdateTargetAngle_GoStraight_zero(float targetAngle[3]){
01524 
01525     autopwm[RUD] =  trimpwm[RUD];
01526     targetAngle[ROLL] = g_gostraightROLL;
01527     targetAngle[PITCH] = g_gostraightPITCH;
01528     autopwm[THR] = minpwm[THR];
01529     
01530     //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
01531 }
01532 
01533 //右旋回
01534 void UpdateTargetAngle_Rightloop(float targetAngle[3]){ //右旋回
01535 
01536     targetAngle[PITCH] = g_rightloopPITCH ;
01537     autopwm[RUD]=g_rightloopRUD;              //RUD固定
01538     autopwm[THR] = SetTHRinRatio(0.5);                  //手動スロットル記憶
01539     
01540     /*
01541     if (nowAngle[ROLL]>20.0||nowAngle[ROLL]<-20.0){
01542         t2.start();
01543         pc.printf("Timer start.");
01544     }
01545     if(0.0<t2.read()<5.0){
01546             //pc.printf("tagetAngle is changed.");
01547             targetAngle[ROLL] = rightloopROLL2;
01548             }
01549         else {
01550             t2.stop();
01551             t2.reset();
01552             pc.printf("Timer stopped.");
01553             targetAngle[ROLL] = g_rightloopROLL;
01554         }    
01555 */
01556     if(autopwm[AIL_R]<trimpwm[AIL_R]){                                                                                  //エルロン上がりやすさ調節
01557         autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01558         }
01559     else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01560     autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
01561     
01562     
01563     //checkHeight(targetAngle);
01564     //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
01565 }
01566 
01567 //右旋回(着陸時スロットル0の時)
01568 void UpdateTargetAngle_Rightloop_zero(float targetAngle[3]){ //右旋回
01569     autopwm[THR]=minpwm[THR];
01570     targetAngle[ROLL] = g_rightloopROLL;
01571     targetAngle[PITCH] = g_rightloopPITCH ;
01572     autopwm[RUD]=g_rightloopRUD;              //RUD固定
01573     if(autopwm[AIL_R]<trimpwm[AIL_R]){                                                                                  //エルロン上がりやすさ調節
01574             autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01575             }
01576         else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01577         autopwm[AIL_R]=autopwm[AIL_R]+AIL_R_correctionrightloop;
01578 
01579     //checkHeight(targetAngle);
01580     //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
01581 }
01582 
01583 void UpdateTargetAngle_Rightloop_short(float targetAngle[3]){ //右旋回
01584 
01585     targetAngle[ROLL] = g_rightloopROLLshort;
01586     targetAngle[PITCH] = g_rightloopPITCHshort;
01587     autopwm[RUD]=g_rightloopshortRUD;
01588     autopwm[THR] = SetTHRinRatio(0.5);
01589     if(autopwm[AIL_R]<trimpwm[AIL_R]){
01590         autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01591         }
01592     else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionrightloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01593     
01594     //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
01595 }
01596 
01597 //左旋回
01598 void UpdateTargetAngle_Leftloop(float targetAngle[3]){
01599     
01600     targetAngle[ROLL] = g_leftloopROLL;
01601     targetAngle[PITCH] = g_leftloopPITCH;
01602     autopwm[RUD]=g_leftloopRUD;
01603     autopwm[THR] = SetTHRinRatio(0.5);
01604     if(autopwm[AIL_R]<trimpwm[AIL_R]){
01605         autopwm[AIL_L]=trimpwm[AIL_L]+g_AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01606         }
01607     else autopwm[AIL_L]=trimpwm[AIL_L]+g_AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01608     //checkHeight(targetAngle);
01609 
01610     //printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[], targetAngle[PITCH], autopwm[THR]);
01611 }
01612 
01613 //左旋回(着陸時スロットル0のとき)
01614 void UpdateTargetAngle_Leftloop_zero(float targetAngle[3]){
01615     
01616     targetAngle[ROLL] = g_leftloopROLL;
01617     targetAngle[PITCH] = g_leftloopPITCH;
01618     autopwm[RUD]=g_leftloopRUD;
01619     autopwm[THR] = minpwm[THR];
01620     if(autopwm[AIL_R]<trimpwm[AIL_R]){
01621         autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01622         }
01623     else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloop+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01624     //autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_Ratio_leftloop;
01625     //checkHeight(targetAngle);
01626 
01627     //printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[], targetAngle[PITCH], autopwm[THR]);
01628 }
01629 
01630 void UpdateTargetAngle_Leftloop_short(float targetAngle[3]){
01631     
01632     targetAngle[ROLL] = g_leftloopROLLshort;
01633     targetAngle[PITCH] = g_leftloopPITCHshort;
01634     autopwm[RUD]=g_leftloopRUD;
01635     autopwm[THR] = SetTHRinRatio(0.5);
01636     if(autopwm[AIL_R]<trimpwm[AIL_R]){
01637         autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioRising;
01638         }
01639     else autopwm[AIL_L]=trimpwm[AIL_L]+AIL_L_correctionleftloopshort+(autopwm[AIL_R]-trimpwm[AIL_R])*AIL_L_RatioDescent;
01640 
01641     //pc.printf("Roll = %f, PITCH = %f, THR = %d \r\n", targetAngle[ROLL], targetAngle[PITCH], autopwm[THR]);
01642 }
01643 
01644 void Sbusprintf(){
01645     
01646     for(uint8_t i=0; i<8; i++) pc.printf("ch.%d = %d ",i+1,sbus.manualpwm[i]);
01647     pc.printf("\r\n");
01648     
01649     }
01650 
01651 
01652 
01653 //デバッグ用
01654 void DebugPrint(){    
01655     /*
01656     static int16_t deltaT = 0, t_start = 0;
01657     deltaT = t.read_u2s() - t_start;
01658     pc.printf("t:%d us, ",deltaT);
01659     pc.printf("\r\n");
01660     t_start = t.read_us();
01661     */
01662     //for(uint8_t i=0; i<8; i++) pc.printf("%d ",sbus.manualpwm[i]);
01663     //for(uint8_t i=1; i<4; i++) pc.printf("%d ",sbus.manualpwm[i]);
01664     //pc.printf("\r\n");
01665     //for(uint8_t i=0; i<3; i++) pc.printf("%3.2f\t",nowAngle[i]);
01666     //for(uint8_t i=0; i<2; i++) pc.printf("%3.2f\t",nowAngle[i]); //ロール、ピッチのみ 小数点以下2ケタ
01667     //pc.printf("%d\t",autopwm[AIL_L]);  
01668     //pc.printf("%d\t",autopwm[RUD]);
01669     //pc.printf("%d",g_distance);
01670     //NVIC_DisableIRQ(EXTI9_5_IRQn); 
01671     //pc.printf("g_distance = %d",g_distance);
01672     //NVIC_EnableIRQ(EXTI9_5_IRQn);
01673     //pc.printf("Mode: %c: ",g_buf[0]);
01674     //if(g_buf[0] == 'Y') pc.printf(" %3.1f",g_SerialTargetYAW);
01675     //pc.printf("\r\n");
01676 }