Plane: use has_valid_input in place of checking throttle counter
This commit is contained in:
parent
850227ffdb
commit
b19bfba0ec
@ -107,9 +107,8 @@ void Plane::read_control_switch()
|
|||||||
// If we get this value we do not want to change modes.
|
// If we get this value we do not want to change modes.
|
||||||
if(switchPosition == 255) return;
|
if(switchPosition == 255) return;
|
||||||
|
|
||||||
if (failsafe.rc_failsafe || failsafe.throttle_counter > 0) {
|
if (!rc().has_valid_input()) {
|
||||||
// when we are in rc_failsafe mode then RC input is not
|
// ignore the mode switch channel if there is no valid RC input
|
||||||
// working, and we need to ignore the mode switch channel
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1224,7 +1224,8 @@ float QuadPlane::get_desired_yaw_rate_cds(bool should_weathervane)
|
|||||||
// get pilot desired climb rate in cm/s
|
// get pilot desired climb rate in cm/s
|
||||||
float QuadPlane::get_pilot_desired_climb_rate_cms(void) const
|
float QuadPlane::get_pilot_desired_climb_rate_cms(void) const
|
||||||
{
|
{
|
||||||
if (plane.failsafe.rc_failsafe || plane.failsafe.throttle_counter > 0) {
|
if (!rc().has_valid_input()) {
|
||||||
|
// no valid input means no sensible pilot desired climb rate.
|
||||||
// descend at 0.5m/s for now
|
// descend at 0.5m/s for now
|
||||||
return -50;
|
return -50;
|
||||||
}
|
}
|
||||||
@ -1735,8 +1736,7 @@ void QuadPlane::update(void)
|
|||||||
// disable throttle_wait when throttle rises above 10%
|
// disable throttle_wait when throttle rises above 10%
|
||||||
if (throttle_wait &&
|
if (throttle_wait &&
|
||||||
(plane.get_throttle_input() > 10 ||
|
(plane.get_throttle_input() > 10 ||
|
||||||
plane.failsafe.rc_failsafe ||
|
!rc().has_valid_input())) {
|
||||||
plane.failsafe.throttle_counter>0)) {
|
|
||||||
throttle_wait = false;
|
throttle_wait = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -561,7 +561,7 @@ void Plane::set_servos_controlled(void)
|
|||||||
control_mode == &mode_fbwa ||
|
control_mode == &mode_fbwa ||
|
||||||
control_mode == &mode_autotune) {
|
control_mode == &mode_autotune) {
|
||||||
// a manual throttle mode
|
// a manual throttle mode
|
||||||
if (failsafe.throttle_counter) {
|
if (!rc().has_valid_input()) {
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
|
||||||
} else if (g.throttle_passthru_stabilize) {
|
} else if (g.throttle_passthru_stabilize) {
|
||||||
// manual pass through of throttle while in FBWA or
|
// manual pass through of throttle while in FBWA or
|
||||||
@ -615,7 +615,7 @@ void Plane::set_servos_flaps(void)
|
|||||||
int8_t manual_flap_percent = 0;
|
int8_t manual_flap_percent = 0;
|
||||||
|
|
||||||
// work out any manual flap input
|
// work out any manual flap input
|
||||||
if (channel_flap != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) {
|
if (channel_flap != nullptr && rc().has_valid_input()) {
|
||||||
manual_flap_percent = channel_flap->percent_input();
|
manual_flap_percent = channel_flap->percent_input();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user