mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Radio: use GCS_SEND_TEXT rather than gcs().send_text
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
96b5fa6e93
commit
cee45a2fc2
@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal;
|
||||
// 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)
|
||||
// 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
|
||||
|
@ -30,7 +30,7 @@
|
||||
|
||||
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
|
||||
AP_Radio_cc2500 *AP_Radio_cc2500::radio_singleton;
|
||||
|
@ -42,7 +42,7 @@
|
||||
|
||||
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
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user