diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index 1c56e07367f6c..22b2d2502fff4 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -50,12 +50,6 @@ class AP_MotorsHeli_Dual : public AP_MotorsHeli { // calculate_armed_scalars - recalculates scalars that can change while armed void calculate_armed_scalars() override; - // has_flybar - returns true if we have a mechical flybar - bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; } - - // supports_yaw_passthrought - returns true if we support yaw passthrough - bool supports_yaw_passthrough() const override { return false; } - // servo_test - move servos through full range of movement void servo_test() override; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.h b/libraries/AP_Motors/AP_MotorsHeli_Quad.h index 3a3292fa25340..3644255b1cb4b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.h @@ -37,12 +37,6 @@ class AP_MotorsHeli_Quad : public AP_MotorsHeli { // calculate_armed_scalars - recalculates scalars that can change while armed void calculate_armed_scalars() override; - // has_flybar - returns true if we have a mechanical flybar - bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; } - - // supports_yaw_passthrought - returns true if we support yaw passthrough - bool supports_yaw_passthrough() const override { return false; } - // servo_test - move servos through full range of movement void servo_test() override;