mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
RC_Channel: rename in_rc_failsafe to has_valid_input
This commit is contained in:
parent
61c34ea98c
commit
747fc3814d
@ -303,7 +303,8 @@ public:
|
|||||||
void reset_mode_switch();
|
void reset_mode_switch();
|
||||||
virtual void read_mode_switch();
|
virtual void read_mode_switch();
|
||||||
|
|
||||||
virtual bool in_rc_failsafe() const = 0;
|
// has_valid_input should be pure-virtual when Plane is converted
|
||||||
|
virtual bool has_valid_input() const { return false; };
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static RC_Channels *_singleton;
|
static RC_Channels *_singleton;
|
||||||
|
@ -143,8 +143,8 @@ bool RC_Channels::receiver_bind(const int dsmMode)
|
|||||||
// read_aux_switches - checks aux switch positions and invokes configured actions
|
// read_aux_switches - checks aux switch positions and invokes configured actions
|
||||||
void RC_Channels::read_aux_all()
|
void RC_Channels::read_aux_all()
|
||||||
{
|
{
|
||||||
if (in_rc_failsafe()) {
|
if (!has_valid_input()) {
|
||||||
// exit immediately during radio failsafe
|
// exit immediately when no RC input
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -195,7 +195,8 @@ void RC_Channels::reset_mode_switch()
|
|||||||
|
|
||||||
void RC_Channels::read_mode_switch()
|
void RC_Channels::read_mode_switch()
|
||||||
{
|
{
|
||||||
if (in_rc_failsafe()) {
|
if (!has_valid_input()) {
|
||||||
|
// exit immediately when no RC input
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
RC_Channel *c = flight_mode_channel();
|
RC_Channel *c = flight_mode_channel();
|
||||||
|
Loading…
Reference in New Issue
Block a user