mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 23:35:34 +03:00
Improving code readability by aligning comments with code and removing
comments that duplicated code. Comments are harder to refactor than code and become stale. Updating default and limit values for some settings to use enum values.
This commit is contained in:
parent
f7c937a323
commit
3007d3cbdc
7 changed files with 42 additions and 29 deletions
21
src/board.h
21
src/board.h
|
@ -90,19 +90,30 @@ typedef enum {
|
||||||
GPS_MTK_NMEA,
|
GPS_MTK_NMEA,
|
||||||
GPS_MTK_BINARY,
|
GPS_MTK_BINARY,
|
||||||
GPS_MAG_BINARY,
|
GPS_MAG_BINARY,
|
||||||
|
GPS_HARDWARE_MAX = GPS_MAG_BINARY,
|
||||||
} GPSHardware;
|
} GPSHardware;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
GPS_BAUD_115200 = 0,
|
||||||
|
GPS_BAUD_57600,
|
||||||
|
GPS_BAUD_38400,
|
||||||
|
GPS_BAUD_19200,
|
||||||
|
GPS_BAUD_9600,
|
||||||
|
GPS_BAUD_MAX = GPS_BAUD_9600
|
||||||
|
} GPSBaudRates;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
TELEMETRY_PROVIDER_FRSKY = 0,
|
TELEMETRY_PROVIDER_FRSKY = 0,
|
||||||
TELEMETRY_PROVIDER_HOTT
|
TELEMETRY_PROVIDER_HOTT,
|
||||||
|
TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_HOTT
|
||||||
} TelemetryProvider;
|
} TelemetryProvider;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
TELEMETRY_UART = 0,
|
TELEMETRY_PORT_UART = 0,
|
||||||
TELEMETRY_SOFTSERIAL_1,
|
TELEMETRY_PORT_SOFTSERIAL_1, // Requires FEATURE_SOFTSERIAL
|
||||||
TELEMETRY_SOFTSERIAL_2,
|
TELEMETRY_PORT_SOFTSERIAL_2, // Requires FEATURE_SOFTSERIAL
|
||||||
} TelemetrySerial;
|
TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2
|
||||||
|
} TelemetryPort;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
X = 0,
|
X = 0,
|
||||||
|
|
|
@ -133,11 +133,11 @@ const clivalue_t valueTable[] = {
|
||||||
{ "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 1200, 19200 },
|
{ "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 1200, 19200 },
|
||||||
{ "softserial_1_inverted", VAR_UINT8, &mcfg.softserial_1_inverted, 0, 1 },
|
{ "softserial_1_inverted", VAR_UINT8, &mcfg.softserial_1_inverted, 0, 1 },
|
||||||
{ "softserial_2_inverted", VAR_UINT8, &mcfg.softserial_2_inverted, 0, 1 },
|
{ "softserial_2_inverted", VAR_UINT8, &mcfg.softserial_2_inverted, 0, 1 },
|
||||||
{ "gps_type", VAR_UINT8, &mcfg.gps_type, 0, 3 },
|
{ "gps_type", VAR_UINT8, &mcfg.gps_type, 0, GPS_HARDWARE_MAX },
|
||||||
{ "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, 4 },
|
{ "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, GPS_BAUD_MAX },
|
||||||
{ "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 3 },
|
{ "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 3 },
|
||||||
{ "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, 1 },
|
{ "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
||||||
{ "telemetry_softserial", VAR_UINT8, &mcfg.telemetry_softserial, 0, 2 },
|
{ "telemetry_port", VAR_UINT8, &mcfg.telemetry_port, 0, TELEMETRY_PORT_MAX },
|
||||||
{ "telemetry_switch", VAR_UINT8, &mcfg.telemetry_switch, 0, 1 },
|
{ "telemetry_switch", VAR_UINT8, &mcfg.telemetry_switch, 0, 1 },
|
||||||
{ "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 },
|
{ "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 },
|
||||||
{ "vbatmaxcellvoltage", VAR_UINT8, &mcfg.vbatmaxcellvoltage, 10, 50 },
|
{ "vbatmaxcellvoltage", VAR_UINT8, &mcfg.vbatmaxcellvoltage, 10, 50 },
|
||||||
|
|
|
@ -193,7 +193,7 @@ static void resetConf(void)
|
||||||
mcfg.power_adc_channel = 0;
|
mcfg.power_adc_channel = 0;
|
||||||
mcfg.serialrx_type = 0;
|
mcfg.serialrx_type = 0;
|
||||||
mcfg.telemetry_provider = TELEMETRY_PROVIDER_FRSKY;
|
mcfg.telemetry_provider = TELEMETRY_PROVIDER_FRSKY;
|
||||||
mcfg.telemetry_softserial = TELEMETRY_UART;
|
mcfg.telemetry_port = TELEMETRY_PORT_UART;
|
||||||
mcfg.telemetry_switch = 0;
|
mcfg.telemetry_switch = 0;
|
||||||
mcfg.midrc = 1500;
|
mcfg.midrc = 1500;
|
||||||
mcfg.mincheck = 1100;
|
mcfg.mincheck = 1100;
|
||||||
|
@ -213,7 +213,7 @@ static void resetConf(void)
|
||||||
mcfg.servo_pwm_rate = 50;
|
mcfg.servo_pwm_rate = 50;
|
||||||
// gps/nav stuff
|
// gps/nav stuff
|
||||||
mcfg.gps_type = GPS_NMEA;
|
mcfg.gps_type = GPS_NMEA;
|
||||||
mcfg.gps_baudrate = 0;
|
mcfg.gps_baudrate = GPS_BAUD_115200;
|
||||||
// serial (USART1) baudrate
|
// serial (USART1) baudrate
|
||||||
mcfg.serial_baudrate = 115200;
|
mcfg.serial_baudrate = 115200;
|
||||||
mcfg.softserial_baudrate = 9600;
|
mcfg.softserial_baudrate = 9600;
|
||||||
|
|
20
src/gps.c
20
src/gps.c
|
@ -8,22 +8,24 @@
|
||||||
// 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)
|
||||||
#define GPS_TIMEOUT (2500)
|
#define GPS_TIMEOUT (2500)
|
||||||
// How many entries in gpsInitData array below
|
// How many entries in gpsInitData array below
|
||||||
#define GPS_INIT_ENTRIES (5)
|
#define GPS_INIT_ENTRIES (GPS_BAUD_MAX + 1)
|
||||||
#define GPS_BAUD_DELAY (100)
|
#define GPS_BAUD_DELAY (100)
|
||||||
|
|
||||||
typedef struct gpsInitData_t {
|
typedef struct gpsInitData_t {
|
||||||
|
uint8_t index;
|
||||||
uint32_t baudrate;
|
uint32_t baudrate;
|
||||||
const char *ubx;
|
const char *ubx;
|
||||||
const char *mtk;
|
const char *mtk;
|
||||||
} gpsInitData_t;
|
} gpsInitData_t;
|
||||||
|
|
||||||
|
// NMEA will cycle through these until valid data is received
|
||||||
static const gpsInitData_t gpsInitData[] = {
|
static const gpsInitData_t gpsInitData[] = {
|
||||||
{ 115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" },
|
{ GPS_BAUD_115200, 115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" },
|
||||||
{ 57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" },
|
{ GPS_BAUD_57600, 57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" },
|
||||||
{ 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" },
|
{ GPS_BAUD_38400, 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" },
|
||||||
{ 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" },
|
{ GPS_BAUD_19200, 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" },
|
||||||
// 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed
|
// 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed
|
||||||
{ 9600, "", "" }
|
{ GPS_BAUD_9600, 9600, "", "" }
|
||||||
};
|
};
|
||||||
|
|
||||||
static const uint8_t ubloxInit[] = {
|
static const uint8_t ubloxInit[] = {
|
||||||
|
@ -74,7 +76,7 @@ static void gpsSetState(uint8_t state)
|
||||||
gpsData.state_ts = millis();
|
gpsData.state_ts = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
void gpsInit(uint8_t baudrate)
|
void gpsInit(uint8_t baudrateIndex)
|
||||||
{
|
{
|
||||||
portMode_t mode = MODE_RXTX;
|
portMode_t mode = MODE_RXTX;
|
||||||
|
|
||||||
|
@ -83,7 +85,7 @@ void gpsInit(uint8_t baudrate)
|
||||||
if (!feature(FEATURE_GPS))
|
if (!feature(FEATURE_GPS))
|
||||||
return;
|
return;
|
||||||
|
|
||||||
gpsData.baudrateIndex = baudrate;
|
gpsData.baudrateIndex = baudrateIndex;
|
||||||
gpsData.lastMessage = millis();
|
gpsData.lastMessage = millis();
|
||||||
gpsData.errors = 0;
|
gpsData.errors = 0;
|
||||||
// only RX is needed for NMEA-style GPS
|
// only RX is needed for NMEA-style GPS
|
||||||
|
@ -91,7 +93,7 @@ void gpsInit(uint8_t baudrate)
|
||||||
mode = MODE_RX;
|
mode = MODE_RX;
|
||||||
|
|
||||||
gpsSetPIDs();
|
gpsSetPIDs();
|
||||||
core.gpsport = uartOpen(USART2, gpsNewData, gpsInitData[baudrate].baudrate, mode);
|
core.gpsport = uartOpen(USART2, gpsNewData, 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);
|
||||||
}
|
}
|
||||||
|
|
8
src/mw.h
8
src/mw.h
|
@ -271,8 +271,8 @@ typedef struct master_t {
|
||||||
uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable.
|
uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable.
|
||||||
|
|
||||||
// gps-related stuff
|
// gps-related stuff
|
||||||
uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2: MTK NMEA 3: MTK Binary
|
uint8_t gps_type; // See GPSHardware enum.
|
||||||
int8_t gps_baudrate; // GPS baudrate, 0: 115200, 1: 57600, 2: 38400, 3: 19200, 4: 9600. NMEA will cycle through these until valid data is received
|
int8_t gps_baudrate; // See GPSBaudRates enum.
|
||||||
|
|
||||||
uint32_t serial_baudrate;
|
uint32_t serial_baudrate;
|
||||||
|
|
||||||
|
@ -280,8 +280,8 @@ typedef struct master_t {
|
||||||
uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1
|
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 softserial_2_inverted; // use inverted softserial input and output signals on port 2
|
||||||
|
|
||||||
uint8_t telemetry_provider; // Telemetry provider. 0:FRSKY
|
uint8_t telemetry_provider; // See TelemetryProvider enum.
|
||||||
uint8_t telemetry_softserial; // Serial to use for Telemetry. 0:USART1, 1:SoftSerial1 (Enable FEATURE_SOFTSERIAL first)
|
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
|
||||||
|
|
|
@ -8,11 +8,11 @@ void initTelemetry(void)
|
||||||
{
|
{
|
||||||
// Sanity check for softserial vs. telemetry port
|
// Sanity check for softserial vs. telemetry port
|
||||||
if (!feature(FEATURE_SOFTSERIAL))
|
if (!feature(FEATURE_SOFTSERIAL))
|
||||||
mcfg.telemetry_softserial = TELEMETRY_UART;
|
mcfg.telemetry_port = TELEMETRY_PORT_UART;
|
||||||
|
|
||||||
if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_1)
|
if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1)
|
||||||
core.telemport = &(softSerialPorts[0].port);
|
core.telemport = &(softSerialPorts[0].port);
|
||||||
else if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_2)
|
else if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2)
|
||||||
core.telemport = &(softSerialPorts[1].port);
|
core.telemport = &(softSerialPorts[1].port);
|
||||||
else
|
else
|
||||||
core.telemport = core.mainport;
|
core.telemport = core.mainport;
|
||||||
|
@ -26,7 +26,7 @@ bool isTelemetryEnabled(void)
|
||||||
{
|
{
|
||||||
bool telemetryCurrentlyEnabled = true;
|
bool telemetryCurrentlyEnabled = true;
|
||||||
|
|
||||||
if (mcfg.telemetry_softserial == TELEMETRY_UART) {
|
if (mcfg.telemetry_port == TELEMETRY_PORT_UART) {
|
||||||
if (!mcfg.telemetry_switch)
|
if (!mcfg.telemetry_switch)
|
||||||
telemetryCurrentlyEnabled = f.ARMED;
|
telemetryCurrentlyEnabled = f.ARMED;
|
||||||
else
|
else
|
||||||
|
|
|
@ -230,7 +230,7 @@ void updateFrSkyTelemetryState(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mcfg.telemetry_softserial == TELEMETRY_UART && mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY) {
|
if (mcfg.telemetry_port == TELEMETRY_PORT_UART && mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY) {
|
||||||
if (frSkyTelemetryCurrentlyEnabled)
|
if (frSkyTelemetryCurrentlyEnabled)
|
||||||
serialInit(9600);
|
serialInit(9600);
|
||||||
else
|
else
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue