mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Parachute: move to new relay functions
This commit is contained in:
parent
8ab6f01942
commit
5a5ee0c44c
@ -142,7 +142,7 @@ void AP_Parachute::update()
|
|||||||
// set relay
|
// set relay
|
||||||
AP_Relay*_relay = AP::relay();
|
AP_Relay*_relay = AP::relay();
|
||||||
if (_relay != nullptr) {
|
if (_relay != nullptr) {
|
||||||
_relay->on(_release_type);
|
_relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, true);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@ -159,7 +159,7 @@ void AP_Parachute::update()
|
|||||||
// set relay back to zero volts
|
// set relay back to zero volts
|
||||||
AP_Relay*_relay = AP::relay();
|
AP_Relay*_relay = AP::relay();
|
||||||
if (_relay != nullptr) {
|
if (_relay != nullptr) {
|
||||||
_relay->off(_release_type);
|
_relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, false);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@ -218,8 +218,8 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const
|
|||||||
} else {
|
} else {
|
||||||
#if AP_RELAY_ENABLED
|
#if AP_RELAY_ENABLED
|
||||||
AP_Relay*_relay = AP::relay();
|
AP_Relay*_relay = AP::relay();
|
||||||
if (_relay == nullptr || !_relay->enabled(_release_type)) {
|
if (_relay == nullptr || !_relay->enabled(AP_Relay_Params::FUNCTION::PARACHUTE)) {
|
||||||
hal.util->snprintf(buffer, buflen, "Chute invalid relay %d", int(_release_type));
|
hal.util->snprintf(buffer, buflen, "Chute has no relay");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
@ -235,6 +235,19 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const
|
|||||||
return true;
|
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
|
// singleton instance
|
||||||
AP_Parachute *AP_Parachute::_singleton;
|
AP_Parachute *AP_Parachute::_singleton;
|
||||||
|
|
||||||
|
@ -85,7 +85,10 @@ public:
|
|||||||
|
|
||||||
// check settings are valid
|
// check settings are valid
|
||||||
bool arming_checks(size_t buflen, char *buffer) const;
|
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[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
// get singleton instance
|
// get singleton instance
|
||||||
|
Loading…
Reference in New Issue
Block a user