From 2b4772269d42e21fa939a8c1bd3c52a50b896d99 Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Thu, 11 Jun 2020 09:15:56 -0600 Subject: [PATCH] Plane: tiltrotors: allow vectored yaw motor tilt when disarmed add disarm tilt delay add arming delay add Q_OPTIONS for disarmed motor tilt and delayed arming add comment explaining arming delay option eliminate millis() wrap in arming delay --- ArduPlane/AP_Arming.cpp | 1 + ArduPlane/quadplane.cpp | 21 +++++++++++++++++++-- ArduPlane/quadplane.h | 8 +++++++- ArduPlane/tiltrotor.cpp | 19 ++++++++++++++++++- 4 files changed, 45 insertions(+), 4 deletions(-) diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index c849f1584b..4a528b9735 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -187,6 +187,7 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c } change_arm_state(); + plane.quadplane.delay_arming = true; gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed"); diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index bb73cc09ca..c39e6b0e04 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -329,7 +329,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: OPTIONS // @DisplayName: quadplane options // @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight, and the vehicle will not use the vertical lift motors to climb during the transition. If AllowFWTakeoff bit is not set then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand bit is not set then fixed wing land on quadplanes will instead perform a VTOL land. If respect takeoff frame is not set the vehicle will interpret all takeoff waypoints as an altitude above the current position. When Use QRTL is set it will replace QLAND with QRTL for failsafe actions when in VTOL modes. When AIRMODE is set AirMode is automatically enabled if arming by RC channel. - // @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings,5:Use QRTL instead of QLAND for failsafe when in VTOL modes,6:Use idle governor in MANUAL,7:QAssist force enabled,8:Tailsitter QAssist motors only,9:enable AirMode if arming by aux switch + // @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings,5:Use QRTL instead of QLAND for failsafe when in VTOL modes,6:Use idle governor in MANUAL,7:QAssist force enabled,8:Tailsitter QAssist motors only,9:enable AirMode if arming by aux switch,10:Enable motor tilt when disarmed,11:Delay spoolup for 2 seconds after arming AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0), AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2), @@ -483,7 +483,6 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Range: 0.1 1 // @User: Standard AP_GROUPINFO("TAILSIT_GSCMIN", 18, QuadPlane, tailsitter.gain_scaling_min, 0.4), - // @Param: ASSIST_DELAY // @DisplayName: Quadplane assistance delay // @Description: This is delay between the assistance thresholds being met and the assistance starting. @@ -2006,6 +2005,24 @@ void QuadPlane::motors_output(bool run_rate_controller) attitude_control->rate_controller_run(); } + /* Delay for ARMING_DELAY_MS after arming before allowing props to spin: + 1) for safety (OPTION_DELAY_ARMING) + 2) to allow motors to return to vertical (OPTION_DISARMED_TILT) + */ + if ((options & OPTION_DISARMED_TILT) || (options & OPTION_DELAY_ARMING)) { + constexpr uint32_t ARMING_DELAY_MS = 2000; + if (delay_arming) { + if (AP_HAL::millis() - hal.util->get_last_armed_change() < ARMING_DELAY_MS) { + // delay motor start after arming + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); + motors->output(); + return; + } else { + delay_arming = false; + } + } + } + #if ADVANCED_FAILSAFE == ENABLED if (!hal.util->get_soft_armed() || (plane.afs.should_crash_vehicle() && !plane.afs.terminating_vehicle_via_landing()) || diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index c1545f96b1..e2ed416cb0 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -195,7 +195,7 @@ private: // air mode state: OFF, ON AirMode air_mode; - // check for quadplane assistance needed + // check for quadplane assistance needed bool assistance_needed(float aspeed, bool have_airspeed); // check if it is safe to provide assistance @@ -564,6 +564,8 @@ private: OPTION_Q_ASSIST_FORCE_ENABLE=(1<<7), OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY=(1<<8), OPTION_AIRMODE=(1<<9), + OPTION_DISARMED_TILT=(1<<10), + OPTION_DELAY_ARMING=(1<<11), }; AP_Float takeoff_failure_scalar; @@ -573,6 +575,10 @@ private: float last_land_final_agl; + // oneshot with duration ARMING_DELAY_MS used by quadplane to delay spoolup after arming: + // ignored unless OPTION_DELAY_ARMING or OPTION_TILT_DISARMED is set + bool delay_arming; + /* return true if current mission item is a vtol takeoff */ diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index f2d1ce3a18..3732f3575e 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -374,7 +374,24 @@ void QuadPlane::tiltrotor_vectored_yaw(void) // calculate the basic tilt amount from current_tilt float base_output = zero_out + (tilt.current_tilt * (1 - zero_out)); - + + // for testing when disarmed, apply vectored yaw in proportion to rudder stick + // Wait TILT_DELAY_MS after disarming to allow props to spin down first. + constexpr uint32_t TILT_DELAY_MS = 3000; + uint32_t now = AP_HAL::millis(); + if (!hal.util->get_soft_armed() && (plane.quadplane.options & OPTION_DISARMED_TILT)) { + // this test is subject to wrapping at ~49 days, but the consequences are insignificant + if ((now - hal.util->get_last_armed_change()) > TILT_DELAY_MS) { + float yaw_out = plane.channel_rudder->get_control_in(); + yaw_out /= plane.channel_rudder->get_range(); + float yaw_range = zero_out; + + SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, 1000 * (base_output + yaw_out * yaw_range)); + SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, 1000 * (base_output - yaw_out * yaw_range)); + } + return; + } + float tilt_threshold = (tilt.max_angle_deg/90.0f); bool no_yaw = (tilt.current_tilt > tilt_threshold); if (no_yaw) {