mirror of https://github.com/ArduPilot/ardupilot
AP_Relay: added relay output invert function
This commit is contained in:
parent
6f9967a8f7
commit
01b0e0c27c
|
@ -408,6 +408,10 @@ void AP_Relay::set_pin_by_instance(uint8_t instance, bool value)
|
|||
|
||||
const bool initial_value = get_pin(pin);
|
||||
|
||||
if (_params[instance].inverted > 0) {
|
||||
value = !value;
|
||||
}
|
||||
|
||||
if (initial_value != value) {
|
||||
set_pin(pin, value);
|
||||
#if HAL_LOGGING_ENABLED
|
||||
|
@ -496,6 +500,10 @@ bool AP_Relay::get(uint8_t instance) const
|
|||
return false;
|
||||
}
|
||||
|
||||
if (_params[instance].inverted > 0) {
|
||||
return !get_pin(_params[instance].pin.get());
|
||||
}
|
||||
|
||||
return get_pin(_params[instance].pin.get());
|
||||
}
|
||||
|
||||
|
|
|
@ -60,11 +60,18 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
|
|||
|
||||
// @Param: DEFAULT
|
||||
// @DisplayName: Relay default state
|
||||
// @Description: Should the relay default to on or off, this only applies to RELAYx_FUNC "Relay" (1). All other uses will pick the appropriate default output state from within the controlling function's parameters.
|
||||
// @Description: Should the relay default to on or off, this only applies to RELAYx_FUNC "Relay" (1). All other uses will pick the appropriate default output state from within the controlling function's parameters. Note that if INVERTED is set then the default is inverted.
|
||||
// @Values: 0: Off,1:On,2:NoChange
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("DEFAULT", 3, AP_Relay_Params, default_state, (float)DefaultState::OFF),
|
||||
|
||||
// @Param: INVERTED
|
||||
// @DisplayName: Relay invert output signal
|
||||
// @Description: Should the relay output signal be inverted. If enabled, relay on would be pin low and relay off would be pin high. NOTE: this impact's DEFAULT.
|
||||
// @Values: 0:Normal,1:Inverted
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("INVERTED", 4, AP_Relay_Params, inverted, false),
|
||||
|
||||
AP_GROUPEND
|
||||
|
||||
};
|
||||
|
|
|
@ -70,4 +70,5 @@ public:
|
|||
AP_Enum<FUNCTION> function; // relay function
|
||||
AP_Int16 pin; // gpio pin number
|
||||
AP_Enum<DefaultState> default_state; // default state
|
||||
AP_Int8 inverted; // inverted signal
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue