1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

decouple cli/msp from each other. relocated non-msp code into

serial_common.c/h. decouple runtime_config from serial ports.  decouple
buzzer from serial ports.  decouple opening of the main serial port from
the msp code.  decouple serial rx providers from runtime_config.  rename
core_t to serialPorts_t since it only contained serial ports.  It's now
clear which files use serial ports based on the header files they
include.
This commit is contained in:
Dominic Clifton 2014-04-19 01:01:31 +01:00
parent 2baf385b99
commit a7e4c859bd
26 changed files with 209 additions and 135 deletions

View file

@ -23,6 +23,7 @@
#include "gimbal.h"
#include "rx_common.h"
#include "gps_common.h"
#include "serial_common.h"
#include "runtime_config.h"
#include "config.h"
@ -40,7 +41,7 @@ void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h
master_t mcfg; // master config struct with data independent from profiles
config_t cfg; // profile config struct
static const uint8_t EEPROM_CONF_VERSION = 63;
static const uint8_t EEPROM_CONF_VERSION = 64;
static void resetConf(void);
static uint8_t validEEPROM(void)
@ -216,11 +217,14 @@ static void resetConf(void)
// gps/nav stuff
mcfg.gps_type = GPS_NMEA;
mcfg.gps_baudrate = GPS_BAUD_115200;
// serial (USART1) baudrate
mcfg.serial_baudrate = 115200;
mcfg.softserial_baudrate = 9600;
mcfg.softserial_1_inverted = 0;
mcfg.softserial_2_inverted = 0;
mcfg.serialConfig.port1_baudrate = 115200;
mcfg.serialConfig.softserial_baudrate = 9600;
mcfg.serialConfig.softserial_1_inverted = 0;
mcfg.serialConfig.softserial_2_inverted = 0;
mcfg.serialConfig.reboot_character = 'R';
mcfg.looptime = 3500;
mcfg.rssi_aux_channel = 0;
@ -314,9 +318,6 @@ static void resetConf(void)
cfg.nav_speed_max = 300;
cfg.ap_mode = 40;
// control stuff
mcfg.reboot_character = 'R';
// custom mixer. clear by defaults.
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
mcfg.customMixer[i].throttle = 0.0f;