From b7ccee5ebe2b604a7bd39f69515651d3f4ffca20 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 22 Sep 2024 15:53:10 +1000 Subject: [PATCH] Plane: reorder initialisation of member variables to make -Werror=reorder work --- ArduPlane/Parameters.h | 6 +++--- ArduPlane/mode.cpp | 7 ++++--- ArduPlane/mode.h | 3 +++ 3 files changed, 10 insertions(+), 6 deletions(-) diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 377eb9ded8..d29243d1ef 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -483,6 +483,9 @@ public: // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; + // just to make compilation easier when all things are compiled out... + uint8_t unused_integer; + // button reporting library #if HAL_BUTTON_ENABLED AP_Button *button_ptr; @@ -579,9 +582,6 @@ public: AP_Int8 axis_bitmask; // axes to be autotuned - // just to make compilation easier when all things are compiled out... - uint8_t unused_integer; - #if AP_RANGEFINDER_ENABLED // orientation of rangefinder to use for landing AP_Int8 rangefinder_land_orient; diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index e4f97acc2c..8bece6d418 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -1,14 +1,15 @@ #include "Plane.h" Mode::Mode() : - ahrs(plane.ahrs) + unused_integer{17}, #if HAL_QUADPLANE_ENABLED - , quadplane(plane.quadplane), pos_control(plane.quadplane.pos_control), attitude_control(plane.quadplane.attitude_control), loiter_nav(plane.quadplane.loiter_nav), - poscontrol(plane.quadplane.poscontrol) + quadplane(plane.quadplane), + poscontrol(plane.quadplane.poscontrol), #endif + ahrs(plane.ahrs) { } diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index 230b372499..8260924afc 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -159,6 +159,9 @@ protected: // Output pilot throttle, this is used in stabilized modes without auto throttle control void output_pilot_throttle(); + // makes the initialiser list in the constructor manageable + uint8_t unused_integer; + #if HAL_QUADPLANE_ENABLED // References for convenience, used by QModes AC_PosControl*& pos_control;