diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 76e4928cb3f664..688d4ec3726685 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -156,6 +156,7 @@ class AP_Motors { float get_yaw_ff() const { return _yaw_in_ff; } float get_throttle_out() const { return _throttle_out; } virtual bool get_thrust(uint8_t motor_num, float& thr_out) const { return false; } + float get_throttle_in() const { return _throttle_in; } float get_throttle() const { return constrain_float(_throttle_filter.get(), 0.0f, 1.0f); } float get_throttle_bidirectional() const { return constrain_float(2 * (_throttle_filter.get() - 0.5f), -1.0f, 1.0f); } float get_throttle_slew_rate() const { return _throttle_slew_rate; }