mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
RC_Channel: Add option bit for arming checking the throttle input (opt-in)
Also adds interface to find out what channel is used for rudder arming
This commit is contained in:
parent
7ec0cb47a5
commit
2b9aa9bc21
@ -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:
|
||||
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:
|
||||
*/
|
||||
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:
|
||||
// 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;
|
||||
|
@ -74,6 +74,8 @@ bool RC_Channels::read_input(void)
|
||||
|
||||
has_new_overrides = false;
|
||||
|
||||
last_update_ms = AP_HAL::millis();
|
||||
|
||||
bool success = false;
|
||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
success |= channel(i)->update();
|
||||
|
@ -86,7 +86,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = {
|
||||
// @DisplayName: RC options
|
||||
// @Description: RC input options
|
||||
// @User: Advanced
|
||||
// @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe, 3:FPort Pad
|
||||
// @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yay sticks
|
||||
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
|
Loading…
Reference in New Issue
Block a user