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/commands.cpp
Views: 1798
/*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 == 0) {35next_WP_loc.alt = current_loc.alt;36next_WP_loc.relative_alt = false;37next_WP_loc.terrain_alt = false;38}39}4041// convert relative alt to absolute alt42if (next_WP_loc.relative_alt) {43next_WP_loc.relative_alt = false;44next_WP_loc.alt += home.alt;45}4647// are we already past the waypoint? This happens when we jump48// waypoints, and it can cause us to skip a waypoint. If we are49// past the waypoint when we start on a leg, then use the current50// location as the previous waypoint, to prevent immediately51// considering the waypoint complete52if (current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {53prev_WP_loc = current_loc;54}5556// zero out our loiter vals to watch for missed waypoints57loiter_angle_reset();5859setup_glide_slope();60setup_turn_angle();6162// update plane.target_altitude straight away, or if we are too63// close to out loiter point we may decide we are at the correct64// altitude before updating it (this is based on scheduler table65// ordering, where we navigate() before we66// adjust_altitude_target(), and navigate() uses values updated in67// adjust_altitude_target()68adjust_altitude_target();69}7071void Plane::set_guided_WP(const Location &loc)72{73if (aparm.loiter_radius < 0 || loc.loiter_ccw) {74loiter.direction = -1;75} else {76loiter.direction = 1;77}7879// copy the current location into the OldWP slot80// ---------------------------------------81prev_WP_loc = current_loc;8283// Load the next_WP slot84// ---------------------85next_WP_loc = loc;8687// used to control FBW and limit the rate of climb88// -----------------------------------------------89set_target_altitude_current();9091setup_glide_slope();92setup_turn_angle();9394// disable crosstrack, head directly to the point95auto_state.crosstrack = false;9697// reset loiter start time.98loiter.start_time_ms = 0;99100// start in non-VTOL mode101auto_state.vtol_loiter = false;102103loiter_angle_reset();104105#if HAL_QUADPLANE_ENABLED106// cancel pending takeoff107quadplane.guided_takeoff = false;108#endif109}110111/*112update home location from GPS113this is called as long as we have 3D lock and the arming switch is114not pushed115116returns true if home is changed117*/118bool Plane::update_home()119{120if (hal.util->was_watchdog_armed()) {121return false;122}123if ((g2.home_reset_threshold == -1) ||124((g2.home_reset_threshold > 0) &&125(fabsf(barometer.get_altitude()) > g2.home_reset_threshold))) {126// don't auto-update if we have changed barometer altitude127// significantly. This allows us to cope with slow baro drift128// but not re-do home and the baro if we have changed height129// significantly130return false;131}132bool ret = false;133if (ahrs.home_is_set() && !ahrs.home_is_locked() && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {134Location loc;135if (ahrs.get_location(loc)) {136// we take the altitude directly from the GPS as we are137// about to reset the baro calibration. We can't use AHRS138// altitude or we can end up perpetuating a bias in139// altitude, as AHRS alt depends on home alt, which means140// we would have a circular dependency141loc.alt = gps.location().alt;142ret = AP::ahrs().set_home(loc);143}144}145146// even if home is not updated we do a baro reset to stop baro147// drift errors while disarmed148barometer.update_calibration();149ahrs.resetHeightDatum();150151update_current_loc();152153return ret;154}155156bool Plane::set_home_persistently(const Location &loc)157{158if (hal.util->was_watchdog_armed()) {159return false;160}161if (!AP::ahrs().set_home(loc)) {162return false;163}164165// Save Home to EEPROM166mission.write_home_to_storage();167168return true;169}170171172