Copter: fix Cygwin build

Static initialization doesn't have an exact order, we can't rely on it
This commit is contained in:
Francisco Ferreira 2018-12-11 17:11:49 +00:00 committed by Randy Mackay
parent cf5dd7cdd7
commit a2fa63bcf7
6 changed files with 12 additions and 13 deletions

View File

@ -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

View File

@ -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;

View File

@ -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()

View File

@ -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;

View File

@ -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

View File

@ -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();