Browse Source

AP_Motors: add override keyword to get_motor_mask

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
f85e84cc89
  1. 2
      libraries/AP_Motors/AP_MotorsCoax.h
  2. 2
      libraries/AP_Motors/AP_MotorsMatrix.h
  3. 2
      libraries/AP_Motors/AP_MotorsSingle.h
  4. 2
      libraries/AP_Motors/AP_MotorsTailsitter.h
  5. 2
      libraries/AP_Motors/AP_MotorsTri.h

2
libraries/AP_Motors/AP_MotorsCoax.h

@ -47,7 +47,7 @@ public: @@ -47,7 +47,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();
uint16_t get_motor_mask() override;
protected:
// output - sends commands to the motors

2
libraries/AP_Motors/AP_MotorsMatrix.h

@ -46,7 +46,7 @@ public: @@ -46,7 +46,7 @@ public:
// 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();
uint16_t get_motor_mask() override;
protected:
// output - sends commands to the motors

2
libraries/AP_Motors/AP_MotorsSingle.h

@ -47,7 +47,7 @@ public: @@ -47,7 +47,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();
uint16_t get_motor_mask() override;
protected:
// output - sends commands to the motors

2
libraries/AP_Motors/AP_MotorsTailsitter.h

@ -27,7 +27,7 @@ public: @@ -27,7 +27,7 @@ public:
void output_to_motors();
// return 0 motor mask
uint16_t get_motor_mask() { return 0; }
uint16_t get_motor_mask() override { return 0; }
protected:
// calculate motor outputs

2
libraries/AP_Motors/AP_MotorsTri.h

@ -42,7 +42,7 @@ public: @@ -42,7 +42,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();
uint16_t get_motor_mask() override;
// output a thrust to all motors that match a given motor
// mask. This is used to control tiltrotor motors in forward

Loading…
Cancel
Save