mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-12 19:03:58 -04:00
AC_PosControl: reincarnate dead block of code
This commit is contained in:
parent
d6c48e422a
commit
9ebd0e9960
@ -303,7 +303,6 @@ void AC_PosControl::rate_to_accel_z()
|
|||||||
// reset last velocity target to current target
|
// reset last velocity target to current target
|
||||||
if (_flags.reset_rate_to_accel_z) {
|
if (_flags.reset_rate_to_accel_z) {
|
||||||
_vel_last.z = _vel_target.z;
|
_vel_last.z = _vel_target.z;
|
||||||
_flags.reset_rate_to_accel_z = false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// feed forward desired acceleration calculation
|
// feed forward desired acceleration calculation
|
||||||
|
Loading…
Reference in New Issue
Block a user