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

Merge pull request #1712 from betaflight/disable_gps

Disable GPS by default on smaller Sizes
This commit is contained in:
borisbstyle 2016-12-01 00:30:42 +01:00 committed by GitHub
commit 8a9d3818bd
10 changed files with 49 additions and 38 deletions

View file

@ -756,7 +756,11 @@ ifeq ($(DEBUG),GDB)
OPTIMIZE = -O0 OPTIMIZE = -O0
LTO_FLAGS = $(OPTIMIZE) LTO_FLAGS = $(OPTIMIZE)
else else
ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
OPTIMIZE = -Os OPTIMIZE = -Os
else
OPTIMIZE = -Ofast
endif
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
endif endif

View file

@ -32,7 +32,7 @@
#define CROSSFIRE_RSSI_FRAME_ID 0x14 #define CROSSFIRE_RSSI_FRAME_ID 0x14
#define CLEANFLIGHT_MODE_FRAME_ID 0x20 #define CLEANFLIGHT_MODE_FRAME_ID 0x20
#define DATA_BUFFER_SIZE 64 #define DATA_BUFFER_SIZE 128
typedef enum BSTDevice { typedef enum BSTDevice {
BSTDEV_1, BSTDEV_1,

View file

@ -1519,6 +1519,7 @@ void taskBstMasterProcess(uint32_t currentTime)
if(sensors(SENSOR_GPS) && !bstWriteBusy()) if(sensors(SENSOR_GPS) && !bstWriteBusy())
writeGpsPositionPrameToBST(); writeGpsPositionPrameToBST();
} }
bstMasterWriteLoop(); bstMasterWriteLoop();
if (isRebootScheduled) { if (isRebootScheduled) {
@ -1550,22 +1551,25 @@ static void bstMasterWrite16(uint16_t data)
bstMasterWrite8((uint8_t)(data >> 0)); bstMasterWrite8((uint8_t)(data >> 0));
} }
/*************************************************************************************************/
#define PUBLIC_ADDRESS 0x00
#ifdef GPS
static void bstMasterWrite32(uint32_t data) static void bstMasterWrite32(uint32_t data)
{ {
bstMasterWrite16((uint8_t)(data >> 16)); bstMasterWrite16((uint8_t)(data >> 16));
bstMasterWrite16((uint8_t)(data >> 0)); bstMasterWrite16((uint8_t)(data >> 0));
} }
/*************************************************************************************************/
#define PUBLIC_ADDRESS 0x00
static int32_t lat = 0; static int32_t lat = 0;
static int32_t lon = 0; static int32_t lon = 0;
static uint16_t alt = 0; static uint16_t alt = 0;
static uint8_t numOfSat = 0; static uint8_t numOfSat = 0;
#endif
bool writeGpsPositionPrameToBST(void) bool writeGpsPositionPrameToBST(void)
{ {
#ifdef GPS
if((lat != GPS_coord[LAT]) || (lon != GPS_coord[LON]) || (alt != GPS_altitude) || (numOfSat != GPS_numSat)) { if((lat != GPS_coord[LAT]) || (lon != GPS_coord[LON]) || (alt != GPS_altitude) || (numOfSat != GPS_numSat)) {
lat = GPS_coord[LAT]; lat = GPS_coord[LAT];
lon = GPS_coord[LON]; lon = GPS_coord[LON];
@ -1590,6 +1594,9 @@ bool writeGpsPositionPrameToBST(void)
return bstMasterWrite(masterWriteData); return bstMasterWrite(masterWriteData);
} else } else
return false; return false;
#else
return true;
#endif
} }
bool writeRollPitchYawToBST(void) bool writeRollPitchYawToBST(void)

View file

@ -148,9 +148,9 @@
#define LED_STRIP #define LED_STRIP
#define SONAR //#define SONAR
#define SONAR_ECHO_PIN PB1 //#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0 //#define SONAR_TRIGGER_PIN PB0
#define DEFAULT_FEATURES FEATURE_BLACKBOX #define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_RX_FEATURE FEATURE_RX_PPM

View file

@ -45,14 +45,14 @@
#define BMP280_SPI_INSTANCE SPI1 #define BMP280_SPI_INSTANCE SPI1
#define BMP280_CS_PIN PA13 #define BMP280_CS_PIN PA13
#define BARO //#define BARO
#define USE_BARO_BMP280 //#define USE_BARO_BMP280
#define USE_BARO_SPI_BMP280 //#define USE_BARO_SPI_BMP280
#define MAG // External //#define MAG // External
#define USE_MAG_AK8963 //#define USE_MAG_AK8963
#define USE_MAG_AK8975 //#define USE_MAG_AK8975
#define USE_MAG_HMC5883 //#define USE_MAG_HMC5883
//#define SONAR //#define SONAR
//#define SONAR_ECHO_PIN PB1 //#define SONAR_ECHO_PIN PB1

View file

@ -109,15 +109,15 @@
#define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1 #define SERIALRX_UART SERIAL_PORT_USART1
#define NAV //#define NAV
#define NAV_AUTO_MAG_DECLINATION //#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION //#define NAV_GPS_GLITCH_DETECTION
#define NAV_MAX_WAYPOINTS 60 //#define NAV_MAX_WAYPOINTS 60
#define GPS //#define GPS
#define BLACKBOX #define BLACKBOX
#define TELEMETRY #define TELEMETRY
#define SERIAL_RX #define SERIAL_RX
#define AUTOTUNE //#define AUTOTUNE
#define USE_SERVOS #define USE_SERVOS
#define USE_CLI #define USE_CLI

View file

@ -55,10 +55,10 @@
#define USE_BARO_MS5611 #define USE_BARO_MS5611
#define USE_BARO_BMP085 #define USE_BARO_BMP085
#define MAG //#define MAG
#define USE_MAG_AK8975 //#define USE_MAG_AK8975
#define USE_MAG_HMC5883 //#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW270_DEG //#define MAG_HMC5883_ALIGN CW270_DEG
#define USE_MAG_DATA_READY_SIGNAL #define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH #define ENSURE_MAG_DATA_READY_IS_HIGH
@ -69,9 +69,9 @@
#define USE_FLASHFS #define USE_FLASHFS
#define USE_FLASH_M25P16 #define USE_FLASH_M25P16
#define SONAR //#define SONAR
#define SONAR_TRIGGER_PIN PB0 //#define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1 //#define SONAR_ECHO_PIN PB1
#define USE_UART1 #define USE_UART1
#define USE_UART2 #define USE_UART2

View file

@ -50,8 +50,8 @@
#define BARO #define BARO
#define USE_BARO_BMP280 #define USE_BARO_BMP280
#define MAG //#define MAG
#define USE_MAG_AK8963 //#define USE_MAG_AK8963
//#define USE_MAG_HMC5883 // External //#define USE_MAG_HMC5883 // External
#define MAG_AK8963_ALIGN CW90_DEG_FLIP #define MAG_AK8963_ALIGN CW90_DEG_FLIP

View file

@ -51,15 +51,15 @@
#define BARO #define BARO
#define USE_BARO_BMP280 #define USE_BARO_BMP280
#define MAG //#define MAG
#define USE_MPU9250_MAG // Enables bypass configuration //#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8975 //#define USE_MAG_AK8975
#define USE_MAG_HMC5883 // External //#define USE_MAG_HMC5883 // External
#define MAG_AK8975_ALIGN CW90_DEG_FLIP //#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define SONAR //#define SONAR
#define SONAR_ECHO_PIN PB1 //#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0 //#define SONAR_TRIGGER_PIN PB0
#define USB_IO #define USB_IO
#define USB_CABLE_DETECTION #define USB_CABLE_DETECTION

View file

@ -34,6 +34,7 @@
#define STM_FAST_TARGET #define STM_FAST_TARGET
#define USE_DSHOT #define USE_DSHOT
#define I2C3_OVERCLOCK true #define I2C3_OVERCLOCK true
#define GPS
#endif #endif
#ifdef STM32F3 #ifdef STM32F3
@ -70,7 +71,6 @@
#if (FLASH_SIZE > 64) #if (FLASH_SIZE > 64)
#define BLACKBOX #define BLACKBOX
#define GPS
#define TELEMETRY #define TELEMETRY
#define TELEMETRY_FRSKY #define TELEMETRY_FRSKY
#define TELEMETRY_HOTT #define TELEMETRY_HOTT