From a2fa63bcf7b658fc63da337958a879433de68593 Mon Sep 17 00:00:00 2001 From: Francisco Ferreira Date: Tue, 11 Dec 2018 17:11:49 +0000 Subject: [PATCH] Copter: fix Cygwin build Static initialization doesn't have an exact order, we can't rely on it --- ArduCopter/ArduCopter.cpp | 2 +- ArduCopter/Copter.h | 1 - ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/RC_Channel.cpp | 10 +++++----- ArduCopter/commands.cpp | 4 ++-- ArduCopter/mode.cpp | 4 ++-- 6 files changed, 12 insertions(+), 13 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index a0258a9f22..1d2eee4c81 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -582,7 +582,7 @@ void Copter::publish_osd_info() nav_info.wp_distance = flightmode->wp_distance() * 1.0e-2f; nav_info.wp_bearing = flightmode->wp_bearing(); nav_info.wp_xtrack_error = flightmode->crosstrack_error() * 1.0e-2f; - nav_info.wp_number = mission.get_current_nav_index(); + nav_info.wp_number = mode_auto.mission.get_current_nav_index(); osd.set_nav_info(nav_info); } #endif diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 99c819ea90..9930d986b6 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -910,7 +910,6 @@ private: ModeAltHold mode_althold; #if MODE_AUTO_ENABLED == ENABLED ModeAuto mode_auto; - AP_Mission &mission = mode_auto.mission; // so parameters work only! #endif #if AUTOTUNE_ENABLED == ENABLED ModeAutoTune mode_autotune; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index a60b452e84..b8f4564371 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -660,7 +660,7 @@ const AP_Param::Info Copter::var_info[] = { #if MODE_AUTO_ENABLED == ENABLED // @Group: MIS_ // @Path: ../libraries/AP_Mission/AP_Mission.cpp - GOBJECT(mission, "MIS_", AP_Mission), + GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission), #endif // @Group: RSSI_ @@ -1002,7 +1002,7 @@ ParametersG2::ParametersG2(void) , proximity(copter.serial_manager) #endif #if ADVANCED_FAILSAFE == ENABLED - ,afs(copter.mission, copter.gps) + ,afs(copter.mode_auto.mission, copter.gps) #endif #if MODE_SMARTRTL_ENABLED == ENABLED ,smart_rtl() diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 7777171860..7aedde6b50 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -173,7 +173,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw } // do not allow saving the first waypoint with zero throttle - if ((copter.mission.num_commands() == 0) && (copter.channel_throttle->get_control_in() == 0)) { + if ((copter.mode_auto.mission.num_commands() == 0) && (copter.channel_throttle->get_control_in() == 0)) { return; } @@ -181,7 +181,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw AP_Mission::Mission_Command cmd = {}; // if the mission is empty save a takeoff command - if (copter.mission.num_commands() == 0) { + if (copter.mode_auto.mission.num_commands() == 0) { // set our location ID to 16, MAV_CMD_NAV_WAYPOINT cmd.id = MAV_CMD_NAV_TAKEOFF; cmd.content.location.options = 0; @@ -192,7 +192,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw // use the current altitude for the target alt for takeoff. // only altitude will matter to the AP mission script for takeoff. - if (copter.mission.add_cmd(cmd)) { + if (copter.mode_auto.mission.add_cmd(cmd)) { // log event copter.Log_Write_Event(DATA_SAVEWP_ADD_WP); } @@ -210,7 +210,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw } // save command - if (copter.mission.add_cmd(cmd)) { + if (copter.mode_auto.mission.add_cmd(cmd)) { // log event copter.Log_Write_Event(DATA_SAVEWP_ADD_WP); } @@ -221,7 +221,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw case MISSION_RESET: #if MODE_AUTO_ENABLED == ENABLED if (ch_flag == HIGH) { - copter.mission.reset(); + copter.mode_auto.mission.reset(); } #endif break; diff --git a/ArduCopter/commands.cpp b/ArduCopter/commands.cpp index 3411d24817..8f32b423bb 100644 --- a/ArduCopter/commands.cpp +++ b/ArduCopter/commands.cpp @@ -88,8 +88,8 @@ bool Copter::set_home(const Location& loc, bool lock) // log new home position which mission library will pull from ahrs if (should_log(MASK_LOG_CMD)) { AP_Mission::Mission_Command temp_cmd; - if (mission.read_cmd_from_storage(0, temp_cmd)) { - DataFlash.Log_Write_Mission_Cmd(mission, temp_cmd); + if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) { + DataFlash.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd); } } #endif diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index be8473f472..acb5df0adf 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -269,8 +269,8 @@ void Copter::exit_mode(Copter::Mode *&old_flightmode, // stop mission when we leave auto mode #if MODE_AUTO_ENABLED == ENABLED if (old_flightmode == &mode_auto) { - if (mission.state() == AP_Mission::MISSION_RUNNING) { - mission.stop(); + if (mode_auto.mission.state() == AP_Mission::MISSION_RUNNING) { + mode_auto.mission.stop(); } #if MOUNT == ENABLED camera_mount.set_mode_to_default();