mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_RCProtocol: added failsafe_active() API
This commit is contained in:
parent
e8115a99bc
commit
522173328c
@ -67,6 +67,13 @@ public:
|
||||
void process_handshake(uint32_t baudrate);
|
||||
void update(void);
|
||||
|
||||
bool failsafe_active() const {
|
||||
return _failsafe_active;
|
||||
}
|
||||
void set_failsafe_active(bool active) {
|
||||
_failsafe_active = active;
|
||||
}
|
||||
|
||||
void disable_for_pulses(enum rcprotocol_t protocol) {
|
||||
_disabled_for_pulses |= (1U<<(uint8_t)protocol);
|
||||
}
|
||||
@ -147,6 +154,7 @@ private:
|
||||
AP_RCProtocol_Backend *backend[NONE];
|
||||
bool _new_input;
|
||||
uint32_t _last_input_ms;
|
||||
bool _failsafe_active;
|
||||
bool _valid_serial_prot;
|
||||
|
||||
// optional additional uart
|
||||
|
@ -64,7 +64,11 @@ void AP_RCProtocol_Backend::add_input(uint8_t num_values, uint16_t *values, bool
|
||||
memcpy(_pwm_values, values, num_values*sizeof(uint16_t));
|
||||
_num_channels = num_values;
|
||||
rc_frame_count++;
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_iofirmware)
|
||||
frontend.set_failsafe_active(in_failsafe);
|
||||
#if APM_BUILD_TYPE(APM_BUILD_iofirmware)
|
||||
// failsafed is sorted out in AP_IOMCU.cpp
|
||||
in_failsafe = false;
|
||||
#else
|
||||
if (rc().ignore_rc_failsafe()) {
|
||||
in_failsafe = false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user