#include "mode.h"1#include "Plane.h"2#include <GCS_MAVLink/GCS.h>34#if MODE_AUTOLAND_ENABLED56// This is added to the target altitude to make sure the true target is exceeded.7// This should be larger than the expected steady state error.8constexpr float fast_climb_extra_alt = 10;910/*11mode AutoLand parameters12*/13const AP_Param::GroupInfo ModeAutoLand::var_info[] = {14// @Param: WP_ALT15// @DisplayName: Final approach WP altitude16// @Description: This is the target altitude above HOME for final approach waypoint17// @Range: 0 20018// @Increment: 119// @Units: m20// @User: Standard21AP_GROUPINFO("WP_ALT", 1, ModeAutoLand, final_wp_alt, 55),2223// @Param: WP_DIST24// @DisplayName: Final approach WP distance25// @Description: This is the distance from Home that the final approach waypoint is set. The waypoint point will be in the opposite direction of takeoff (the direction the plane is facing when the plane sets its takeoff heading)26// @Range: 0 70027// @Increment: 128// @Units: m29// @User: Standard30AP_GROUPINFO("WP_DIST", 2, ModeAutoLand, final_wp_dist, 400),3132// @Param: DIR_OFF33// @DisplayName: Landing direction offset from takeoff34// @Description: The captured takeoff direction after ground course is established in autotakeoffsis offset by this amount to create a different landing direction and approach.However,if TKOFF_OPTION bit1 is set, the takeoff(landing) direction is captured immediately via compass heading upon arming, then this offset is NOT applied.35// @Range: -360 36036// @Increment: 137// @Units: deg38// @User: Standard39AP_GROUPINFO("DIR_OFF", 3, ModeAutoLand, landing_dir_off, 0),4041// @Param: OPTIONS42// @DisplayName: Autoland mode options43// @Description: Enables optional autoland mode behaviors44// @Bitmask: 0: When set if there is a healthy compass in use the compass heading will be captured at arming and used for the AUTOLAND mode's initial takeoff direction instead of capturing ground course in NAV_TAKEOFF or Mode TAKEOFF or other modes.45// @User: Standard46AP_GROUPINFO("OPTIONS", 4, ModeAutoLand, options, 0),4748// @Param: CLIMB49// @DisplayName: Minimum altitude above terrain before turning upon entry50// @Description: Vehicle will climb with limited turn ability (LEVEL_ROLL_LIMIT) until it is at least this altitude above the terrain at the point of entry, before proceeding to loiter-to-alt and landing legs. 0 Disables.51// @Range: 0 10052// @Increment: 153// @Units: m54// @User: Standard55AP_GROUPINFO("CLIMB", 5, ModeAutoLand, terrain_alt_min, 0),565758AP_GROUPEND59};6061ModeAutoLand::ModeAutoLand() :62Mode()63{64AP_Param::setup_object_defaults(this, var_info);65}6667bool ModeAutoLand::_enter()68{69//must be flying to enter70if (!plane.is_flying()) {71gcs().send_text(MAV_SEVERITY_WARNING, "Must already be flying!");72return false;73}7475// autoland not available for quadplanes as capture of takeoff direction76// doesn't make sense77#if HAL_QUADPLANE_ENABLED78if (quadplane.available()) {79gcs().send_text(MAV_SEVERITY_WARNING, "autoland not available");80return false;81}82#endif8384if (!plane.takeoff_state.initial_direction.initialized) {85gcs().send_text(MAV_SEVERITY_WARNING, "Takeoff initial direction not set");86return false;87}8889plane.set_target_altitude_current();90plane.auto_state.next_wp_crosstrack = true;9192plane.prev_WP_loc = plane.current_loc;9394// In flight stage normal for approach95plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);9697const Location &home = ahrs.get_home();9899#ifndef HAL_LANDING_DEEPSTALL_ENABLED100if (plane.landing.get_type() == AP_Landing::TYPE_DEEPSTALL) {101// Deep stall landings require only a landing location, they do there own loiter to alt and approach102cmd_land.id = MAV_CMD_NAV_LAND;103cmd_land.content.location = home;104105// p1 gives the altitude from which to start the deep stall above the location alt106cmd_land.p1 = final_wp_alt;107plane.start_command(cmd_land);108109stage = AutoLandStage::LANDING;110return true;111}112#endif // HAL_LANDING_DEEPSTALL_ENABLED113114/*115Glide slope landing is in 3 steps:1161) a loitering to alt waypoint centered on base leg1172) exiting and proceeeing to a final approach land start WP, with crosstrack1183) the landing WP at home, with crosstrack119120the base leg point is 90 degrees off from the landing leg121*/122123/*124first calculate the starting waypoint we will use when doing the125NAV_LAND. This is offset by final_wp_dist from home, in a126direction 180 degrees from takeoff direction127*/128land_start = home;129land_start.offset_bearing(plane.takeoff_state.initial_direction.heading, -final_wp_dist);130land_start.set_alt_m(final_wp_alt, Location::AltFrame::ABOVE_HOME);131land_start.change_alt_frame(Location::AltFrame::ABSOLUTE);132133/*134now create the initial target waypoint for the loitering to alt centered on base leg waypoint. We135choose if we will do a right or left turn onto the landing based136on where we are when we enter the landing mode137*/138const float bearing_to_current_deg = degrees(land_start.get_bearing(plane.current_loc));139const float bearing_err_deg = wrap_180(plane.takeoff_state.initial_direction.heading - bearing_to_current_deg);140const float bearing_offset_deg = (bearing_err_deg > 0) ? -90 : 90;141142// Try and minimize loiter radius by using the smaller of the waypoint loiter radius or 1/3 of the final WP distance143const float loiter_radius = MIN(final_wp_dist * 0.333, abs(plane.aparm.loiter_radius));144145// corrected_loiter_radius is the radius the vehicle will actually fly, this gets larger as altitude increases.146// Strictly this gets the loiter radius at the current altitude, really we want the loiter radius at final_wp_alt.147const float corrected_loiter_radius = plane.nav_controller->loiter_radius(loiter_radius);148149cmd_loiter.id = MAV_CMD_NAV_LOITER_TO_ALT;150cmd_loiter.p1 = loiter_radius;151cmd_loiter.content.location = land_start;152cmd_loiter.content.location.offset_bearing(plane.takeoff_state.initial_direction.heading + bearing_offset_deg, corrected_loiter_radius);153cmd_loiter.content.location.loiter_ccw = bearing_err_deg>0? 1 :0;154155// May need to climb first156bool climb_first = false;157if (terrain_alt_min > 0) {158// Work out the distance needed to climb above terrain159#if AP_TERRAIN_AVAILABLE160const bool use_terrain = plane.terrain_enabled_in_current_mode();161#else162const bool use_terrain = false;163#endif164const float dist_to_climb = terrain_alt_min - plane.relative_ground_altitude(RangeFinderUse::CLIMB, use_terrain);165if (is_positive(dist_to_climb)) {166// Copy loiter and update target altitude to current altitude plus climb altitude167cmd_climb = cmd_loiter;168float abs_alt;169if (plane.current_loc.get_alt_m(Location::AltFrame::ABSOLUTE, abs_alt)) {170cmd_climb.content.location.set_alt_m(abs_alt + dist_to_climb + fast_climb_extra_alt, Location::AltFrame::ABSOLUTE);171climb_first = true;172}173}174}175176#if AP_TERRAIN_AVAILABLE177// Update loiter location to be relative terrain if enabled178if (plane.terrain_enabled_in_current_mode()) {179cmd_loiter.content.location.set_alt_m(final_wp_alt, Location::AltFrame::ABOVE_TERRAIN);180};181#endif182// land WP at home183cmd_land.id = MAV_CMD_NAV_LAND;184cmd_land.content.location = home;185186// start first leg toward the base leg loiter to alt point187if (climb_first) {188stage = AutoLandStage::CLIMB;189plane.start_command(cmd_climb);190191} else {192stage = AutoLandStage::LOITER;193plane.start_command(cmd_loiter);194}195196return true;197}198199void ModeAutoLand::update()200{201plane.calc_nav_roll();202203// Apply level roll limit in climb stage204if (stage == AutoLandStage::CLIMB) {205plane.roll_limit_cd = MIN(plane.roll_limit_cd, plane.g.level_roll_limit*100);206plane.nav_roll_cd = constrain_int16(plane.nav_roll_cd, -plane.roll_limit_cd, plane.roll_limit_cd);207}208209plane.calc_nav_pitch();210if (plane.landing.is_throttle_suppressed()) {211// if landing is considered complete throttle is never allowed, regardless of landing type212SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);213} else {214plane.calc_throttle();215}216}217218void ModeAutoLand::navigate()219{220switch (stage) {221case AutoLandStage::CLIMB:222// Update loiter, although roll limit is applied the vehicle will still navigate (slowly)223plane.update_loiter(cmd_climb.p1);224225ftype dist;226if (plane.reached_loiter_target() || !cmd_climb.content.location.get_height_above(plane.current_loc, dist) || (dist < fast_climb_extra_alt)) {227// Reached destination or Climb is done, move onto loiter228plane.auto_state.next_wp_crosstrack = true;229stage = AutoLandStage::LOITER;230plane.start_command(cmd_loiter);231plane.prev_WP_loc = plane.current_loc;232}233break;234235case AutoLandStage::LOITER:236// check if we have arrived and completed loiter at base leg waypoint237if (plane.verify_loiter_to_alt(cmd_loiter)) {238stage = AutoLandStage::LANDING;239plane.start_command(cmd_land);240// Crosstrack from the land start location241plane.prev_WP_loc = land_start;242243}244break;245246case AutoLandStage::LANDING:247plane.set_flight_stage(AP_FixedWing::FlightStage::LAND);248plane.verify_command(cmd_land);249// make sure we line up250plane.auto_state.crosstrack = true;251break;252}253}254255/*256Takeoff direction is initialized after arm when sufficient altitude257and ground speed is obtained, then captured takeoff direction +258offset used as landing direction in AUTOLAND259*/260void ModeAutoLand::check_takeoff_direction()261{262#if HAL_QUADPLANE_ENABLED263// we don't allow fixed wing autoland for quadplanes264if (quadplane.available()) {265return;266}267#endif268269if (plane.takeoff_state.initial_direction.initialized) {270return;271}272//set autoland direction to GPS course over ground273if (plane.control_mode->allows_autoland_direction_capture() &&274plane.is_flying() &&275hal.util->get_soft_armed() &&276plane.gps.ground_speed() > GPS_GND_CRS_MIN_SPD) {277set_autoland_direction(plane.gps.ground_course() + landing_dir_off);278}279}280281// Sets autoland direction using ground course + offset parameter282void ModeAutoLand::set_autoland_direction(const float heading)283{284plane.takeoff_state.initial_direction.heading = wrap_360(heading);285plane.takeoff_state.initial_direction.initialized = true;286gcs().send_text(MAV_SEVERITY_INFO, "Autoland direction= %u",int(plane.takeoff_state.initial_direction.heading));287}288289/*290return true when the LOITER_TO_ALT is lined up ready for the landing, used in commands_logic verify loiter to alt291*/292bool ModeAutoLand::landing_lined_up(void)293{294// use the line between the center of the LOITER_TO_ALT on the base leg and the295// start of the landing leg (land_start_WP)296return plane.mode_loiter.isHeadingLinedUp(cmd_loiter.content.location, cmd_land.content.location);297}298299// possibly capture heading on arming for autoland mode if option is set and using a compass300void ModeAutoLand::arm_check(void)301{302if (plane.ahrs.use_compass() && autoland_option_is_set(ModeAutoLand::AutoLandOption::AUTOLAND_DIR_ON_ARM)) {303set_autoland_direction(plane.ahrs.get_yaw_deg());304}305}306307bool ModeAutoLand::is_landing() const308{309return (plane.flight_stage == AP_FixedWing::FlightStage::LAND);310}311312313#endif // MODE_AUTOLAND_ENABLED314315316317