mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
GCS_MAVLink: added send_statustext_all() method
used for sending text messages from libraries
This commit is contained in:
parent
1d4d848300
commit
f49258eb31
@ -200,6 +200,13 @@ public:
|
||||
// over active channels to send to all active channels
|
||||
static uint8_t active_channel_mask(void) { return mavlink_active; }
|
||||
|
||||
/*
|
||||
send a statustext message to all active MAVLink
|
||||
connections. This function is static so it can be called from
|
||||
any library
|
||||
*/
|
||||
static void send_statustext_all(const prog_char_t *msg);
|
||||
|
||||
private:
|
||||
void handleMessage(mavlink_message_t * msg);
|
||||
|
||||
|
@ -1128,3 +1128,28 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs)
|
||||
ahrs.get_error_rp(),
|
||||
ahrs.get_error_yaw());
|
||||
}
|
||||
|
||||
/*
|
||||
send a statustext message to all active MAVLink connections
|
||||
*/
|
||||
void GCS_MAVLINK::send_statustext_all(const prog_char_t *msg)
|
||||
{
|
||||
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||
if ((1U<<i) & mavlink_active) {
|
||||
mavlink_channel_t chan = (mavlink_channel_t)i;
|
||||
if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_STATUSTEXT_LEN) {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
char msg2[50];
|
||||
strncpy_P(msg2, msg, sizeof(msg2));
|
||||
mavlink_msg_statustext_send(chan,
|
||||
SEVERITY_HIGH,
|
||||
msg2);
|
||||
#else
|
||||
mavlink_msg_statustext_send(chan,
|
||||
SEVERITY_HIGH,
|
||||
msg);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user