AP_Relay: param conversion from ICE, chute and camera
This commit is contained in:
parent
5a5ee0c44c
commit
abcbc66c5c
@ -15,6 +15,10 @@
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
#include <AP_ICEngine/AP_ICEngine.h>
|
||||
#include <AP_Parachute/AP_Parachute.h>
|
||||
#include <AP_Camera/AP_Camera.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#define RELAY1_PIN_DEFAULT 13
|
||||
|
||||
@ -113,12 +117,45 @@ AP_Relay::AP_Relay(void)
|
||||
|
||||
void AP_Relay::convert_params()
|
||||
{
|
||||
// PARAMETER_CONVERSION - Added: Dec-2023
|
||||
|
||||
// Before converting local params we must find any relays being used by index from external libs
|
||||
int8_t relay_index;
|
||||
|
||||
int8_t ice_relay = -1;
|
||||
#if AP_ICENGINE_ENABLED
|
||||
AP_ICEngine *ice = AP::ice();
|
||||
if (ice != nullptr && ice->get_legacy_ignition_relay_index(relay_index)) {
|
||||
ice_relay = relay_index;
|
||||
}
|
||||
#endif
|
||||
|
||||
int8_t chute_relay = -1;
|
||||
#if HAL_PARACHUTE_ENABLED
|
||||
AP_Parachute *parachute = AP::parachute();
|
||||
if (parachute != nullptr && parachute->get_legacy_relay_index(relay_index)) {
|
||||
chute_relay = relay_index;
|
||||
}
|
||||
#endif
|
||||
|
||||
int8_t cam_relay = -1;
|
||||
#if AP_CAMERA_ENABLED
|
||||
AP_Camera *camera = AP::camera();
|
||||
if ((camera != nullptr) && (camera->get_legacy_relay_index(relay_index))) {
|
||||
cam_relay = relay_index;
|
||||
}
|
||||
#endif
|
||||
|
||||
// Find old default param
|
||||
int8_t default_state = 0; // off was the old behaviour
|
||||
const bool have_default = AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &default_state);
|
||||
|
||||
// grab the old values if they were set
|
||||
for (uint8_t i = 0; i < MIN(AP_RELAY_NUM_RELAYS, 6); i++) {
|
||||
if (_params[i].function.configured()) {
|
||||
// Conversion already done, or user has configured manually
|
||||
continue;
|
||||
}
|
||||
|
||||
uint8_t param_index = i;
|
||||
if (i > 3) {
|
||||
@ -128,15 +165,34 @@ void AP_Relay::convert_params()
|
||||
|
||||
int8_t pin = 0;
|
||||
if (!_params[i].pin.configured() && AP_Param::get_param_by_index(this, param_index, AP_PARAM_INT8, &pin) && (pin >= 0)) {
|
||||
// if the pin isn't negative we can assume the user might have been using it, map it to the old school relay interface
|
||||
// Copy old pin parameter
|
||||
_params[i].pin.set_and_save(pin);
|
||||
}
|
||||
if (_params[i].pin < 0) {
|
||||
// Don't enable if pin is invalid
|
||||
continue;
|
||||
}
|
||||
// Valid pin, this is either due to the param conversion or default value
|
||||
|
||||
// Work out what function this relay should be
|
||||
if (i == chute_relay) {
|
||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::parachute));
|
||||
|
||||
} else if (i == ice_relay) {
|
||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::ignition));
|
||||
|
||||
} else if (i == cam_relay) {
|
||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::camera));
|
||||
|
||||
} else {
|
||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::relay));
|
||||
|
||||
if (have_default) {
|
||||
_params[i].default_state.set_and_save(default_state);
|
||||
}
|
||||
}
|
||||
|
||||
// Set the default state
|
||||
if (have_default) {
|
||||
_params[i].default_state.set_and_save(default_state);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -302,13 +358,12 @@ bool AP_Relay::enabled(uint8_t instance) const
|
||||
// see if the relay is enabled
|
||||
bool AP_Relay::enabled(AP_Relay_Params::Function function) const
|
||||
{
|
||||
bool valid = false;
|
||||
for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) {
|
||||
if ((_params[instance].function == function) && (_params[instance].pin != -1)) {
|
||||
valid = true;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return valid;
|
||||
return false;
|
||||
}
|
||||
|
||||
#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
|
||||
|
@ -5,7 +5,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
|
||||
// @Param: FUNCTION
|
||||
// @DisplayName: Relay function
|
||||
// @Description: The function the relay channel is mapped to.
|
||||
// @Values: 0:None,1:Relay,2:Ignition,3:Starter
|
||||
// @Values: 0:None,1:Relay,2:Ignition,3:Parachute,4:Camera
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
@ -15,7 +15,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
|
||||
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,62:BBBMini Pin P8.13,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("PIN", 2, AP_Relay_Params, pin, -1),
|
||||
|
||||
|
||||
// @Param: DEFAULT
|
||||
// @DisplayName: Relay default state
|
||||
// @Description: Should the relay default to on or off, this only applies to function Relay. All other uses will pick the appropriate default output state.
|
||||
|
@ -21,6 +21,9 @@ public:
|
||||
enum class Function : uint8_t {
|
||||
none = 0,
|
||||
relay = 1,
|
||||
ignition = 2,
|
||||
parachute = 3,
|
||||
camera = 4,
|
||||
num_functions // must be the last entry
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user