mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 10:13:57 -04:00
Plane: add midposition to flare RC option sw
This commit is contained in:
parent
6f92abea63
commit
cf055fd1e0
@ -124,8 +124,8 @@ void Plane::stabilize_pitch(float speed_scaler)
|
||||
disable_integrator = true;
|
||||
}
|
||||
|
||||
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_CD
|
||||
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && channel_throttle->in_trim_dz() && !auto_throttle_mode && flare_switch_active) {
|
||||
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_CD if flight option FORCE_FLARE_ATTITUDE is set
|
||||
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && channel_throttle->in_trim_dz() && !auto_throttle_mode && flare_mode == FlareMode::ENABLED_PITCH_TARGET) {
|
||||
demanded_pitch = landing.get_pitch_cd();
|
||||
}
|
||||
|
||||
|
@ -1129,7 +1129,13 @@ private:
|
||||
|
||||
CrowMode crow_mode = CrowMode::NORMAL;
|
||||
|
||||
bool flare_switch_active;
|
||||
enum class FlareMode {
|
||||
FLARE_DISABLED = 0,
|
||||
ENABLED_NO_PITCH_TARGET,
|
||||
ENABLED_PITCH_TARGET
|
||||
};
|
||||
|
||||
FlareMode flare_mode;
|
||||
|
||||
public:
|
||||
void failsafe_check(void);
|
||||
|
@ -121,14 +121,16 @@ void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag)
|
||||
{
|
||||
switch(ch_flag) {
|
||||
case AuxSwitchPos::HIGH:
|
||||
plane.flare_switch_active = true;
|
||||
plane.flare_mode = Plane::FlareMode::ENABLED_PITCH_TARGET;
|
||||
plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED);
|
||||
break;
|
||||
case AuxSwitchPos::MIDDLE:
|
||||
plane.flare_mode = Plane::FlareMode::ENABLED_NO_PITCH_TARGET;
|
||||
plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED);
|
||||
break;
|
||||
case AuxSwitchPos::LOW:
|
||||
plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED);
|
||||
plane.flare_switch_active = false;
|
||||
plane.flare_mode = Plane::FlareMode::FLARE_DISABLED;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -735,7 +735,7 @@ void Plane::servos_twin_engine_mix(void)
|
||||
*/
|
||||
void Plane::force_flare(void)
|
||||
{
|
||||
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && !auto_throttle_mode && channel_throttle->in_trim_dz() && flare_switch_active) {
|
||||
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && !auto_throttle_mode && channel_throttle->in_trim_dz() && flare_mode != FlareMode::FLARE_DISABLED) {
|
||||
int32_t tilt = -SERVO_MAX; //this is tilts up for a normal tiltrotor
|
||||
if (quadplane.tilt.tilt_type == QuadPlane::TILT_TYPE_BICOPTER) {
|
||||
tilt = 0; // this is tilts up for a Bicopter
|
||||
|
Loading…
Reference in New Issue
Block a user