Browse Source

Copter: mode_land sends dt to sqrt controller

master
Leonard Hall 7 years ago committed by Randy Mackay
parent
commit
48d0ad26a6
  1. 2
      ArduCopter/mode_land.cpp

2
ArduCopter/mode_land.cpp

@ -184,7 +184,7 @@ void Copter::land_run_vertical_control(bool pause_descent) @@ -184,7 +184,7 @@ void Copter::land_run_vertical_control(bool pause_descent)
max_land_descent_velocity = MIN(max_land_descent_velocity, -abs(g.land_speed));
// Compute a vertical velocity demand such that the vehicle approaches LAND_START_ALT. Without the below constraint, this would cause the vehicle to hover at LAND_START_ALT.
cmb_rate = AC_AttitudeControl::sqrt_controller(LAND_START_ALT-alt_above_ground, g.p_alt_hold.kP(), pos_control->get_accel_z());
cmb_rate = AC_AttitudeControl::sqrt_controller(LAND_START_ALT-alt_above_ground, g.p_alt_hold.kP(), pos_control->get_accel_z(), G_Dt);
// Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed.
cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed));

Loading…
Cancel
Save