mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: Quadplane: never run Z controller in tailsiter VTOL transtion
This commit is contained in:
parent
9df753551e
commit
c215fa0745
@ -885,6 +885,10 @@ void QuadPlane::hold_stabilize(float throttle_in)
|
|||||||
void QuadPlane::run_z_controller(void)
|
void QuadPlane::run_z_controller(void)
|
||||||
{
|
{
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
|
if (tailsitter.in_vtol_transition(now)) {
|
||||||
|
// never run Z controller in tailsitter transtion
|
||||||
|
return;
|
||||||
|
}
|
||||||
if (!pos_control->is_active_z()) {
|
if (!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