mirror of https://github.com/ArduPilot/ardupilot
Plane: do not trust fence-channel PWM during RC failsafe
This commit is contained in:
parent
ce963c8f0f
commit
bee4ad24d8
|
@ -160,6 +160,11 @@ bool Plane::geofence_present(void)
|
|||
*/
|
||||
void Plane::geofence_update_pwm_enabled_state()
|
||||
{
|
||||
if (rc_failsafe_active()) {
|
||||
// do nothing based on the radio channel value as it may be at bind value
|
||||
return;
|
||||
}
|
||||
|
||||
bool is_pwm_enabled;
|
||||
if (g.fence_channel == 0) {
|
||||
is_pwm_enabled = false;
|
||||
|
|
Loading…
Reference in New Issue