mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter:AP_ARMING - remove collective position prearm check for heli
This commit is contained in:
parent
83b882417f
commit
e56c970eb0
@ -547,10 +547,12 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method
|
||||
return false;
|
||||
}
|
||||
// in manual modes throttle must be at zero
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
if ((copter.flightmode->has_manual_throttle() || control_mode == DRIFT) && copter.channel_throttle->get_control_in() > 0) {
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s too high", rc_item);
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user