mirror of https://github.com/ArduPilot/ardupilot
AP_Relay: change parameter name from relay to instance
This commit is contained in:
parent
1c3b2f9699
commit
06df44c184
|
@ -125,23 +125,23 @@ void AP_Relay::init()
|
|||
}
|
||||
}
|
||||
|
||||
void AP_Relay::set(const uint8_t relay, const bool value)
|
||||
void AP_Relay::set(const uint8_t instance, const bool value)
|
||||
{
|
||||
if (relay >= AP_RELAY_NUM_RELAYS) {
|
||||
if (instance >= AP_RELAY_NUM_RELAYS) {
|
||||
return;
|
||||
}
|
||||
if (_pin[relay] == -1) {
|
||||
if (_pin[instance] == -1) {
|
||||
return;
|
||||
}
|
||||
hal.gpio->pinMode(_pin[relay], HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(_pin[relay], value);
|
||||
hal.gpio->pinMode(_pin[instance], HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(_pin[instance], value);
|
||||
}
|
||||
|
||||
void AP_Relay::toggle(uint8_t relay)
|
||||
void AP_Relay::toggle(uint8_t instance)
|
||||
{
|
||||
if (relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1) {
|
||||
bool ison = hal.gpio->read(_pin[relay]);
|
||||
set(relay, !ison);
|
||||
if (instance < AP_RELAY_NUM_RELAYS && _pin[instance] != -1) {
|
||||
bool ison = hal.gpio->read(_pin[instance]);
|
||||
set(instance, !ison);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -27,16 +27,16 @@ public:
|
|||
void init();
|
||||
|
||||
// activate the relay
|
||||
void on(uint8_t relay) { set(relay, true); }
|
||||
void on(uint8_t instance) { set(instance, true); }
|
||||
|
||||
// de-activate the relay
|
||||
void off(uint8_t relay) { set(relay, false); }
|
||||
void off(uint8_t instance) { set(instance, false); }
|
||||
|
||||
// see if the relay is enabled
|
||||
bool enabled(uint8_t relay) { return relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1; }
|
||||
bool enabled(uint8_t instance) { return instance < AP_RELAY_NUM_RELAYS && _pin[instance] != -1; }
|
||||
|
||||
// toggle the relay status
|
||||
void toggle(uint8_t relay);
|
||||
void toggle(uint8_t instance);
|
||||
|
||||
static AP_Relay *get_singleton(void) {return singleton; }
|
||||
|
||||
|
@ -48,7 +48,7 @@ private:
|
|||
AP_Int8 _pin[AP_RELAY_NUM_RELAYS];
|
||||
AP_Int8 _default;
|
||||
|
||||
void set(uint8_t relay, bool value);
|
||||
void set(uint8_t instance, bool value);
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
Loading…
Reference in New Issue