RC_Channel: move RC bits in mavlink to common code

Plane's semantics change to be like Copter. Rover, Sub and Tracker will start reporting the bits
This commit is contained in:
Peter Barker 2024-02-07 15:14:27 +11:00 committed by Peter Barker
parent c23ba04638
commit 821cfcd6ac
2 changed files with 11 additions and 0 deletions

View File

@ -589,6 +589,12 @@ public:
bool get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos); bool get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos);
#endif #endif
// returns true if we've ever seen RC input, via overrides or via
// AP_RCProtocol
bool has_ever_seen_rc_input() const {
return _has_ever_seen_rc_input;
}
// get failsafe timeout in milliseconds // get failsafe timeout in milliseconds
uint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); } uint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); }
@ -614,6 +620,9 @@ private:
AP_Int32 _protocols; AP_Int32 _protocols;
AP_Float _fs_timeout; AP_Float _fs_timeout;
// set to true if we see overrides or other RC input
bool _has_ever_seen_rc_input;
RC_Channel *flight_mode_channel() const; RC_Channel *flight_mode_channel() const;
// Allow override by default at start // Allow override by default at start

View File

@ -78,6 +78,8 @@ bool RC_Channels::read_input(void)
return false; return false;
} }
_has_ever_seen_rc_input = true;
has_new_overrides = false; has_new_overrides = false;
last_update_ms = AP_HAL::millis(); last_update_ms = AP_HAL::millis();