Browse Source

AC_PosControl: fixed leash length calc for descent speed

mission-4.1.18
Holger Steinhaus 11 years ago committed by Randy Mackay
parent
commit
345115fddd
  1. 2
      libraries/AC_AttitudeControl/AC_PosControl.cpp

2
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -190,7 +190,7 @@ void AC_PosControl::calc_leash_length_z() @@ -190,7 +190,7 @@ void AC_PosControl::calc_leash_length_z()
{
if (_flags.recalc_leash_z) {
_leash_up_z = calc_leash_length(_speed_up_cms, _accel_z_cms, _p_alt_pos.kP());
_leash_down_z = calc_leash_length(_speed_down_cms, _accel_z_cms, _p_alt_pos.kP());
_leash_down_z = calc_leash_length(-_speed_down_cms, _accel_z_cms, _p_alt_pos.kP());
_flags.recalc_leash_z = false;
}
}

Loading…
Cancel
Save