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/altitude.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "Plane.h"1617/*18altitude handling routines. These cope with both barometric control19and terrain following control20*/2122/*23adjust altitude target depending on mode24*/25void Plane::adjust_altitude_target()26{27control_mode->update_target_altitude();28}2930void Plane::check_home_alt_change(void)31{32int32_t home_alt_cm = ahrs.get_home().alt;33if (home_alt_cm != auto_state.last_home_alt_cm && hal.util->get_soft_armed()) {34// cope with home altitude changing35const int32_t alt_change_cm = home_alt_cm - auto_state.last_home_alt_cm;36if (next_WP_loc.terrain_alt) {37/*38next_WP_loc for terrain alt WP are quite strange. They39have terrain_alt=1, but also have relative_alt=0 and40have been calculated to be relative to home. We need to41adjust for the change in home alt42*/43next_WP_loc.alt += alt_change_cm;44}45// reset TECS to force the field elevation estimate to reset46TECS_controller.offset_altitude(alt_change_cm * 0.01f);47}48auto_state.last_home_alt_cm = home_alt_cm;49}5051/*52setup for a gradual glide slope to the next waypoint, if appropriate53*/54void Plane::setup_glide_slope(void)55{56// establish the distance we are travelling to the next waypoint,57// for calculating out rate of change of altitude58auto_state.wp_distance = current_loc.get_distance(next_WP_loc);59auto_state.wp_proportion = current_loc.line_path_proportion(prev_WP_loc, next_WP_loc);60TECS_controller.set_path_proportion(auto_state.wp_proportion);61update_flight_stage();6263/*64work out if we will gradually change altitude, or try to get to65the new altitude as quickly as possible.66*/67switch (control_mode->mode_number()) {68case Mode::Number::RTL:69case Mode::Number::AVOID_ADSB:70case Mode::Number::GUIDED:71/* glide down slowly if above target altitude, but ascend more72rapidly if below it. See73https://github.com/ArduPilot/ardupilot/issues/3974*/75if (above_location_current(next_WP_loc)) {76set_offset_altitude_location(prev_WP_loc, next_WP_loc);77} else {78reset_offset_altitude();79}80break;8182case Mode::Number::AUTO:8384//climb without doing glide slope if option is enabled85if (!above_location_current(next_WP_loc) && plane.flight_option_enabled(FlightOptions::IMMEDIATE_CLIMB_IN_AUTO)) {86reset_offset_altitude();87break;88}8990// we only do glide slide handling in AUTO when above 20m or91// when descending. The 20 meter threshold is arbitrary, and92// is basically to prevent situations where we try to slowly93// gain height at low altitudes, potentially hitting94// obstacles.95if (adjusted_relative_altitude_cm() > 2000 || above_location_current(next_WP_loc)) {96set_offset_altitude_location(prev_WP_loc, next_WP_loc);97} else {98reset_offset_altitude();99}100break;101default:102reset_offset_altitude();103break;104}105}106107/*108return RTL altitude as AMSL cm109*/110int32_t Plane::get_RTL_altitude_cm() const111{112if (g.RTL_altitude < 0) {113return current_loc.alt;114}115return g.RTL_altitude*100 + home.alt;116}117118/*119return relative altitude in meters (relative to terrain, if available,120or home otherwise)121*/122float Plane::relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available)123{124#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED125float height_AGL;126// use external HAGL if available127if (get_external_HAGL(height_AGL)) {128return height_AGL;129}130#endif // AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED131132#if AP_RANGEFINDER_ENABLED133if (use_rangefinder_if_available && rangefinder_state.in_range) {134return rangefinder_state.height_estimate;135}136#endif137138#if HAL_QUADPLANE_ENABLED && AP_RANGEFINDER_ENABLED139if (use_rangefinder_if_available && quadplane.in_vtol_land_final() &&140rangefinder.status_orient(rangefinder_orientation()) == RangeFinder::Status::OutOfRangeLow) {141// a special case for quadplane landing when rangefinder goes142// below minimum. Consider our height above ground to be zero143return 0;144}145#endif146147#if AP_TERRAIN_AVAILABLE148float altitude;149if (use_terrain_if_available &&150terrain.status() == AP_Terrain::TerrainStatusOK &&151terrain.height_above_terrain(altitude, true)) {152return altitude;153}154#endif155156#if HAL_QUADPLANE_ENABLED157if (quadplane.in_vtol_land_descent() &&158!quadplane.landing_with_fixed_wing_spiral_approach()) {159// when doing a VTOL landing we can use the waypoint height as160// ground height. We can't do this if using the161// LAND_FW_APPROACH as that uses the wp height as the approach162// height163return height_above_target();164}165#endif166167return relative_altitude;168}169170// Helper for above method using terrain if the vehicle is currently terrain following171float Plane::relative_ground_altitude(bool use_rangefinder_if_available)172{173#if AP_TERRAIN_AVAILABLE174return relative_ground_altitude(use_rangefinder_if_available, target_altitude.terrain_following);175#else176return relative_ground_altitude(use_rangefinder_if_available, false);177#endif178}179180181/*182set the target altitude to the current altitude. This is used when183setting up for altitude hold, such as when releasing elevator in184CRUISE mode.185*/186void Plane::set_target_altitude_current(void)187{188// record altitude above sea level at the current time as our189// target altitude190target_altitude.amsl_cm = current_loc.alt;191192// reset any glide slope offset193reset_offset_altitude();194195#if AP_TERRAIN_AVAILABLE196// also record the terrain altitude if possible197float terrain_altitude;198if (terrain_enabled_in_current_mode() && terrain.height_above_terrain(terrain_altitude, true) && !terrain_disabled()) {199target_altitude.terrain_following = true;200target_altitude.terrain_alt_cm = terrain_altitude*100;201} else {202// if terrain following is disabled, or we don't know our203// terrain altitude when we set the altitude then don't204// terrain follow205target_altitude.terrain_following = false;206}207#endif208}209210/*211set the target altitude to the current altitude, with ALT_OFFSET adjustment212*/213void Plane::set_target_altitude_current_adjusted(void)214{215set_target_altitude_current();216217// use adjusted_altitude_cm() to take account of ALTITUDE_OFFSET218target_altitude.amsl_cm = adjusted_altitude_cm();219}220221/*222set target altitude based on a location structure223*/224void Plane::set_target_altitude_location(const Location &loc)225{226target_altitude.amsl_cm = loc.alt;227if (loc.relative_alt) {228target_altitude.amsl_cm += home.alt;229}230#if AP_TERRAIN_AVAILABLE231if (target_altitude.terrain_following_pending) {232/* we didn't get terrain data to init when we started on this233target, retry234*/235setup_terrain_target_alt(next_WP_loc);236}237/*238if this location has the terrain_alt flag set and we know the239terrain altitude of our current location then treat it as a240terrain altitude241*/242float height;243if (loc.terrain_alt && terrain.height_above_terrain(height, true)) {244target_altitude.terrain_following = true;245target_altitude.terrain_alt_cm = loc.alt;246if (!loc.relative_alt) {247// it has home added, remove it248target_altitude.terrain_alt_cm -= home.alt;249}250} else {251target_altitude.terrain_following = false;252}253#endif254}255256/*257return relative to home target altitude in centimeters. Used for258altitude control libraries259*/260int32_t Plane::relative_target_altitude_cm(void)261{262#if AP_TERRAIN_AVAILABLE263float relative_home_height;264if (target_altitude.terrain_following &&265terrain.height_relative_home_equivalent(target_altitude.terrain_alt_cm*0.01f,266relative_home_height, true)) {267// add lookahead adjustment the target altitude268target_altitude.lookahead = lookahead_adjustment();269relative_home_height += target_altitude.lookahead;270271#if AP_RANGEFINDER_ENABLED272// correct for rangefinder data273relative_home_height += rangefinder_correction();274#endif275276// we are following terrain, and have terrain data for the277// current location. Use it.278return relative_home_height*100;279}280#endif281int32_t relative_alt = target_altitude.amsl_cm - home.alt;282relative_alt += mission_alt_offset()*100;283#if AP_RANGEFINDER_ENABLED284relative_alt += rangefinder_correction() * 100;285#endif286return relative_alt;287}288289/*290change the current target altitude by an amount in centimeters. Used291to cope with changes due to elevator in CRUISE or FBWB292*/293void Plane::change_target_altitude(int32_t change_cm)294{295target_altitude.amsl_cm += change_cm;296#if AP_TERRAIN_AVAILABLE297if (target_altitude.terrain_following && !terrain_disabled()) {298target_altitude.terrain_alt_cm += change_cm;299}300#endif301}302/*303change target altitude by a proportion of the target altitude offset304(difference in height to next WP from previous WP). proportion305should be between 0 and 1.306307When proportion is zero we have reached the destination. When308proportion is 1 we are at the starting waypoint.309310Note that target_altitude is setup initially based on the311destination waypoint312*/313void Plane::set_target_altitude_proportion(const Location &loc, float proportion)314{315set_target_altitude_location(loc);316proportion = constrain_float(proportion, 0.0f, 1.0f);317change_target_altitude(-target_altitude.offset_cm*proportion);318//rebuild the glide slope if we are above it and supposed to be climbing319if(g.glide_slope_threshold > 0) {320if(target_altitude.offset_cm > 0 && calc_altitude_error_cm() < -100 * g.glide_slope_threshold) {321set_target_altitude_location(loc);322set_offset_altitude_location(current_loc, loc);323change_target_altitude(-target_altitude.offset_cm*proportion);324//adjust the new target offset altitude to reflect that we are partially already done325if(proportion > 0.0f)326target_altitude.offset_cm = ((float)target_altitude.offset_cm)/proportion;327}328}329}330331/*332constrain target altitude to be between two locations. Used to333ensure we stay within two waypoints in altitude334*/335void Plane::constrain_target_altitude_location(const Location &loc1, const Location &loc2)336{337if (loc1.alt > loc2.alt) {338target_altitude.amsl_cm = constrain_int32(target_altitude.amsl_cm, loc2.alt, loc1.alt);339} else {340target_altitude.amsl_cm = constrain_int32(target_altitude.amsl_cm, loc1.alt, loc2.alt);341}342}343344/*345return error between target altitude and current altitude346*/347int32_t Plane::calc_altitude_error_cm(void)348{349#if AP_TERRAIN_AVAILABLE350float terrain_height;351if (target_altitude.terrain_following &&352terrain.height_above_terrain(terrain_height, true)) {353return target_altitude.lookahead*100 + target_altitude.terrain_alt_cm - (terrain_height*100);354}355#endif356return target_altitude.amsl_cm - adjusted_altitude_cm();357}358359/*360check for cruise_alt_floor and fence min/max altitude361*/362void Plane::check_fbwb_altitude(void)363{364float max_alt_cm = 0.0;365float min_alt_cm = 0.0;366bool should_check_max = false;367bool should_check_min = false;368369#if AP_FENCE_ENABLED370// taking fence max and min altitude (with margin)371const uint8_t enabled_fences = plane.fence.get_enabled_fences();372if ((enabled_fences & AC_FENCE_TYPE_ALT_MIN) != 0) {373min_alt_cm = plane.fence.get_safe_alt_min()*100.0;374should_check_min = true;375}376if ((enabled_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {377max_alt_cm = plane.fence.get_safe_alt_max()*100.0;378should_check_max = true;379}380#endif381382if (g.cruise_alt_floor > 0) {383// FBWB min altitude exists384min_alt_cm = MAX(min_alt_cm, plane.g.cruise_alt_floor*100.0);385should_check_min = true;386}387388if (!should_check_min && !should_check_max) {389return;390}391392//check if terrain following (min and max)393#if AP_TERRAIN_AVAILABLE394if (target_altitude.terrain_following) {395// set our target terrain height to be at least the min set396if (should_check_max) {397target_altitude.terrain_alt_cm = MIN(target_altitude.terrain_alt_cm, max_alt_cm);398}399if (should_check_min) {400target_altitude.terrain_alt_cm = MAX(target_altitude.terrain_alt_cm, min_alt_cm);401}402return;403}404#endif405406if (should_check_max) {407target_altitude.amsl_cm = MIN(target_altitude.amsl_cm, home.alt + max_alt_cm);408}409if (should_check_min) {410target_altitude.amsl_cm = MAX(target_altitude.amsl_cm, home.alt + min_alt_cm);411}412}413414/*415reset the altitude offset used for glide slopes416*/417void Plane::reset_offset_altitude(void)418{419target_altitude.offset_cm = 0;420}421422423/*424reset the altitude offset used for glide slopes, based on difference425between altitude at a destination and a specified start altitude. If426destination is above the starting altitude then the result is427positive.428*/429void Plane::set_offset_altitude_location(const Location &start_loc, const Location &destination_loc)430{431target_altitude.offset_cm = destination_loc.alt - start_loc.alt;432433#if AP_TERRAIN_AVAILABLE434/*435if this location has the terrain_alt flag set and we know the436terrain altitude of our current location then treat it as a437terrain altitude438*/439float height;440if (destination_loc.terrain_alt &&441target_altitude.terrain_following &&442terrain.height_above_terrain(height, true)) {443target_altitude.offset_cm = target_altitude.terrain_alt_cm - (height * 100);444}445#endif446447if (flight_stage != AP_FixedWing::FlightStage::LAND) {448// if we are within GLIDE_SLOPE_MIN meters of the target altitude449// then reset the offset to not use a glide slope. This allows for450// more accurate flight of missions where the aircraft may lose or451// gain a bit of altitude near waypoint turn points due to local452// terrain changes453if (g.glide_slope_min <= 0 ||454labs(target_altitude.offset_cm)*0.01f < g.glide_slope_min) {455target_altitude.offset_cm = 0;456}457}458}459460/*461return true if current_loc is above loc. Used for glide slope462calculations.463464"above" is simple if we are not terrain following, as it just means465the pressure altitude of one is above the other.466467When in terrain following mode "above" means the over-the-terrain468current altitude is above the over-the-terrain alt of loc. It is469quite possible for current_loc to be "above" loc when it is at a470lower pressure altitude, if current_loc is in a low part of the471terrain472*/473bool Plane::above_location_current(const Location &loc)474{475#if AP_TERRAIN_AVAILABLE476float terrain_alt;477if (loc.terrain_alt &&478terrain.height_above_terrain(terrain_alt, true)) {479float loc_alt = loc.alt*0.01f;480if (!loc.relative_alt) {481loc_alt -= home.alt*0.01f;482}483return terrain_alt > loc_alt;484}485#endif486487float loc_alt_cm = loc.alt;488if (loc.relative_alt) {489loc_alt_cm += home.alt;490}491return current_loc.alt > loc_alt_cm;492}493494/*495modify a destination to be setup for terrain following if496TERRAIN_FOLLOW is enabled497*/498void Plane::setup_terrain_target_alt(Location &loc)499{500#if AP_TERRAIN_AVAILABLE501if (terrain_enabled_in_current_mode()) {502if (!loc.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN)) {503target_altitude.terrain_following_pending = true;504return;505}506}507target_altitude.terrain_following_pending = false;508#endif509}510511/*512return current_loc.alt adjusted for ALT_OFFSET513This is useful during long flights to account for barometer changes514from the GCS, or to adjust the flying height of a long mission515*/516int32_t Plane::adjusted_altitude_cm(void)517{518return current_loc.alt - (mission_alt_offset()*100);519}520521/*522return home-relative altitude adjusted for ALT_OFFSET. This is useful523during long flights to account for barometer changes from the GCS,524or to adjust the flying height of a long mission.525*/526int32_t Plane::adjusted_relative_altitude_cm(void)527{528return (relative_altitude - mission_alt_offset())*100;529}530531532/*533return the mission altitude offset. This raises or lowers all534mission items. It is primarily set using the ALT_OFFSET parameter,535but can also be adjusted by the rangefinder landing code for a536NAV_LAND command if we have aborted a steep landing537*/538float Plane::mission_alt_offset(void)539{540float ret = g.alt_offset;541if (control_mode == &mode_auto &&542(flight_stage == AP_FixedWing::FlightStage::LAND || auto_state.wp_is_land_approach)) {543// when landing after an aborted landing due to too high glide544// slope we use an offset from the last landing attempt545ret += landing.alt_offset;546}547return ret;548}549550/*551return the height in meters above the next_WP_loc altitude552*/553float Plane::height_above_target(void)554{555float target_alt = next_WP_loc.alt*0.01;556if (!next_WP_loc.relative_alt) {557target_alt -= ahrs.get_home().alt*0.01f;558}559560#if AP_TERRAIN_AVAILABLE561// also record the terrain altitude if possible562float terrain_altitude;563if (next_WP_loc.terrain_alt &&564terrain.height_above_terrain(terrain_altitude, true)) {565return terrain_altitude - target_alt;566}567#endif568569return (adjusted_altitude_cm()*0.01f - ahrs.get_home().alt*0.01f) - target_alt;570}571572/*573work out target altitude adjustment from terrain lookahead574*/575float Plane::lookahead_adjustment(void)576{577#if AP_TERRAIN_AVAILABLE578int32_t bearing_cd;579int16_t distance;580// work out distance and bearing to target581if (control_mode == &mode_fbwb) {582// there is no target waypoint in FBWB, so use yaw as an approximation583bearing_cd = ahrs.yaw_sensor;584distance = g.terrain_lookahead;585} else if (!reached_loiter_target()) {586bearing_cd = nav_controller->target_bearing_cd();587distance = constrain_float(auto_state.wp_distance, 0, g.terrain_lookahead);588} else {589// no lookahead when loitering590bearing_cd = 0;591distance = 0;592}593if (distance <= 0) {594// no lookahead595return 0;596}597598599float groundspeed = ahrs.groundspeed();600if (groundspeed < 1) {601// we're not moving602return 0;603}604// we need to know the climb ratio. We use 50% of the maximum605// climb rate so we are not constantly at 100% throttle and to606// give a bit more margin on terrain607float climb_ratio = 0.5f * TECS_controller.get_max_climbrate() / groundspeed;608609if (climb_ratio <= 0) {610// lookahead makes no sense for negative climb rates611return 0;612}613614// ask the terrain code for the lookahead altitude change615float lookahead = terrain.lookahead(bearing_cd*0.01f, distance, climb_ratio);616617if (target_altitude.offset_cm < 0) {618// we are heading down to the waypoint, so we don't need to619// climb as much620lookahead += target_altitude.offset_cm*0.01f;621}622623// constrain lookahead to a reasonable limit624return constrain_float(lookahead, 0, 1000.0f);625#else626return 0;627#endif628}629630631#if AP_RANGEFINDER_ENABLED632/*633correct target altitude using rangefinder data. Returns offset in634meters to correct target altitude. A positive number means we need635to ask the speed/height controller to fly higher636*/637float Plane::rangefinder_correction(void)638{639if (millis() - rangefinder_state.last_correction_time_ms > 5000) {640// we haven't had any rangefinder data for 5s - don't use it641return 0;642}643644// for now we only support the rangefinder for landing645bool using_rangefinder = (g.rangefinder_landing && flight_stage == AP_FixedWing::FlightStage::LAND);646if (!using_rangefinder) {647return 0;648}649650return rangefinder_state.correction;651}652653/*654correct rangefinder data for terrain height difference between655NAV_LAND point and current location656*/657void Plane::rangefinder_terrain_correction(float &height)658{659#if AP_TERRAIN_AVAILABLE660if (!g.rangefinder_landing ||661flight_stage != AP_FixedWing::FlightStage::LAND ||662!terrain_enabled_in_current_mode()) {663return;664}665float terrain_amsl1, terrain_amsl2;666if (!terrain.height_amsl(current_loc, terrain_amsl1) ||667!terrain.height_amsl(next_WP_loc, terrain_amsl2)) {668return;669}670float correction = (terrain_amsl1 - terrain_amsl2);671height += correction;672auto_state.terrain_correction = correction;673#endif674}675676/*677update the offset between rangefinder height and terrain height678*/679void Plane::rangefinder_height_update(void)680{681const auto orientation = rangefinder_orientation();682bool range_ok = rangefinder.status_orient(orientation) == RangeFinder::Status::Good;683float distance = rangefinder.distance_orient(orientation);684float corrected_distance = distance;685686/*687correct distance for attitude688*/689if (range_ok) {690// correct the range for attitude691const auto &dcm = ahrs.get_rotation_body_to_ned();692693Vector3f v{corrected_distance, 0, 0};694v.rotate(orientation);695v = dcm * v;696697if (!is_positive(v.z)) {698// not pointing at the ground699range_ok = false;700} else {701corrected_distance = v.z;702}703}704705if (range_ok && ahrs.home_is_set()) {706if (!rangefinder_state.have_initial_reading) {707rangefinder_state.have_initial_reading = true;708rangefinder_state.initial_range = distance;709}710rangefinder_state.height_estimate = corrected_distance;711712rangefinder_terrain_correction(rangefinder_state.height_estimate);713714// we consider ourselves to be fully in range when we have 10715// good samples (0.2s) that are different by 5% of the maximum716// range from the initial range we see. The 5% change is to717// catch Lidars that are giving a constant range, either due718// to misconfiguration or a faulty sensor719if (rangefinder_state.in_range_count < 10) {720if (!is_equal(distance, rangefinder_state.last_distance) &&721fabsf(rangefinder_state.initial_range - distance) > 0.05f * rangefinder.max_distance_cm_orient(rangefinder_orientation())*0.01f) {722rangefinder_state.in_range_count++;723}724if (fabsf(rangefinder_state.last_distance - distance) > rangefinder.max_distance_cm_orient(rangefinder_orientation())*0.01*0.2) {725// changes by more than 20% of full range will reset counter726rangefinder_state.in_range_count = 0;727}728} else {729rangefinder_state.in_range = true;730bool flightstage_good_for_rangefinder_landing = false;731if (flight_stage == AP_FixedWing::FlightStage::LAND) {732flightstage_good_for_rangefinder_landing = true;733}734#if HAL_QUADPLANE_ENABLED735if (control_mode == &mode_qland ||736control_mode == &mode_qrtl ||737(control_mode == &mode_auto && quadplane.is_vtol_land(plane.mission.get_current_nav_cmd().id))) {738flightstage_good_for_rangefinder_landing = true;739}740#endif741if (!rangefinder_state.in_use &&742flightstage_good_for_rangefinder_landing &&743g.rangefinder_landing) {744rangefinder_state.in_use = true;745gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder engaged at %.2fm", (double)rangefinder_state.height_estimate);746}747}748rangefinder_state.last_distance = distance;749} else {750rangefinder_state.in_range_count = 0;751rangefinder_state.in_range = false;752}753754if (rangefinder_state.in_range) {755// If not using terrain data, we expect zero correction when our height above target is equal to our rangefinder measurement756float correction = height_above_target() - rangefinder_state.height_estimate;757758#if AP_TERRAIN_AVAILABLE759// if we are terrain following then correction is based on terrain data760float terrain_altitude;761if ((target_altitude.terrain_following || terrain_enabled_in_current_mode()) &&762terrain.height_above_terrain(terrain_altitude, true)) {763correction = terrain_altitude - rangefinder_state.height_estimate;764}765#endif766767// remember the last correction. Use a low pass filter unless768// the old data is more than 5 seconds old769uint32_t now = millis();770if (now - rangefinder_state.last_correction_time_ms > 5000) {771rangefinder_state.correction = correction;772rangefinder_state.initial_correction = correction;773if (g.rangefinder_landing) {774landing.set_initial_slope();775}776rangefinder_state.last_correction_time_ms = now;777} else {778rangefinder_state.correction = 0.8f*rangefinder_state.correction + 0.2f*correction;779rangefinder_state.last_correction_time_ms = now;780if (fabsf(rangefinder_state.correction - rangefinder_state.initial_correction) > 30) {781// the correction has changed by more than 30m, reset use of Lidar. We may have a bad lidar782if (rangefinder_state.in_use) {783gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder disengaged at %.2fm", (double)rangefinder_state.height_estimate);784}785memset(&rangefinder_state, 0, sizeof(rangefinder_state));786}787}788789}790}791#endif // AP_RANGEFINDER_ENABLED792793/*794determine if Non Auto Terrain Disable is active and allowed in present control mode795*/796bool Plane::terrain_disabled()797{798return control_mode->allows_terrain_disable() && non_auto_terrain_disable;799}800801802/*803Check if terrain following is enabled for the current mode804*/805#if AP_TERRAIN_AVAILABLE806const Plane::TerrainLookupTable Plane::Terrain_lookup[] = {807{Mode::Number::FLY_BY_WIRE_B, terrain_bitmask::FLY_BY_WIRE_B},808{Mode::Number::CRUISE, terrain_bitmask::CRUISE},809{Mode::Number::AUTO, terrain_bitmask::AUTO},810{Mode::Number::RTL, terrain_bitmask::RTL},811{Mode::Number::AVOID_ADSB, terrain_bitmask::AVOID_ADSB},812{Mode::Number::GUIDED, terrain_bitmask::GUIDED},813{Mode::Number::LOITER, terrain_bitmask::LOITER},814{Mode::Number::CIRCLE, terrain_bitmask::CIRCLE},815#if HAL_QUADPLANE_ENABLED816{Mode::Number::QRTL, terrain_bitmask::QRTL},817{Mode::Number::QLAND, terrain_bitmask::QLAND},818{Mode::Number::QLOITER, terrain_bitmask::QLOITER},819#endif820};821822bool Plane::terrain_enabled_in_current_mode() const823{824return terrain_enabled_in_mode(control_mode->mode_number());825}826827bool Plane::terrain_enabled_in_mode(Mode::Number num) const828{829// Global enable830if ((g.terrain_follow.get() & int32_t(terrain_bitmask::ALL)) != 0) {831return true;832}833834// Specific enable835for (const struct TerrainLookupTable entry : Terrain_lookup) {836if (entry.mode_num == num) {837if ((g.terrain_follow.get() & int32_t(entry.bitmask)) != 0) {838return true;839}840break;841}842}843844return false;845}846#endif847848#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED849/*850handle a MAV_CMD_SET_HAGL request. The accuracy is ignored851*/852void Plane::handle_external_hagl(const mavlink_command_int_t &packet)853{854auto &hagl = plane.external_hagl;855hagl.hagl = packet.param1;856hagl.last_update_ms = AP_HAL::millis();857hagl.timeout_ms = uint32_t(packet.param3 * 1000);858}859860/*861get HAGL from external source if current862*/863bool Plane::get_external_HAGL(float &height_agl)864{865auto &hagl = plane.external_hagl;866if (hagl.last_update_ms != 0) {867const uint32_t now_ms = AP_HAL::millis();868if (now_ms - hagl.last_update_ms <= hagl.timeout_ms) {869height_agl = hagl.hagl;870return true;871}872hagl.last_update_ms = 0;873}874return false;875}876#endif // AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED877878/*879get height for landing. Set using_rangefinder to true if a rangefinder880or external HAGL source is active881*/882float Plane::get_landing_height(bool &rangefinder_active)883{884float height;885886#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED887// if external HAGL is active use that888if (get_external_HAGL(height)) {889// ensure no terrain correction is applied - that is the job890// of the external system if it is wanted891auto_state.terrain_correction = 0;892893// an external HAGL is considered to be a type of rangefinder894rangefinder_active = true;895return height;896}897#endif898899// get basic height above target900height = height_above_target();901rangefinder_active = false;902903#if AP_RANGEFINDER_ENABLED904// possibly correct with rangefinder905height -= rangefinder_correction();906rangefinder_active = g.rangefinder_landing && rangefinder_state.in_range;907#endif908909return height;910}911912913