mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 04:28:30 -04:00
AP_Motors: make output_test signatures consistent and ensure override
specifier on derived classes
This commit is contained in:
parent
dcd3f83539
commit
9ce9f95692
@ -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();
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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();
|
||||
|
@ -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();
|
||||
|
@ -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();
|
||||
|
@ -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…
Reference in New Issue
Block a user