AP_Relay: enable up to 4 relay pins

This commit is contained in:
Andrew Tridgell 2014-01-20 12:59:21 +11:00
parent d3adf4c32c
commit e42ba853ec
2 changed files with 52 additions and 22 deletions

View File

@ -15,19 +15,44 @@
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#define RELAY_PIN 13 #define RELAY_PIN 13
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
#define RELAY_PIN 111 #define RELAY_PIN 111
#else #else
#define RELAY_PIN 54
#endif
#else
// no relay for this board // no relay for this board
#define RELAY_PIN -1 #define RELAY_PIN -1
#endif #endif
const AP_Param::GroupInfo AP_Relay::var_info[] PROGMEM = { const AP_Param::GroupInfo AP_Relay::var_info[] PROGMEM = {
// @Param: PIN // @Param: PIN
// @DisplayName: Relay Pin // @DisplayName: First Relay Pin
// @Description: Digital pin number for relay control. // @Description: Digital pin number for first relay control. This is the pin used for camera control.
// @User: Standard // @User: Standard
// @Values: 13:APM2 A9 pin,47:APM1 relay,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2 // @Values: 13:APM2 A9 pin,47:APM1 relay,54:Pixhawk FMU AUX1,55:Pixhawk FMU AUX2,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2
AP_GROUPINFO("PIN", 0, AP_Relay, _pin, RELAY_PIN), AP_GROUPINFO("PIN", 0, AP_Relay, _pin[0], RELAY_PIN),
// @Param: PIN2
// @DisplayName: Second Relay Pin
// @Description: Digital pin number for 2nd relay control.
// @User: Standard
// @Values: 13:APM2 A9 pin,47:APM1 relay,54:Pixhawk FMU AUX1,55:Pixhawk FMU AUX2,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2
AP_GROUPINFO("PIN2", 1, AP_Relay, _pin[1], -1),
// @Param: PIN3
// @DisplayName: Third Relay Pin
// @Description: Digital pin number for 3rd relay control.
// @User: Standard
// @Values: 13:APM2 A9 pin,47:APM1 relay,54:Pixhawk FMU AUX1,55:Pixhawk FMU AUX2,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2
AP_GROUPINFO("PIN3", 2, AP_Relay, _pin[2], -1),
// @Param: PIN4
// @DisplayName: Fourth Relay Pin
// @Description: Digital pin number for 4th relay control.
// @User: Standard
// @Values: 13:APM2 A9 pin,47:APM1 relay,54:Pixhawk FMU AUX1,55:Pixhawk FMU AUX2,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2
AP_GROUPINFO("PIN4", 3, AP_Relay, _pin[3], -1),
AP_GROUPEND AP_GROUPEND
}; };
@ -43,36 +68,39 @@ AP_Relay::AP_Relay(void)
void AP_Relay::init() void AP_Relay::init()
{ {
if (_pin != -1) { for (uint8_t i=0; i<AP_RELAY_NUM_RELAYS; i++) {
hal.gpio->pinMode(_pin, GPIO_OUTPUT); if (_pin[i].get() != -1) {
off(); off(i);
}
} }
} }
void AP_Relay::on() void AP_Relay::on(uint8_t relay)
{ {
if (_pin != -1) { if (relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1) {
hal.gpio->write(_pin, 1); hal.gpio->pinMode(_pin[relay], GPIO_OUTPUT);
hal.gpio->write(_pin[relay], 1);
} }
} }
void AP_Relay::off() void AP_Relay::off(uint8_t relay)
{ {
if (_pin != -1) { if (relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1) {
hal.gpio->write(_pin, 0); hal.gpio->pinMode(_pin[relay], GPIO_OUTPUT);
hal.gpio->write(_pin[relay], 0);
} }
} }
void AP_Relay::toggle() void AP_Relay::toggle(uint8_t relay)
{ {
if (_pin != -1) { if (relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1) {
bool ison = hal.gpio->read(_pin); bool ison = hal.gpio->read(_pin[relay]);
if (ison) if (ison)
off(); off(relay);
else else
on(); on(relay);
} }
} }

View File

@ -15,6 +15,8 @@
#include <AP_Param.h> #include <AP_Param.h>
#define AP_RELAY_NUM_RELAYS 4
/// @class AP_Relay /// @class AP_Relay
/// @brief Class to manage the APM relay /// @brief Class to manage the APM relay
class AP_Relay { class AP_Relay {
@ -25,18 +27,18 @@ public:
void init(); void init();
// activate the relay // activate the relay
void on(); void on(uint8_t relay);
// de-activate the relay // de-activate the relay
void off(); void off(uint8_t relay);
// toggle the relay status // toggle the relay status
void toggle(); void toggle(uint8_t relay);
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
private: private:
AP_Int8 _pin; AP_Int8 _pin[AP_RELAY_NUM_RELAYS];
}; };
#endif /* AP_RELAY_H_ */ #endif /* AP_RELAY_H_ */