Skip to content

Commit

Permalink
Plane: added TKOFF_THR_MIN for quadplane SLT
Browse files Browse the repository at this point in the history
allows for higher min throttle to get past transition drag
  • Loading branch information
tridge committed Aug 14, 2024
1 parent 2ea522d commit add4a68
Show file tree
Hide file tree
Showing 6 changed files with 45 additions and 1 deletion.
24 changes: 24 additions & 0 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4064,6 +4064,21 @@ bool QuadPlane::in_transition(void) const
return available() && transition->active();
}

/*
return true if we are in a fwd transition for a SLT quadplane
and in an auto-throttle mode
*/
bool QuadPlane::in_slt_fwd_transition(void) const
{
if (!in_transition() || tiltrotor.enabled() || tailsitter.enabled()) {
return false;
}
if (!plane.control_mode->does_auto_throttle()) {
return false;
}
return transition->in_fwd_transition();
}

/*
calculate current stopping distance for a quadplane in fixed wing flight
*/
Expand Down Expand Up @@ -4554,6 +4569,15 @@ void SLT_Transition::set_last_fw_pitch()
last_fw_nav_pitch_cd = plane.nav_pitch_cd;
}

/*
return true if in a forward transition
*/
bool SLT_Transition::in_fwd_transition() const
{
return transition_state == TRANSITION_AIRSPEED_WAIT ||
transition_state == TRANSITION_TIMER;
}

void SLT_Transition::force_transition_complete() {
transition_state = TRANSITION_DONE;
in_forced_transition = false;
Expand Down
6 changes: 6 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,12 @@ class QuadPlane
*/
bool in_transition(void) const;

/*
return true if we are in a fwd transition for a SLT quadplane
and in an auto-throttle mode
*/
bool in_slt_fwd_transition(void) const;

bool handle_do_vtol_transition(enum MAV_VTOL_STATE state) const;

bool do_vtol_takeoff(const AP_Mission::Mission_Command& cmd);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -517,7 +517,7 @@ float Plane::apply_throttle_limits(float throttle_in)

const bool use_takeoff_throttle_max =
#if HAL_QUADPLANE_ENABLED
quadplane.in_transition() ||
quadplane.in_slt_fwd_transition() ||
#endif
(flight_stage == AP_FixedWing::FlightStage::TAKEOFF) ||
(flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING);
Expand Down
8 changes: 8 additions & 0 deletions ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1034,4 +1034,12 @@ bool Tailsitter_Transition::allow_weathervane()
return !tailsitter.in_vtol_transition() && (vtol_limit_start_ms == 0);
}

/*
return true if in a forward transition
*/
bool Tailsitter_Transition::in_fwd_transition() const
{
return transition_state == TRANSITION_ANGLE_WAIT_FW;
}

#endif // HAL_QUADPLANE_ENABLED
2 changes: 2 additions & 0 deletions ArduPlane/tailsitter.h
Original file line number Diff line number Diff line change
Expand Up @@ -189,6 +189,8 @@ friend class Tailsitter;

bool allow_weathervane() override;

bool in_fwd_transition() const override;

private:

enum {
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/transition.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ class Transition

virtual bool allow_stick_mixing() const { return true; }

virtual bool in_fwd_transition() const = 0;

protected:

// refences for convenience
Expand Down Expand Up @@ -101,6 +103,8 @@ class SLT_Transition : public Transition

void set_last_fw_pitch(void) override;

bool in_fwd_transition() const override;

protected:

enum {
Expand Down

0 comments on commit add4a68

Please sign in to comment.