mirror of https://github.com/ArduPilot/ardupilot
Plane: reorder initialisation of member variables to make -Werror=reorder work
This commit is contained in:
parent
6ee1d94ec7
commit
b7ccee5ebe
|
@ -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;
|
||||
|
|
|
@ -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)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue