From f55267017b382285740d8fae55358d7808133bc8 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 30 Jun 2023 19:32:10 +0100 Subject: [PATCH] AP_Motors: Heli: Remove unused init_output return and don't assume single for initialised OK --- libraries/AP_Motors/AP_MotorsHeli.cpp | 8 +------- libraries/AP_Motors/AP_MotorsHeli.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 4 +--- libraries/AP_Motors/AP_MotorsHeli_Dual.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_Quad.cpp | 6 ++---- libraries/AP_Motors/AP_MotorsHeli_Quad.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 4 +--- libraries/AP_Motors/AP_MotorsHeli_Single.h | 2 +- 8 files changed, 9 insertions(+), 21 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index fb59e7718b..41eff40153 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -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; diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 7bddb306e1..2ae7fff1a4 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -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; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 48e16416fe..783e511a9b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -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 diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index f71d59da4c..4531aa57a0 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -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; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index 4a7a5fcb9c..f545b4c3e8 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -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