mirror of https://github.com/ArduPilot/ardupilot
Copter: reorder initialisation of member variables to make -Werror=reorder work
This commit is contained in:
parent
8a58642cd1
commit
6ee1d94ec7
|
@ -1240,8 +1240,11 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
|
||||||
/*
|
/*
|
||||||
constructor for g2 object
|
constructor for g2 object
|
||||||
*/
|
*/
|
||||||
ParametersG2::ParametersG2(void)
|
ParametersG2::ParametersG2(void) :
|
||||||
: command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)
|
unused_integer{17}
|
||||||
|
#if HAL_BUTTON_ENABLED
|
||||||
|
,button_ptr(&copter.button)
|
||||||
|
#endif
|
||||||
#if AP_TEMPCALIBRATION_ENABLED
|
#if AP_TEMPCALIBRATION_ENABLED
|
||||||
, temp_calibration()
|
, temp_calibration()
|
||||||
#endif
|
#endif
|
||||||
|
@ -1257,15 +1260,15 @@ ParametersG2::ParametersG2(void)
|
||||||
#if MODE_SMARTRTL_ENABLED
|
#if MODE_SMARTRTL_ENABLED
|
||||||
,smart_rtl()
|
,smart_rtl()
|
||||||
#endif
|
#endif
|
||||||
|
#if USER_PARAMS_ENABLED
|
||||||
|
,user_parameters()
|
||||||
|
#endif
|
||||||
#if MODE_FLOWHOLD_ENABLED
|
#if MODE_FLOWHOLD_ENABLED
|
||||||
,mode_flowhold_ptr(&copter.mode_flowhold)
|
,mode_flowhold_ptr(&copter.mode_flowhold)
|
||||||
#endif
|
#endif
|
||||||
#if MODE_FOLLOW_ENABLED
|
#if MODE_FOLLOW_ENABLED
|
||||||
,follow()
|
,follow()
|
||||||
#endif
|
#endif
|
||||||
#if USER_PARAMS_ENABLED
|
|
||||||
,user_parameters()
|
|
||||||
#endif
|
|
||||||
#if AUTOTUNE_ENABLED
|
#if AUTOTUNE_ENABLED
|
||||||
,autotune_ptr(&copter.mode_autotune.autotune)
|
,autotune_ptr(&copter.mode_autotune.autotune)
|
||||||
#endif
|
#endif
|
||||||
|
@ -1275,13 +1278,9 @@ ParametersG2::ParametersG2(void)
|
||||||
#if MODE_AUTOROTATE_ENABLED
|
#if MODE_AUTOROTATE_ENABLED
|
||||||
,arot()
|
,arot()
|
||||||
#endif
|
#endif
|
||||||
#if HAL_BUTTON_ENABLED
|
|
||||||
,button_ptr(&copter.button)
|
|
||||||
#endif
|
|
||||||
#if MODE_ZIGZAG_ENABLED
|
#if MODE_ZIGZAG_ENABLED
|
||||||
,mode_zigzag_ptr(&copter.mode_zigzag)
|
,mode_zigzag_ptr(&copter.mode_zigzag)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
|
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
|
||||||
,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f)
|
,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f)
|
||||||
#endif
|
#endif
|
||||||
|
@ -1290,6 +1289,8 @@ ParametersG2::ParametersG2(void)
|
||||||
,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f)
|
,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)
|
||||||
|
|
||||||
#if WEATHERVANE_ENABLED
|
#if WEATHERVANE_ENABLED
|
||||||
,weathervane()
|
,weathervane()
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -499,6 +499,11 @@ public:
|
||||||
// altitude at which nav control can start in takeoff
|
// altitude at which nav control can start in takeoff
|
||||||
AP_Float wp_navalt_min;
|
AP_Float wp_navalt_min;
|
||||||
|
|
||||||
|
// unused_integer simply exists so that the constructor for
|
||||||
|
// ParametersG2 can be created with a relatively easy syntax in
|
||||||
|
// the face of many #ifs:
|
||||||
|
uint8_t unused_integer;
|
||||||
|
|
||||||
// button checking
|
// button checking
|
||||||
#if HAL_BUTTON_ENABLED
|
#if HAL_BUTTON_ENABLED
|
||||||
AP_Button *button_ptr;
|
AP_Button *button_ptr;
|
||||||
|
|
Loading…
Reference in New Issue