Tracker: convert to using static send_statustext

- no more MSG_STATUSTEXT
- TODO: replace calls to gcs_send_text and gcs_send_text_fmt to GCS_MAVLINK::send_statustext()
This commit is contained in:
Tom Pittenger 2016-02-23 12:56:56 -08:00 committed by Andrew Tridgell
parent 6568402b28
commit 0709cc6b25
2 changed files with 7 additions and 34 deletions

View File

@ -127,15 +127,6 @@ void Tracker::send_waypoint_request(mavlink_channel_t chan)
gcs[chan-MAVLINK_COMM_0].queued_waypoint_send();
}
void Tracker::send_statustext(mavlink_channel_t chan)
{
mavlink_statustext_t *s = &gcs[chan-MAVLINK_COMM_0].pending_status;
mavlink_msg_statustext_send(
chan,
s->severity,
s->text);
}
void Tracker::send_nav_controller_output(mavlink_channel_t chan)
{
mavlink_msg_nav_controller_output_send(
@ -240,9 +231,8 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
break;
case MSG_STATUSTEXT:
CHECK_PAYLOAD_SIZE(STATUSTEXT);
tracker.send_statustext(chan);
break;
// depreciated, use GCS_MAVLINK::send_statustext*
return false;
case MSG_AHRS:
CHECK_PAYLOAD_SIZE(AHRS);
@ -989,14 +979,7 @@ void Tracker::gcs_update(void)
void Tracker::gcs_send_text(MAV_SEVERITY severity, const char *str)
{
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
gcs[i].send_text(severity, str);
}
}
#if LOGGING_ENABLED == ENABLED
DataFlash.Log_Write_Message(str);
#endif
GCS_MAVLINK::send_statustext(severity, 0xFF, str);
}
/*
@ -1006,22 +989,12 @@ void Tracker::gcs_send_text(MAV_SEVERITY severity, const char *str)
*/
void Tracker::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
{
char str[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] {};
va_list arg_list;
gcs[0].pending_status.severity = (uint8_t)severity;
va_start(arg_list, fmt);
hal.util->vsnprintf((char *)gcs[0].pending_status.text,
sizeof(gcs[0].pending_status.text), fmt, arg_list);
hal.util->vsnprintf((char *)str, sizeof(str), fmt, arg_list);
va_end(arg_list);
#if LOGGING_ENABLED == ENABLED
DataFlash.Log_Write_Message(gcs[0].pending_status.text);
#endif
gcs[0].send_message(MSG_STATUSTEXT);
for (uint8_t i=1; i<num_gcs; i++) {
if (gcs[i].initialised) {
gcs[i].pending_status = gcs[0].pending_status;
gcs[i].send_message(MSG_STATUSTEXT);
}
}
GCS_MAVLINK::send_statustext(severity, 0xFF, str);
}
/**
@ -1030,4 +1003,5 @@ void Tracker::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
void Tracker::gcs_retry_deferred(void)
{
gcs_send_message(MSG_RETRY_DEFERRED);
GCS_MAVLINK::service_statustext();
}

View File

@ -202,7 +202,6 @@ private:
void send_radio_out(mavlink_channel_t chan);
void send_hwstatus(mavlink_channel_t chan);
void send_waypoint_request(mavlink_channel_t chan);
void send_statustext(mavlink_channel_t chan);
void send_nav_controller_output(mavlink_channel_t chan);
void send_simstate(mavlink_channel_t chan);
void mavlink_check_target(const mavlink_message_t* msg);