Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: TKOFF_THR_MIN is applied to SLT transitions #27770

Merged
merged 4 commits into from
Aug 28, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,9 +204,9 @@ float Plane::stabilize_pitch_get_pitch_out()
#endif
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_DEG if flight option FORCE_FLARE_ATTITUDE is set
#if HAL_QUADPLANE_ENABLED
const bool quadplane_in_transition = quadplane.in_transition();
const bool quadplane_in_frwd_transition = quadplane.in_frwd_transition();
#else
const bool quadplane_in_transition = false;
const bool quadplane_in_frwd_transition = false;
#endif

int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
Expand All @@ -219,7 +219,7 @@ float Plane::stabilize_pitch_get_pitch_out()
- throttle stick at zero thrust
- in fixed wing non auto-throttle mode
*/
if (!quadplane_in_transition &&
if (!quadplane_in_frwd_transition &&
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is specifically aiming for TVBS landing, so not fwd transition

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we will need @Hwurzburg to have a look at how this is defined, and for what classes of aircraft

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

tilt rotor VTOLs landing conventionally as fixed wing....with switch active in pilot throttle controlled modes it will force tilts up at low throttle to clear props...at highest switch position it also sets pitch to flare pitch .....use it on all my tvbs for emergency fw landing when batts are low

@Hwurzburg the reason we ask is that we want to decide if the quadplane.in_transition() test needs to be replaced with a check for forward transition only.
Based on your description, I understand now that the !quadplane_in_transition check is meant to protect against the case where the pilot is currently commanding a forward transition while on low throttle. In this case we don't want to force the landing pitch.

@tridge, on second inspection, I see that there is an additional check here for !control_mode->is_vtol_mode(). When quadplane.is_back_transition()==true then tautologically is_vtol_mode()==true as well.
So adding a definition of and using is_back_transition() is superfluous.

I think we can simply replace in_transition() with in_frwd_transition() and spare us the definition of in_back_transition().

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just tested the feature. I loaded Convergence in RealFligth, and set long DO_AUX_FUNCTION 89 1. This is the flare switch.
Took off in QSTAB, then I transitioned to FBWA.
Every time I closed the throttle to zero, the front tilt servos would raise the motors vertically.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

great!

!control_mode->is_vtol_mode() &&
!control_mode->does_auto_throttle() &&
flare_mode == FlareMode::ENABLED_PITCH_TARGET &&
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Range: 0 100
// @Increment: 1
// @User: Standard
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60),
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),

// @Param: TKOFF_OPTIONS
// @DisplayName: Takeoff options
Expand Down
10 changes: 7 additions & 3 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -810,6 +810,10 @@ bool QuadPlane::setup(void)
pilot_speed_z_max_dn.convert_centi_parameter(AP_PARAM_INT16);
pilot_accel_z.convert_centi_parameter(AP_PARAM_INT16);

// Provisionally assign the SLT thrust type.
// It will be overwritten by tailsitter or tiltorotor setups.
thrust_type = ThrustType::SLT;

tailsitter.setup();

tiltrotor.setup();
Expand Down Expand Up @@ -3969,9 +3973,9 @@ bool QuadPlane::is_vtol_land(uint16_t id) const
/*
return true if we are in a transition to fwd flight from hover
*/
bool QuadPlane::in_transition(void) const
bool QuadPlane::in_frwd_transition(void) const
{
return available() && transition->active();
return available() && transition->active_frwd();
}

/*
Expand Down Expand Up @@ -4350,7 +4354,7 @@ bool SLT_Transition::allow_update_throttle_mix() const
return !(quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER));
}

bool SLT_Transition::active() const
bool SLT_Transition::active_frwd() const
{
return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER));
}
Expand Down
15 changes: 11 additions & 4 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,13 @@ class QuadPlane
void control_auto(void);
bool setup(void);

enum class ThrustType : uint8_t {
SLT=0, // Traditional quadplane, with a pusher motor and independent multicopter lift.
TAILSITTER,
TILTROTOR,
};
ThrustType get_thrust_type(void) {return thrust_type;}

void vtol_position_controller(void);
void setup_target_position(void);
void takeoff_controller(void);
Expand Down Expand Up @@ -103,10 +110,7 @@ class QuadPlane
// abort landing, only valid when in a VTOL landing descent
bool abort_landing(void);

/*
return true if we are in a transition to fwd flight from hover
*/
bool in_transition(void) const;
bool in_frwd_transition(void) const;

bool handle_do_vtol_transition(enum MAV_VTOL_STATE state) const;

Expand Down Expand Up @@ -198,6 +202,9 @@ class QuadPlane
AP_Enum<AP_Motors::motor_frame_class> frame_class;
AP_Enum<AP_Motors::motor_frame_type> frame_type;

// Types of different "quadplane" configurations.
ThrustType thrust_type;

// Initialise motors to allow passing it to tailsitter in its constructor
AP_MotorsMulticopter *motors = nullptr;
const struct AP_Param::GroupInfo *motors_var_info;
Expand Down
18 changes: 15 additions & 3 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
slewrate = g.takeoff_throttle_slewrate;
}
#if HAL_QUADPLANE_ENABLED
if (g.takeoff_throttle_slewrate != 0 && quadplane.in_transition()) {
if (g.takeoff_throttle_slewrate != 0 && quadplane.in_frwd_transition()) {
slewrate = g.takeoff_throttle_slewrate;
}
#endif
Expand Down Expand Up @@ -555,10 +555,22 @@ float Plane::apply_throttle_limits(float throttle_in)

// Handle throttle limits for transition conditions.
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_transition()) {
if (quadplane.in_frwd_transition()) {
if (aparm.takeoff_throttle_max != 0) {
max_throttle = aparm.takeoff_throttle_max.get();
}

// Apply minimum throttle limits only for SLT thrust types.
// The other types don't support it well.
if (quadplane.get_thrust_type() == QuadPlane::ThrustType::SLT
&& control_mode->does_auto_throttle()
) {
if (aparm.takeoff_throttle_min.get() != 0) {
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get());
} else {
min_throttle = MAX(min_throttle, aparm.throttle_cruise.get());
}
}
}
#endif

Expand Down Expand Up @@ -793,7 +805,7 @@ void Plane::servos_twin_engine_mix(void)
void Plane::force_flare(void)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_transition() && plane.arming.is_armed()) { //allows for ground checking of flare tilts
if (quadplane.in_frwd_transition() && plane.arming.is_armed()) { //allows for ground checking of flare tilts
return;
}
if (control_mode->is_vtol_mode()) {
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,8 @@ void Tailsitter::setup()
return;
}

quadplane.thrust_type = QuadPlane::ThrustType::TAILSITTER;

// Set tailsitter transition rate to match old calculation
if (!transition_rate_fw.configured()) {
transition_rate_fw.set_and_save(transition_angle_fw / (quadplane.transition_time_ms/2000.0f));
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/tailsitter.h
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ friend class Tailsitter;

uint8_t get_log_transition_state() const override { return static_cast<uint8_t>(transition_state); }

bool active() const override { return transition_state != TRANSITION_DONE; }
bool active_frwd() const override { return transition_state == TRANSITION_ANGLE_WAIT_FW; }

bool show_vtol_view() const override;

Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,8 @@ void Tiltrotor::setup()
return;
}

quadplane.thrust_type = QuadPlane::ThrustType::TILTROTOR;

_is_vectored = tilt_mask != 0 && type == TILT_TYPE_VECTORED_YAW;

// true if a fixed forward motor is configured, either throttle, throttle left or throttle right.
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/transition.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class Transition

virtual uint8_t get_log_transition_state() const = 0;

virtual bool active() const = 0;
virtual bool active_frwd() const = 0;

virtual bool show_vtol_view() const = 0;

Expand Down Expand Up @@ -85,7 +85,7 @@ class SLT_Transition : public Transition

uint8_t get_log_transition_state() const override { return static_cast<uint8_t>(transition_state); }

bool active() const override;
bool active_frwd() const override;

bool show_vtol_view() const override;

Expand Down
24 changes: 24 additions & 0 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1560,6 +1560,29 @@ def mavlink_MAV_CMD_DO_VTOL_TRANSITION(self):

self.fly_home_land_and_disarm()

def TransitionMinThrottle(self):
'''Ensure that TKOFF_THR_MIN is applied during the forward transition'''
wps = self.create_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
])
self.check_mission_upload_download(wps)
self.set_parameter('TKOFF_THR_MIN', 80)

self.change_mode('AUTO')
self.wait_ready_to_arm()

self.arm_vehicle()
self.wait_current_waypoint(2)
# Wait for 5 seconds into the transition.
self.delay_sim_time(5)
# Ensure TKOFF_THR_MIN is still respected.
thr_min = self.get_parameter('TKOFF_THR_MIN')
self.wait_servo_channel_value(3, 1000+thr_min*10, comparator=operator.eq)

self.fly_home_land_and_disarm()

def MAV_CMD_NAV_TAKEOFF(self):
'''test issuing takeoff command via mavlink'''
self.change_mode('GUIDED')
Expand Down Expand Up @@ -1815,6 +1838,7 @@ def tests(self):
self.RCDisableAirspeedUse,
self.mission_MAV_CMD_DO_VTOL_TRANSITION,
self.mavlink_MAV_CMD_DO_VTOL_TRANSITION,
self.TransitionMinThrottle,
self.MAV_CMD_NAV_TAKEOFF,
self.Q_GUIDED_MODE,
self.DCMClimbRate,
Expand Down
Loading