GCS_MAVLink: make send_statustext_all() take a format string

this allows for formatted messages to all groundstations in libraries
This commit is contained in:
Andrew Tridgell 2015-09-08 13:53:58 +10:00
parent f953f03916
commit f3e8819d1e
2 changed files with 6 additions and 3 deletions

View File

@ -163,7 +163,7 @@ public:
connections. This function is static so it can be called from connections. This function is static so it can be called from
any library any library
*/ */
static void send_statustext_all(const prog_char_t *msg); static void send_statustext_all(const prog_char_t *fmt, ...);
/* /*
send a MAVLink message to all components with this vehicle's system id send a MAVLink message to all components with this vehicle's system id

View File

@ -1169,14 +1169,17 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs)
/* /*
send a statustext message to all active MAVLink connections send a statustext message to all active MAVLink connections
*/ */
void GCS_MAVLINK::send_statustext_all(const prog_char_t *msg) void GCS_MAVLINK::send_statustext_all(const prog_char_t *fmt, ...)
{ {
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) { for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
if ((1U<<i) & mavlink_active) { if ((1U<<i) & mavlink_active) {
mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0+i); mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_STATUSTEXT_LEN) { if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_STATUSTEXT_LEN) {
char msg2[50]; char msg2[50];
strncpy_P(msg2, msg, sizeof(msg2)); va_list arg_list;
va_start(arg_list, fmt);
hal.util->vsnprintf_P((char *)msg2, sizeof(msg2), fmt, arg_list);
va_end(arg_list);
mavlink_msg_statustext_send(chan, mavlink_msg_statustext_send(chan,
MAV_SEVERITY_CRITICAL, MAV_SEVERITY_CRITICAL,
msg2); msg2);