From 5a5ee0c44c41ac1acbde18662281a1bbb9b6ab0f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 04:36:47 +0000 Subject: [PATCH] AP_Parachute: move to new relay functions --- libraries/AP_Parachute/AP_Parachute.cpp | 21 +++++++++++++++++---- libraries/AP_Parachute/AP_Parachute.h | 5 ++++- 2 files changed, 21 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 9b4075dc71..6ed1618b19 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -142,7 +142,7 @@ void AP_Parachute::update() // set relay AP_Relay*_relay = AP::relay(); if (_relay != nullptr) { - _relay->on(_release_type); + _relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, true); } #endif } @@ -159,7 +159,7 @@ void AP_Parachute::update() // set relay back to zero volts AP_Relay*_relay = AP::relay(); if (_relay != nullptr) { - _relay->off(_release_type); + _relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, false); } #endif } @@ -218,8 +218,8 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const } else { #if AP_RELAY_ENABLED AP_Relay*_relay = AP::relay(); - if (_relay == nullptr || !_relay->enabled(_release_type)) { - hal.util->snprintf(buffer, buflen, "Chute invalid relay %d", int(_release_type)); + if (_relay == nullptr || !_relay->enabled(AP_Relay_Params::FUNCTION::PARACHUTE)) { + hal.util->snprintf(buffer, buflen, "Chute has no relay"); return false; } #else @@ -235,6 +235,19 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const return true; } +#if AP_RELAY_ENABLED +// Return the relay index that would be used for param conversion to relay functions +bool AP_Parachute::get_legacy_relay_index(int8_t &index) const +{ + // PARAMETER_CONVERSION - Added: Dec-2023 + if (!enabled() || (_release_type > AP_PARACHUTE_TRIGGER_TYPE_RELAY_3)) { + return false; + } + index = _release_type; + return true; +} +#endif + // singleton instance AP_Parachute *AP_Parachute::_singleton; diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index 7793a202d2..30005e7543 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -85,7 +85,10 @@ public: // check settings are valid bool arming_checks(size_t buflen, char *buffer) const; - + + // Return the relay index that would be used for param conversion to relay functions + bool get_legacy_relay_index(int8_t &index) const; + static const struct AP_Param::GroupInfo var_info[]; // get singleton instance