AP_Relay: add init method
This commit is contained in:
parent
70a3ee738a
commit
4d0b1e6571
@ -14,6 +14,10 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define RELAY_PIN 47
|
||||
|
||||
void AP_Relay::init() {
|
||||
hal.gpio->pinMode(RELAY_PIN, GPIO_OUTPUT);
|
||||
}
|
||||
|
||||
void AP_Relay::on() {
|
||||
hal.gpio->write(RELAY_PIN, 1);
|
||||
}
|
||||
@ -32,12 +36,10 @@ void AP_Relay::toggle() {
|
||||
on();
|
||||
}
|
||||
|
||||
|
||||
void AP_Relay::set(bool status){
|
||||
hal.gpio->write(RELAY_PIN, status);
|
||||
}
|
||||
|
||||
|
||||
bool AP_Relay::get() {
|
||||
return hal.gpio->read(RELAY_PIN);
|
||||
}
|
||||
|
@ -17,6 +17,9 @@
|
||||
/// @brief Class to manage the APM relay
|
||||
class AP_Relay {
|
||||
public:
|
||||
// setup the relay pin
|
||||
void init();
|
||||
|
||||
// activate the relay
|
||||
void on();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user