ArduSub: re-order initialiser lines so -Werror=reorder will work

This commit is contained in:
Peter Barker 2024-09-20 22:20:44 +10:00 committed by Peter Barker
parent 2bbf1a63a7
commit 3a4d890a83
1 changed files with 3 additions and 3 deletions

View File

@ -27,8 +27,6 @@ Sub::Sub()
: :
control_mode(Mode::Number::MANUAL), control_mode(Mode::Number::MANUAL),
motors(MAIN_LOOP_RATE), motors(MAIN_LOOP_RATE),
auto_mode(Auto_WP),
guided_mode(Guided_WP),
auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP), auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP),
inertial_nav(ahrs), inertial_nav(ahrs),
ahrs_view(ahrs, ROTATION_NONE), ahrs_view(ahrs, ROTATION_NONE),
@ -38,7 +36,9 @@ Sub::Sub()
loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control), loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
circle_nav(inertial_nav, ahrs_view, pos_control), circle_nav(inertial_nav, ahrs_view, pos_control),
param_loader(var_info), param_loader(var_info),
flightmode(&mode_manual) flightmode(&mode_manual),
auto_mode(Auto_WP),
guided_mode(Guided_WP)
{ {
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
failsafe.pilot_input = true; failsafe.pilot_input = true;