mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
HAL_ChibiOS: enable UART monitor
enabled if GPS moving baseline available or the board flash size is 256k or over
This commit is contained in:
parent
62b2fdb8f8
commit
a3eba8bbd3
@ -3322,6 +3322,14 @@ INCLUDE common.ld
|
|||||||
#define AP_BOOTLOADER_ALWAYS_ERASE 1
|
#define AP_BOOTLOADER_ALWAYS_ERASE 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef GPS_MOVING_BASELINE
|
||||||
|
#define GPS_MOVING_BASELINE 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_UART_MONITOR_ENABLED
|
||||||
|
#define AP_UART_MONITOR_ENABLED AP_GPS_ENABLED && (GPS_MOVING_BASELINE || BOARD_FLASH_SIZE>=256)
|
||||||
|
#endif
|
||||||
|
|
||||||
// end AP_Periph defaults
|
// end AP_Periph defaults
|
||||||
''')
|
''')
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user