mirror of https://github.com/ArduPilot/ardupilot
Plane generalize Aux Switch VTOL abort for any plane abort landings
This commit is contained in:
parent
6b4cf06243
commit
3ac55f97b1
|
@ -649,6 +649,56 @@ void Plane::disarm_if_autoland_complete()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Plane::trigger_land_abort(const float climb_to_alt_m)
|
||||||
|
{
|
||||||
|
if (plane.control_mode != &plane.mode_auto) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
if (plane.quadplane.in_vtol_auto()) {
|
||||||
|
return quadplane.abort_landing();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
uint16_t mission_id = plane.mission.get_current_nav_cmd().id;
|
||||||
|
bool is_in_landing = (plane.flight_stage == AP_FixedWing::FlightStage::LAND) ||
|
||||||
|
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()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// only fly a fixed wing abort if we aren't doing quadplane stuff, or potentially
|
||||||
|
// shooting a quadplane approach
|
||||||
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
const bool attempt_go_around =
|
||||||
|
(!plane.quadplane.available()) ||
|
||||||
|
((!plane.quadplane.in_vtol_auto()) &&
|
||||||
|
(!plane.quadplane.landing_with_fixed_wing_spiral_approach()));
|
||||||
|
#else
|
||||||
|
const bool attempt_go_around = true;
|
||||||
|
#endif
|
||||||
|
if (attempt_go_around) {
|
||||||
|
// Initiate an aborted landing. This will trigger a pitch-up and
|
||||||
|
// climb-out to a safe altitude holding heading then one of the
|
||||||
|
// following actions will occur, check for in this order:
|
||||||
|
// - If MAV_CMD_CONTINUE_AND_CHANGE_ALT is next command in mission,
|
||||||
|
// increment mission index to execute it
|
||||||
|
// - else if DO_LAND_START is available, jump to it
|
||||||
|
// - else decrement the mission index to repeat the landing approach
|
||||||
|
|
||||||
|
if (!is_zero(climb_to_alt_m)) {
|
||||||
|
plane.auto_state.takeoff_altitude_rel_cm = climb_to_alt_m * 100;
|
||||||
|
}
|
||||||
|
if (plane.landing.request_go_around()) {
|
||||||
|
plane.auto_state.next_wp_crosstrack = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1036,46 +1036,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
|
||||||
case MAV_CMD_DO_GO_AROUND:
|
case MAV_CMD_DO_GO_AROUND:
|
||||||
{
|
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
|
||||||
uint16_t mission_id = plane.mission.get_current_nav_cmd().id;
|
|
||||||
bool is_in_landing = (plane.flight_stage == AP_FixedWing::FlightStage::LAND) ||
|
|
||||||
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()) {
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
}
|
|
||||||
|
|
||||||
// only fly a fixed wing abort if we aren't doing quadplane stuff, or potentially
|
|
||||||
// shooting a quadplane approach
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
|
||||||
const bool attempt_go_around =
|
|
||||||
(!plane.quadplane.available()) ||
|
|
||||||
((!plane.quadplane.in_vtol_auto()) &&
|
|
||||||
(!plane.quadplane.landing_with_fixed_wing_spiral_approach()));
|
|
||||||
#else
|
|
||||||
const bool attempt_go_around = true;
|
|
||||||
#endif
|
|
||||||
if (attempt_go_around) {
|
|
||||||
// Initiate an aborted landing. This will trigger a pitch-up and
|
|
||||||
// climb-out to a safe altitude holding heading then one of the
|
|
||||||
// following actions will occur, check for in this order:
|
|
||||||
// - If MAV_CMD_CONTINUE_AND_CHANGE_ALT is next command in mission,
|
|
||||||
// increment mission index to execute it
|
|
||||||
// - else if DO_LAND_START is available, jump to it
|
|
||||||
// - else decrement the mission index to repeat the landing approach
|
|
||||||
|
|
||||||
if (!is_zero(packet.param1)) {
|
|
||||||
plane.auto_state.takeoff_altitude_rel_cm = packet.param1 * 100;
|
|
||||||
}
|
|
||||||
if (plane.landing.request_go_around()) {
|
|
||||||
plane.auto_state.next_wp_crosstrack = false;
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return MAV_RESULT_FAILED;
|
|
||||||
|
|
||||||
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
||||||
// param1 : enable/disable
|
// param1 : enable/disable
|
||||||
|
|
|
@ -987,6 +987,7 @@ private:
|
||||||
|
|
||||||
// ArduPlane.cpp
|
// ArduPlane.cpp
|
||||||
void disarm_if_autoland_complete();
|
void disarm_if_autoland_complete();
|
||||||
|
bool trigger_land_abort(const float climb_to_alt_m);
|
||||||
void get_osd_roll_pitch_rad(float &roll, float &pitch) const override;
|
void get_osd_roll_pitch_rad(float &roll, float &pitch) const override;
|
||||||
float tecs_hgt_afe(void);
|
float tecs_hgt_afe(void);
|
||||||
void efi_update(void);
|
void efi_update(void);
|
||||||
|
|
|
@ -166,8 +166,8 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
||||||
case AUX_FUNC::CRUISE:
|
case AUX_FUNC::CRUISE:
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
case AUX_FUNC::ARMDISARM_AIRMODE:
|
case AUX_FUNC::ARMDISARM_AIRMODE:
|
||||||
case AUX_FUNC::AUTO_VTOL_LANDING_ABORT:
|
|
||||||
#endif
|
#endif
|
||||||
|
case AUX_FUNC::PLANE_AUTO_LANDING_ABORT:
|
||||||
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
|
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
|
||||||
case AUX_FUNC::EMERGENCY_LANDING_EN:
|
case AUX_FUNC::EMERGENCY_LANDING_EN:
|
||||||
case AUX_FUNC::FW_AUTOTUNE:
|
case AUX_FUNC::FW_AUTOTUNE:
|
||||||
|
@ -386,19 +386,18 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
case AUX_FUNC::AUTO_VTOL_LANDING_ABORT: {
|
case AUX_FUNC::PLANE_AUTO_LANDING_ABORT:
|
||||||
switch(ch_flag) {
|
switch(ch_flag) {
|
||||||
case AuxSwitchPos::HIGH:
|
case AuxSwitchPos::HIGH:
|
||||||
plane.quadplane.abort_landing();
|
IGNORE_RETURN(plane.trigger_land_abort(0));
|
||||||
break;
|
break;
|
||||||
case AuxSwitchPos::MIDDLE:
|
case AuxSwitchPos::MIDDLE:
|
||||||
case AuxSwitchPos::LOW:
|
case AuxSwitchPos::LOW:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
|
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
|
||||||
if (ch_flag == AuxSwitchPos::HIGH) {
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
||||||
|
|
Loading…
Reference in New Issue