mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
AP_HAL_ChibiOS: move from HAL_NO_GCS to HAL_GCS_ENABLED
This commit is contained in:
parent
6d615a3e16
commit
1bd62362a4
@ -227,11 +227,15 @@ uint64_t Util::get_hw_rtc() const
|
||||
|
||||
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
|
||||
|
||||
#if defined(HAL_NO_GCS) || defined(HAL_BOOTLOADER_BUILD)
|
||||
#define Debug(fmt, args ...) do { hal.console->printf(fmt, ## args); } while (0)
|
||||
#else
|
||||
#ifndef HAL_BOOTLOADER_BUILD
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#if HAL_GCS_ENABLED
|
||||
#define Debug(fmt, args ...) do { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } while (0)
|
||||
#endif // HAL_GCS_ENABLED
|
||||
#endif // ifndef HAL_BOOT_LOADER_BUILD
|
||||
|
||||
#ifndef Debug
|
||||
#define Debug(fmt, args ...) do { hal.console->printf(fmt, ## args); } while (0)
|
||||
#endif
|
||||
|
||||
Util::FlashBootloader Util::flash_bootloader()
|
||||
|
@ -106,7 +106,7 @@ define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.birdcandy"
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_GCS_ENABLED 0
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
|
@ -133,7 +133,6 @@ define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -39,7 +39,6 @@ define GPS_MAX_RECEIVERS 1
|
||||
define GPS_MAX_INSTANCES 1
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
@ -35,7 +35,6 @@ define GPS_MAX_RECEIVERS 1
|
||||
define GPS_MAX_INSTANCES 1
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
@ -129,7 +129,6 @@ define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -137,7 +137,6 @@ define HAL_UART_MIN_RX_SIZE 128
|
||||
define HAL_UART_STACK_SIZE 0x200
|
||||
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -26,7 +26,7 @@ FLASH_SIZE_KB 2048
|
||||
# env AP_PERIPH 1
|
||||
|
||||
# define HAL_BUILD_AP_PERIPH
|
||||
# define HAL_NO_GCS
|
||||
# define HAL_GCS_ENABLED 0
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
@ -26,7 +26,7 @@ FLASH_SIZE_KB 2048
|
||||
# env AP_PERIPH 1
|
||||
|
||||
# define HAL_BUILD_AP_PERIPH
|
||||
# define HAL_NO_GCS
|
||||
# define HAL_GCS_ENABLED 0
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
@ -81,4 +81,4 @@ define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
define HAL_NO_GCS
|
||||
define HAL_GCS_ENABLED 0
|
||||
|
@ -40,7 +40,6 @@ SERIAL_ORDER OTG1 UART7
|
||||
|
||||
define HAL_NO_LOGGING TRUE
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_NO_GCS
|
||||
|
||||
# USART3 F9
|
||||
PD9 USART3_RX USART3
|
||||
|
@ -59,7 +59,7 @@ define CONFIGURE_PPS_PIN TRUE
|
||||
FLASH_RESERVE_START_KB 256
|
||||
|
||||
define GPS_UBLOX_MOVING_BASELINE TRUE
|
||||
# define HAL_NO_LOGGING TRUE
|
||||
define HAL_GCS_ENABLED 1
|
||||
define HAL_LOGGING_ENABLED TRUE
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
@ -111,7 +111,6 @@ define HAL_UART_MIN_RX_SIZE 128
|
||||
define HAL_UART_STACK_SIZE 0x200
|
||||
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -144,7 +144,6 @@ define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS"
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
|
@ -49,7 +49,6 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3
|
||||
# default ADSB off by setting 0 baudrate
|
||||
define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_USE_RTC FALSE
|
||||
|
@ -39,7 +39,6 @@ define GPS_MAX_RECEIVERS 1
|
||||
define GPS_MAX_INSTANCES 1
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
@ -103,7 +103,6 @@ define HAL_UART_MIN_RX_SIZE 128
|
||||
define HAL_UART_STACK_SIZE 256
|
||||
define STORAGE_THD_WA_SIZE 512
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -155,7 +155,6 @@ define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
|
@ -104,7 +104,6 @@ define HAL_UART_STACK_SIZE 256
|
||||
define STORAGE_THD_WA_SIZE 300
|
||||
define IO_THD_WA_SIZE 300
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -81,8 +81,6 @@ define HAL_UART_STACK_SIZE 512
|
||||
define STORAGE_THD_WA_SIZE 512
|
||||
define IO_THD_WA_SIZE 512
|
||||
|
||||
define HAL_NO_GCS
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
||||
define HAL_BUILD_AP_PERIPH
|
||||
|
@ -104,8 +104,6 @@ define HAL_UART_STACK_SIZE 0x300
|
||||
define STORAGE_THD_WA_SIZE 512
|
||||
define IO_THD_WA_SIZE 512
|
||||
|
||||
define HAL_NO_GCS
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
||||
define HAL_BUILD_AP_PERIPH
|
||||
|
@ -49,7 +49,6 @@ define DMA_RESERVE_SIZE 0
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -86,7 +86,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
@ -2358,6 +2358,9 @@ def add_apperiph_defaults(f):
|
||||
#ifndef HAL_LOGGING_ENABLED
|
||||
#define HAL_LOGGING_ENABLED 0
|
||||
#endif
|
||||
#ifndef HAL_GCS_ENABLED
|
||||
#define HAL_GCS_ENABLED 0
|
||||
#endif
|
||||
// default to no protocols, AP_Periph enables with params
|
||||
#define HAL_SERIAL1_PROTOCOL -1
|
||||
#define HAL_SERIAL2_PROTOCOL -1
|
||||
|
Loading…
Reference in New Issue
Block a user