Path: blob/master/ArduCopter/baro_ground_effect.cpp
9451 views
#include "Copter.h"12void Copter::update_ground_effect_detector(void)3{4if(!g2.gndeffect_comp_enabled || !motors->armed()) {5// disarmed - disable ground effect and return6gndeffect_state.takeoff_expected = false;7gndeffect_state.touchdown_expected = false;8ahrs.set_takeoff_expected(gndeffect_state.takeoff_expected);9ahrs.set_touchdown_expected(gndeffect_state.touchdown_expected);10return;11}1213// variable initialization14uint32_t tnow_ms = millis();15float des_speed_ne_ms = 0.0f;16float des_climb_rate_ms = pos_control->get_vel_desired_U_ms();1718if (pos_control->NE_is_active()) {19des_speed_ne_ms = pos_control->get_vel_target_NED_ms().xy().length();20}2122// takeoff logic2324if (flightmode->mode_number() == Mode::Number::THROW) {25// throw mode never wants the takeoff expected EKF code26gndeffect_state.takeoff_expected = false;27} else if (motors->armed() && ap.land_complete) {28// if we are armed and haven't yet taken off then we expect an imminent takeoff29gndeffect_state.takeoff_expected = true;30}3132// get altitude estimate33float pos_d_m = 0;34UNUSED_RESULT(AP::ahrs().get_relative_position_D_origin_float(pos_d_m));3536// if we aren't taking off yet, reset the takeoff timer, altitude and complete flag37const bool throttle_up = flightmode->has_manual_throttle() && channel_throttle->get_control_in() > 0;38if (!throttle_up && ap.land_complete) {39gndeffect_state.takeoff_time_ms = tnow_ms;40gndeffect_state.takeoff_alt_m = -pos_d_m;41}4243// if we are in takeoff_expected and we meet the conditions for having taken off44// end the takeoff_expected state45if (gndeffect_state.takeoff_expected && (tnow_ms - gndeffect_state.takeoff_time_ms > 5000 || (-pos_d_m - gndeffect_state.takeoff_alt_m) > 0.50)) {46gndeffect_state.takeoff_expected = false;47}4849// landing logic50Vector3f angle_target_rad = attitude_control->get_att_target_euler_rad();51bool small_angle_request = cosf(angle_target_rad.x) * cosf(angle_target_rad.y) > cosf(radians(7.5f));52Vector3f vel_ned_ms;53bool xy_speed_low = AP::ahrs().get_velocity_NED(vel_ned_ms) && (vel_ned_ms.xy().length() < 1.25);54bool xy_speed_demand_low = pos_control->NE_is_active() && des_speed_ne_ms <= 1.25;55bool slow_horizontal = xy_speed_demand_low || (xy_speed_low && !pos_control->NE_is_active()) || (flightmode->mode_number() == Mode::Number::ALT_HOLD && small_angle_request);5657bool descent_demanded = pos_control->D_is_active() && des_climb_rate_ms < 0.0f;58bool slow_descent_demanded = descent_demanded && des_climb_rate_ms >= -1.00;59bool speed_low_d_ms = AP::ahrs().get_velocity_D(vel_ned_ms.z, vibration_check.high_vibes) && fabsf(vel_ned_ms.z) <= 0.6f;60bool slow_descent = (slow_descent_demanded || (speed_low_d_ms && descent_demanded));6162gndeffect_state.touchdown_expected = slow_horizontal && slow_descent;6364// Prepare the EKF for ground effect if either takeoff or touchdown is expected.65ahrs.set_takeoff_expected(gndeffect_state.takeoff_expected);66ahrs.set_touchdown_expected(gndeffect_state.touchdown_expected);67}6869// update ekf terrain height stable setting70// when set to true, this allows the EKF to stabilize the normally barometer based altitude using a rangefinder71// this is not related to terrain following72void Copter::update_ekf_terrain_height_stable()73{74// set to false if no position estimate75if (!position_ok() && !ekf_has_relative_position()) {76ahrs.set_terrain_hgt_stable(false);77return;78}7980// consider terrain height stable if vehicle is taking off or landing81ahrs.set_terrain_hgt_stable(flightmode->is_taking_off() || flightmode->is_landing());82}838485