1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

moved some of init logic around to get sensors + other important hardware checked first; added dummy implementation of production test for future use, outputting debug info over PB6 (USART1_TX remap)

This commit is contained in:
dongie 2014-05-01 19:05:13 +09:00
parent be5896f5b3
commit cce4d4975d
4 changed files with 51 additions and 24 deletions

View file

@ -239,6 +239,7 @@ typedef struct baro_t
#define LED1 #define LED1
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG) #define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
// #define PROD_DEBUG
#endif #endif
#endif #endif

View file

@ -36,6 +36,7 @@ int main(void)
serialPort_t* loopbackPort1 = NULL; serialPort_t* loopbackPort1 = NULL;
serialPort_t* loopbackPort2 = NULL; serialPort_t* loopbackPort2 = NULL;
#endif #endif
checkFirstTime(false); checkFirstTime(false);
readEEPROM(); readEEPROM();
systemInit(mcfg.emf_avoidance); systemInit(mcfg.emf_avoidance);
@ -54,12 +55,25 @@ int main(void)
} }
adcInit(&adc_params); adcInit(&adc_params);
// Check battery type/voltage
if (feature(FEATURE_VBAT))
batteryInit();
initBoardAlignment(); initBoardAlignment();
// We have these sensors; SENSORS_SET defined in board.h depending on hardware platform // We have these sensors; SENSORS_SET defined in board.h depending on hardware platform
sensorsSet(SENSORS_SET); sensorsSet(SENSORS_SET);
// 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
mixerInit(); // this will set core.useServo var depending on mixer type mixerInit(); // this will set core.useServo var depending on mixer type
// production debug output
#ifdef PROD_DEBUG
productionDebug();
#endif
serialInit(mcfg.serial_baudrate);
// when using airplane/wing mixer, servo/motor outputs are remapped // when using airplane/wing mixer, servo/motor outputs are remapped
if (mcfg.mixerConfiguration == MULTITYPE_AIRPLANE || mcfg.mixerConfiguration == MULTITYPE_FLYING_WING) if (mcfg.mixerConfiguration == MULTITYPE_AIRPLANE || mcfg.mixerConfiguration == MULTITYPE_FLYING_WING)
pwm_params.airplane = true; pwm_params.airplane = true;
@ -129,29 +143,6 @@ int main(void)
} }
#endif #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();
serialInit(mcfg.serial_baudrate);
if (feature(FEATURE_SOFTSERIAL)) { if (feature(FEATURE_SOFTSERIAL)) {
//mcfg.softserial_baudrate = 19200; // Uncomment to override config value //mcfg.softserial_baudrate = 19200; // Uncomment to override config value
@ -178,6 +169,19 @@ int main(void)
calibratingB = CALIBRATING_BARO_CYCLES; // 10 seconds init_delay + 200 * 25 ms = 15 seconds before ground pressure settles calibratingB = CALIBRATING_BARO_CYCLES; // 10 seconds init_delay + 200 * 25 ms = 15 seconds before ground pressure settles
f.SMALL_ANGLE = 1; f.SMALL_ANGLE = 1;
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;
// loopy // loopy
while (1) { while (1) {
loop(); loop();

View file

@ -119,3 +119,24 @@ void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation)
if (!standardBoardAlignment) if (!standardBoardAlignment)
alignBoard(dest); alignBoard(dest);
} }
#ifdef PROD_DEBUG
void productionDebug(void)
{
gpio_config_t gpio;
// remap PB6 to USART1_TX
gpio.pin = Pin_6;
gpio.mode = Mode_AF_PP;
gpio.speed = Speed_2MHz;
gpioInit(GPIOB, &gpio);
gpioPinRemapConfig(AFIO_MAPR_USART1_REMAP, true);
serialInit(mcfg.serial_baudrate);
delay(25);
serialPrint(core.mainport, "DBG ");
printf("%08x%08x%08x OK\n", U_ID_0, U_ID_1, U_ID_2);
serialPrint(core.mainport, "EOF");
delay(25);
gpioPinRemapConfig(AFIO_MAPR_USART1_REMAP, false);
}
#endif

View file

@ -4,3 +4,4 @@ int constrain(int amt, int low, int high);
// sensor orientation // sensor orientation
void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation); void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation);
void initBoardAlignment(void); void initBoardAlignment(void);
void productionDebug(void);