ardupilot/libraries/AP_Relay/AP_Relay.cpp

52 lines
880 B
C++
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* AP_Relay.cpp
*
* Created on: Oct 2, 2011
* Author: Amilcar Lucas
*/
2012-11-30 21:47:32 -04:00
#include <AP_HAL.h>
#include "AP_Relay.h"
2012-11-30 21:47:32 -04:00
extern const AP_HAL::HAL& hal;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
2012-11-30 21:47:32 -04:00
#define RELAY_PIN 47
2013-01-01 18:53:43 -04:00
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
#define RELAY_PIN 26
#else
#error "no RELAY_PIN defined for this board"
#endif
2012-12-04 19:26:30 -04:00
void AP_Relay::init() {
hal.gpio->pinMode(RELAY_PIN, GPIO_OUTPUT);
}
2012-11-30 21:47:32 -04:00
void AP_Relay::on() {
hal.gpio->write(RELAY_PIN, 1);
}
2012-11-30 21:47:32 -04:00
void AP_Relay::off() {
hal.gpio->write(RELAY_PIN, 0);
}
2012-11-30 21:47:32 -04:00
void AP_Relay::toggle() {
bool ison = hal.gpio->read(RELAY_PIN);
if (ison)
off();
2012-11-30 21:47:32 -04:00
else
on();
}
void AP_Relay::set(bool status){
hal.gpio->write(RELAY_PIN, status);
}
2012-11-30 21:47:32 -04:00
bool AP_Relay::get() {
return hal.gpio->read(RELAY_PIN);
}