#include "GCS.h" extern const AP_HAL::HAL& hal; /* send a text message to all GCS */ void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list) { char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; hal.util->vsnprintf((char *)text, sizeof(text)-1, fmt, arg_list); send_statustext(severity, GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask(), text); } void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...) { va_list arg_list; va_start(arg_list, fmt); send_textv(severity, fmt, arg_list); va_end(arg_list); } #define FOR_EACH_ACTIVE_CHANNEL(methodcall) \ do { \ for (uint8_t i=0; i= num_gcs()) { return false; } if (chan(c).alternative.handler) { // already have one installed - we may need to add support for // multiple alternative handlers return false; } chan(c).alternative.handler = handler; return true; } #undef FOR_EACH_ACTIVE_CHANNEL