mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: fixed transitions for tailsitters after auto-takeoff
need to use angle wait
This commit is contained in:
parent
f02db254b7
commit
b59bbdab8c
@ -1252,6 +1252,11 @@ void QuadPlane::update_transition(void)
|
|||||||
|
|
||||||
float aspeed;
|
float aspeed;
|
||||||
bool have_airspeed = ahrs.airspeed_estimate(&aspeed);
|
bool have_airspeed = ahrs.airspeed_estimate(&aspeed);
|
||||||
|
|
||||||
|
// tailsitters use angle wait, not airspeed wait
|
||||||
|
if (is_tailsitter() && transition_state == TRANSITION_AIRSPEED_WAIT) {
|
||||||
|
transition_state = TRANSITION_ANGLE_WAIT_FW;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
see if we should provide some assistance
|
see if we should provide some assistance
|
||||||
@ -2202,7 +2207,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
|
|||||||
if (plane.current_loc.alt < plane.next_WP_loc.alt) {
|
if (plane.current_loc.alt < plane.next_WP_loc.alt) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
transition_state = TRANSITION_AIRSPEED_WAIT;
|
transition_state = is_tailsitter() ? TRANSITION_ANGLE_WAIT_FW : TRANSITION_AIRSPEED_WAIT;
|
||||||
plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
|
plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
|
||||||
set_alt_target_current();
|
set_alt_target_current();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user