Skip to content

Commit

Permalink
AP_Relay: capitalize function and defualt enums
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Dec 12, 2023
1 parent 28a870c commit 03b0b2b
Show file tree
Hide file tree
Showing 4 changed files with 41 additions and 41 deletions.
40 changes: 20 additions & 20 deletions libraries/AP_Relay/AP_Relay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,28 +183,28 @@ void AP_Relay::convert_params()
}

// Work out what function this relay should be
AP_Relay_Params::Function new_fun;
AP_Relay_Params::FUNCTION new_fun;
if (i == chute_relay) {
new_fun = AP_Relay_Params::Function::parachute;
new_fun = AP_Relay_Params::FUNCTION::PARACHUTE;

} else if (i == ice_relay) {
new_fun = AP_Relay_Params::Function::ignition;
new_fun = AP_Relay_Params::FUNCTION::IGNITION;

} else if (i == cam_relay) {
new_fun = AP_Relay_Params::Function::camera;
new_fun = AP_Relay_Params::FUNCTION::CAMERA;

#if APM_BUILD_TYPE(APM_BUILD_Rover)
} else if (i == rover_relay[0]) {
new_fun = AP_Relay_Params::Function::brushed_reverse_1;
new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_1;

} else if (i == rover_relay[1]) {
new_fun = AP_Relay_Params::Function::brushed_reverse_2;
new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_2;

} else if (i == rover_relay[2]) {
new_fun = AP_Relay_Params::Function::brushed_reverse_3;
new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_3;

} else if (i == rover_relay[3]) {
new_fun = AP_Relay_Params::Function::brushed_reverse_4;
new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_4;
#endif

} else {
Expand All @@ -214,7 +214,7 @@ void AP_Relay::convert_params()
// This will result in a pre-arm promoting the user to resolve
continue;
}
new_fun = AP_Relay_Params::Function::relay;
new_fun = AP_Relay_Params::FUNCTION::RELAY;

}
_params[i].function.set_and_save(int8_t(new_fun));
Expand Down Expand Up @@ -257,17 +257,17 @@ void AP_Relay::init()
continue;
}

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

if (function == AP_Relay_Params::Function::relay) {
if (function == AP_Relay_Params::FUNCTION::RELAY) {
// relay by instance number, set the state to match our output
const AP_Relay_Params::Default_State default_state = _params[instance].default_state;
if ((default_state == AP_Relay_Params::Default_State::Off) ||
(default_state == AP_Relay_Params::Default_State::On)) {
const AP_Relay_Params::DEFAULT_STATE default_state = _params[instance].default_state;
if ((default_state == AP_Relay_Params::DEFAULT_STATE::OFF) ||
(default_state == AP_Relay_Params::DEFAULT_STATE::ON)) {

set_pin_by_instance(instance, (bool)default_state);
}
Expand All @@ -279,8 +279,8 @@ void AP_Relay::init()
}
}

void AP_Relay::set(const AP_Relay_Params::Function function, const bool value) {
if (function <= AP_Relay_Params::Function::none && function >= AP_Relay_Params::Function::num_functions) {
void AP_Relay::set(const AP_Relay_Params::FUNCTION function, const bool value) {
if (function <= AP_Relay_Params::FUNCTION::NONE && function >= AP_Relay_Params::FUNCTION::NUM_FUNCTIONS) {
// invalid function
return;
}
Expand Down Expand Up @@ -327,7 +327,7 @@ void AP_Relay::set(const uint8_t instance, const bool value)
return;
}

if (_params[instance].function != AP_Relay_Params::Function::relay) {
if (_params[instance].function != AP_Relay_Params::FUNCTION::RELAY) {
return;
}

Expand Down Expand Up @@ -384,11 +384,11 @@ bool AP_Relay::get(uint8_t instance) const
bool AP_Relay::enabled(uint8_t instance) const
{
// Must be a valid instance with function relay and pin set
return (instance < AP_RELAY_NUM_RELAYS) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::Function::relay);
return (instance < AP_RELAY_NUM_RELAYS) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::FUNCTION::RELAY);
}

// see if the relay is enabled
bool AP_Relay::enabled(AP_Relay_Params::Function function) const
bool AP_Relay::enabled(AP_Relay_Params::FUNCTION function) const
{
for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) {
if ((_params[instance].function == function) && (_params[instance].pin != -1)) {
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Relay/AP_Relay.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,10 @@ class AP_Relay {

bool send_relay_status(const class GCS_MAVLINK &link) const;

void set(AP_Relay_Params::Function function, bool value);
void set(AP_Relay_Params::FUNCTION function, bool value);

// see if the relay is enabled
bool enabled(AP_Relay_Params::Function function) const;
bool enabled(AP_Relay_Params::FUNCTION function) const;

private:
static AP_Relay *singleton;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Relay/AP_Relay_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
// @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4

// @User: Standard
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)FUNCTION::NONE, AP_PARAM_FLAG_ENABLE),

// @Param: PIN
// @DisplayName: Relay pin
Expand All @@ -30,7 +30,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
// @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.
// @Values: 0: Off,1:On,2:NoChange
// @User: Standard
AP_GROUPINFO("DEFAULT", 3, AP_Relay_Params, default_state, (float)Default_State::Off),
AP_GROUPINFO("DEFAULT", 3, AP_Relay_Params, default_state, (float)DEFAULT_STATE::OFF),

AP_GROUPEND

Expand Down
34 changes: 17 additions & 17 deletions libraries/AP_Relay/AP_Relay_Params.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,26 +12,26 @@ class AP_Relay_Params {
/* Do not allow copies */
CLASS_NO_COPY(AP_Relay_Params);

enum class Default_State : uint8_t {
Off = 0,
On = 1,
NoChange = 2,
enum class DEFAULT_STATE : uint8_t {
OFF = 0,
ON = 1,
NO_CHANGE = 2,
};

enum class Function : uint8_t {
none = 0,
relay = 1,
ignition = 2,
parachute = 3,
camera = 4,
brushed_reverse_1 = 5,
brushed_reverse_2 = 6,
brushed_reverse_3 = 7,
brushed_reverse_4 = 8,
num_functions // must be the last entry
enum class FUNCTION : uint8_t {
NONE = 0,
RELAY = 1,
IGNITION = 2,
PARACHUTE = 3,
CAMERA = 4,
BRUSHED_REVERSE_1 = 5,
BRUSHED_REVERSE_2 = 6,
BRUSHED_REVERSE_3 = 7,
BRUSHED_REVERSE_4 = 8,
NUM_FUNCTIONS // must be the last entry
};

AP_Enum<Function> function; // relay function
AP_Enum<FUNCTION> function; // relay function
AP_Int16 pin; // gpio pin number
AP_Enum<Default_State> default_state; // default state
AP_Enum<DEFAULT_STATE> default_state; // default state
};

0 comments on commit 03b0b2b

Please sign in to comment.