diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index af4026e0eb..d90cd4d2a8 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -29,13 +29,13 @@ public: }; // init - void init(motor_frame_class frame_class, motor_frame_type frame_type); + void init(motor_frame_class frame_class, motor_frame_type frame_type) override; // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) - void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type); + void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override; // set update rate to motors - a value in hertz - void set_update_rate( uint16_t speed_hz ); + void set_update_rate( uint16_t speed_hz ) override; // output_test_seq - 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 @@ -43,7 +43,7 @@ public: virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors - virtual void output_to_motors(); + virtual void output_to_motors() override; // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict @@ -51,7 +51,7 @@ public: protected: // output - sends commands to the motors - void output_armed_stabilizing(); + void output_armed_stabilizing() override; float _actuator_out[NUM_ACTUATORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range float _thrust_yt_ccw; diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 0677615c96..6efe07fffc 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -59,16 +59,16 @@ public: }; // init - void init(motor_frame_class frame_class, motor_frame_type frame_type); + void init(motor_frame_class frame_class, motor_frame_type frame_type) override; // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) - void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type); + void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override; // set update rate to motors - a value in hertz - virtual void set_update_rate( uint16_t speed_hz ) = 0; + virtual void set_update_rate( uint16_t speed_hz ) override = 0; // output_min - sets servos to neutral point with motors stopped - void output_min(); + void output_min() override; // output_test_seq - 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 @@ -114,7 +114,7 @@ public: // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - virtual uint16_t get_motor_mask() = 0; + virtual uint16_t get_motor_mask() override = 0; virtual void set_acro_tail(bool set) {} @@ -122,12 +122,12 @@ public: virtual void ext_gyro_gain(float gain) {} // output - sends commands to the motors - void output(); + void output() override; // supports_yaw_passthrough virtual bool supports_yaw_passthrough() const { return false; } - float get_throttle_hover() const { return 0.5f; } + float get_throttle_hover() const override { return 0.5f; } // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; @@ -145,7 +145,7 @@ protected: }; // output - sends commands to the motors - void output_armed_stabilizing(); + void output_armed_stabilizing() override; void output_armed_zero_throttle(); void output_disarmed(); @@ -156,7 +156,7 @@ protected: void reset_flight_controls(); // update the throttle input filter - void update_throttle_filter(); + void update_throttle_filter() override; // move_actuators - moves swash plate and tail rotor virtual void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) = 0; diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index d78a023fa7..090bee5f2e 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -20,14 +20,14 @@ public: {}; // init - void init(motor_frame_class frame_class, motor_frame_type frame_type); + void init(motor_frame_class frame_class, motor_frame_type frame_type) override; // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) - void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type); + void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override; // set update rate to motors - a value in hertz // you must have setup_motors before calling this - void set_update_rate(uint16_t speed_hz); + void set_update_rate(uint16_t speed_hz) override; // output_test_seq - 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 @@ -42,18 +42,18 @@ public: bool output_test_num(uint8_t motor, int16_t pwm); // output_to_motors - sends minimum values out to the motors - void output_to_motors(); + void output_to_motors() override; // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict uint16_t get_motor_mask() override; // return number of motor that has failed. Should only be called if get_thrust_boost() returns true - uint8_t get_lost_motor() const { return _motor_lost_index; } + uint8_t get_lost_motor() const override { return _motor_lost_index; } protected: // output - sends commands to the motors - void output_armed_stabilizing(); + void output_armed_stabilizing() override; // check for failed motor void check_for_failed_motor(float throttle_thrust_best); diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 06c144a540..e1375cba9b 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -37,10 +37,10 @@ public: AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); // output - sends commands to the motors - virtual void output(); + virtual void output() override; // output_min - sends minimum values out to the motors - void output_min(); + void output_min() override; // set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm) void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; } @@ -51,7 +51,7 @@ public: // update estimated throttle required to hover void update_throttle_hover(float dt); - virtual float get_throttle_hover() const { return _throttle_hover; } + virtual float get_throttle_hover() const override { return _throttle_hover; } // spool up states enum spool_up_down_mode { @@ -112,7 +112,7 @@ protected: virtual void output_to_motors() = 0; // update the throttle input filter - virtual void update_throttle_filter(); + virtual void update_throttle_filter() override; // return current_limit as a number from 0 ~ 1 in the range throttle_min to throttle_max virtual float get_current_limit_max_throttle(); @@ -139,7 +139,7 @@ protected: virtual void output_boost_throttle(void); // save parameters as part of disarming - void save_params_on_disarm(); + void save_params_on_disarm() override; // enum values for HOVER_LEARN parameter enum HoverLearn { diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 784eed9bb0..5276c25d74 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -29,13 +29,13 @@ public: }; // init - void init(motor_frame_class frame_class, motor_frame_type frame_type); + void init(motor_frame_class frame_class, motor_frame_type frame_type) override; // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) - void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type); + void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override; // set update rate to motors - a value in hertz - void set_update_rate( uint16_t speed_hz ); + void set_update_rate( uint16_t speed_hz ) override; // output_test_seq - 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 @@ -43,7 +43,7 @@ public: virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors - virtual void output_to_motors(); + virtual void output_to_motors() override; // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict @@ -51,7 +51,7 @@ public: protected: // output - sends commands to the motors - void output_armed_stabilizing(); + void output_armed_stabilizing() override; int16_t _throttle_radio_output; // total throttle pwm value, summed onto throttle channel minimum, typically ~1100-1900 float _actuator_out[NUM_ACTUATORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.h b/libraries/AP_Motors/AP_MotorsTailsitter.h index 23820811f6..1220a6b967 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.h +++ b/libraries/AP_Motors/AP_MotorsTailsitter.h @@ -15,23 +15,23 @@ public: AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); // init - void init(motor_frame_class frame_class, motor_frame_type frame_type); + void init(motor_frame_class frame_class, motor_frame_type frame_type) override; // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) - 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 set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override {} + void set_update_rate( uint16_t speed_hz ) override {} virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override {} // output_to_motors - sends output to named servos - void output_to_motors(); + void output_to_motors() override; // return 0 motor mask uint16_t get_motor_mask() override { return 0; } protected: // calculate motor outputs - void output_armed_stabilizing(); + void output_armed_stabilizing() override; // calculated outputs float _aileron; // -1..1 diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 8aa0185868..87d7715411 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -24,13 +24,13 @@ public: }; // init - void init(motor_frame_class frame_class, motor_frame_type frame_type); + void init(motor_frame_class frame_class, motor_frame_type frame_type) override; // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) - void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type); + void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override; // set update rate to motors - a value in hertz - void set_update_rate( uint16_t speed_hz ); + void set_update_rate( uint16_t speed_hz ) override; // output_test_seq - 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 @@ -38,7 +38,7 @@ public: virtual void output_test_seq(uint8_t motor_seq, int16_t pwm) override; // output_to_motors - sends minimum values out to the motors - virtual void output_to_motors(); + virtual void output_to_motors() override; // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict @@ -51,7 +51,7 @@ public: protected: // output - sends commands to the motors - void output_armed_stabilizing(); + void output_armed_stabilizing() override; // call vehicle supplied thrust compensation if set void thrust_compensation(void) override;