diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index fd7de528ca..99110425f2 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -40,7 +40,7 @@ public: // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm); + virtual void output_test(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors virtual void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 1e357d9e4a..87542566c7 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -77,7 +77,7 @@ public: // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm) = 0; + virtual void output_test(uint8_t motor_seq, int16_t pwm) override = 0; // // heli specific methods diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index 0e97918279..f68e5f3cb6 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -59,7 +59,7 @@ public: void set_update_rate( uint16_t speed_hz ) override; // output_test - spin a motor at the pwm value specified - void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test(uint8_t motor_seq, int16_t pwm) override; // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000 void set_desired_rotor_speed(float desired_speed) override; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.h b/libraries/AP_Motors/AP_MotorsHeli_Quad.h index 33c1035928..f3118b9134 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.h @@ -34,7 +34,7 @@ public: void set_update_rate( uint16_t speed_hz ) override; // output_test - spin a motor at the pwm value specified - void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test(uint8_t motor_seq, int16_t pwm) override; // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000 void set_desired_rotor_speed(float desired_speed) override; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index d3fe441a4f..c3999a71d6 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -63,7 +63,7 @@ public: // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - void output_test(uint8_t motor_seq, int16_t pwm) override; + virtual void output_test(uint8_t motor_seq, int16_t pwm) override; // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1 void set_desired_rotor_speed(float desired_speed) override; diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index 65cab404fc..1c51e77501 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -32,7 +32,7 @@ public: // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - void output_test(uint8_t motor_seq, int16_t pwm); + virtual void output_test(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 85e5716572..61d689fed7 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -40,7 +40,7 @@ public: // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm); + virtual void output_test(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors virtual void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.h b/libraries/AP_Motors/AP_MotorsTailsitter.h index 13dfd63718..7ccfd2ca16 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.h +++ b/libraries/AP_Motors/AP_MotorsTailsitter.h @@ -21,7 +21,7 @@ public: void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) {} void set_update_rate( uint16_t speed_hz ) {} - void output_test(uint8_t motor_seq, int16_t pwm) {} + virtual void output_test(uint8_t motor_seq, int16_t pwm) override {} // output_to_motors - sends output to named servos void output_to_motors(); diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index f572f9207f..d93fa3c299 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -35,7 +35,7 @@ public: // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 - virtual void output_test(uint8_t motor_seq, int16_t pwm); + virtual void output_test(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors virtual void output_to_motors();