mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: add send_textv functions
This commit is contained in:
parent
b94e31b21a
commit
a44c1378f7
|
@ -5,15 +5,19 @@ extern const AP_HAL::HAL& hal;
|
||||||
/*
|
/*
|
||||||
send a text message to all GCS
|
send a text message to all GCS
|
||||||
*/
|
*/
|
||||||
void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
||||||
{
|
{
|
||||||
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
|
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_list arg_list;
|
||||||
va_start(arg_list, fmt);
|
va_start(arg_list, fmt);
|
||||||
hal.util->vsnprintf((char *)text, sizeof(text)-1, fmt, arg_list);
|
send_textv(severity, fmt, arg_list);
|
||||||
va_end(arg_list);
|
va_end(arg_list);
|
||||||
text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0;
|
|
||||||
send_statustext(severity, GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask(), text);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#define FOR_EACH_ACTIVE_CHANNEL(methodcall) \
|
#define FOR_EACH_ACTIVE_CHANNEL(methodcall) \
|
||||||
|
|
|
@ -109,6 +109,7 @@ public:
|
||||||
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
|
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
|
||||||
void send_message(enum ap_message id);
|
void send_message(enum ap_message id);
|
||||||
void send_text(MAV_SEVERITY severity, const char *fmt, ...);
|
void send_text(MAV_SEVERITY severity, const char *fmt, ...);
|
||||||
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
||||||
void data_stream_send();
|
void data_stream_send();
|
||||||
void queued_param_send();
|
void queued_param_send();
|
||||||
void queued_waypoint_send();
|
void queued_waypoint_send();
|
||||||
|
@ -580,6 +581,7 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
void send_text(MAV_SEVERITY severity, const char *fmt, ...);
|
void send_text(MAV_SEVERITY severity, const char *fmt, ...);
|
||||||
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
||||||
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
|
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
|
||||||
void service_statustext(void);
|
void service_statustext(void);
|
||||||
virtual GCS_MAVLINK &chan(const uint8_t ofs) = 0;
|
virtual GCS_MAVLINK &chan(const uint8_t ofs) = 0;
|
||||||
|
|
|
@ -606,15 +606,18 @@ void GCS_MAVLINK::handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
void GCS_MAVLINK::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
||||||
{
|
{
|
||||||
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
|
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
|
||||||
|
hal.util->vsnprintf((char *)text, sizeof(text)-1, fmt, arg_list);
|
||||||
|
gcs().send_statustext(severity, (1<<chan), text);
|
||||||
|
}
|
||||||
|
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
||||||
|
{
|
||||||
va_list arg_list;
|
va_list arg_list;
|
||||||
va_start(arg_list, fmt);
|
va_start(arg_list, fmt);
|
||||||
hal.util->vsnprintf((char *)text, sizeof(text), fmt, arg_list);
|
send_textv(severity, fmt, arg_list);
|
||||||
va_end(arg_list);
|
va_end(arg_list);
|
||||||
text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0;
|
|
||||||
gcs().send_statustext(severity, (1<<chan), text);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio)
|
void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio)
|
||||||
|
|
Loading…
Reference in New Issue