/*1* logic for dealing with the current command in the mission and home location2*/34#include "Plane.h"56/*7* set_next_WP - sets the target location the vehicle should fly to8*/9void Plane::set_next_WP(const Location &loc)10{11if (auto_state.next_wp_crosstrack) {12// copy the current WP into the OldWP slot13prev_WP_loc = next_WP_loc;14auto_state.crosstrack = true;15} else {16// we should not try to cross-track for this waypoint17prev_WP_loc = current_loc;18// use cross-track for the next waypoint19auto_state.next_wp_crosstrack = true;20auto_state.crosstrack = false;21}2223// Load the next_WP slot24// ---------------------25next_WP_loc = loc;2627// if lat and lon is zero, then use current lat/lon28// this allows a mission to contain a "loiter on the spot"29// command30if (next_WP_loc.lat == 0 && next_WP_loc.lng == 0) {31next_WP_loc.lat = current_loc.lat;32next_WP_loc.lng = current_loc.lng;33// additionally treat zero altitude as current altitude34if (next_WP_loc.alt_is_zero()) {35next_WP_loc.copy_alt_from(current_loc);36}37}3839fix_terrain_WP(next_WP_loc, __LINE__);4041// convert relative alt to absolute alt42if (!next_WP_loc.terrain_alt) {43next_WP_loc.change_alt_frame(Location::AltFrame::ABSOLUTE);44}4546// are we already past the waypoint? This happens when we jump47// waypoints, and it can cause us to skip a waypoint. If we are48// past the waypoint when we start on a leg, then use the current49// location as the previous waypoint, to prevent immediately50// considering the waypoint complete51if (current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {52prev_WP_loc = current_loc;53}5455// zero out our loiter vals to watch for missed waypoints56loiter_angle_reset();5758setup_alt_slope();59setup_turn_angle();6061// update plane.target_altitude straight away, or if we are too62// close to out loiter point we may decide we are at the correct63// altitude before updating it (this is based on scheduler table64// ordering, where we navigate() before we65// adjust_altitude_target(), and navigate() uses values updated in66// adjust_altitude_target()67adjust_altitude_target();68}6970void Plane::set_guided_WP(const Location &loc)71{72if (aparm.loiter_radius < 0 || loc.loiter_ccw) {73loiter.direction = -1;74} else {75loiter.direction = 1;76}7778// copy the current location into the OldWP slot79// ---------------------------------------80prev_WP_loc = current_loc;8182// Load the next_WP slot83// ---------------------84next_WP_loc = loc;8586fix_terrain_WP(next_WP_loc, __LINE__);8788// used to control FBW and limit the rate of climb89// -----------------------------------------------90set_target_altitude_current();9192setup_alt_slope();93setup_turn_angle();9495// disable crosstrack, head directly to the point96auto_state.crosstrack = false;9798// reset loiter start time.99loiter.start_time_ms = 0;100101// start in non-VTOL mode102auto_state.vtol_loiter = false;103104loiter_angle_reset();105106#if HAL_QUADPLANE_ENABLED107// cancel pending takeoff108quadplane.guided_takeoff = false;109#endif110}111112/*113update home location from GPS114this is called as long as we have 3D lock and the arming switch is115not pushed116117returns true if home is changed118*/119bool Plane::update_home()120{121if (hal.util->was_watchdog_armed()) {122return false;123}124if ((g2.home_reset_threshold == -1) ||125((g2.home_reset_threshold > 0) &&126(fabsf(barometer.get_altitude()) > g2.home_reset_threshold))) {127// don't auto-update if we have changed barometer altitude128// significantly. This allows us to cope with slow baro drift129// but not re-do home and the baro if we have changed height130// significantly131return false;132}133bool ret = false;134if (ahrs.home_is_set() && !ahrs.home_is_locked() && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {135Location loc;136if (ahrs.get_location(loc)) {137// we take the altitude directly from the GPS as we are138// about to reset the baro calibration. We can't use AHRS139// altitude or we can end up perpetuating a bias in140// altitude, as AHRS alt depends on home alt, which means141// we would have a circular dependency142loc.set_alt_cm(gps.location().alt,143Location::AltFrame::ABSOLUTE);144ret = AP::ahrs().set_home(loc);145}146}147148// even if home is not updated we do a baro reset to stop baro149// drift errors while disarmed150barometer.update_calibration();151ahrs.resetHeightDatum();152153update_current_loc();154155return ret;156}157158bool Plane::set_home_persistently(const Location &loc)159{160if (hal.util->was_watchdog_armed()) {161return false;162}163if (!AP::ahrs().set_home(loc)) {164return false;165}166167return true;168}169170171