mirror of https://github.com/ArduPilot/ardupilot
Copter: fix Cygwin build
Static initialization doesn't have an exact order, we can't rely on it
This commit is contained in:
parent
cf5dd7cdd7
commit
a2fa63bcf7
|
@ -582,7 +582,7 @@ void Copter::publish_osd_info()
|
||||||
nav_info.wp_distance = flightmode->wp_distance() * 1.0e-2f;
|
nav_info.wp_distance = flightmode->wp_distance() * 1.0e-2f;
|
||||||
nav_info.wp_bearing = flightmode->wp_bearing();
|
nav_info.wp_bearing = flightmode->wp_bearing();
|
||||||
nav_info.wp_xtrack_error = flightmode->crosstrack_error() * 1.0e-2f;
|
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);
|
osd.set_nav_info(nav_info);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -910,7 +910,6 @@ private:
|
||||||
ModeAltHold mode_althold;
|
ModeAltHold mode_althold;
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
ModeAuto mode_auto;
|
ModeAuto mode_auto;
|
||||||
AP_Mission &mission = mode_auto.mission; // so parameters work only!
|
|
||||||
#endif
|
#endif
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
ModeAutoTune mode_autotune;
|
ModeAutoTune mode_autotune;
|
||||||
|
|
|
@ -660,7 +660,7 @@ const AP_Param::Info Copter::var_info[] = {
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
// @Group: MIS_
|
// @Group: MIS_
|
||||||
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
||||||
GOBJECT(mission, "MIS_", AP_Mission),
|
GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Group: RSSI_
|
// @Group: RSSI_
|
||||||
|
@ -1002,7 +1002,7 @@ ParametersG2::ParametersG2(void)
|
||||||
, proximity(copter.serial_manager)
|
, proximity(copter.serial_manager)
|
||||||
#endif
|
#endif
|
||||||
#if ADVANCED_FAILSAFE == ENABLED
|
#if ADVANCED_FAILSAFE == ENABLED
|
||||||
,afs(copter.mission, copter.gps)
|
,afs(copter.mode_auto.mission, copter.gps)
|
||||||
#endif
|
#endif
|
||||||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||||
,smart_rtl()
|
,smart_rtl()
|
||||||
|
|
|
@ -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
|
// 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;
|
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 = {};
|
AP_Mission::Mission_Command cmd = {};
|
||||||
|
|
||||||
// if the mission is empty save a takeoff command
|
// 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
|
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
|
||||||
cmd.id = MAV_CMD_NAV_TAKEOFF;
|
cmd.id = MAV_CMD_NAV_TAKEOFF;
|
||||||
cmd.content.location.options = 0;
|
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.
|
// use the current altitude for the target alt for takeoff.
|
||||||
// only altitude will matter to the AP mission script 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
|
// log event
|
||||||
copter.Log_Write_Event(DATA_SAVEWP_ADD_WP);
|
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
|
// save command
|
||||||
if (copter.mission.add_cmd(cmd)) {
|
if (copter.mode_auto.mission.add_cmd(cmd)) {
|
||||||
// log event
|
// log event
|
||||||
copter.Log_Write_Event(DATA_SAVEWP_ADD_WP);
|
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:
|
case MISSION_RESET:
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
if (ch_flag == HIGH) {
|
if (ch_flag == HIGH) {
|
||||||
copter.mission.reset();
|
copter.mode_auto.mission.reset();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -88,8 +88,8 @@ bool Copter::set_home(const Location& loc, bool lock)
|
||||||
// log new home position which mission library will pull from ahrs
|
// log new home position which mission library will pull from ahrs
|
||||||
if (should_log(MASK_LOG_CMD)) {
|
if (should_log(MASK_LOG_CMD)) {
|
||||||
AP_Mission::Mission_Command temp_cmd;
|
AP_Mission::Mission_Command temp_cmd;
|
||||||
if (mission.read_cmd_from_storage(0, temp_cmd)) {
|
if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) {
|
||||||
DataFlash.Log_Write_Mission_Cmd(mission, temp_cmd);
|
DataFlash.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -269,8 +269,8 @@ void Copter::exit_mode(Copter::Mode *&old_flightmode,
|
||||||
// stop mission when we leave auto mode
|
// stop mission when we leave auto mode
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
if (old_flightmode == &mode_auto) {
|
if (old_flightmode == &mode_auto) {
|
||||||
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
if (mode_auto.mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||||
mission.stop();
|
mode_auto.mission.stop();
|
||||||
}
|
}
|
||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
camera_mount.set_mode_to_default();
|
camera_mount.set_mode_to_default();
|
||||||
|
|
Loading…
Reference in New Issue