Browse Source

AC_PosControl: smooth take-off with accel PID's I term

This avoids an instantaneous jump in throttle during take-off by loading
the accel PID's I term with the expected change in throttle level
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
1362bdc338
  1. 9
      libraries/AC_AttitudeControl/AC_PosControl.cpp

9
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -195,10 +195,11 @@ void AC_PosControl::init_takeoff()
_pos_target.z = curr_pos.z + POSCONTROL_TAKEOFF_JUMP_CM; _pos_target.z = curr_pos.z + POSCONTROL_TAKEOFF_JUMP_CM;
// clear i term from acceleration controller // freeze feedforward to avoid jump
if (_pid_alt_accel.get_integrator() < 0) { freeze_ff_z();
_pid_alt_accel.reset_I();
} // shift difference between last motor out and hover throttle into accelerometer I
_pid_alt_accel.set_integrator(_motors.get_throttle_out()-_throttle_hover);
} }
// is_active_z - returns true if the z-axis position controller has been run very recently // is_active_z - returns true if the z-axis position controller has been run very recently

Loading…
Cancel
Save