mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-08 22:53:57 -04:00
ArduPlane: fix flare rc switch action with flight option bit 10 active
This commit is contained in:
parent
1162d556c6
commit
5cafccd447
@ -190,11 +190,16 @@ float Plane::stabilize_pitch_get_pitch_out(float speed_scaler)
|
||||
if (control_mode == &mode_stabilize && channel_pitch->get_control_in() != 0) {
|
||||
disable_integrator = true;
|
||||
}
|
||||
/* force landing pitch if:
|
||||
- flare switch high
|
||||
- throttle stick at zero thrust
|
||||
- in fixed wing non auto-throttle mode
|
||||
*/
|
||||
if (!quadplane_in_transition &&
|
||||
!control_mode->is_vtol_mode() &&
|
||||
channel_throttle->in_trim_dz() &&
|
||||
!control_mode->does_auto_throttle() &&
|
||||
flare_mode == FlareMode::ENABLED_PITCH_TARGET) {
|
||||
flare_mode == FlareMode::ENABLED_PITCH_TARGET &&
|
||||
throttle_at_zero()) {
|
||||
demanded_pitch = landing.get_pitch_cd();
|
||||
}
|
||||
|
||||
|
@ -1201,6 +1201,7 @@ private:
|
||||
};
|
||||
|
||||
FlareMode flare_mode;
|
||||
bool throttle_at_zero(void) const;
|
||||
|
||||
// expo handling
|
||||
float roll_in_expo(bool use_dz) const;
|
||||
|
@ -419,3 +419,15 @@ float Plane::rudder_in_expo(bool use_dz) const
|
||||
{
|
||||
return channel_expo(channel_rudder, g2.man_expo_roll, use_dz);
|
||||
}
|
||||
|
||||
bool Plane::throttle_at_zero(void) const
|
||||
{
|
||||
/* true if throttle stick is at idle position...if throttle trim has been moved
|
||||
to center stick area in conjunction with sprung throttle, cannot use in_trim, must use rc_min
|
||||
*/
|
||||
if (((!(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM) && channel_throttle->in_trim_dz()) ||
|
||||
(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM && channel_throttle->within_min_dz()))) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -764,23 +764,25 @@ void Plane::servos_twin_engine_mix(void)
|
||||
void Plane::force_flare(void)
|
||||
{
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
if (quadplane.in_transition()) {
|
||||
if (quadplane.in_transition() && plane.arming.is_armed()) { //allows for ground checking of flare tilts
|
||||
return;
|
||||
}
|
||||
if (control_mode->is_vtol_mode()) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if (!control_mode->does_auto_throttle() && channel_throttle->in_trim_dz() && flare_mode != FlareMode::FLARE_DISABLED) {
|
||||
int32_t tilt = -SERVO_MAX; //this is tilts up for a normal tiltrotor
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
/* to be active must be:
|
||||
-manual throttle mode
|
||||
-in an enabled flare mode (RC switch active)
|
||||
-at zero thrust: in throttle trim dz except for sprung throttle option where trim is at hover stick
|
||||
*/
|
||||
if (!control_mode->does_auto_throttle() && flare_mode != FlareMode::FLARE_DISABLED && throttle_at_zero()) {
|
||||
int32_t tilt = -SERVO_MAX; //this is tilts up for a normal tiltrotor if at zero thrust throttle stick
|
||||
if (quadplane.tiltrotor.enabled() && (quadplane.tiltrotor.type == Tiltrotor::TILT_TYPE_BICOPTER)) {
|
||||
tilt = 0; // this is tilts up for a Bicopter
|
||||
}
|
||||
if (quadplane.tailsitter.enabled()) {
|
||||
tilt = SERVO_MAX; //this is tilts up for a tailsitter
|
||||
}
|
||||
#endif
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, tilt);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, tilt);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, tilt);
|
||||
@ -793,7 +795,8 @@ void Plane::force_flare(void)
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_min);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_min);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Set the flight control servos based on the current calculated values
|
||||
|
Loading…
Reference in New Issue
Block a user