mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_ChibiOS: define HAL_ENABLE_SAVE_PERSISTENT_PARAMS for bootloader in hwdef.h
This commit is contained in:
parent
8ecd1d9a37
commit
47c7acf1b3
@ -27,7 +27,7 @@ class ExpandingString;
|
||||
// on F7 and H7 we will try to save key persistent parameters at the
|
||||
// end of the bootloader sector. This enables temperature calibration
|
||||
// data to be saved persistently in the factory
|
||||
#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS !defined(HAL_BOOTLOADER_BUILD) && !defined(HAL_BUILD_AP_PERIPH) && (defined(STM32F7) || defined(STM32H7))
|
||||
#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS (defined(STM32F7) || defined(STM32H7))
|
||||
#endif
|
||||
|
||||
class ChibiOS::Util : public AP_HAL::Util {
|
||||
|
@ -2989,6 +2989,11 @@ def add_apperiph_defaults(f):
|
||||
#ifndef AP_FENCE_ENABLED
|
||||
#define AP_FENCE_ENABLED 0
|
||||
#endif
|
||||
|
||||
// periph does not save temperature cals etc:
|
||||
#ifndef HAL_ENABLE_SAVE_PERSISTENT_PARAMS
|
||||
#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0
|
||||
#endif
|
||||
''')
|
||||
|
||||
def add_bootloader_defaults(f):
|
||||
@ -3018,6 +3023,11 @@ def add_bootloader_defaults(f):
|
||||
#endif
|
||||
|
||||
#define HAL_MAX_CAN_PROTOCOL_DRIVERS 0
|
||||
|
||||
// bootloader does not save temperature cals etc:
|
||||
#ifndef HAL_ENABLE_SAVE_PERSISTENT_PARAMS
|
||||
#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0
|
||||
#endif
|
||||
''')
|
||||
|
||||
def add_iomcu_firmware_defaults(f):
|
||||
|
Loading…
Reference in New Issue
Block a user