AP_Motors: Heli: Remove unused init_output return and don't assume single for initialised OK

This commit is contained in:
Iampete1 2023-06-30 19:32:10 +01:00 committed by Andrew Tridgell
parent 810dfaf4f6
commit f55267017b
8 changed files with 9 additions and 21 deletions

View File

@ -173,17 +173,11 @@ void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_t
_throttle_radio_passthrough = 0.5f;
// initialise Servo/PWM ranges and endpoints
if (!init_outputs()) {
// don't set initialised_ok
return;
}
init_outputs();
// calculate all scalars
calculate_scalars();
// record successful initialisation if what we setup was the desired frame_class
set_initialised_ok(frame_class == MOTOR_FRAME_HELI);
// set flag to true so targets are initialized once aircraft is armed for first time
_heliflags.init_targets_on_arming = true;

View File

@ -211,7 +211,7 @@ protected:
// init_outputs - initialise Servo/PWM ranges and endpoints. This
// method also updates the initialised flag.
virtual bool init_outputs() = 0;
virtual void init_outputs() = 0;
// calculate_armed_scalars - must be implemented by child classes
virtual void calculate_armed_scalars() = 0;

View File

@ -230,7 +230,7 @@ void AP_MotorsHeli_Dual::set_update_rate( uint16_t speed_hz )
}
// init_outputs
bool AP_MotorsHeli_Dual::init_outputs()
void AP_MotorsHeli_Dual::init_outputs()
{
if (!initialised_ok()) {
// make sure 6 output channels are mapped
@ -261,8 +261,6 @@ bool AP_MotorsHeli_Dual::init_outputs()
}
set_initialised_ok(_frame_class == MOTOR_FRAME_HELI_DUAL);
return true;
}
// calculate_armed_scalars

View File

@ -73,7 +73,7 @@ public:
protected:
// init_outputs
bool init_outputs () override;
void init_outputs () override;
// update_motor_controls - sends commands to motor controllers
void update_motor_control(RotorControlState state) override;

View File

@ -46,10 +46,10 @@ void AP_MotorsHeli_Quad::set_update_rate( uint16_t speed_hz )
}
// init_outputs
bool AP_MotorsHeli_Quad::init_outputs()
void AP_MotorsHeli_Quad::init_outputs()
{
if (initialised_ok()) {
return true;
return;
}
for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
@ -61,8 +61,6 @@ bool AP_MotorsHeli_Quad::init_outputs()
_main_rotor.init_servo();
set_initialised_ok(_frame_class == MOTOR_FRAME_HELI_QUAD);
return true;
}
// calculate_armed_scalars

View File

@ -52,7 +52,7 @@ public:
protected:
// init_outputs
bool init_outputs () override;
void init_outputs () override;
// update_motor_controls - sends commands to motor controllers
void update_motor_control(RotorControlState state) override;

View File

@ -200,7 +200,7 @@ void AP_MotorsHeli_Single::set_update_rate( uint16_t speed_hz )
}
// init_outputs - initialise Servo/PWM ranges and endpoints
bool AP_MotorsHeli_Single::init_outputs()
void AP_MotorsHeli_Single::init_outputs()
{
if (!initialised_ok()) {
// map primary swash servos
@ -244,8 +244,6 @@ bool AP_MotorsHeli_Single::init_outputs()
}
set_initialised_ok(_frame_class == MOTOR_FRAME_HELI);
return true;
}
// set_desired_rotor_speed

View File

@ -89,7 +89,7 @@ public:
protected:
// init_outputs - initialise Servo/PWM ranges and endpoints
bool init_outputs() override;
void init_outputs() override;
// update_motor_controls - sends commands to motor controllers
void update_motor_control(RotorControlState state) override;