#include "Plane.h"
void Plane::adjust_altitude_target()
{
control_mode->update_target_altitude();
}
void Plane::check_home_alt_change(void)
{
int32_t home_alt_cm = ahrs.get_home().alt;
if (home_alt_cm != auto_state.last_home_alt_cm && hal.util->get_soft_armed()) {
const int32_t alt_change_cm = home_alt_cm - auto_state.last_home_alt_cm;
fix_terrain_WP(next_WP_loc, __LINE__);
TECS_controller.offset_altitude(alt_change_cm * 0.01f);
}
auto_state.last_home_alt_cm = home_alt_cm;
}
void Plane::setup_alt_slope(void)
{
auto_state.wp_distance = current_loc.get_distance(next_WP_loc);
auto_state.wp_proportion = current_loc.line_path_proportion(prev_WP_loc, next_WP_loc);
TECS_controller.set_path_proportion(auto_state.wp_proportion);
update_flight_stage();
switch (control_mode->mode_number()) {
#if MODE_AUTOLAND_ENABLED
case Mode::Number::AUTOLAND:
#endif
case Mode::Number::RTL:
case Mode::Number::AVOID_ADSB:
case Mode::Number::GUIDED:
if (above_location_current(next_WP_loc)) {
set_offset_altitude_location(prev_WP_loc, next_WP_loc);
} else {
reset_offset_altitude();
}
break;
case Mode::Number::AUTO:
if (!above_location_current(next_WP_loc) && plane.flight_option_enabled(FlightOptions::IMMEDIATE_CLIMB_IN_AUTO)) {
reset_offset_altitude();
break;
}
set_offset_altitude_location(prev_WP_loc, next_WP_loc);
break;
default:
reset_offset_altitude();
break;
}
}
int32_t Plane::get_RTL_altitude_cm() const
{
if (g.RTL_altitude < 0) {
return current_loc.alt;
}
return g.RTL_altitude*100 + home.alt;
}
float Plane::relative_ground_altitude(enum RangeFinderUse use_rangefinder, bool use_terrain_if_available)
{
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
float height_AGL;
if (get_external_HAGL(height_AGL)) {
return height_AGL;
}
#endif
#if AP_RANGEFINDER_ENABLED
if (rangefinder_use(use_rangefinder) && rangefinder_state.in_range) {
return rangefinder_state.height_estimate;
}
#endif
#if HAL_QUADPLANE_ENABLED && AP_RANGEFINDER_ENABLED
if (rangefinder_use(use_rangefinder) && quadplane.in_vtol_land_final() &&
rangefinder.status_orient(rangefinder_orientation()) == RangeFinder::Status::OutOfRangeLow) {
return 0;
}
#endif
#if AP_TERRAIN_AVAILABLE
float altitude;
if (use_terrain_if_available &&
terrain.status() == AP_Terrain::TerrainStatusOK &&
terrain.height_above_terrain(altitude, true)) {
return altitude;
}
#endif
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_land_descent() &&
!quadplane.landing_with_fixed_wing_spiral_approach()) {
return height_above_target();
}
#endif
return relative_altitude;
}
bool Plane::rangefinder_use(enum RangeFinderUse use_rangefinder) const
{
const uint8_t use = uint8_t(g.rangefinder_landing.get());
if (use == uint8_t(RangeFinderUse::NONE)) {
return false;
}
if (use & uint8_t(RangeFinderUse::ALL)) {
return true;
}
return (use & uint8_t(use_rangefinder)) != 0;
}
float Plane::relative_ground_altitude(enum RangeFinderUse use_rangefinder)
{
#if AP_TERRAIN_AVAILABLE
return relative_ground_altitude(use_rangefinder, target_altitude.terrain_following);
#else
return relative_ground_altitude(use_rangefinder, false);
#endif
}
void Plane::set_target_altitude_current(void)
{
target_altitude.amsl_cm = current_loc.alt;
reset_offset_altitude();
#if AP_TERRAIN_AVAILABLE
float terrain_altitude;
if (terrain_enabled_in_current_mode() && terrain.height_above_terrain(terrain_altitude, true) && !terrain_disabled()) {
target_altitude.terrain_following = true;
target_altitude.terrain_alt_cm = terrain_altitude*100;
} else {
target_altitude.terrain_following = false;
}
#endif
}
void Plane::set_target_altitude_location(const Location &loc)
{
target_altitude.amsl_cm = loc.alt;
if (loc.relative_alt) {
target_altitude.amsl_cm += home.alt;
}
#if AP_TERRAIN_AVAILABLE
if (target_altitude.terrain_following_pending) {
setup_terrain_target_alt(next_WP_loc);
}
float height;
if (loc.terrain_alt && terrain.height_above_terrain(height, true)) {
target_altitude.terrain_following = true;
target_altitude.terrain_alt_cm = loc.alt;
} else {
target_altitude.terrain_following = false;
}
#endif
}
int32_t Plane::relative_target_altitude_cm(void)
{
#if AP_TERRAIN_AVAILABLE
float relative_home_height;
if (target_altitude.terrain_following &&
terrain.height_relative_home_equivalent(target_altitude.terrain_alt_cm*0.01f,
relative_home_height, true)) {
target_altitude.lookahead = lookahead_adjustment();
relative_home_height += target_altitude.lookahead;
#if AP_RANGEFINDER_ENABLED
relative_home_height += rangefinder_correction();
#endif
return relative_home_height*100;
}
#endif
int32_t relative_alt = target_altitude.amsl_cm - home.alt;
relative_alt += mission_alt_offset()*100;
#if AP_RANGEFINDER_ENABLED
relative_alt += rangefinder_correction() * 100;
#endif
return relative_alt;
}
void Plane::change_target_altitude(int32_t change_cm)
{
target_altitude.amsl_cm += change_cm;
#if AP_TERRAIN_AVAILABLE
if (target_altitude.terrain_following && !terrain_disabled()) {
target_altitude.terrain_alt_cm += change_cm;
}
#endif
}
void Plane::set_target_altitude_proportion(const Location &loc, float proportion)
{
set_target_altitude_location(loc);
if (target_altitude.offset_cm > 0 &&
(adjusted_relative_altitude_cm() <
(g2.waypoint_climb_slope_height_min * 100))) {
return;
}
proportion = constrain_float(proportion, 0.0f, 1.0f);
change_target_altitude(-target_altitude.offset_cm*proportion);
if (g.alt_slope_max_height > 0) {
if (target_altitude.offset_cm > 0 && calc_altitude_error_cm() < -100 * g.alt_slope_max_height) {
set_target_altitude_location(loc);
set_offset_altitude_location(current_loc, loc);
change_target_altitude(-target_altitude.offset_cm*proportion);
if (proportion > 0.0f)
target_altitude.offset_cm = ((float)target_altitude.offset_cm)/proportion;
}
}
}
#if AP_TERRAIN_AVAILABLE
bool Plane::set_target_altitude_proportion_terrain(void)
{
if (!next_WP_loc.terrain_alt ||
!next_WP_loc.relative_alt) {
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return false;
}
float prev_WP_height_terrain;
if (!plane.prev_WP_loc.get_alt_m(Location::AltFrame::ABOVE_TERRAIN,
prev_WP_height_terrain)) {
return false;
}
float next_WP_height_terrain;
if (!plane.next_WP_loc.get_alt_m(Location::AltFrame::ABOVE_TERRAIN,
next_WP_height_terrain)) {
return false;
}
Location loc = next_WP_loc;
const auto alt = linear_interpolate(prev_WP_height_terrain, next_WP_height_terrain,
plane.auto_state.wp_proportion, 0, 1);
loc.set_alt_m(alt, Location::AltFrame::ABOVE_TERRAIN);
set_target_altitude_location(loc);
return true;
}
#endif
void Plane::constrain_target_altitude_location(const Location &loc1, const Location &loc2)
{
if (loc1.alt > loc2.alt) {
target_altitude.amsl_cm = constrain_int32(target_altitude.amsl_cm, loc2.alt, loc1.alt);
} else {
target_altitude.amsl_cm = constrain_int32(target_altitude.amsl_cm, loc1.alt, loc2.alt);
}
}
int32_t Plane::calc_altitude_error_cm(void)
{
#if AP_TERRAIN_AVAILABLE
float terrain_height;
if (target_altitude.terrain_following &&
terrain.height_above_terrain(terrain_height, true)) {
return target_altitude.lookahead*100 + target_altitude.terrain_alt_cm - (terrain_height*100);
}
#endif
return target_altitude.amsl_cm - adjusted_altitude_cm();
}
void Plane::check_fbwb_altitude(void)
{
float max_alt_cm = 0.0;
float min_alt_cm = 0.0;
bool should_check_max = false;
bool should_check_min = false;
#if AP_FENCE_ENABLED
const uint8_t enabled_fences = plane.fence.get_enabled_fences();
if ((enabled_fences & AC_FENCE_TYPE_ALT_MIN) != 0) {
min_alt_cm = plane.fence.get_safe_alt_min_m()*100.0;
should_check_min = true;
}
if ((enabled_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
max_alt_cm = plane.fence.get_safe_alt_max_m()*100.0;
should_check_max = true;
}
#endif
if (g.cruise_alt_floor > 0) {
min_alt_cm = MAX(min_alt_cm, plane.g.cruise_alt_floor*100.0);
should_check_min = true;
}
if (!should_check_min && !should_check_max) {
return;
}
#if AP_TERRAIN_AVAILABLE
if (target_altitude.terrain_following) {
if (should_check_max) {
target_altitude.terrain_alt_cm = MIN(target_altitude.terrain_alt_cm, max_alt_cm);
}
if (should_check_min) {
target_altitude.terrain_alt_cm = MAX(target_altitude.terrain_alt_cm, min_alt_cm);
}
return;
}
#endif
if (should_check_max) {
target_altitude.amsl_cm = MIN(target_altitude.amsl_cm, home.alt + max_alt_cm);
}
if (should_check_min) {
target_altitude.amsl_cm = MAX(target_altitude.amsl_cm, home.alt + min_alt_cm);
}
}
void Plane::reset_offset_altitude(void)
{
target_altitude.offset_cm = 0;
}
void Plane::set_offset_altitude_location(const Location &start_loc, const Location &destination_loc)
{
ftype alt_difference_m = 0;
if (destination_loc.get_height_above(start_loc, alt_difference_m)) {
target_altitude.offset_cm = alt_difference_m * 100;
} else {
target_altitude.offset_cm = 0;
}
#if AP_TERRAIN_AVAILABLE
float height;
if (destination_loc.terrain_alt &&
target_altitude.terrain_following &&
terrain.height_above_terrain(height, true)) {
target_altitude.offset_cm = target_altitude.terrain_alt_cm - (height * 100);
}
#endif
if (flight_stage != AP_FixedWing::FlightStage::LAND) {
if (g.alt_slope_min <= 0 ||
labs(target_altitude.offset_cm)*0.01f < g.alt_slope_min) {
target_altitude.offset_cm = 0;
}
}
}
bool Plane::above_location_current(const Location &loc)
{
#if AP_TERRAIN_AVAILABLE
float terrain_alt;
if (loc.terrain_alt &&
terrain.height_above_terrain(terrain_alt, true)) {
float loc_alt = loc.alt*0.01f;
if (!loc.relative_alt) {
loc_alt -= home.alt*0.01f;
}
return terrain_alt > loc_alt;
}
#endif
float loc_alt_cm = loc.alt;
if (loc.relative_alt) {
loc_alt_cm += home.alt;
}
return current_loc.alt > loc_alt_cm;
}
void Plane::setup_terrain_target_alt(Location &loc)
{
#if AP_TERRAIN_AVAILABLE
if (terrain_enabled_in_current_mode()) {
if (!loc.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN)) {
target_altitude.terrain_following_pending = true;
return;
}
}
target_altitude.terrain_following_pending = false;
#endif
}
int32_t Plane::adjusted_altitude_cm(void)
{
return current_loc.alt - (mission_alt_offset()*100);
}
int32_t Plane::adjusted_relative_altitude_cm(void)
{
return (relative_altitude - mission_alt_offset())*100;
}
float Plane::mission_alt_offset(void)
{
float ret = g.alt_offset;
if (control_mode == &mode_auto &&
(flight_stage == AP_FixedWing::FlightStage::LAND || auto_state.wp_is_land_approach)) {
ret += landing.alt_offset;
}
return ret;
}
float Plane::height_above_target(void)
{
float target_alt = next_WP_loc.alt*0.01;
if (!next_WP_loc.relative_alt) {
target_alt -= ahrs.get_home().alt*0.01f;
}
#if AP_TERRAIN_AVAILABLE
float terrain_altitude;
if (next_WP_loc.terrain_alt &&
terrain.height_above_terrain(terrain_altitude, true)) {
return terrain_altitude - target_alt;
}
#endif
return (adjusted_altitude_cm()*0.01f - ahrs.get_home().alt*0.01f) - target_alt;
}
float Plane::lookahead_adjustment(void)
{
#if AP_TERRAIN_AVAILABLE
int32_t bearing_cd;
int16_t distance;
if (control_mode == &mode_fbwb) {
bearing_cd = ahrs.yaw_sensor;
distance = g.terrain_lookahead;
} else if (!reached_loiter_target()) {
bearing_cd = nav_controller->target_bearing_cd();
distance = constrain_float(auto_state.wp_distance, 0, g.terrain_lookahead);
} else {
bearing_cd = 0;
distance = 0;
}
if (distance <= 0) {
return 0;
}
float groundspeed = ahrs.groundspeed();
if (groundspeed < 1) {
return 0;
}
float climb_ratio = 0.5f * TECS_controller.get_max_climbrate() / groundspeed;
if (climb_ratio <= 0) {
return 0;
}
float lookahead = terrain.lookahead(bearing_cd*0.01f, distance, climb_ratio);
if (target_altitude.offset_cm < 0) {
lookahead += target_altitude.offset_cm*0.01f;
}
return constrain_float(lookahead, 0, 1000.0f);
#else
return 0;
#endif
}
#if AP_RANGEFINDER_ENABLED
float Plane::rangefinder_correction(void)
{
if (millis() - rangefinder_state.last_correction_time_ms > 5000) {
return 0;
}
bool using_rangefinder = (rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) && flight_stage == AP_FixedWing::FlightStage::LAND);
if (!using_rangefinder) {
return 0;
}
return rangefinder_state.correction;
}
void Plane::rangefinder_terrain_correction(float &height)
{
#if AP_TERRAIN_AVAILABLE
if (!rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) ||
flight_stage != AP_FixedWing::FlightStage::LAND ||
!terrain_enabled_in_current_mode()) {
return;
}
float terrain_amsl1, terrain_amsl2;
if (!terrain.height_amsl(current_loc, terrain_amsl1) ||
!terrain.height_amsl(next_WP_loc, terrain_amsl2)) {
return;
}
float correction = (terrain_amsl1 - terrain_amsl2);
height += correction;
auto_state.terrain_correction = correction;
#endif
}
void Plane::rangefinder_height_update(void)
{
const auto orientation = rangefinder_orientation();
bool range_ok = rangefinder.status_orient(orientation) == RangeFinder::Status::Good;
float distance = rangefinder.distance_orient(orientation);
float corrected_distance = distance;
if (range_ok) {
const auto &dcm = ahrs.get_rotation_body_to_ned();
Vector3f v{corrected_distance, 0, 0};
v.rotate(orientation);
v = dcm * v;
if (!is_positive(v.z)) {
range_ok = false;
} else {
corrected_distance = v.z;
}
}
if (range_ok && ahrs.home_is_set()) {
if (!rangefinder_state.have_initial_reading) {
rangefinder_state.have_initial_reading = true;
rangefinder_state.initial_range = distance;
}
rangefinder_state.height_estimate = corrected_distance;
rangefinder_terrain_correction(rangefinder_state.height_estimate);
if (rangefinder_state.in_range_count < 10) {
if (!is_equal(distance, rangefinder_state.last_distance) &&
fabsf(rangefinder_state.initial_range - distance) > 0.05f * rangefinder.max_distance_orient(rangefinder_orientation())) {
rangefinder_state.in_range_count++;
}
if (fabsf(rangefinder_state.last_distance - distance) > rangefinder.max_distance_orient(rangefinder_orientation())*0.2) {
rangefinder_state.in_range_count = 0;
}
} else {
rangefinder_state.in_range = true;
bool flightstage_good_for_rangefinder_landing = false;
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
flightstage_good_for_rangefinder_landing = true;
}
#if HAL_QUADPLANE_ENABLED
if (control_mode == &mode_qland ||
control_mode == &mode_qrtl ||
(control_mode == &mode_auto && quadplane.is_vtol_land(plane.mission.get_current_nav_cmd().id))) {
flightstage_good_for_rangefinder_landing = true;
}
#endif
if (!rangefinder_state.in_use &&
flightstage_good_for_rangefinder_landing &&
rangefinder_use(RangeFinderUse::TAKEOFF_LANDING)) {
rangefinder_state.in_use = true;
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder engaged at %.2fm", (double)rangefinder_state.height_estimate);
}
}
rangefinder_state.last_distance = distance;
} else {
rangefinder_state.in_range_count = 0;
rangefinder_state.in_range = false;
}
if (rangefinder_state.in_range) {
float correction = height_above_target() - rangefinder_state.height_estimate;
#if AP_TERRAIN_AVAILABLE
float terrain_altitude;
if ((target_altitude.terrain_following || terrain_enabled_in_current_mode()) &&
terrain.height_above_terrain(terrain_altitude, true)) {
correction = terrain_altitude - rangefinder_state.height_estimate;
}
#endif
uint32_t now = millis();
if (now - rangefinder_state.last_correction_time_ms > 5000) {
rangefinder_state.correction = correction;
rangefinder_state.initial_correction = correction;
if (rangefinder_use(RangeFinderUse::TAKEOFF_LANDING)) {
landing.set_initial_slope();
}
rangefinder_state.last_correction_time_ms = now;
} else {
rangefinder_state.correction = 0.8f*rangefinder_state.correction + 0.2f*correction;
rangefinder_state.last_correction_time_ms = now;
if (fabsf(rangefinder_state.correction - rangefinder_state.initial_correction) > 30) {
if (rangefinder_state.in_use) {
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder disengaged at %.2fm", (double)rangefinder_state.height_estimate);
}
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
}
}
}
}
#endif
bool Plane::terrain_disabled()
{
return control_mode->allows_terrain_disable() && non_auto_terrain_disable;
}
#if AP_TERRAIN_AVAILABLE
const Plane::TerrainLookupTable Plane::Terrain_lookup[] = {
{Mode::Number::FLY_BY_WIRE_B, terrain_bitmask::FLY_BY_WIRE_B},
{Mode::Number::CRUISE, terrain_bitmask::CRUISE},
{Mode::Number::AUTO, terrain_bitmask::AUTO},
{Mode::Number::RTL, terrain_bitmask::RTL},
{Mode::Number::AVOID_ADSB, terrain_bitmask::AVOID_ADSB},
{Mode::Number::GUIDED, terrain_bitmask::GUIDED},
{Mode::Number::LOITER, terrain_bitmask::LOITER},
{Mode::Number::CIRCLE, terrain_bitmask::CIRCLE},
#if HAL_QUADPLANE_ENABLED
{Mode::Number::QRTL, terrain_bitmask::QRTL},
{Mode::Number::QLAND, terrain_bitmask::QLAND},
{Mode::Number::QLOITER, terrain_bitmask::QLOITER},
#endif
#if MODE_AUTOLAND_ENABLED
{Mode::Number::AUTOLAND, terrain_bitmask::AUTOLAND},
#endif
};
bool Plane::terrain_enabled_in_current_mode() const
{
return terrain_enabled_in_mode(control_mode->mode_number());
}
bool Plane::terrain_enabled_in_mode(Mode::Number num) const
{
if ((g.terrain_follow.get() & int32_t(terrain_bitmask::ALL)) != 0) {
return true;
}
for (const struct TerrainLookupTable entry : Terrain_lookup) {
if (entry.mode_num == num) {
if ((g.terrain_follow.get() & int32_t(entry.bitmask)) != 0) {
return true;
}
break;
}
}
return false;
}
#endif
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
void Plane::handle_external_hagl(const mavlink_command_int_t &packet)
{
auto &hagl = plane.external_hagl;
hagl.hagl = packet.param1;
hagl.last_update_ms = AP_HAL::millis();
hagl.timeout_ms = uint32_t(packet.param3 * 1000);
}
bool Plane::get_external_HAGL(float &height_agl)
{
auto &hagl = plane.external_hagl;
if (hagl.last_update_ms != 0) {
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - hagl.last_update_ms <= hagl.timeout_ms) {
height_agl = hagl.hagl;
return true;
}
hagl.last_update_ms = 0;
}
return false;
}
#endif
float Plane::get_landing_height(bool &rangefinder_active)
{
float height;
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
if (get_external_HAGL(height)) {
auto_state.terrain_correction = 0;
rangefinder_active = true;
return height;
}
#endif
height = height_above_target();
rangefinder_active = false;
#if AP_RANGEFINDER_ENABLED
height -= rangefinder_correction();
rangefinder_active = rangefinder_use(RangeFinderUse::TAKEOFF_LANDING) && rangefinder_state.in_range;
#endif
return height;
}
void Plane::fix_terrain_WP(Location &loc, uint32_t linenum)
{
if (loc.terrain_alt && !loc.relative_alt) {
AP::internalerror().error(AP_InternalError::error_t::flow_of_control, linenum);
if (loc.alt - home.alt > -500) {
loc.alt -= home.alt;
}
loc.relative_alt = true;
}
}