AP_MotorsHeli: Remove pure virtuals and unnecessary overrides

This commit is contained in:
Gone4Dirt 2023-04-29 23:10:43 +01:00 committed by Bill Geyer
parent 4b2c1368bd
commit 191ce55e1d
7 changed files with 7 additions and 55 deletions

View File

@ -624,3 +624,9 @@ uint32_t AP_MotorsHeli::get_motor_mask()
{
return _main_rotor.get_output_mask();
}
// set_desired_rotor_speed
void AP_MotorsHeli::set_desired_rotor_speed(float desired_speed)
{
_main_rotor.set_desired_speed(desired_speed);
}

View File

@ -306,12 +306,6 @@ void AP_MotorsHeli_Dual::_output_test_seq(uint8_t motor_seq, int16_t pwm)
}
}
// set_desired_rotor_speed
void AP_MotorsHeli_Dual::set_desired_rotor_speed(float desired_speed)
{
_main_rotor.set_desired_speed(desired_speed);
}
// calculate_armed_scalars
void AP_MotorsHeli_Dual::calculate_armed_scalars()
{

View File

@ -52,21 +52,6 @@ public:
// output_to_motors - sends values out to the motors
void output_to_motors() override;
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
void set_desired_rotor_speed(float desired_speed) override;
// get_estimated_rotor_speed - gets estimated rotor speed as a number from 0 ~ 1000
float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
float get_desired_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
// get_governor_output
float get_governor_output() const override { return _main_rotor.get_governor_output(); }
// get_control_output
float get_control_output() const override { return _main_rotor.get_control_output(); }
// calculate_scalars - recalculates various scalars used
void calculate_scalars() override;

View File

@ -85,12 +85,6 @@ void AP_MotorsHeli_Quad::_output_test_seq(uint8_t motor_seq, int16_t pwm)
}
}
// set_desired_rotor_speed
void AP_MotorsHeli_Quad::set_desired_rotor_speed(float desired_speed)
{
_main_rotor.set_desired_speed(desired_speed);
}
// calculate_armed_scalars
void AP_MotorsHeli_Quad::calculate_armed_scalars()
{

View File

@ -31,21 +31,6 @@ public:
// output_to_motors - sends values out to the motors
void output_to_motors() override;
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
void set_desired_rotor_speed(float desired_speed) override;
// get_estimated_rotor_speed - gets estimated rotor speed as a number from 0 ~ 1000
float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
float get_desired_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
// get_governor_output
float get_governor_output() const override { return _main_rotor.get_governor_output(); }
// get_control_output
float get_control_output() const override { return _main_rotor.get_control_output(); }
// calculate_scalars - recalculates various scalars used
void calculate_scalars() override;

View File

@ -442,7 +442,7 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
// rudder feed forward based on collective
// the feed-forward is not required when the motor is stopped or at idle, and thus not creating torque
// also not required if we are using external gyro
if ((_main_rotor.get_control_output() > _main_rotor.get_idle_output()) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
if ((get_control_output() > _main_rotor.get_idle_output()) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
// sanity check collective_yaw_scale
_collective_yaw_scale.set(constrain_float(_collective_yaw_scale, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE));
// This feedforward compensation follows the hover performance theory that hover power required

View File

@ -55,18 +55,6 @@ public:
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1
void set_desired_rotor_speed(float desired_speed) override;
// get_main_rotor_speed - estimated rotor speed when no speed sensor or governor is used
float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1
float get_desired_rotor_speed() const override { return _main_rotor.get_desired_speed(); }
// get_governor_output
float get_governor_output() const override { return _main_rotor.get_governor_output(); }
// get_control_output
float get_control_output() const override{ return _main_rotor.get_control_output(); }
// calculate_scalars - recalculates various scalars used
void calculate_scalars() override;