|
|
|
@ -330,6 +330,8 @@ public:
@@ -330,6 +330,8 @@ public:
|
|
|
|
|
// has_valid_input should be pure-virtual when Plane is converted
|
|
|
|
|
virtual bool has_valid_input() const { return false; }; |
|
|
|
|
|
|
|
|
|
virtual RC_Channel *get_arming_channel(void) const { return nullptr; }; |
|
|
|
|
|
|
|
|
|
bool gcs_overrides_enabled() const { return _gcs_overrides_enabled; } |
|
|
|
|
void set_gcs_overrides_enabled(bool enable) { |
|
|
|
|
_gcs_overrides_enabled = enable; |
|
|
|
@ -360,6 +362,14 @@ public:
@@ -360,6 +362,14 @@ public:
|
|
|
|
|
return _options & uint32_t(Option::LOG_DATA); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool arming_check_throttle() const { |
|
|
|
|
return _options & uint32_t(Option::ARMING_CHECK_THROTTLE); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool arming_skip_checks_rpy() const { |
|
|
|
|
return _options & uint32_t(Option::ARMING_SKIP_CHECK_RPY); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
float override_timeout_ms() const { |
|
|
|
|
return _override_timeout.get() * 1e3f; |
|
|
|
|
} |
|
|
|
@ -371,14 +381,18 @@ public:
@@ -371,14 +381,18 @@ public:
|
|
|
|
|
*/ |
|
|
|
|
bool get_pwm(uint8_t channel, uint16_t &pwm) const; |
|
|
|
|
|
|
|
|
|
uint32_t last_input_ms() const { return last_update_ms; }; |
|
|
|
|
|
|
|
|
|
protected: |
|
|
|
|
|
|
|
|
|
enum class Option { |
|
|
|
|
IGNORE_RECEIVER = (1 << 0), // RC receiver modules
|
|
|
|
|
IGNORE_OVERRIDES = (1 << 1), // MAVLink overrides
|
|
|
|
|
IGNORE_FAILSAFE = (1 << 2), // ignore RC failsafe bits
|
|
|
|
|
FPORT_PAD = (1 << 3), // pad fport telem output
|
|
|
|
|
LOG_DATA = (1 << 4), // log rc input bytes
|
|
|
|
|
IGNORE_RECEIVER = (1 << 0), // RC receiver modules
|
|
|
|
|
IGNORE_OVERRIDES = (1 << 1), // MAVLink overrides
|
|
|
|
|
IGNORE_FAILSAFE = (1 << 2), // ignore RC failsafe bits
|
|
|
|
|
FPORT_PAD = (1 << 3), // pad fport telem output
|
|
|
|
|
LOG_DATA = (1 << 4), // log rc input bytes
|
|
|
|
|
ARMING_CHECK_THROTTLE = (1 << 5), // run an arming check for neutral throttle
|
|
|
|
|
ARMING_SKIP_CHECK_RPY = (1 << 6), // skip the an arming checks for the roll/pitch/yaw channels
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
void new_override_received() { |
|
|
|
@ -390,6 +404,7 @@ private:
@@ -390,6 +404,7 @@ private:
|
|
|
|
|
// this static arrangement is to avoid static pointers in AP_Param tables
|
|
|
|
|
static RC_Channel *channels; |
|
|
|
|
|
|
|
|
|
uint32_t last_update_ms; |
|
|
|
|
bool has_new_overrides; |
|
|
|
|
|
|
|
|
|
AP_Float _override_timeout; |
|
|
|
|