Skip to content

Commit 03b0b2b

Browse files
committed
AP_Relay: capitalize function and defualt enums
1 parent 28a870c commit 03b0b2b

File tree

4 files changed

+41
-41
lines changed

4 files changed

+41
-41
lines changed

libraries/AP_Relay/AP_Relay.cpp

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -183,28 +183,28 @@ void AP_Relay::convert_params()
183183
}
184184

185185
// Work out what function this relay should be
186-
AP_Relay_Params::Function new_fun;
186+
AP_Relay_Params::FUNCTION new_fun;
187187
if (i == chute_relay) {
188-
new_fun = AP_Relay_Params::Function::parachute;
188+
new_fun = AP_Relay_Params::FUNCTION::PARACHUTE;
189189

190190
} else if (i == ice_relay) {
191-
new_fun = AP_Relay_Params::Function::ignition;
191+
new_fun = AP_Relay_Params::FUNCTION::IGNITION;
192192

193193
} else if (i == cam_relay) {
194-
new_fun = AP_Relay_Params::Function::camera;
194+
new_fun = AP_Relay_Params::FUNCTION::CAMERA;
195195

196196
#if APM_BUILD_TYPE(APM_BUILD_Rover)
197197
} else if (i == rover_relay[0]) {
198-
new_fun = AP_Relay_Params::Function::brushed_reverse_1;
198+
new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_1;
199199

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

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

206206
} else if (i == rover_relay[3]) {
207-
new_fun = AP_Relay_Params::Function::brushed_reverse_4;
207+
new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_4;
208208
#endif
209209

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

219219
}
220220
_params[i].function.set_and_save(int8_t(new_fun));
@@ -257,17 +257,17 @@ void AP_Relay::init()
257257
continue;
258258
}
259259

260-
const AP_Relay_Params::Function function = _params[instance].function;
261-
if (function < AP_Relay_Params::Function::relay || function >= AP_Relay_Params::Function::num_functions) {
260+
const AP_Relay_Params::FUNCTION function = _params[instance].function;
261+
if (function <= AP_Relay_Params::FUNCTION::NONE || function >= AP_Relay_Params::FUNCTION::NUM_FUNCTIONS) {
262262
// invalid function, skip it
263263
continue;
264264
}
265265

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

272272
set_pin_by_instance(instance, (bool)default_state);
273273
}
@@ -279,8 +279,8 @@ void AP_Relay::init()
279279
}
280280
}
281281

282-
void AP_Relay::set(const AP_Relay_Params::Function function, const bool value) {
283-
if (function <= AP_Relay_Params::Function::none && function >= AP_Relay_Params::Function::num_functions) {
282+
void AP_Relay::set(const AP_Relay_Params::FUNCTION function, const bool value) {
283+
if (function <= AP_Relay_Params::FUNCTION::NONE && function >= AP_Relay_Params::FUNCTION::NUM_FUNCTIONS) {
284284
// invalid function
285285
return;
286286
}
@@ -327,7 +327,7 @@ void AP_Relay::set(const uint8_t instance, const bool value)
327327
return;
328328
}
329329

330-
if (_params[instance].function != AP_Relay_Params::Function::relay) {
330+
if (_params[instance].function != AP_Relay_Params::FUNCTION::RELAY) {
331331
return;
332332
}
333333

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

390390
// see if the relay is enabled
391-
bool AP_Relay::enabled(AP_Relay_Params::Function function) const
391+
bool AP_Relay::enabled(AP_Relay_Params::FUNCTION function) const
392392
{
393393
for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) {
394394
if ((_params[instance].function == function) && (_params[instance].pin != -1)) {

libraries/AP_Relay/AP_Relay.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -55,10 +55,10 @@ class AP_Relay {
5555

5656
bool send_relay_status(const class GCS_MAVLINK &link) const;
5757

58-
void set(AP_Relay_Params::Function function, bool value);
58+
void set(AP_Relay_Params::FUNCTION function, bool value);
5959

6060
// see if the relay is enabled
61-
bool enabled(AP_Relay_Params::Function function) const;
61+
bool enabled(AP_Relay_Params::FUNCTION function) const;
6262

6363
private:
6464
static AP_Relay *singleton;

libraries/AP_Relay/AP_Relay_Params.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
1616
// @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4
1717

1818
// @User: Standard
19-
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE),
19+
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)FUNCTION::NONE, AP_PARAM_FLAG_ENABLE),
2020

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

3535
AP_GROUPEND
3636

libraries/AP_Relay/AP_Relay_Params.h

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -12,26 +12,26 @@ class AP_Relay_Params {
1212
/* Do not allow copies */
1313
CLASS_NO_COPY(AP_Relay_Params);
1414

15-
enum class Default_State : uint8_t {
16-
Off = 0,
17-
On = 1,
18-
NoChange = 2,
15+
enum class DEFAULT_STATE : uint8_t {
16+
OFF = 0,
17+
ON = 1,
18+
NO_CHANGE = 2,
1919
};
2020

21-
enum class Function : uint8_t {
22-
none = 0,
23-
relay = 1,
24-
ignition = 2,
25-
parachute = 3,
26-
camera = 4,
27-
brushed_reverse_1 = 5,
28-
brushed_reverse_2 = 6,
29-
brushed_reverse_3 = 7,
30-
brushed_reverse_4 = 8,
31-
num_functions // must be the last entry
21+
enum class FUNCTION : uint8_t {
22+
NONE = 0,
23+
RELAY = 1,
24+
IGNITION = 2,
25+
PARACHUTE = 3,
26+
CAMERA = 4,
27+
BRUSHED_REVERSE_1 = 5,
28+
BRUSHED_REVERSE_2 = 6,
29+
BRUSHED_REVERSE_3 = 7,
30+
BRUSHED_REVERSE_4 = 8,
31+
NUM_FUNCTIONS // must be the last entry
3232
};
3333

34-
AP_Enum<Function> function; // relay function
34+
AP_Enum<FUNCTION> function; // relay function
3535
AP_Int16 pin; // gpio pin number
36-
AP_Enum<Default_State> default_state; // default state
36+
AP_Enum<DEFAULT_STATE> default_state; // default state
3737
};

0 commit comments

Comments
 (0)