ardupilot/libraries/AP_Relay/AP_Relay.cpp

67 lines
1.1 KiB
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 19:19:43 -04:00
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#define RELAY_PIN 13
#else
2013-01-01 21:51:56 -04:00
// no relay for this board
#define RELAY_PIN -1
#endif
2012-12-04 19:26:30 -04:00
void AP_Relay::init() {
2013-01-01 21:51:56 -04:00
#if RELAY_PIN != -1
2012-12-04 19:26:30 -04:00
hal.gpio->pinMode(RELAY_PIN, GPIO_OUTPUT);
2013-01-01 21:51:56 -04:00
#endif
2012-12-04 19:26:30 -04:00
}
2012-11-30 21:47:32 -04:00
void AP_Relay::on() {
2013-01-01 21:51:56 -04:00
#if RELAY_PIN != -1
2012-11-30 21:47:32 -04:00
hal.gpio->write(RELAY_PIN, 1);
2013-01-01 21:51:56 -04:00
#endif
}
2012-11-30 21:47:32 -04:00
void AP_Relay::off() {
2013-01-01 21:51:56 -04:00
#if RELAY_PIN != -1
2012-11-30 21:47:32 -04:00
hal.gpio->write(RELAY_PIN, 0);
2013-01-01 21:51:56 -04:00
#endif
}
2012-11-30 21:47:32 -04:00
void AP_Relay::toggle() {
2013-01-01 21:51:56 -04:00
#if RELAY_PIN != -1
2012-11-30 21:47:32 -04:00
bool ison = hal.gpio->read(RELAY_PIN);
if (ison)
off();
2012-11-30 21:47:32 -04:00
else
on();
2013-01-01 21:51:56 -04:00
#endif
2012-11-30 21:47:32 -04:00
}
void AP_Relay::set(bool status){
2013-01-01 21:51:56 -04:00
#if RELAY_PIN != -1
2012-11-30 21:47:32 -04:00
hal.gpio->write(RELAY_PIN, status);
2013-01-01 21:51:56 -04:00
#endif
}
2012-11-30 21:47:32 -04:00
bool AP_Relay::get() {
2013-01-01 21:51:56 -04:00
#if RELAY_PIN != -1
2012-11-30 21:47:32 -04:00
return hal.gpio->read(RELAY_PIN);
2013-01-01 21:51:56 -04:00
#else
return false;
#endif
}