Plane: check airspeed and active Z controll for hover learning

This commit is contained in:
Andrew Tridgell 2019-10-04 10:28:08 +10:00
parent 39182e70e4
commit db4ae9ff24
1 changed files with 10 additions and 3 deletions

View File

@ -475,7 +475,6 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = {
{ "Q_A_RAT_PIT_I", 0.25 }, { "Q_A_RAT_PIT_I", 0.25 },
{ "Q_A_RAT_PIT_FLTD", 10.0 }, { "Q_A_RAT_PIT_FLTD", 10.0 },
{ "Q_M_SPOOL_TIME", 0.25 }, { "Q_M_SPOOL_TIME", 0.25 },
{ "Q_M_HOVER_LEARN", 0 },
{ "Q_LOIT_ANG_MAX", 15.0 }, { "Q_LOIT_ANG_MAX", 15.0 },
{ "Q_LOIT_ACC_MAX", 250.0 }, { "Q_LOIT_ACC_MAX", 250.0 },
{ "Q_LOIT_BRK_ACCEL", 50.0 }, { "Q_LOIT_BRK_ACCEL", 50.0 },
@ -1825,12 +1824,20 @@ void QuadPlane::update_throttle_hover()
return; return;
} }
// don't update if Z controller not running
const uint32_t now = AP_HAL::millis();
if (now - last_pidz_active_ms > 20) {
return;
}
// get throttle output // get throttle output
float throttle = motors->get_throttle(); float throttle = motors->get_throttle();
// calc average throttle if we are in a level hover float aspeed;
// calc average throttle if we are in a level hover and low airspeed
if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z()) < 60 && if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z()) < 60 &&
labs(ahrs_view->roll_sensor) < 500 && labs(ahrs_view->pitch_sensor) < 500) { labs(ahrs_view->roll_sensor) < 500 && labs(ahrs_view->pitch_sensor) < 500 &&
ahrs.airspeed_estimate(&aspeed) && aspeed < plane.aparm.airspeed_min*0.3) {
// Can we set the time constant automatically // Can we set the time constant automatically
motors->update_throttle_hover(0.01f); motors->update_throttle_hover(0.01f);
} }