APM:Libraries
AP_Relay.cpp
Go to the documentation of this file.
1 /*
2  * AP_Relay.cpp
3  *
4  * Created on: Oct 2, 2011
5  * Author: Amilcar Lucas
6  */
7 
8 #include <AP_HAL/AP_HAL.h>
9 #include "AP_Relay.h"
10 
11 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
12  #define RELAY1_PIN_DEFAULT 13
13 
14 #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
15  #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
16  #define RELAY1_PIN_DEFAULT 111
17 
18  #elif !defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
19  #define RELAY1_PIN_DEFAULT 54
20  #define RELAY2_PIN_DEFAULT 55
21  #endif
22 
23 #elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
24  #define RELAY1_PIN_DEFAULT 33
25 
26 #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
27  #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
28  #define RELAY1_PIN_DEFAULT 57
29  #define RELAY2_PIN_DEFAULT 49
30  #define RELAY3_PIN_DEFAULT 116
31  #define RELAY4_PIN_DEFAULT 113
32  #endif
33 #endif
34 
35 #ifndef RELAY1_PIN_DEFAULT
36  #define RELAY1_PIN_DEFAULT -1
37 #endif
38 
39 #ifndef RELAY2_PIN_DEFAULT
40  #define RELAY2_PIN_DEFAULT -1
41 #endif
42 
43 #ifndef RELAY3_PIN_DEFAULT
44  #define RELAY3_PIN_DEFAULT -1
45 #endif
46 
47 #ifndef RELAY4_PIN_DEFAULT
48  #define RELAY4_PIN_DEFAULT -1
49 #endif
50 
51 
53  // @Param: PIN
54  // @DisplayName: First Relay Pin
55  // @Description: Digital pin number for first relay control. This is the pin used for camera control.
56  // @User: Standard
57  // @Values: -1:Disabled,13:APM2 A9 pin,47:APM1 relay,49:BB Blue GP0 pin 4,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,57:BB Blue GP0 pin 3,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1/BB Blue GP0 pin 6,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2/BB Blue GP0 pin 5
58  AP_GROUPINFO("PIN", 0, AP_Relay, _pin[0], RELAY1_PIN_DEFAULT),
59 
60  // @Param: PIN2
61  // @DisplayName: Second Relay Pin
62  // @Description: Digital pin number for 2nd relay control.
63  // @User: Standard
64  // @Values: -1:Disabled,13:APM2 A9 pin,47:APM1 relay,49:BB Blue GP0 pin 4,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,57:BB Blue GP0 pin 3,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1/BB Blue GP0 pin 6,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2/BB Blue GP0 pin 5
65  AP_GROUPINFO("PIN2", 1, AP_Relay, _pin[1], RELAY2_PIN_DEFAULT),
66 
67  // @Param: PIN3
68  // @DisplayName: Third Relay Pin
69  // @Description: Digital pin number for 3rd relay control.
70  // @User: Standard
71  // @Values: -1:Disabled,13:APM2 A9 pin,47:APM1 relay,49:BB Blue GP0 pin 4,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,57:BB Blue GP0 pin 3,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1/BB Blue GP0 pin 6,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2/BB Blue GP0 pin 5
72  AP_GROUPINFO("PIN3", 2, AP_Relay, _pin[2], RELAY3_PIN_DEFAULT),
73 
74  // @Param: PIN4
75  // @DisplayName: Fourth Relay Pin
76  // @Description: Digital pin number for 4th relay control.
77  // @User: Standard
78  // @Values: -1:Disabled,13:APM2 A9 pin,47:APM1 relay,49:BB Blue GP0 pin 4,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,57:BB Blue GP0 pin 3,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1/BB Blue GP0 pin 6,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2/BB Blue GP0 pin 5
79  AP_GROUPINFO("PIN4", 3, AP_Relay, _pin[3], RELAY4_PIN_DEFAULT),
80 
81  // @Param: DEFAULT
82  // @DisplayName: Default relay state
83  // @Description: The state of the relay on boot.
84  // @User: Standard
85  // @Values: 0:Off,1:On,2:NoChange
86  AP_GROUPINFO("DEFAULT", 4, AP_Relay, _default, 0),
87 
89 };
90 
91 
92 extern const AP_HAL::HAL& hal;
93 
95 {
97 }
98 
99 
101 {
102  for (uint8_t i=0; i<AP_RELAY_NUM_RELAYS; i++) {
103  if (_pin[i].get() != -1) {
104  switch (_default) {
105  case 0:
106  off(i);
107  break;
108  case 1:
109  on(i);
110  break;
111  default:
112  break;
113  }
114  }
115  }
116 }
117 
118 void AP_Relay::on(uint8_t relay)
119 {
120  if (relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1) {
121  hal.gpio->pinMode(_pin[relay], HAL_GPIO_OUTPUT);
122  hal.gpio->write(_pin[relay], 1);
123  }
124 }
125 
126 
127 void AP_Relay::off(uint8_t relay)
128 {
129  if (relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1) {
130  hal.gpio->pinMode(_pin[relay], HAL_GPIO_OUTPUT);
131  hal.gpio->write(_pin[relay], 0);
132  }
133 }
134 
135 
136 void AP_Relay::toggle(uint8_t relay)
137 {
138  if (relay < AP_RELAY_NUM_RELAYS && _pin[relay] != -1) {
139  bool ison = hal.gpio->read(_pin[relay]);
140  if (ison)
141  off(relay);
142  else
143  on(relay);
144  }
145 }
146 
AP_Relay()
Definition: AP_Relay.cpp:94
static AP_Relay relay
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define RELAY1_PIN_DEFAULT
Definition: AP_Relay.cpp:12
void off(uint8_t relay)
Definition: AP_Relay.cpp:127
#define RELAY3_PIN_DEFAULT
Definition: AP_Relay.cpp:44
virtual void write(uint8_t pin, uint8_t value)=0
void init()
Definition: AP_Relay.cpp:100
void on(uint8_t relay)
Definition: AP_Relay.cpp:118
void toggle(uint8_t relay)
Definition: AP_Relay.cpp:136
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define RELAY4_PIN_DEFAULT
Definition: AP_Relay.cpp:48
AP_Int8 _pin[AP_RELAY_NUM_RELAYS]
Definition: AP_Relay.h:44
virtual void pinMode(uint8_t pin, uint8_t output)=0
AP_Int8 _default
Definition: AP_Relay.h:45
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
Class to manage the ArduPilot relay.
Definition: AP_Relay.h:18
virtual uint8_t read(uint8_t pin)=0
#define RELAY2_PIN_DEFAULT
Definition: AP_Relay.cpp:40
#define AP_RELAY_NUM_RELAYS
Definition: AP_Relay.h:14
AP_HAL::GPIO * gpio
Definition: HAL.h:111
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Relay.h:41
#define AP_GROUPEND
Definition: AP_Param.h:121
APM relay control class.
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214