AP_HAL_ChibiOS: disable RPM by default on Periph

This commit is contained in:
Tom Pittenger 2023-08-08 21:57:48 -07:00 committed by Tom Pittenger
parent 1a67775c52
commit 2b30fbcfb2

View File

@ -307,6 +307,7 @@
#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_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM)
#ifndef AP_BOOTLOADER_ALWAYS_ERASE
#define AP_BOOTLOADER_ALWAYS_ERASE 1