@@ -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
384384bool 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 )) {
0 commit comments