mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use can_printf_severity() for AP_Periph
This commit is contained in:
parent
ed27e30f9e
commit
632bb71c87
|
@ -1346,9 +1346,9 @@ GCS &gcs();
|
|||
#define AP_HAVE_GCS_SEND_TEXT 1
|
||||
#else
|
||||
extern "C" {
|
||||
void can_printf(const char *fmt, ...);
|
||||
void can_printf_severity(uint8_t severity, const char *fmt, ...);
|
||||
}
|
||||
#define GCS_SEND_TEXT(severity, format, args...) (void)severity; can_printf(format, ##args)
|
||||
#define GCS_SEND_TEXT(severity, format, args...) can_printf_severity(severity, format, ##args)
|
||||
#define AP_HAVE_GCS_SEND_TEXT 1
|
||||
#endif
|
||||
|
||||
|
@ -1358,12 +1358,31 @@ void can_printf(const char *fmt, ...);
|
|||
|
||||
// map send text to can_printf() on larger AP_Periph boards
|
||||
extern "C" {
|
||||
void can_printf(const char *fmt, ...);
|
||||
void can_printf_severity(uint8_t severity, const char *fmt, ...);
|
||||
}
|
||||
#define GCS_SEND_TEXT(severity, format, args...) can_printf(format, ##args)
|
||||
#define GCS_SEND_TEXT(severity, format, args...) can_printf_severity(severity, format, ##args)
|
||||
#define GCS_SEND_MESSAGE(msg)
|
||||
#define AP_HAVE_GCS_SEND_TEXT 1
|
||||
|
||||
/*
|
||||
we need a severity enum for the can_printf_severity function with no GCS present
|
||||
*/
|
||||
#ifndef HAVE_ENUM_MAV_SEVERITY
|
||||
enum MAV_SEVERITY
|
||||
{
|
||||
MAV_SEVERITY_EMERGENCY=0,
|
||||
MAV_SEVERITY_ALERT=1,
|
||||
MAV_SEVERITY_CRITICAL=2,
|
||||
MAV_SEVERITY_ERROR=3,
|
||||
MAV_SEVERITY_WARNING=4,
|
||||
MAV_SEVERITY_NOTICE=5,
|
||||
MAV_SEVERITY_INFO=6,
|
||||
MAV_SEVERITY_DEBUG=7,
|
||||
MAV_SEVERITY_ENUM_END=8,
|
||||
};
|
||||
#define HAVE_ENUM_MAV_SEVERITY
|
||||
#endif
|
||||
|
||||
#else // HAL_GCS_ENABLED
|
||||
// empty send text when we have no GCS
|
||||
#define GCS_SEND_TEXT(severity, format, args...)
|
||||
|
|
Loading…
Reference in New Issue