1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +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

@ -78,6 +78,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
telemetry_common.c \ telemetry_common.c \
telemetry_frsky.c \ telemetry_frsky.c \
telemetry_hott.c \ telemetry_hott.c \
serial_common.c \
serial_cli.c \ serial_cli.c \
serial_msp.c \ serial_msp.c \
statusindicator.c \ statusindicator.c \

View file

@ -18,7 +18,7 @@
#include "config.h" #include "config.h"
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "runtime_config.h" #include "serial_common.h"
#if MAX_MOTORS != MAX_SUPPORTED_MOTORS #if MAX_MOTORS != MAX_SUPPORTED_MOTORS
@ -35,7 +35,7 @@
// gcc/GNU version // gcc/GNU version
static void _putc(void *p, char c) static void _putc(void *p, char c)
{ {
serialWrite(core.mainport, c); serialWrite(serialPorts.mainport, c);
} }
void initPrintfSupport(void) void initPrintfSupport(void)
@ -49,8 +49,8 @@ void initPrintfSupport(void)
int fputc(int c, FILE *f) int fputc(int c, FILE *f)
{ {
// let DMA catch up a bit when using set or dump, we're too fast. // let DMA catch up a bit when using set or dump, we're too fast.
while (!isSerialTransmitBufferEmpty(core.mainport)); while (!isSerialTransmitBufferEmpty(serialPorts.mainport));
serialWrite(core.mainport, c); serialWrite(serialPorts.mainport, c);
return c; return c;
} }

View file

@ -4,7 +4,6 @@
#include "platform.h" #include "platform.h"
#include "drivers/sound_beeper.h" #include "drivers/sound_beeper.h"
#include "drivers/system_common.h" #include "drivers/system_common.h"
#include "drivers/serial_common.h" // FIXME this file should not have a dependency on serial ports, see core_t from runtime_config.h
#include "failsafe.h" #include "failsafe.h"
#include "sensors_common.h" #include "sensors_common.h"
#include "runtime_config.h" #include "runtime_config.h"

View file

@ -36,7 +36,7 @@
#include "build_config.h" #include "build_config.h"
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "runtime_config.h" #include "serial_common.h"
#include "printf.h" #include "printf.h"
@ -154,7 +154,7 @@ void tfp_printf(char *fmt, ...)
va_start(va, fmt); va_start(va, fmt);
tfp_format(stdout_putp, stdout_putf, fmt, va); tfp_format(stdout_putp, stdout_putf, fmt, va);
va_end(va); va_end(va);
while (!isSerialTransmitBufferEmpty(core.mainport)); while (!isSerialTransmitBufferEmpty(serialPorts.mainport));
} }
static void putcp(void *p, char c) static void putcp(void *p, char c)

View file

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

View file

@ -113,18 +113,12 @@ typedef struct master_t {
uint8_t gps_type; // See GPSHardware enum. uint8_t gps_type; // See GPSHardware enum.
int8_t gps_baudrate; // See GPSBaudRates enum. int8_t gps_baudrate; // See GPSBaudRates enum.
uint32_t serial_baudrate; serialConfig_t serialConfig;
uint32_t softserial_baudrate; // shared by both soft serial ports
uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1
uint8_t softserial_2_inverted; // use inverted softserial input and output signals on port 2
uint8_t telemetry_provider; // See TelemetryProvider enum. uint8_t telemetry_provider; // See TelemetryProvider enum.
uint8_t telemetry_port; // See TelemetryPort enum. uint8_t telemetry_port; // See TelemetryPort enum.
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed. uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
config_t profile[3]; // 3 separate profiles config_t profile[3]; // 3 separate profiles
uint8_t current_profile; // currently loaded profile uint8_t current_profile; // currently loaded profile
uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else.
uint8_t magic_ef; // magic number, should be 0xEF uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum uint8_t chk; // XOR checksum

View file

@ -1,16 +1,19 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include "common/axis.h" // FIXME this file should not have a dependency axis // FIXME a solution to the dependency problems here is to roll up the failsafe configuration into a structure in failsafe.h and supply it using failsafeInit()
#include "common/axis.h" // FIXME this file should not have this dependency
#include "rx_common.h" #include "rx_common.h"
#include "drivers/serial_common.h" // FIXME this file should not have a dependency on serial ports, see core_t from runtime_config.h #include "drivers/serial_common.h" // FIXME this file should not have this dependency
#include "flight_mixer.h" // FIXME this file should not have a dependency on the flight mixer, see config_t, servoParam_t, etc from config_storage.h #include "serial_common.h" // FIXME this file should not have this dependency
#include "flight_common.h" // FIXME this file should not have a dependency on the flight common, see config_t from config_storage.h #include "flight_mixer.h" // FIXME this file should not have this dependency
#include "sensors_common.h" // FIXME this file should not have a dependency on the sensors, see sensor_align_e from config_storage.h #include "flight_common.h" // FIXME this file should not have this dependency
#include "boardalignment.h" // FIXME this file should not have a dependency on board alignment #include "sensors_common.h" // FIXME this file should not have this dependency
#include "battery.h" // FIXME this file should not have a dependency on battery, see batteryConfig_t from config_storage.h #include "boardalignment.h" // FIXME this file should not have this dependency
#include "battery.h" // FIXME this file should not have this dependency
#include "runtime_config.h" #include "runtime_config.h"
#include "config.h" #include "config.h"

View file

@ -5,6 +5,9 @@
#include "flight_common.h" #include "flight_common.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "gps_common.h" #include "gps_common.h"
// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second) // GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second)
@ -95,7 +98,7 @@ void gpsInit(uint8_t baudrateIndex)
gpsSetPIDs(); gpsSetPIDs();
// Open GPS UART, no callback - buffer will be read out in gpsThread() // Open GPS UART, no callback - buffer will be read out in gpsThread()
core.gpsport = uartOpen(USART2, NULL, gpsInitData[baudrateIndex].baudrate, mode); serialPorts.gpsport = uartOpen(USART2, NULL, gpsInitData[baudrateIndex].baudrate, mode);
// signal GPS "thread" to initialize when it gets to it // signal GPS "thread" to initialize when it gets to it
gpsSetState(GPS_INITIALIZING); gpsSetState(GPS_INITIALIZING);
} }
@ -105,7 +108,7 @@ void gpsInitHardware(void)
switch (mcfg.gps_type) { switch (mcfg.gps_type) {
case GPS_NMEA: case GPS_NMEA:
// nothing to do, just set baud rate and try receiving some stuff and see if it parses // nothing to do, just set baud rate and try receiving some stuff and see if it parses
serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); serialSetBaudRate(serialPorts.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate);
gpsSetState(GPS_RECEIVINGDATA); gpsSetState(GPS_RECEIVINGDATA);
break; break;
@ -113,7 +116,7 @@ void gpsInitHardware(void)
// UBX will run at mcfg.gps_baudrate, it shouldn't be "autodetected". So here we force it to that rate // UBX will run at mcfg.gps_baudrate, it shouldn't be "autodetected". So here we force it to that rate
// Wait until GPS transmit buffer is empty // Wait until GPS transmit buffer is empty
if (!isSerialTransmitBufferEmpty(core.gpsport)) if (!isSerialTransmitBufferEmpty(serialPorts.gpsport))
break; break;
if (gpsData.state == GPS_INITIALIZING) { if (gpsData.state == GPS_INITIALIZING) {
@ -123,9 +126,9 @@ void gpsInitHardware(void)
if (gpsData.state_position < GPS_INIT_ENTRIES) { if (gpsData.state_position < GPS_INIT_ENTRIES) {
// try different speed to INIT // try different speed to INIT
serialSetBaudRate(core.gpsport, gpsInitData[gpsData.state_position].baudrate); serialSetBaudRate(serialPorts.gpsport, gpsInitData[gpsData.state_position].baudrate);
// but print our FIXED init string for the baudrate we want to be at // but print our FIXED init string for the baudrate we want to be at
serialPrint(core.gpsport, gpsInitData[gpsData.baudrateIndex].ubx); serialPrint(serialPorts.gpsport, gpsInitData[gpsData.baudrateIndex].ubx);
gpsData.state_position++; gpsData.state_position++;
gpsData.state_ts = m; gpsData.state_ts = m;
@ -136,10 +139,10 @@ void gpsInitHardware(void)
} else { } else {
// GPS_INITDONE, set our real baud rate and push some ublox config strings // GPS_INITDONE, set our real baud rate and push some ublox config strings
if (gpsData.state_position == 0) if (gpsData.state_position == 0)
serialSetBaudRate(core.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate); serialSetBaudRate(serialPorts.gpsport, gpsInitData[gpsData.baudrateIndex].baudrate);
if (gpsData.state_position < sizeof(ubloxInit)) { if (gpsData.state_position < sizeof(ubloxInit)) {
serialWrite(core.gpsport, ubloxInit[gpsData.state_position]); // send ubx init binary serialWrite(serialPorts.gpsport, ubloxInit[gpsData.state_position]); // send ubx init binary
gpsData.state_position++; gpsData.state_position++;
} else { } else {
@ -161,9 +164,9 @@ void gpsInitHardware(void)
void gpsThread(void) void gpsThread(void)
{ {
// read out available GPS bytes // read out available GPS bytes
if (core.gpsport) { if (serialPorts.gpsport) {
while (serialTotalBytesWaiting(core.gpsport)) while (serialTotalBytesWaiting(serialPorts.gpsport))
gpsNewData(serialRead(core.gpsport)); gpsNewData(serialRead(serialPorts.gpsport));
} }
switch (gpsData.state) { switch (gpsData.state) {
@ -549,14 +552,14 @@ int8_t gpsSetPassthrough(void)
LED1_OFF; LED1_OFF;
while(1) { while(1) {
if (serialTotalBytesWaiting(core.gpsport)) { if (serialTotalBytesWaiting(serialPorts.gpsport)) {
LED0_ON; LED0_ON;
serialWrite(core.mainport, serialRead(core.gpsport)); serialWrite(serialPorts.mainport, serialRead(serialPorts.gpsport));
LED0_OFF; LED0_OFF;
} }
if (serialTotalBytesWaiting(core.mainport)) { if (serialTotalBytesWaiting(serialPorts.mainport)) {
LED1_ON; LED1_ON;
serialWrite(core.gpsport, serialRead(core.mainport)); serialWrite(serialPorts.gpsport, serialRead(serialPorts.mainport));
LED1_OFF; LED1_OFF;
} }
} }

View file

@ -1,10 +1,12 @@
#include "board.h" #include "board.h"
#include "flight_common.h" #include "flight_common.h"
#include "flight_mixer.h" #include "flight_mixer.h"
#include "serial_common.h"
#include "mw.h" #include "mw.h"
#include "gps_common.h" #include "gps_common.h"
#include "rx_common.h" #include "rx_common.h"
#include "drivers/serial_common.h"
#include "telemetry_common.h" #include "telemetry_common.h"
#include "boardalignment.h" #include "boardalignment.h"
#include "config.h" #include "config.h"
@ -12,10 +14,11 @@
#include "build_config.h" #include "build_config.h"
core_t core;
extern rcReadRawDataPtr rcReadRawFunc; extern rcReadRawDataPtr rcReadRawFunc;
void initTelemetry(serialPorts_t *serialPorts);
void serialInit(serialConfig_t *initialSerialConfig);
int main(void) int main(void)
{ {
uint8_t i; uint8_t i;
@ -115,14 +118,14 @@ int main(void)
if (feature(FEATURE_VBAT)) if (feature(FEATURE_VBAT))
batteryInit(&mcfg.batteryConfig); batteryInit(&mcfg.batteryConfig);
serialInit(mcfg.serial_baudrate); serialInit(&mcfg.serialConfig);
#ifndef FY90Q #ifndef FY90Q
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
setupSoftSerialPrimary(mcfg.softserial_baudrate, mcfg.softserial_1_inverted); setupSoftSerialPrimary(mcfg.serialConfig.softserial_baudrate, mcfg.serialConfig.softserial_1_inverted);
setupSoftSerialSecondary(mcfg.softserial_2_inverted); setupSoftSerialSecondary(mcfg.serialConfig.softserial_2_inverted);
#ifdef SOFTSERIAL_LOOPBACK #ifdef SOFTSERIAL_LOOPBACK
loopbackPort1 = (serialPort_t*)&(softSerialPorts[0]); loopbackPort1 = (serialPort_t*)&(softSerialPorts[0]);
@ -136,7 +139,7 @@ int main(void)
#endif #endif
if (feature(FEATURE_TELEMETRY)) if (feature(FEATURE_TELEMETRY))
initTelemetry(); initTelemetry(&serialPorts);
previousTime = micros(); previousTime = micros();
if (mcfg.mixerConfiguration == MULTITYPE_GIMBAL) if (mcfg.mixerConfiguration == MULTITYPE_GIMBAL)

View file

@ -175,7 +175,7 @@ void annexCode(void)
} }
} }
serialCom(); handleSerial();
if (!cliMode && feature(FEATURE_TELEMETRY)) { if (!cliMode && feature(FEATURE_TELEMETRY)) {
handleTelemetry(); handleTelemetry();

View file

@ -31,6 +31,7 @@ enum {
#define CALIBRATING_ACC_CYCLES 400 #define CALIBRATING_ACC_CYCLES 400
#define CALIBRATING_BARO_CYCLES 200 #define CALIBRATING_BARO_CYCLES 200
#include "serial_common.h"
#include "rx_common.h" #include "rx_common.h"
#include "config.h" #include "config.h"
#include "config_storage.h" #include "config_storage.h"
@ -120,10 +121,6 @@ void writeMotors(void);
void writeAllMotors(int16_t mc); void writeAllMotors(int16_t mc);
void mixTable(void); void mixTable(void);
// Serial
void serialInit(uint32_t baudrate);
void serialCom(void);
// buzzer // buzzer
void buzzer(bool warn_vbat); void buzzer(bool warn_vbat);
void systemBeep(bool onoff); void systemBeep(bool onoff);

View file

@ -1,8 +1,6 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include "drivers/serial_common.h"
#include "runtime_config.h" #include "runtime_config.h"
flags_t f; flags_t f;

View file

@ -47,17 +47,8 @@ typedef struct flags_t {
uint8_t FIXED_WING; // set when in flying_wing or airplane mode. currently used by althold selection code uint8_t FIXED_WING; // set when in flying_wing or airplane mode. currently used by althold selection code
} flags_t; } flags_t;
// Core runtime settings
typedef struct core_t {
serialPort_t *mainport;
serialPort_t *gpsport;
serialPort_t *telemport;
serialPort_t *rcvrport;
} core_t;
typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype
extern core_t core;
extern flags_t f; extern flags_t f;
bool sensors(uint32_t mask); bool sensors(uint32_t mask);

View file

@ -7,7 +7,8 @@
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "drivers/serial_uart.h" #include "drivers/serial_uart.h"
#include "runtime_config.h" #include "serial_common.h"
#include "failsafe.h" #include "failsafe.h"
@ -37,7 +38,7 @@ void sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
for (b = 0; b < SBUS_MAX_CHANNEL; b++) for (b = 0; b < SBUS_MAX_CHANNEL; b++)
sbusChannelData[b] = 2 * (rxConfig->midrc - SBUS_OFFSET); sbusChannelData[b] = 2 * (rxConfig->midrc - SBUS_OFFSET);
core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS)); serialPorts.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS));
if (callback) if (callback)
*callback = sbusReadRawRC; *callback = sbusReadRawRC;
rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL; rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;

View file

@ -7,7 +7,7 @@
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "drivers/serial_uart.h" #include "drivers/serial_uart.h"
#include "runtime_config.h" #include "serial_common.h"
#include "failsafe.h" #include "failsafe.h"
@ -53,7 +53,7 @@ void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcRe
break; break;
} }
core.rcvrport = uartOpen(USART2, spektrumDataReceive, 115200, MODE_RX); serialPorts.rcvrport = uartOpen(USART2, spektrumDataReceive, 115200, MODE_RX);
if (callback) if (callback)
*callback = spektrumReadRawRC; *callback = spektrumReadRawRC;
} }

View file

@ -7,7 +7,7 @@
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "drivers/serial_uart.h" #include "drivers/serial_uart.h"
#include "runtime_config.h" #include "serial_common.h"
#include "failsafe.h" #include "failsafe.h"
@ -28,7 +28,7 @@ static uint32_t sumdChannelData[SUMD_MAX_CHANNEL];
void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback) void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
core.rcvrport = uartOpen(USART2, sumdDataReceive, 115200, MODE_RX); serialPorts.rcvrport = uartOpen(USART2, sumdDataReceive, 115200, MODE_RX);
if (callback) if (callback)
*callback = sumdReadRawRC; *callback = sumdReadRawRC;

View file

@ -5,6 +5,9 @@
#include "common/printf.h" #include "common/printf.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "telemetry_common.h" #include "telemetry_common.h"
#include "gps_common.h" #include "gps_common.h"
#include "sensors_acceleration.h" #include "sensors_acceleration.h"
@ -135,11 +138,11 @@ const clivalue_t valueTable[] = {
{ "retarded_arm", VAR_UINT8, &mcfg.retarded_arm, 0, 1 }, { "retarded_arm", VAR_UINT8, &mcfg.retarded_arm, 0, 1 },
{ "flaps_speed", VAR_UINT8, &mcfg.flaps_speed, 0, 100 }, { "flaps_speed", VAR_UINT8, &mcfg.flaps_speed, 0, 100 },
{ "fixedwing_althold_dir", VAR_INT8, &mcfg.fixedwing_althold_dir, -1, 1 }, { "fixedwing_althold_dir", VAR_INT8, &mcfg.fixedwing_althold_dir, -1, 1 },
{ "reboot_character", VAR_UINT8, &mcfg.reboot_character, 48, 126 }, { "reboot_character", VAR_UINT8, &mcfg.serialConfig.reboot_character, 48, 126 },
{ "serial_baudrate", VAR_UINT32, &mcfg.serial_baudrate, 1200, 115200 }, { "serial_baudrate", VAR_UINT32, &mcfg.serialConfig.port1_baudrate, 1200, 115200 },
{ "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 1200, 19200 }, { "softserial_baudrate", VAR_UINT32, &mcfg.serialConfig.softserial_baudrate, 1200, 19200 },
{ "softserial_1_inverted", VAR_UINT8, &mcfg.softserial_1_inverted, 0, 1 }, { "softserial_1_inverted", VAR_UINT8, &mcfg.serialConfig.softserial_1_inverted, 0, 1 },
{ "softserial_2_inverted", VAR_UINT8, &mcfg.softserial_2_inverted, 0, 1 }, { "softserial_2_inverted", VAR_UINT8, &mcfg.serialConfig.softserial_2_inverted, 0, 1 },
{ "gps_type", VAR_UINT8, &mcfg.gps_type, 0, GPS_HARDWARE_MAX }, { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, GPS_HARDWARE_MAX },
{ "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, GPS_BAUD_MAX }, { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, GPS_BAUD_MAX },
{ "serialrx_type", VAR_UINT8, &mcfg.rxConfig.serialrx_type, 0, 3 }, { "serialrx_type", VAR_UINT8, &mcfg.rxConfig.serialrx_type, 0, 3 },
@ -850,12 +853,12 @@ static void cliSave(char *cmdline)
static void cliPrint(const char *str) static void cliPrint(const char *str)
{ {
while (*str) while (*str)
serialWrite(core.mainport, *(str++)); serialWrite(serialPorts.mainport, *(str++));
} }
static void cliWrite(uint8_t ch) static void cliWrite(uint8_t ch)
{ {
serialWrite(core.mainport, ch); serialWrite(serialPorts.mainport, ch);
} }
static void cliPrintVar(const clivalue_t *var, uint32_t full) static void cliPrintVar(const clivalue_t *var, uint32_t full)
@ -1016,8 +1019,8 @@ void cliProcess(void)
cliPrompt(); cliPrompt();
} }
while (serialTotalBytesWaiting(core.mainport)) { while (serialTotalBytesWaiting(serialPorts.mainport)) {
uint8_t c = serialRead(core.mainport); uint8_t c = serialRead(serialPorts.mainport);
if (c == '\t' || c == '?') { if (c == '\t' || c == '?') {
// do tab completion // do tab completion
const clicmd_t *cmd, *pstart = NULL, *pend = NULL; const clicmd_t *cmd, *pstart = NULL, *pend = NULL;

View file

@ -10,4 +10,6 @@
extern uint8_t cliMode; extern uint8_t cliMode;
void cliProcess(void);
#endif /* CLI_H_ */ #endif /* CLI_H_ */

57
src/serial_common.c Normal file
View file

@ -0,0 +1,57 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "drivers/system_common.h"
#include "drivers/serial_common.h"
#include "drivers/serial_uart.h"
#include "serial_cli.h"
#include "serial_msp.h"
#include "serial_common.h"
static serialConfig_t *serialConfig;
serialPorts_t serialPorts;
void serialInit(serialConfig_t *initialSerialConfig)
{
serialConfig = initialSerialConfig;
resetMainSerialPort();
mspInit();
}
void resetMainSerialPort(void)
{
openMainSerialPort(serialConfig->port1_baudrate);
}
void openMainSerialPort(uint32_t baudrate)
{
serialPorts.mainport = uartOpen(USART1, NULL, baudrate, MODE_RXTX);
}
void handleSerial(void)
{
// in cli mode, all serial stuff goes to here. enter cli mode by sending #
if (cliMode) {
cliProcess();
return;
}
mspProcess();
}
// evaluate all other incoming serial data
void evaluateOtherData(uint8_t sr)
{
if (sr == '#')
cliProcess();
else if (sr == serialConfig->reboot_character)
systemReset(true); // reboot to bootloader
}

24
src/serial_common.h Normal file
View file

@ -0,0 +1,24 @@
#pragma once
typedef struct serialPorts_s {
serialPort_t *mainport;
serialPort_t *gpsport;
serialPort_t *telemport;
serialPort_t *rcvrport;
} serialPorts_t;
typedef struct serialConfig_s {
uint32_t port1_baudrate;
uint32_t softserial_baudrate; // shared by both soft serial ports
uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1
uint8_t softserial_2_inverted; // use inverted softserial input and output signals on port 2
uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else.
} serialConfig_t;
extern serialPorts_t serialPorts;
void resetMainSerialPort(void);
void openMainSerialPort(uint32_t baudrate);
void evaluateOtherData(uint8_t sr);
void handleSerial(void);

View file

@ -1,8 +1,10 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "gps_common.h" #include "gps_common.h"
#include "serial_cli.h"
#include "telemetry_common.h" #include "telemetry_common.h"
#include "flight_common.h" #include "flight_common.h"
#include "sensors_compass.h" #include "sensors_compass.h"
@ -126,16 +128,16 @@ void serialize32(uint32_t a)
{ {
static uint8_t t; static uint8_t t;
t = a; t = a;
serialWrite(core.mainport, t); serialWrite(serialPorts.mainport, t);
checksum ^= t; checksum ^= t;
t = a >> 8; t = a >> 8;
serialWrite(core.mainport, t); serialWrite(serialPorts.mainport, t);
checksum ^= t; checksum ^= t;
t = a >> 16; t = a >> 16;
serialWrite(core.mainport, t); serialWrite(serialPorts.mainport, t);
checksum ^= t; checksum ^= t;
t = a >> 24; t = a >> 24;
serialWrite(core.mainport, t); serialWrite(serialPorts.mainport, t);
checksum ^= t; checksum ^= t;
} }
@ -143,16 +145,16 @@ void serialize16(int16_t a)
{ {
static uint8_t t; static uint8_t t;
t = a; t = a;
serialWrite(core.mainport, t); serialWrite(serialPorts.mainport, t);
checksum ^= t; checksum ^= t;
t = a >> 8 & 0xff; t = a >> 8 & 0xff;
serialWrite(core.mainport, t); serialWrite(serialPorts.mainport, t);
checksum ^= t; checksum ^= t;
} }
void serialize8(uint8_t a) void serialize8(uint8_t a)
{ {
serialWrite(core.mainport, a); serialWrite(serialPorts.mainport, a);
checksum ^= a; checksum ^= a;
} }
@ -239,12 +241,10 @@ reset:
} }
} }
void serialInit(uint32_t baudrate) void mspInit(void)
{ {
int idx; int idx;
core.mainport = uartOpen(USART1, NULL, baudrate, MODE_RXTX);
// calculate used boxes based on features and fill availableBoxes[] array // calculate used boxes based on features and fill availableBoxes[] array
memset(availableBoxes, 0xFF, sizeof(availableBoxes)); memset(availableBoxes, 0xFF, sizeof(availableBoxes));
@ -655,16 +655,7 @@ static void evaluateCommand(void)
tailSerialReply(); tailSerialReply();
} }
// evaluate all other incoming serial data void mspProcess(void)
static void evaluateOtherData(uint8_t sr)
{
if (sr == '#')
cliProcess();
else if (sr == mcfg.reboot_character)
systemReset(true); // reboot to bootloader
}
void serialCom(void)
{ {
uint8_t c; uint8_t c;
static uint8_t offset; static uint8_t offset;
@ -678,14 +669,8 @@ void serialCom(void)
HEADER_CMD, HEADER_CMD,
} c_state = IDLE; } c_state = IDLE;
// in cli mode, all serial stuff goes to here. enter cli mode by sending # while (serialTotalBytesWaiting(serialPorts.mainport)) {
if (cliMode) { c = serialRead(serialPorts.mainport);
cliProcess();
return;
}
while (serialTotalBytesWaiting(core.mainport)) {
c = serialRead(core.mainport);
if (c_state == IDLE) { if (c_state == IDLE) {
c_state = (c == '$') ? HEADER_START : IDLE; c_state = (c == '$') ? HEADER_START : IDLE;

5
src/serial_msp.h Normal file
View file

@ -0,0 +1,5 @@
#pragma once
void mspProcess(void);
void mspInit(void);

View file

@ -1,6 +1,9 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "telemetry_frsky.h" #include "telemetry_frsky.h"
#include "telemetry_hott.h" #include "telemetry_hott.h"
@ -20,7 +23,6 @@ bool isTelemetryProviderHoTT(void)
bool canUseTelemetryWithCurrentConfiguration(void) bool canUseTelemetryWithCurrentConfiguration(void)
{ {
if (!feature(FEATURE_TELEMETRY)) { if (!feature(FEATURE_TELEMETRY)) {
return false; return false;
} }
@ -42,7 +44,7 @@ bool canUseTelemetryWithCurrentConfiguration(void)
return true; return true;
} }
void initTelemetry(void) void initTelemetry(serialPorts_t *serialPorts)
{ {
// Force telemetry to uart when softserial disabled // Force telemetry to uart when softserial disabled
if (!feature(FEATURE_SOFTSERIAL)) if (!feature(FEATURE_SOFTSERIAL))
@ -51,18 +53,18 @@ void initTelemetry(void)
#ifdef FY90Q #ifdef FY90Q
// FY90Q does not support softserial // FY90Q does not support softserial
mcfg.telemetry_port = TELEMETRY_PORT_UART; mcfg.telemetry_port = TELEMETRY_PORT_UART;
core.telemport = core.mainport; serialPorts->telemport = serialPorts.mainport;
#endif #endif
isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration(); isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration();
#ifndef FY90Q #ifndef FY90Q
if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1) if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1)
core.telemport = &(softSerialPorts[0].port); serialPorts->telemport = &(softSerialPorts[0].port);
else if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2) else if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2)
core.telemport = &(softSerialPorts[1].port); serialPorts->telemport = &(softSerialPorts[1].port);
else else
core.telemport = core.mainport; serialPorts->telemport = serialPorts->mainport;
#endif #endif
checkTelemetryState(); checkTelemetryState();

View file

@ -21,8 +21,6 @@ typedef enum {
TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2 TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2
} TelemetryPort; } TelemetryPort;
// telemetry
void initTelemetry(void);
void checkTelemetryState(void); void checkTelemetryState(void);
void handleTelemetry(void); void handleTelemetry(void);

View file

@ -6,6 +6,9 @@
#include "flight_common.h" #include "flight_common.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "gps_common.h" #include "gps_common.h"
#include "telemetry_common.h" #include "telemetry_common.h"
@ -59,26 +62,26 @@ extern uint8_t batteryCellCount;
static void sendDataHead(uint8_t id) static void sendDataHead(uint8_t id)
{ {
serialWrite(core.telemport, PROTOCOL_HEADER); serialWrite(serialPorts.telemport, PROTOCOL_HEADER);
serialWrite(core.telemport, id); serialWrite(serialPorts.telemport, id);
} }
static void sendTelemetryTail(void) static void sendTelemetryTail(void)
{ {
serialWrite(core.telemport, PROTOCOL_TAIL); serialWrite(serialPorts.telemport, PROTOCOL_TAIL);
} }
static void serializeFrsky(uint8_t data) static void serializeFrsky(uint8_t data)
{ {
// take care of byte stuffing // take care of byte stuffing
if (data == 0x5e) { if (data == 0x5e) {
serialWrite(core.telemport, 0x5d); serialWrite(serialPorts.telemport, 0x5d);
serialWrite(core.telemport, 0x3e); serialWrite(serialPorts.telemport, 0x3e);
} else if (data == 0x5d) { } else if (data == 0x5d) {
serialWrite(core.telemport, 0x5d); serialWrite(serialPorts.telemport, 0x5d);
serialWrite(core.telemport, 0x3d); serialWrite(serialPorts.telemport, 0x3d);
} else } else
serialWrite(core.telemport, data); serialWrite(serialPorts.telemport, data);
} }
static void serialize16(int16_t a) static void serialize16(int16_t a)
@ -222,14 +225,14 @@ static void sendHeading(void)
void freeFrSkyTelemetryPort(void) void freeFrSkyTelemetryPort(void)
{ {
if (mcfg.telemetry_port == TELEMETRY_PORT_UART) { if (mcfg.telemetry_port == TELEMETRY_PORT_UART) {
serialInit(mcfg.serial_baudrate); resetMainSerialPort();
} }
} }
void configureFrSkyTelemetryPort(void) void configureFrSkyTelemetryPort(void)
{ {
if (mcfg.telemetry_port == TELEMETRY_PORT_UART) { if (mcfg.telemetry_port == TELEMETRY_PORT_UART) {
serialInit(9600); openMainSerialPort(9600);
} }
} }
@ -238,7 +241,7 @@ static uint8_t cycleNum = 0;
bool canSendFrSkyTelemetry(void) bool canSendFrSkyTelemetry(void)
{ {
return serialTotalBytesWaiting(core.telemport) == 0; return serialTotalBytesWaiting(serialPorts.telemport) == 0;
} }
bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis) bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis)

View file

@ -44,7 +44,11 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "gps_common.h" #include "gps_common.h"
#include "telemetry_hott.h" #include "telemetry_hott.h"
@ -218,7 +222,7 @@ void hottV4FormatAndSendEAMResponse(void)
static void hottV4Respond(uint8_t *data, uint8_t size) static void hottV4Respond(uint8_t *data, uint8_t size)
{ {
serialSetMode(core.telemport, MODE_TX); serialSetMode(serialPorts.telemport, MODE_TX);
uint16_t crc = 0; uint16_t crc = 0;
uint8_t i; uint8_t i;
@ -235,31 +239,31 @@ static void hottV4Respond(uint8_t *data, uint8_t size)
delayMicroseconds(HOTTV4_TX_DELAY); delayMicroseconds(HOTTV4_TX_DELAY);
serialSetMode(core.telemport, MODE_RX); serialSetMode(serialPorts.telemport, MODE_RX);
} }
static void hottV4SerialWrite(uint8_t c) static void hottV4SerialWrite(uint8_t c)
{ {
serialWrite(core.telemport, c); serialWrite(serialPorts.telemport, c);
} }
void configureHoTTTelemetryPort(void) void configureHoTTTelemetryPort(void)
{ {
// TODO set speed here to 19200? // TODO set speed here to 19200?
serialSetMode(core.telemport, MODE_RX); serialSetMode(serialPorts.telemport, MODE_RX);
} }
void freeHoTTTelemetryPort(void) void freeHoTTTelemetryPort(void)
{ {
serialSetMode(core.telemport, MODE_RXTX); serialSetMode(serialPorts.telemport, MODE_RXTX);
} }
void handleHoTTTelemetry(void) void handleHoTTTelemetry(void)
{ {
uint8_t c; uint8_t c;
while (serialTotalBytesWaiting(core.telemport) > 0) { while (serialTotalBytesWaiting(serialPorts.telemport) > 0) {
c = serialRead(core.telemport); c = serialRead(serialPorts.telemport);
// Protocol specific waiting time to avoid collisions // Protocol specific waiting time to avoid collisions
delay(5); delay(5);