From e2975a67e709394d4a0770c229e48b052976ae44 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Sep 2023 18:16:34 +1000 Subject: [PATCH] AP_HAL_ChibiOS: use AP_GPS_ENABLED to exclude more code when GPS not compiled in --- libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc | 4 +++- .../AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc | 1 + .../AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h | 10 ++++++++-- 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc index e5e18f3d68..cd519bdd32 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc @@ -2,4 +2,6 @@ define AP_GPS_BACKEND_DEFAULT_ENABLED 0 define AP_GPS_UBLOX_ENABLED 1 - +define AP_GPS_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS +undef HAL_MSP_GPS_ENABLED +define HAL_MSP_GPS_ENABLED HAL_MSP_SENSORS_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc index 6448335d68..05a48aec92 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc @@ -9,6 +9,7 @@ define AP_OPTICALFLOW_ENABLED 0 define AP_GPS_BACKEND_DEFAULT_ENABLED 0 define AP_GPS_UBLOX_ENABLED 1 define AP_GPS_NMEA_ENABLED 1 +define HAL_MSP_GPS_ENABLED HAL_MSP_SENSORS_ENABLED define AP_MOTORS_FRAME_DEFAULT_ENABLED 0 define AP_MOTORS_FRAME_QUAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index af253acccf..ba6a4b895e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -157,6 +157,12 @@ * Note also that f103-GPS explicitly disables some of these backends. */ #define AP_GPS_BACKEND_DEFAULT_ENABLED 0 +#ifndef AP_GPS_UBLOX_ENABLED +#define AP_GPS_UBLOX_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#endif +#ifndef HAL_MSP_GPS_ENABLED +#define HAL_MSP_GPS_ENABLED defined(HAL_PERIPH_ENABLE_GPS) && HAL_MSP_SENSORS_ENABLED +#endif #ifndef AP_GPS_ERB_ENABLED #define AP_GPS_ERB_ENABLED 0 @@ -311,7 +317,7 @@ #define AP_AHRS_ENABLED defined(HAL_PERIPH_ENABLE_AHRS) #define AP_COMPASS_ENABLED defined(HAL_PERIPH_ENABLE_MAG) #define AP_BARO_ENABLED defined(HAL_PERIPH_ENABLE_BARO) -#define AP_GPS_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#define AP_GPS_ENABLED 1 // FIXME: should be defined(HAL_PERIPH_ENABLE_GPS) #define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM) #define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN) @@ -324,7 +330,7 @@ #endif #ifndef AP_UART_MONITOR_ENABLED -#define AP_UART_MONITOR_ENABLED AP_GPS_ENABLED && (GPS_MOVING_BASELINE || BOARD_FLASH_SIZE>=256) +#define AP_UART_MONITOR_ENABLED defined(HAL_PERIPH_ENABLE_GPS) && (GPS_MOVING_BASELINE || BOARD_FLASH_SIZE>=256) #endif #ifndef HAL_BOARD_LOG_DIRECTORY