GCS_MAVLink: remove global static send_statustext_chan

This commit is contained in:
Peter Barker 2017-07-09 18:31:30 +10:00 committed by Francisco Ferreira
parent a599bc9031
commit 5c0aa27b2f
2 changed files with 8 additions and 24 deletions

View File

@ -89,7 +89,7 @@ public:
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
void send_message(enum ap_message id);
void send_text(MAV_SEVERITY severity, const char *str);
void send_text(MAV_SEVERITY severity, const char *fmt, ...);
virtual void data_stream_send(void) = 0;
void queued_param_send();
void queued_waypoint_send();
@ -181,12 +181,6 @@ public:
// return a bitmap of streaming channels
static uint8_t streaming_channel_mask(void) { return chan_is_streaming; }
/*
send a statustext message to specific MAVLINK Connection
This function is static so it can be called from any library.
*/
static void send_statustext_chan(MAV_SEVERITY severity, uint8_t dest_chan, const char *fmt, ...);
// send a PARAM_VALUE message to all active MAVLink connections.
static void send_parameter_value_all(const char *param_name, ap_var_type param_type, float param_value);

View File

@ -527,10 +527,14 @@ void GCS_MAVLINK::handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg)
}
void
GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *str)
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
{
GCS_MAVLINK::send_statustext_chan(severity, chan, str);
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] {};
va_list arg_list;
va_start(arg_list, fmt);
hal.util->vsnprintf((char *)text, sizeof(text), fmt, arg_list);
va_end(arg_list);
gcs().send_statustext(severity, (1<<chan), text);
}
void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio)
@ -1141,20 +1145,6 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs)
ahrs.get_error_yaw());
}
/*
send a statustext message to specific MAVLink channel, zero indexed
*/
void GCS_MAVLINK::send_statustext_chan(MAV_SEVERITY severity, uint8_t dest_chan, const char *fmt, ...)
{
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] {};
va_list arg_list;
va_start(arg_list, fmt);
hal.util->vsnprintf((char *)text, sizeof(text), fmt, arg_list);
va_end(arg_list);
gcs().send_statustext(severity, (1<<dest_chan), text);
}
/*
send a statustext text string to specific MAVLink bitmask
*/