#else
initializeSoftPWM();
#endif
#endif
#if(NUMBER_MOTOR>6)
#ifdefined(HWPWM6)
initializeSoftPWM();
#endif
#endif
#endif
/********特殊的PWM定时器&暂存器fortheatmega328P(Promini)************/
#ifdefined(PROMINI)
#if(NUMBER_MOTOR>0)
TCCR1A|=_BV(COM1A1);//连接针9到定时器1channelA
#endif
#if(NUMBER_MOTOR>1)
TCCR1A|=_BV(COM1B1);//connectpin10totimer1channelB
#endif
#if(NUMBER_MOTOR>2)
TCCR2A|=_BV(COM2A1);//connectpin11totimer2channelA
#endif
#if(NUMBER_MOTOR>3)
TCCR2A|=_BV(COM2B1);//connectpin3totimer2channelB
#endif
#if(NUMBER_MOTOR>4)//PIN5&6orA0&A1
initializeSoftPWM();//初始化定时器和PWM通道
#ifdefined(A0_A1_PIN_HEX)||(NUMBER_MOTOR>6)
pinMode(5,INPUT);pinMode(6,INPUT);//wereactivatetheINPUTaffectationforthesetwoPINs
pinMode(A0,OUTPUT);pinMode(A1,OUTPUT);
#endif
#endif
#endif
/********specialversionofMultiWiitocalibrateallattachedESCs************/
/********设置特殊电子调速器************/
#ifdefined(ESC_CALIB_CANNOT_FLY)
writeAllMotors(ESC_CALIB_HIGH);
blinkLED(2,20,2);
delay(4000);
writeAllMotors(ESC_CALIB_LOW);
blinkLED(3,20,2);
while
(1){
delay(5000);
blinkLED(4,20,2);
#ifdefined(BUZZER)
alarmArray[7]=2;
#endif
}
exit;//statementneverreached
#endif
writeAllMotors(MINCOMMAND);
delay(300);
#ifdefined(SERVO)
initializeServo();
#endif
}
readGlobalSet();//读取存储的全局变量
#ifndefNO_FLASH_CHECK
#ifdefined(MEGA)
uint16_ti=65000;//onlyfirst~64Kformegaboardduetopgm_read_bytelimitation
#else
uint16_ti=32000;
#endif
uint16_tflashsum=0;
uint8_tpbyt;
while(i--){
pbyt=pgm_read_byte(i);//calculateflashchecksum
flashsum+=pbyt;
flashsum^=(pbyt<<8);
}
#endif
#ifdefMULTIPLE_CONFIGURATION_PROFILES
global_conf.currentSet=2;
#else
global_conf.currentSet=0;
#endif
while
(1){//checksettingsintegrity
#ifndefNO_FLASH_CHECK
if(readEEPROM()){//checkcurrentsettingintegrity
if(flashsum!
=global_conf.flashsum)update_constants();//updateconstantsiffirmwareischangedandintegrityisOK
}
#else
readEEPROM();//checkcurrentsettingintegrity
#endif
if(global_conf.currentSet==0)break;//allchecksisdone
global_conf.currentSet--;//nextsettingforcheck
}
readGlobalSet();//重新加载全局设置得到最后档案号码
#ifndefNO_FLASH_CHECK
if(flashsum!
=global_conf.flashsum){
global_conf.flashsum=flashsum;//newflashsum
writeGlobalSet
(1);//updateflashsuminglobalconfig
}
#endif
readEEPROM();//loadsettingdatafromlastusedprofile加载设置数据从去年使用概要文件
blinkLED(2,40,global_conf.currentSet+1);
configureReceiver();
#ifdefined(PILOTLAMP)
PL_INIT;
#endif
#ifdefined(OPENLRSv2MULTI)//OpenLRSv2MultiRcReceiverboardincludingITG3205andADXL345
initOpenLRS();
#endif
initSensors();//传感器初始化
#ifdefined(I2C_GPS)||defined(GPS_SERIAL)||defined(GPS_FROM_OSD)
GPS_set_pids();//获取有关PID值和设置的PID控制器
#endif
previousTime=micros();
#ifdefined(GIMBAL)//如果自稳云台(多旋翼飞行器种类)
calibratingA=512;
#endif
calibratingG=512;
calibratingB=200;//10secondsinit_delay+200*25ms=15secondsbeforegroundpressuresettles
#ifdefined(POWERMETER)
for(uint8_tj=0;j<=PMOTOR_SUM;j++)pMeter[j]=0;
#endif
/************************************/
#ifdefined(GPS_SERIAL)//flyduinov2应设为2。
此为arduinoMEGA上的串口号
GPS_SerialInit();//GPS串口初始化
for(uint8_tj=0;j<=5;j++){
GPS_NewData();
LEDPIN_ON
delay(20);
LEDPIN_OFF
delay(80);
}
if(!
GPS_Present){
SerialEnd(GPS_SERIAL);
SerialOpen(0,SERIAL0_COM_SPEED);
}
#if!
defined(GPS_PROMINI)
GPS_Present=1;
#endif
GPS_Enable=GPS_Present;
#endif
/************************************/
#ifdefined(I2C_GPS)||defined(GPS_FROM_OSD)///I2CGPS设置
GPS_Enable=1;
#endif
#ifdefined(LCD_ETPP)||defined(LCD_LCD03)||defined(OLED_I2C_128x64)||defined(OLED_DIGOLE)||defined(LCD_TELEMETRY_STEP)//LCD设置
initLCD();
#endif
#ifdefLCD_TELEMETRY_DEBUG
telemetry_auto=1;
#endif
#ifdefLCD_CONF_DEBUG
configurationLoop();
#endif
#ifdefLANDING_LIGHTS_DDR
init_landing_lights();
#endif
#ifdefFASTER_ANALOG_READS
ADCSRA|=_BV(ADPS2);ADCSRA&=~_BV(ADPS1);ADCSRA&=~_BV(ADPS0);//thisspeedsupanalogReadwithoutloosingtoomuchresolution:
http:
//www.arduino.cc/cgi-bin/yabb2/YaBB.pl?
num=1208715493/11
#endif
#ifdefined(LED_FLASHER)
init_led_flasher();
led_flasher_set_sequence(LED_FLASHER_SEQUENCE);
#endif
f.SMALL_ANGLES_25=1;//importantforgyroonlyconf
#ifdefLOG_PERMANENT
//readlaststoredset
readPLog();
plog.lifetime+=plog.armed_time/1000000;
plog.start++;//#powercycle/reset/initializeevents
//dumpplogdatatoterminal
#ifdefLOG_PERMANENT_SHOW_AT_STARTUP
dumpPLog(0);
#endif
plog.armed_time=0;//lifetimeinseconds
//plog.running=0;//toggleonarm&disarmtomonitorforcleanshutdownvs.powercut
#endif
debugmsg_append_str("initializationcompleted\n");
}
//********MainLoop*********
voidloop(){
staticuint8_trcDelayCommand;//thisindicatesthenumberoftime(multipleofRCmeasurementat50Hz)thesticksmustbemaintainedtorunorswitchoffmotors
staticuint8_trcSticks;
uint8_taxis,i;
int16_terror,errorAngle;
int16_tdelta;
int16_tPTerm=0,ITerm=0,DTerm,PTermACC,ITermACC;
staticint16_tlastGyro[2]={0,0};
staticint16_terrorAngleI[2]={0,0};
#ifPID_CONTROLLER==1
staticint32_terrorGyroI_YAW;
staticint16_tdelta1[2],delta2[2];
staticint16_terrorGyroI[2]={0,0};
#elifPID_CONTROLLER==2
staticint16_tdelta1[3],delta2[3];
staticint32_terrorGyroI[3]={0,0,0};
staticint16_tlastError[3]={0,0,0};
int16_tdeltaSum;
int16_tAngleRateTmp,RateError;
#endif
staticuint32_trcTime=0;
staticint16_tinitialThrottleHold;
stati