Ah, finally fixed spektrum stuff. after PWM rewrite, spektrum init ended up before pwm init, so when rcReadRawFunc was assigned, it was always set to PWM. oops. Thanks to Cerberis @ irc for the patch.

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@240 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2013-01-05 01:13:18 +00:00
parent 006e6629f6
commit bd08f337e7
2 changed files with 3064 additions and 3064 deletions

File diff suppressed because it is too large Load Diff

View File

@ -1,156 +1,156 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
extern uint8_t useServo;
extern rcReadRawDataPtr rcReadRawFunc;
// two receiver read functions
extern uint16_t pwmReadRawRC(uint8_t chan);
extern uint16_t spektrumReadRawRC(uint8_t chan);
static void _putc(void *p, char c)
{
uartWrite(c);
}
int main(void)
{
uint8_t i;
drv_pwm_config_t pwm_params;
drv_adc_config_t adc_params;
#if 0
// PC12, PA15
// using this to write asm for bootloader :)
RCC->APB2ENR |= RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO; // GPIOA/C+AFIO only
AFIO->MAPR &= 0xF0FFFFFF;
AFIO->MAPR = 0x02000000;
GPIOA->CRH = 0x34444444; // PIN 15 Output 50MHz
GPIOA->BRR = 0x8000; // set low 15
GPIOC->CRH = 0x44434444; // PIN 12 Output 50MHz
GPIOC->BRR = 0x1000; // set low 12
#endif
#if 0
// using this to write asm for bootloader :)
RCC->APB2ENR |= RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO; // GPIOB + AFIO
AFIO->MAPR &= 0xF0FFFFFF;
AFIO->MAPR = 0x02000000;
GPIOB->BRR = 0x18; // set low 4 & 3
GPIOB->CRL = 0x44433444; // PIN 4 & 3 Output 50MHz
#endif
systemInit();
init_printf(NULL, _putc);
checkFirstTime(false);
readEEPROM();
// configure power ADC
if (cfg.power_adc_channel > 0 && (cfg.power_adc_channel == 1 || cfg.power_adc_channel == 9))
adc_params.powerAdcChannel = cfg.power_adc_channel;
else {
adc_params.powerAdcChannel = 0;
cfg.power_adc_channel = 0;
}
adcInit(&adc_params); extern uint8_t useServo;
extern rcReadRawDataPtr rcReadRawFunc;
serialInit(cfg.serial_baudrate);
// two receiver read functions
// We have these sensors extern uint16_t pwmReadRawRC(uint8_t chan);
#ifndef FY90Q extern uint16_t spektrumReadRawRC(uint8_t chan);
// AfroFlight32
sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG); static void _putc(void *p, char c)
#else {
// FY90Q uartWrite(c);
sensorsSet(SENSOR_ACC); }
#endif
if (feature(FEATURE_SPEKTRUM)) { int main(void)
spektrumInit(); {
rcReadRawFunc = spektrumReadRawRC; uint8_t i;
} else { drv_pwm_config_t pwm_params;
// spektrum and GPS are mutually exclusive drv_adc_config_t adc_params;
// Optional GPS - available in both PPM and PWM input mode, in PWM input, reduces number of available channels by 2.
if (feature(FEATURE_GPS)) #if 0
gpsInit(cfg.gps_baudrate); // PC12, PA15
} // using this to write asm for bootloader :)
#ifdef SONAR RCC->APB2ENR |= RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO; // GPIOA/C+AFIO only
// sonar stuff only works with PPM AFIO->MAPR &= 0xF0FFFFFF;
if (feature(FEATURE_PPM)) { AFIO->MAPR = 0x02000000;
if (feature(FEATURE_SONAR)) GPIOA->CRH = 0x34444444; // PIN 15 Output 50MHz
Sonar_init(); GPIOA->BRR = 0x8000; // set low 15
} GPIOC->CRH = 0x44434444; // PIN 12 Output 50MHz
#endif GPIOC->BRR = 0x1000; // set low 12
#endif
mixerInit(); // this will set useServo var depending on mixer type
// when using airplane/wing mixer, servo/motor outputs are remapped #if 0
if (cfg.mixerConfiguration == MULTITYPE_AIRPLANE || cfg.mixerConfiguration == MULTITYPE_FLYING_WING) // using this to write asm for bootloader :)
pwm_params.airplane = true; RCC->APB2ENR |= RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO; // GPIOB + AFIO
else AFIO->MAPR &= 0xF0FFFFFF;
pwm_params.airplane = false; AFIO->MAPR = 0x02000000;
pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SPEKTRUM); // spektrum support uses UART too GPIOB->BRR = 0x18; // set low 4 & 3
pwm_params.usePPM = feature(FEATURE_PPM); GPIOB->CRL = 0x44433444; // PIN 4 & 3 Output 50MHz
pwm_params.enableInput = !feature(FEATURE_SPEKTRUM); // disable inputs if using spektrum #endif
pwm_params.useServos = useServo;
pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX; systemInit();
pwm_params.motorPwmRate = cfg.motor_pwm_rate; init_printf(NULL, _putc);
pwm_params.servoPwmRate = cfg.servo_pwm_rate;
switch (cfg.power_adc_channel) { checkFirstTime(false);
case 1: readEEPROM();
pwm_params.adcChannel = PWM2;
break; // configure power ADC
case 9: if (cfg.power_adc_channel > 0 && (cfg.power_adc_channel == 1 || cfg.power_adc_channel == 9))
pwm_params.adcChannel = PWM8; adc_params.powerAdcChannel = cfg.power_adc_channel;
break; else {
default: adc_params.powerAdcChannel = 0;
pwm_params.adcChannel = 0; cfg.power_adc_channel = 0;
break; }
}
adcInit(&adc_params);
pwmInit(&pwm_params);
serialInit(cfg.serial_baudrate);
// configure PWM/CPPM read function. spektrum will override that
rcReadRawFunc = pwmReadRawRC; // We have these sensors
#ifndef FY90Q
LED1_ON; // AfroFlight32
LED0_OFF; sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG);
for (i = 0; i < 10; i++) { #else
LED1_TOGGLE; // FY90Q
LED0_TOGGLE; sensorsSet(SENSOR_ACC);
delay(25); #endif
BEEP_ON;
delay(25); mixerInit(); // this will set useServo var depending on mixer type
BEEP_OFF; // when using airplane/wing mixer, servo/motor outputs are remapped
} if (cfg.mixerConfiguration == MULTITYPE_AIRPLANE || cfg.mixerConfiguration == MULTITYPE_FLYING_WING)
LED0_OFF; pwm_params.airplane = true;
LED1_OFF; else
pwm_params.airplane = false;
// drop out any sensors that don't seem to work, init all the others. halt if gyro is dead. pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SPEKTRUM); // spektrum support uses UART too
sensorsAutodetect(); pwm_params.usePPM = feature(FEATURE_PPM);
imuInit(); // Mag is initialized inside imuInit pwm_params.enableInput = !feature(FEATURE_SPEKTRUM); // disable inputs if using spektrum
pwm_params.useServos = useServo;
// Check battery type/voltage pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX;
if (feature(FEATURE_VBAT)) pwm_params.motorPwmRate = cfg.motor_pwm_rate;
batteryInit(); pwm_params.servoPwmRate = cfg.servo_pwm_rate;
switch (cfg.power_adc_channel) {
previousTime = micros(); case 1:
if (cfg.mixerConfiguration == MULTITYPE_GIMBAL) pwm_params.adcChannel = PWM2;
calibratingA = 400; break;
calibratingG = 1000; case 9:
f.SMALL_ANGLES_25 = 1; pwm_params.adcChannel = PWM8;
break;
// loopy default:
while (1) { pwm_params.adcChannel = 0;
loop(); break;
} }
}
pwmInit(&pwm_params);
void HardFault_Handler(void)
{ // configure PWM/CPPM read function. spektrum below will override that
// fall out of the sky rcReadRawFunc = pwmReadRawRC;
writeAllMotors(cfg.mincommand);
while (1); if (feature(FEATURE_SPEKTRUM)) {
} spektrumInit();
rcReadRawFunc = spektrumReadRawRC;
} else {
// spektrum and GPS are mutually exclusive
// Optional GPS - available in both PPM and PWM input mode, in PWM input, reduces number of available channels by 2.
if (feature(FEATURE_GPS))
gpsInit(cfg.gps_baudrate);
}
#ifdef SONAR
// sonar stuff only works with PPM
if (feature(FEATURE_PPM)) {
if (feature(FEATURE_SONAR))
Sonar_init();
}
#endif
LED1_ON;
LED0_OFF;
for (i = 0; i < 10; i++) {
LED1_TOGGLE;
LED0_TOGGLE;
delay(25);
BEEP_ON;
delay(25);
BEEP_OFF;
}
LED0_OFF;
LED1_OFF;
// drop out any sensors that don't seem to work, init all the others. halt if gyro is dead.
sensorsAutodetect();
imuInit(); // Mag is initialized inside imuInit
// Check battery type/voltage
if (feature(FEATURE_VBAT))
batteryInit();
previousTime = micros();
if (cfg.mixerConfiguration == MULTITYPE_GIMBAL)
calibratingA = 400;
calibratingG = 1000;
f.SMALL_ANGLES_25 = 1;
// loopy
while (1) {
loop();
}
}
void HardFault_Handler(void)
{
// fall out of the sky
writeAllMotors(cfg.mincommand);
while (1);
}