mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_MotorsHeli: Change allow_arming check to use _rotor_speed_estimate
In future, this will be used to check actual rotor speed (measured) if available, to prevent trying to arm with the rotor spinning.
This commit is contained in:
parent
534ba89756
commit
abb6eba291
@ -345,8 +345,8 @@ void AP_MotorsHeli::output_test(uint8_t motor_seq, int16_t pwm)
|
||||
// allow_arming - check if it's safe to arm
|
||||
bool AP_MotorsHeli::allow_arming() const
|
||||
{
|
||||
// returns false if main rotor desired speed is not zero
|
||||
if (_rsc_mode != AP_MOTORS_HELI_RSC_MODE_NONE && _desired_rotor_speed > 0) {
|
||||
// returns false if main rotor speed is not zero
|
||||
if (_rsc_mode != AP_MOTORS_HELI_RSC_MODE_NONE && _rotor_speed_estimate > 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user