Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduPlane/mode_autoland.cpp
Views: 1798
#include "mode.h"1#include "Plane.h"2#include <GCS_MAVLink/GCS.h>34#if MODE_AUTOLAND_ENABLED56/*7mode AutoLand parameters8*/9const AP_Param::GroupInfo ModeAutoLand::var_info[] = {10// @Param: WP_ALT11// @DisplayName: Final approach WP altitude12// @Description: This is the target altitude above HOME for final approach waypoint13// @Range: 0 20014// @Increment: 115// @Units: m16// @User: Standard17AP_GROUPINFO("WP_ALT", 1, ModeAutoLand, final_wp_alt, 55),1819// @Param: WP_DIST20// @DisplayName: Final approach WP distance21// @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)22// @Range: 0 70023// @Increment: 124// @Units: m25// @User: Standard26AP_GROUPINFO("WP_DIST", 2, ModeAutoLand, final_wp_dist, 400),2728// @Param: DIR_OFF29// @DisplayName: Landing direction offset from takeoff30// @Description: The captured takeoff direction (at arming,if TKOFF_OPTION bit1 is set, or after ground course is established in autotakeoffs)is offset by this amount to create a different landing direction and approach.31// @Range: -360 36032// @Increment: 133// @Units: deg34// @User: Standard35AP_GROUPINFO("DIR_OFF", 3, ModeAutoLand, landing_dir_off, 0),3637AP_GROUPEND38};3940ModeAutoLand::ModeAutoLand() :41Mode()42{43AP_Param::setup_object_defaults(this, var_info);44}4546bool ModeAutoLand::_enter()47{48//must be flying to enter49if (!plane.is_flying()) {50gcs().send_text(MAV_SEVERITY_WARNING, "Must already be flying!");51return false;52}5354//takeoff direction must be set and must not be a quadplane, otherwise since flying switch to RTL so this can be used as FS action55#if HAL_QUADPLANE_ENABLED56if (quadplane.available() && !quadplane.option_is_set(QuadPlane::OPTION::ALLOW_FW_LAND)) {57gcs().send_text(MAV_SEVERITY_WARNING, "Option not set to allow fixed wing autoland");58return false;59}60#endif61if (!plane.takeoff_state.initial_direction.initialized) {62gcs().send_text(MAV_SEVERITY_WARNING, "Takeoff initial direction not set,must use autotakeoff");63return false;64}6566plane.prev_WP_loc = plane.current_loc;67plane.set_target_altitude_current();6869/*70landing is in 3 steps:711) a base leg waypoint722) a land start WP, with crosstrack733) the landing WP, with crosstrack7475the base leg point is 90 degrees off from the landing leg76*/77const Location &home = ahrs.get_home();7879/*80first calculate the starting waypoint we will use when doing the81NAV_LAND. This is offset by final_wp_dist from home, in a82direction 180 degrees from takeoff direction83*/84Location land_start_WP = home;85land_start_WP.offset_bearing(wrap_360(plane.takeoff_state.initial_direction.heading + 180), final_wp_dist);86land_start_WP.set_alt_m(final_wp_alt, Location::AltFrame::ABOVE_HOME);87land_start_WP.change_alt_frame(Location::AltFrame::ABSOLUTE);8889/*90now create the initial target waypoint for the base leg. We91choose if we will do a right or left turn onto the landing based92on where we are when we enter the landing mode93*/94const float bearing_to_current_deg = wrap_180(degrees(land_start_WP.get_bearing(plane.current_loc)));95const float bearing_err_deg = wrap_180(wrap_180(plane.takeoff_state.initial_direction.heading) - bearing_to_current_deg);96const float bearing_offset_deg = bearing_err_deg > 0? -90 : 90;97const float base_leg_length = final_wp_dist * 0.333;98cmd[0].id = MAV_CMD_NAV_WAYPOINT;99cmd[0].content.location = land_start_WP;100cmd[0].content.location.offset_bearing(plane.takeoff_state.initial_direction.heading + bearing_offset_deg, base_leg_length);101// set a 1m acceptance radius, we want to fly all the way to this waypoint102cmd[0].p1 = 1;103104/*105create the WP for the start of the landing106*/107cmd[1].content.location = land_start_WP;108cmd[1].id = MAV_CMD_NAV_WAYPOINT;109110// and the land WP111cmd[2].id = MAV_CMD_NAV_LAND;112cmd[2].content.location = home;113114// start first leg115stage = 0;116plane.start_command(cmd[0]);117118// don't crosstrack initially119plane.auto_state.crosstrack = false;120plane.auto_state.next_wp_crosstrack = true;121122return true;123}124125void ModeAutoLand::update()126{127plane.calc_nav_roll();128plane.calc_nav_pitch();129plane.set_offset_altitude_location(plane.prev_WP_loc, plane.next_WP_loc);130if (plane.landing.is_throttle_suppressed()) {131// if landing is considered complete throttle is never allowed, regardless of landing type132SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);133} else {134plane.calc_throttle();135}136}137138void ModeAutoLand::navigate()139{140if (stage == 2) {141// we are on final landing leg142plane.set_flight_stage(AP_FixedWing::FlightStage::LAND);143plane.verify_command(cmd[stage]);144return;145}146147// see if we have completed the leg148if (plane.verify_nav_wp(cmd[stage])) {149stage++;150plane.prev_WP_loc = plane.next_WP_loc;151plane.auto_state.next_turn_angle = 90;152plane.start_command(cmd[stage]);153plane.auto_state.crosstrack = true;154plane.auto_state.next_wp_crosstrack = true;155}156}157#endif158159160