mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl_Sub: do not reset accel_z integrator when relaxing
Doing so caused the ROV to dive and slowly go back to the altitude setpoint
This commit is contained in:
parent
341757b254
commit
678fd8de1d
|
@ -100,7 +100,6 @@ void AC_PosControl_Sub::relax_alt_hold_controllers()
|
|||
_accel_desired.z = 0.0f;
|
||||
_accel_last_z_cms = 0.0f;
|
||||
_flags.reset_rate_to_accel_z = true;
|
||||
_pid_accel_z.set_integrator(-_motors.get_throttle_hover() * 1000.0f);
|
||||
_accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
|
||||
_pid_accel_z.reset_filter();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue