Browse Source

AP_Arming: don't arming check servo functions set to GPIO

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
d069b6503b
  1. 2
      libraries/AP_Arming/AP_Arming.cpp

2
libraries/AP_Arming/AP_Arming.cpp

@ -796,7 +796,7 @@ bool AP_Arming::servo_checks(bool report) const
bool check_passed = true; bool check_passed = true;
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
const SRV_Channel *c = SRV_Channels::srv_channel(i); const SRV_Channel *c = SRV_Channels::srv_channel(i);
if (c == nullptr || c->get_function() == SRV_Channel::k_none) { if (c == nullptr || c->get_function() <= SRV_Channel::k_none) {
continue; continue;
} }

Loading…
Cancel
Save