From 6e0f39e3e1f14082127e814d4bb93c06e556e8d1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 22 Sep 2024 10:37:45 +1000 Subject: [PATCH] Rover: re-order initialiser lines so -Werror=reorder will work --- Rover/Parameters.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 0eb2480343..e60b1fc5d4 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -735,16 +735,16 @@ ParametersG2::ParametersG2(void) #if AP_BEACON_ENABLED beacon(), #endif - motors(wheel_rate_control), wheel_rate_control(wheel_encoder), + motors(wheel_rate_control), attitude_control(), smart_rtl(), -#if MODE_DOCK_ENABLED - mode_dock_ptr(&rover.mode_dock), -#endif #if HAL_PROXIMITY_ENABLED proximity(), #endif +#if MODE_DOCK_ENABLED + mode_dock_ptr(&rover.mode_dock), +#endif #if AP_AVOIDANCE_ENABLED avoid(), #endif @@ -752,9 +752,9 @@ ParametersG2::ParametersG2(void) follow(), #endif windvane(), - pos_control(attitude_control), wp_nav(attitude_control, pos_control), - sailboat() + sailboat(), + pos_control(attitude_control) { AP_Param::setup_object_defaults(this, var_info); }