AP_MotorsHeli: Create parameter_check method.

This commit is contained in:
Robert Lefebvre 2015-07-08 13:14:49 -04:00 committed by Randy Mackay
parent e2fe640e6c
commit 992c9c75bb
2 changed files with 15 additions and 0 deletions

View File

@ -354,6 +354,18 @@ bool AP_MotorsHeli::allow_arming() const
return true;
}
// parameter_check - check if helicopter specific parameters are sensible
bool AP_MotorsHeli::parameter_check() const
{
// returns false if _rsc_setpoint is not higher than _rsc_critical as this would not allow rotor_runup_complete to ever return true
if (_rsc_critical >= _rsc_setpoint) {
return false;
}
// all other cases parameters are OK
return true;
}
// return true if the main rotor is up to speed
bool AP_MotorsHeli::rotor_runup_complete() const
{

View File

@ -151,6 +151,9 @@ public:
// allow_arming - returns true if main rotor is spinning and it is ok to arm
bool allow_arming() const;
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
bool parameter_check() const;
// _tail_type - returns the tail type (servo, servo with ext gyro, direct drive var pitch, direct drive fixed pitch)
int16_t tail_type() const { return _tail_type; }