mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Motors: Heli: Remove unused init_output return and don't assume single for initialised OK
This commit is contained in:
parent
810dfaf4f6
commit
f55267017b
@ -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;
|
||||
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user