Plane: move jump_to_landing_sequence() to AP_Mission
This commit is contained in:
parent
40777e9e74
commit
dc85ffa834
@ -803,7 +803,7 @@ void Plane::update_navigation()
|
||||
reached_loiter_target() &&
|
||||
labs(altitude_error_cm) < 1000) {
|
||||
// we've reached the RTL point, see if we have a landing sequence
|
||||
if (landing.jump_to_landing_sequence()) {
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
// switch from RTL -> AUTO
|
||||
set_mode(AUTO, MODE_REASON_UNKNOWN);
|
||||
}
|
||||
@ -815,7 +815,7 @@ void Plane::update_navigation()
|
||||
else if (g.rtl_autoland == 2 &&
|
||||
!auto_state.checked_for_autoland) {
|
||||
// Go directly to the landing sequence
|
||||
if (landing.jump_to_landing_sequence()) {
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
// switch from RTL -> AUTO
|
||||
set_mode(AUTO, MODE_REASON_UNKNOWN);
|
||||
}
|
||||
|
@ -1335,7 +1335,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
result = MAV_RESULT_FAILED;
|
||||
|
||||
// attempt to switch to next DO_LAND_START command in the mission
|
||||
if (plane.landing.jump_to_landing_sequence()) {
|
||||
if (plane.mission.jump_to_landing_sequence()) {
|
||||
plane.set_mode(AUTO, MODE_REASON_UNKNOWN);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user