mirror of https://github.com/ArduPilot/ardupilot
Plane: pass current location to mission landing methods
This commit is contained in:
parent
77ef4eb4e6
commit
afec757c33
|
@ -701,7 +701,7 @@ bool Plane::trigger_land_abort(const float climb_to_alt_m)
|
||||||
plane.is_land_command(mission_id);
|
plane.is_land_command(mission_id);
|
||||||
if (is_in_landing) {
|
if (is_in_landing) {
|
||||||
// fly a user planned abort pattern if available
|
// 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;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1065,7 +1065,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
||||||
|
|
||||||
case MAV_CMD_DO_LAND_START:
|
case MAV_CMD_DO_LAND_START:
|
||||||
// attempt to switch to next DO_LAND_START command in the mission
|
// 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);
|
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
|
@ -269,14 +269,14 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
|
||||||
already_landing = true;
|
already_landing = true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
if (!already_landing) {
|
if (!already_landing && plane.have_position) {
|
||||||
// never stop a landing if we were already committed
|
// 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
|
// continue mission as it will reach a landing in less distance
|
||||||
plane.mission.set_in_landing_sequence_flag(true);
|
plane.mission.set_in_landing_sequence_flag(true);
|
||||||
break;
|
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);
|
plane.set_mode(mode_auto, ModeReason::BATTERY_FAILSAFE);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -293,7 +293,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
|
||||||
#endif
|
#endif
|
||||||
if (!already_landing) {
|
if (!already_landing) {
|
||||||
// never stop a landing if we were already committed
|
// 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
|
// continue mission as it will reach a landing in less distance
|
||||||
plane.mission.set_in_landing_sequence_flag(true);
|
plane.mission.set_in_landing_sequence_flag(true);
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -102,7 +102,7 @@ void ModeRTL::navigate()
|
||||||
labs(plane.altitude_error_cm) < 1000))
|
labs(plane.altitude_error_cm) < 1000))
|
||||||
{
|
{
|
||||||
// we've reached the RTL point, see if we have a landing sequence
|
// 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
|
// switch from RTL -> AUTO
|
||||||
plane.mission.set_force_resume(true);
|
plane.mission.set_force_resume(true);
|
||||||
if (plane.set_mode(plane.mode_auto, ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND)) {
|
if (plane.set_mode(plane.mode_auto, ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND)) {
|
||||||
|
|
Loading…
Reference in New Issue