Skip to content

Commit

Permalink
Relay
Browse files Browse the repository at this point in the history
  • Loading branch information
WickedShell committed Oct 23, 2023
1 parent 61d041c commit 5c6479b
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 2 deletions.
41 changes: 39 additions & 2 deletions libraries/AP_Relay/AP_Relay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,28 @@ void AP_Relay::init()
set(i, (bool)default_state);
}
}

for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) {
const int8_t pin = _params[instance].pin;
if (pin == -1) {
// no valid pin to set it on, skip it
continue;
}

const AP_Relay_Params::Function function = _params[instance].function;
if (function <= AP_Relay_Params::Function::relay || function >= AP_Relay_Params::Function::num_functions) {
// invalid function, skip it
continue;
}

// all functions are interpreted to be off at power on, so if we tag our pins to the wrong
// state that will trigger the first call to output to update the state, and will get the
// pins into the correct state.
//
// This will need to be made aware of pin inversion when that support is added
_pin_states = _pin_states | (1U<<instance);
}

}

void AP_Relay::set(const AP_Relay_Params::Function function, const bool value) {
Expand All @@ -186,6 +208,13 @@ void AP_Relay::set(const uint8_t instance, const bool value)
return;
}

if (!_relay_by_instance_has_been_asserted.get(instance)) {
// this is the first time this pin has been assigned make sure the tagged previous state was wrong
// so that update is guranteed to cause it to output
_pin_states = !value ? _pin_states | (1U<<instance) : _pin_states & ~(1U<<instance);
_relay_by_instance_has_been_asserted.set(instance);
}

_relay_by_instance.setonoff(instance, value);
}

Expand Down Expand Up @@ -267,8 +296,16 @@ void AP_Relay::update()
continue;
}

const bool instance_numbered_relay = (function == AP_Relay_Params::Function::relay);
const bool value = instance_numbered_relay ? _relay_by_instance.get (instance) : _desired_state.get((uint16_t)function);
bool value;
if (function == AP_Relay_Params::Function::relay) {
if (_relay_by_instance_has_been_asserted.get(instance)) {
value = _relay_by_instance.get (instance);
} else {
continue; // still in the default no change state
}
} else {
value = _desired_state.get((uint16_t)function);
}
const uint8_t old_pin_states = _pin_states;
_pin_states = value ? _pin_states | (1U<<instance) : _pin_states & ~(1U<<instance);
if (old_pin_states != _pin_states) {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Relay/AP_Relay.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ class AP_Relay {
void convert_params();

Bitmask<AP_RELAY_NUM_RELAYS> _relay_by_instance;
Bitmask<AP_RELAY_NUM_RELAYS> _relay_by_instance_has_been_asserted;
Bitmask<(uint16_t)AP_Relay_Params::Function::num_functions> _desired_state;
};

Expand Down

0 comments on commit 5c6479b

Please sign in to comment.