diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 2af3885439..c5ac300688 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -140,6 +140,9 @@ protected: // convert thrust (0~1) range back to pwm range int16_t calc_thrust_to_pwm(float thrust_in) const; + // spin when armed as a percentage of the 0~1 range from 0 to throttle_min + float spin_when_armed_low_end_pct() { return (float)_spin_when_armed.get() / _min_throttle; } + // flag bitmask struct { uint8_t slow_start : 1; // 1 if slow start is active