ardupilot/libraries/AP_Relay/AP_Relay.cpp

175 lines
5.3 KiB
C++

/*
* AP_Relay.cpp
*
* Created on: Oct 2, 2011
* Author: Amilcar Lucas
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_Relay.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define RELAY1_PIN_DEFAULT 13
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
#define RELAY1_PIN_DEFAULT 57
#define RELAY2_PIN_DEFAULT 49
#define RELAY3_PIN_DEFAULT 116
#define RELAY4_PIN_DEFAULT 113
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#define RELAY1_PIN_DEFAULT 27
#define RELAY2_PIN_DEFAULT 65
#define RELAY3_PIN_DEFAULT 22
#define RELAY4_PIN_DEFAULT 81
#define RELAY5_PIN_DEFAULT 23
#define RELAY6_PIN_DEFAULT 26
#endif
#endif
#ifndef RELAY1_PIN_DEFAULT
#define RELAY1_PIN_DEFAULT -1
#endif
#ifndef RELAY2_PIN_DEFAULT
#define RELAY2_PIN_DEFAULT -1
#endif
#ifndef RELAY3_PIN_DEFAULT
#define RELAY3_PIN_DEFAULT -1
#endif
#ifndef RELAY4_PIN_DEFAULT
#define RELAY4_PIN_DEFAULT -1
#endif
#ifndef RELAY5_PIN_DEFAULT
#define RELAY5_PIN_DEFAULT -1
#endif
#ifndef RELAY6_PIN_DEFAULT
#define RELAY6_PIN_DEFAULT -1
#endif
const AP_Param::GroupInfo AP_Relay::var_info[] = {
// @Param: PIN
// @DisplayName: First Relay Pin
// @Description: Digital pin number for first relay control. This is the pin used for camera control.
// @User: Standard
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,27:BBBMini Pin P8.17
AP_GROUPINFO("PIN", 0, AP_Relay, _pin[0], RELAY1_PIN_DEFAULT),
// @Param: PIN2
// @DisplayName: Second Relay Pin
// @Description: Digital pin number for 2nd relay control.
// @User: Standard
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,65:BBBMini Pin P8.18
AP_GROUPINFO("PIN2", 1, AP_Relay, _pin[1], RELAY2_PIN_DEFAULT),
// @Param: PIN3
// @DisplayName: Third Relay Pin
// @Description: Digital pin number for 3rd relay control.
// @User: Standard
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,22:BBBMini Pin P8.19
AP_GROUPINFO("PIN3", 2, AP_Relay, _pin[2], RELAY3_PIN_DEFAULT),
// @Param: PIN4
// @DisplayName: Fourth Relay Pin
// @Description: Digital pin number for 4th relay control.
// @User: Standard
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,63:BBBMini Pin P8.34
AP_GROUPINFO("PIN4", 3, AP_Relay, _pin[3], RELAY4_PIN_DEFAULT),
// @Param: DEFAULT
// @DisplayName: Default relay state
// @Description: The state of the relay on boot.
// @User: Standard
// @Values: 0:Off,1:On,2:NoChange
AP_GROUPINFO("DEFAULT", 4, AP_Relay, _default, 0),
// @Param: PIN5
// @DisplayName: Fifth Relay Pin
// @Description: Digital pin number for 5th relay control.
// @User: Standard
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,62:BBBMini Pin P8.13
AP_GROUPINFO("PIN5", 5, AP_Relay, _pin[4], RELAY5_PIN_DEFAULT),
// @Param: PIN6
// @DisplayName: Sixth Relay Pin
// @Description: Digital pin number for 6th relay control.
// @User: Standard
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,37:BBBMini Pin P8.14
AP_GROUPINFO("PIN6", 6, AP_Relay, _pin[5], RELAY6_PIN_DEFAULT),
AP_GROUPEND
};
AP_Relay *AP_Relay::singleton;
extern const AP_HAL::HAL& hal;
AP_Relay::AP_Relay(void)
{
AP_Param::setup_object_defaults(this, var_info);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (singleton != nullptr) {
AP_HAL::panic("AP_Relay must be singleton");
}
#endif
singleton = this;
}
void AP_Relay::init()
{
if (_default != 0 && _default != 1) {
return;
}
for (uint8_t i=0; i<AP_RELAY_NUM_RELAYS; i++) {
set(i, _default);
}
}
void AP_Relay::set(const uint8_t instance, const bool value)
{
if (instance >= AP_RELAY_NUM_RELAYS) {
return;
}
if (_pin[instance] == -1) {
return;
}
hal.gpio->pinMode(_pin[instance], HAL_GPIO_OUTPUT);
hal.gpio->write(_pin[instance], value);
}
void AP_Relay::toggle(uint8_t instance)
{
if (instance < AP_RELAY_NUM_RELAYS && _pin[instance] != -1) {
bool ison = hal.gpio->read(_pin[instance]);
set(instance, !ison);
}
}
// check settings are valid
bool AP_Relay::arming_checks(size_t buflen, char *buffer) const
{
for (uint8_t i=0; i<AP_RELAY_NUM_RELAYS; i++) {
if (_pin[i] != -1 && !hal.gpio->valid_pin(_pin[i])) {
hal.util->snprintf(buffer, buflen, "Relay[%u] pin %d invalid", i + 1, int(_pin[i].get()));
return false;
}
}
return true;
}
namespace AP {
AP_Relay *relay()
{
return AP_Relay::get_singleton();
}
}