Skip to content

Commit

Permalink
AP_Motors: make output_test signatures consistent and ensure override
Browse files Browse the repository at this point in the history
specifier on derived classes
  • Loading branch information
jaxxzer committed Jul 2, 2018
1 parent dcd3f83 commit 9ce9f95
Show file tree
Hide file tree
Showing 9 changed files with 9 additions and 9 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsCoax.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class AP_MotorsCoax : public AP_MotorsMulticopter {
// 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();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsHeli.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class AP_MotorsHeli : public AP_Motors {
// 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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsHeli_Dual.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class AP_MotorsHeli_Dual : public AP_MotorsHeli {
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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsHeli_Quad.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class AP_MotorsHeli_Quad : public AP_MotorsHeli {
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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsHeli_Single.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli {
// 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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class AP_MotorsMatrix : public AP_MotorsMulticopter {
// 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();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsSingle.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class AP_MotorsSingle : public AP_MotorsMulticopter {
// 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();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsTailsitter.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ class AP_MotorsTailsitter : public AP_MotorsMulticopter {
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();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsTri.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class AP_MotorsTri : public AP_MotorsMulticopter {
// 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();
Expand Down

0 comments on commit 9ce9f95

Please sign in to comment.