AP_Radio: use GCS_SEND_TEXT rather than gcs().send_text

Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
Peter Barker 2024-08-07 13:17:21 +10:00 committed by Andrew Tridgell
parent 96b5fa6e93
commit cee45a2fc2
3 changed files with 3 additions and 3 deletions

View File

@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal;
// This is for debugging issues with frequency hopping and synchronisation. // This is for debugging issues with frequency hopping and synchronisation.
#define DebugPrintf(level, fmt, args...) do { if (AP_Radio_beken::radio_singleton && ((level) <= AP_Radio_beken::radio_singleton->get_debug_level())) { printf(fmt, ##args); }} while (0) #define DebugPrintf(level, fmt, args...) do { if (AP_Radio_beken::radio_singleton && ((level) <= AP_Radio_beken::radio_singleton->get_debug_level())) { printf(fmt, ##args); }} while (0)
// Output debug information on the mavlink to the UART connected to the WiFi, wrapped in MavLink packets // Output debug information on the mavlink to the UART connected to the WiFi, wrapped in MavLink packets
#define DebugMavlink(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) #define DebugMavlink(level, fmt, args...) do { if ((level) <= get_debug_level()) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ##args); }} while (0)
#if SUPPORT_BK_DEBUG_PINS #if SUPPORT_BK_DEBUG_PINS

View File

@ -30,7 +30,7 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) #define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ##args); }} while (0)
// object instance for trampoline // object instance for trampoline
AP_Radio_cc2500 *AP_Radio_cc2500::radio_singleton; AP_Radio_cc2500 *AP_Radio_cc2500::radio_singleton;

View File

@ -42,7 +42,7 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) #define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ##args); }} while (0)
#define LP_FIFO_SIZE 16 // Physical data FIFO lengths in Radio #define LP_FIFO_SIZE 16 // Physical data FIFO lengths in Radio