mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: use GCS_SEND_TEXT rather than gcs().send_text
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
f7767d7fd0
commit
23b7e0f64d
|
@ -269,7 +269,7 @@ uint64_t Util::get_hw_rtc() const
|
|||
|
||||
#if HAL_GCS_ENABLED
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#define Debug(fmt, args ...) do { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } while (0)
|
||||
#define Debug(fmt, args ...) do { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } while (0)
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
||||
#ifndef Debug
|
||||
|
|
Loading…
Reference in New Issue