Browse Source

AP_Motors: make output_test signatures consistent and ensure override

specifier on derived classes
mission-4.1.18
Jacob Walser 7 years ago
parent
commit
9ce9f95692
  1. 2
      libraries/AP_Motors/AP_MotorsCoax.h
  2. 2
      libraries/AP_Motors/AP_MotorsHeli.h
  3. 2
      libraries/AP_Motors/AP_MotorsHeli_Dual.h
  4. 2
      libraries/AP_Motors/AP_MotorsHeli_Quad.h
  5. 2
      libraries/AP_Motors/AP_MotorsHeli_Single.h
  6. 2
      libraries/AP_Motors/AP_MotorsMatrix.h
  7. 2
      libraries/AP_Motors/AP_MotorsSingle.h
  8. 2
      libraries/AP_Motors/AP_MotorsTailsitter.h
  9. 2
      libraries/AP_Motors/AP_MotorsTri.h

2
libraries/AP_Motors/AP_MotorsCoax.h

@ -40,7 +40,7 @@ public: @@ -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();

2
libraries/AP_Motors/AP_MotorsHeli.h

@ -77,7 +77,7 @@ public: @@ -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

2
libraries/AP_Motors/AP_MotorsHeli_Dual.h

@ -59,7 +59,7 @@ public: @@ -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;

2
libraries/AP_Motors/AP_MotorsHeli_Quad.h

@ -34,7 +34,7 @@ public: @@ -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;

2
libraries/AP_Motors/AP_MotorsHeli_Single.h

@ -63,7 +63,7 @@ public: @@ -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;

2
libraries/AP_Motors/AP_MotorsMatrix.h

@ -32,7 +32,7 @@ public: @@ -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();

2
libraries/AP_Motors/AP_MotorsSingle.h

@ -40,7 +40,7 @@ public: @@ -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();

2
libraries/AP_Motors/AP_MotorsTailsitter.h

@ -21,7 +21,7 @@ public: @@ -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();

2
libraries/AP_Motors/AP_MotorsTri.h

@ -35,7 +35,7 @@ public: @@ -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();

Loading…
Cancel
Save