mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Plane: quadplane: don't use is_active_z()
, becasue its wrong
This commit is contained in:
parent
fb1f6b57ad
commit
4848ac9166
@ -892,7 +892,7 @@ void QuadPlane::run_z_controller(void)
|
||||
// never run Z controller in tailsitter transtion
|
||||
return;
|
||||
}
|
||||
if (!pos_control->is_active_z()) {
|
||||
if ((now - last_pidz_active_ms) > 20) {
|
||||
// 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);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user