Plane: holdoff auto takeoff till rudder neutral

when arming with rudder we need to hold off the takeoff until the user
has released the rudder stick or we can yaw badly during the takeoff
This commit is contained in:
Andrew Tridgell 2023-01-16 16:46:22 +11:00
parent 7d12095deb
commit 99f997161a
4 changed files with 37 additions and 7 deletions

View File

@ -779,6 +779,9 @@ private:
// time that rudder arming has been running
uint32_t rudder_arm_timer;
// have we seen neutral rudder since arming with rudder?
bool seen_neutral_rudder;
#if HAL_QUADPLANE_ENABLED
// support for quadcopter-plane
QuadPlane quadplane{ahrs};

View File

@ -2930,12 +2930,33 @@ void QuadPlane::takeoff_controller(void)
return;
}
uint32_t now = AP_HAL::millis();
const auto spool_state = motors->get_desired_spool_state();
if (plane.control_mode == &plane.mode_guided && guided_takeoff
&& tiltrotor.enabled() && !tiltrotor.fully_up()) {
&& tiltrotor.enabled() && !tiltrotor.fully_up() &&
spool_state != AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
// waiting for motors to tilt up
takeoff_start_time_ms = now;
return;
}
// don't takeoff up until rudder is re-centered after rudder arming
if (plane.arming.last_arm_method() == AP_Arming::Method::RUDDER &&
(takeoff_last_run_ms == 0 ||
now - takeoff_last_run_ms < 1000) &&
!plane.seen_neutral_rudder &&
spool_state <= AP_Motors::DesiredSpoolState::GROUND_IDLE) {
// start motor spinning if not spinning already so user sees it is armed
set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
takeoff_start_time_ms = now;
if (now - rudder_takeoff_warn_ms > 3000) {
gcs().send_text(MAV_SEVERITY_WARNING, "takeoff wait rudder release");
rudder_takeoff_warn_ms = now;
}
return;
}
/*
for takeoff we use the position controller
*/
@ -2954,17 +2975,16 @@ void QuadPlane::takeoff_controller(void)
*/
bool no_navigation = false;
if (takeoff_navalt_min > 0) {
uint32_t now = AP_HAL::millis();
const float alt = plane.current_loc.alt*0.01;
if (takeoff_last_run_ms == 0 ||
now - takeoff_last_run_ms > 1000) {
takeoff_start_alt = alt;
}
takeoff_last_run_ms = now;
if (alt - takeoff_start_alt < takeoff_navalt_min) {
no_navigation = true;
}
}
takeoff_last_run_ms = now;
if (no_navigation) {
plane.nav_roll_cd = 0;

View File

@ -583,6 +583,7 @@ private:
AP_Float maximum_takeoff_airspeed;
uint32_t takeoff_start_time_ms;
uint32_t takeoff_time_limit_ms;
uint32_t rudder_takeoff_warn_ms;
float last_land_final_agl;

View File

@ -118,9 +118,14 @@ void Plane::init_rc_out_aux()
*/
void Plane::rudder_arm_disarm_check()
{
const int16_t rudder_in = channel_rudder->get_control_in();
if (rudder_in == 0) {
// remember if we've seen neutral rudder, used for VTOL auto-takeoff
seen_neutral_rudder = true;
}
if (!arming.is_armed()) {
// when not armed, full right rudder starts arming counter
if (channel_rudder->get_control_in() > 4000) {
if (rudder_in > 4000) {
uint32_t now = millis();
if (rudder_arm_timer == 0 ||
@ -133,6 +138,7 @@ void Plane::rudder_arm_disarm_check()
//time to arm!
arming.arm(AP_Arming::Method::RUDDER);
rudder_arm_timer = 0;
seen_neutral_rudder = false;
}
} else {
// not at full right rudder
@ -140,7 +146,7 @@ void Plane::rudder_arm_disarm_check()
}
} else {
// full left rudder starts disarming counter
if (channel_rudder->get_control_in() < -4000) {
if (rudder_in < -4000) {
uint32_t now = millis();
if (rudder_arm_timer == 0 ||