ardupilot/libraries/AP_Relay/AP_Relay.cpp

78 lines
1.4 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"
#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
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
#define RELAY_PIN 99
#else
2013-01-01 21:51:56 -04:00
// no relay for this board
#define RELAY_PIN -1
#endif
const AP_Param::GroupInfo AP_Relay::var_info[] PROGMEM = {
// @Param: PIN
// @DisplayName: Relay Pin
// @Description: Digital pin number for relay control. This is normally 47 for the APM1 relay, 13 for the A9 pin on APM2 and 99 for the high power relay pin on the PX4.
// @User: Standard
AP_GROUPINFO("PIN", 0, AP_Relay, _pin, RELAY_PIN),
2012-12-04 19:26:30 -04:00
AP_GROUPEND
};
extern const AP_HAL::HAL& hal;
AP_Relay::AP_Relay(void)
{
AP_Param::setup_object_defaults(this, var_info);
}
void AP_Relay::init()
{
if (_pin != -1) {
hal.gpio->pinMode(_pin, GPIO_OUTPUT);
off();
}
2012-11-30 21:47:32 -04:00
}
void AP_Relay::on()
{
if (_pin != -1) {
hal.gpio->write(_pin, 1);
}
}
void AP_Relay::off()
{
if (_pin != -1) {
hal.gpio->write(_pin, 0);
}
}
void AP_Relay::toggle()
{
if (_pin != -1) {
bool ison = hal.gpio->read(_pin);
if (ison)
off();
else
on();
}
}