AP_Button: use send_to_active_channels()

This commit is contained in:
Peter Barker 2018-11-07 13:11:36 +11:00 committed by Andrew Tridgell
parent 264a757095
commit 470e88f8b3
1 changed files with 7 additions and 15 deletions

View File

@ -142,21 +142,13 @@ void AP_Button::timer_update(void)
*/ */
void AP_Button::send_report(void) void AP_Button::send_report(void)
{ {
uint8_t chan_mask = GCS_MAVLINK::active_channel_mask(); const mavlink_button_change_t packet{
uint32_t now = AP_HAL::millis(); time_boot_ms: AP_HAL::millis(),
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) { last_change_ms: uint32_t(last_change_time_ms),
if ((chan_mask & (1U<<i)) == 0) { state: last_mask
// not active };
continue; gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE,
} (const char *)&packet);
mavlink_channel_t chan = (mavlink_channel_t)i;
if (HAVE_PAYLOAD_SPACE(chan, BUTTON_CHANGE)) {
mavlink_msg_button_change_send(chan,
now,
(uint32_t)last_change_time_ms,
last_mask);
}
}
} }
/* /*