FlightModeManager: fix integral reset on ground

This information could also be used for yaw and integral
resets of the lower level controllers.
This commit is contained in:
Matthias Grob 2020-10-24 17:27:07 +02:00 committed by Daniel Agar
parent 7de288877a
commit fafbb687d8
3 changed files with 6 additions and 1 deletions

View File

@ -11,4 +11,5 @@ float32 tilt # in radians [0, PI]
float32 min_distance_to_ground # in meters
float32 max_distance_to_ground # in meters
bool want_takeoff # tell the controller to initiate takeoff when idling (ignored during flight)
bool reset_integral # tells controller to reset integrators e.g. since we know the vehicle is not in air
float32 minimum_thrust # tell controller what the minimum collective output thrust should be

View File

@ -454,7 +454,7 @@ void FlightModeManager::generateTrajectorySetpoint(const float dt,
// set yaw-sp to current yaw
setpoint.yawspeed = 0.f;
// prevent any integrator windup
// _control.resetIntegral(); TODO
constraints.reset_integral = true;
}
_trajectory_setpoint_pub.publish(setpoint);

View File

@ -254,6 +254,10 @@ void MulticopterPositionControl::Run()
_control.setConstraints(constraints);
_control.setThrustLimits(constraints.minimum_thrust, _param_mpc_thr_max.get());
if (constraints.reset_integral) {
_control.resetIntegral();
}
// Run position control
if (_control.update(dt)) {
_failsafe_land_hysteresis.set_state_and_update(false, time_stamp_now);