mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: ensure we init z controller when inactive
this prevents us getting the AC_PosControl internal error, which is turning up as a common false positive.
This commit is contained in:
parent
608a9ce2d7
commit
b7d62d5609
@ -963,7 +963,7 @@ void QuadPlane::run_z_controller(void)
|
|||||||
// never run Z controller in tailsitter transtion
|
// never run Z controller in tailsitter transtion
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if ((now - last_pidz_active_ms) > 20) {
|
if ((now - last_pidz_active_ms) > 20 || !pos_control->is_active_z()) {
|
||||||
// set vertical speed and acceleration limits
|
// set vertical speed and acceleration limits
|
||||||
pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_velocity_z_max_up, pilot_accel_z);
|
pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_velocity_z_max_up, pilot_accel_z);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user