mirror of https://github.com/ArduPilot/ardupilot
AP_Relay: send relay status for all relays with valid functions
This commit is contained in:
parent
92ea15f9c3
commit
ad7b8b001b
|
@ -658,7 +658,7 @@ bool AP_Relay::send_relay_status(const GCS_MAVLINK &link) const
|
||||||
uint16_t present_mask = 0;
|
uint16_t present_mask = 0;
|
||||||
uint16_t on_mask = 0;
|
uint16_t on_mask = 0;
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(_params); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(_params); i++) {
|
||||||
if (!enabled(i)) {
|
if (!function_valid(_params[i].function)) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
const uint16_t relay_bit_mask = 1U << i;
|
const uint16_t relay_bit_mask = 1U << i;
|
||||||
|
|
Loading…
Reference in New Issue