Skip to content

Commit

Permalink
Plane: pass current location to mission landing methods
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Apr 2, 2024
1 parent 77ef4eb commit afec757
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -701,7 +701,7 @@ bool Plane::trigger_land_abort(const float climb_to_alt_m)
plane.is_land_command(mission_id);
if (is_in_landing) {
// fly a user planned abort pattern if available
if (plane.mission.jump_to_abort_landing_sequence()) {
if (plane.have_position && plane.mission.jump_to_abort_landing_sequence(plane.current_loc)) {
return true;
}

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1065,7 +1065,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in

case MAV_CMD_DO_LAND_START:
// attempt to switch to next DO_LAND_START command in the mission
if (plane.mission.jump_to_landing_sequence()) {
if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
return MAV_RESULT_ACCEPTED;
}
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,14 +269,14 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
already_landing = true;
}
#endif
if (!already_landing) {
if (!already_landing && plane.have_position) {
// never stop a landing if we were already committed
if (plane.mission.is_best_land_sequence()) {
if (plane.mission.is_best_land_sequence(plane.current_loc)) {
// continue mission as it will reach a landing in less distance
plane.mission.set_in_landing_sequence_flag(true);
break;
}
if (plane.mission.jump_to_landing_sequence()) {
if (plane.mission.jump_to_landing_sequence(plane.current_loc)) {
plane.set_mode(mode_auto, ModeReason::BATTERY_FAILSAFE);
break;
}
Expand All @@ -293,7 +293,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
#endif
if (!already_landing) {
// never stop a landing if we were already committed
if (g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START && plane.mission.is_best_land_sequence()) {
if ((g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) && plane.have_position && plane.mission.is_best_land_sequence(plane.current_loc)) {
// continue mission as it will reach a landing in less distance
plane.mission.set_in_landing_sequence_flag(true);
break;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ void ModeRTL::navigate()
labs(plane.altitude_error_cm) < 1000))
{
// we've reached the RTL point, see if we have a landing sequence
if (plane.mission.jump_to_landing_sequence()) {
if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {
// switch from RTL -> AUTO
plane.mission.set_force_resume(true);
if (plane.set_mode(plane.mode_auto, ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND)) {
Expand Down

0 comments on commit afec757

Please sign in to comment.