mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Button: use send_to_active_channels()
This commit is contained in:
parent
264a757095
commit
470e88f8b3
@ -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);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user