11 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 12 #define RELAY1_PIN_DEFAULT 13 14 #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 15 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 16 #define RELAY1_PIN_DEFAULT 111 18 #elif !defined(CONFIG_ARCH_BOARD_PX4FMU_V4) 19 #define RELAY1_PIN_DEFAULT 54 20 #define RELAY2_PIN_DEFAULT 55 23 #elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 24 #define RELAY1_PIN_DEFAULT 33 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 35 #ifndef RELAY1_PIN_DEFAULT 36 #define RELAY1_PIN_DEFAULT -1 39 #ifndef RELAY2_PIN_DEFAULT 40 #define RELAY2_PIN_DEFAULT -1 43 #ifndef RELAY3_PIN_DEFAULT 44 #define RELAY3_PIN_DEFAULT -1 47 #ifndef RELAY4_PIN_DEFAULT 48 #define RELAY4_PIN_DEFAULT -1 103 if (
_pin[i].
get() != -1) {
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define RELAY1_PIN_DEFAULT
#define RELAY3_PIN_DEFAULT
virtual void write(uint8_t pin, uint8_t value)=0
void toggle(uint8_t relay)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define RELAY4_PIN_DEFAULT
AP_Int8 _pin[AP_RELAY_NUM_RELAYS]
virtual void pinMode(uint8_t pin, uint8_t output)=0
Class to manage the ArduPilot relay.
virtual uint8_t read(uint8_t pin)=0
#define RELAY2_PIN_DEFAULT
#define AP_RELAY_NUM_RELAYS
static const struct AP_Param::GroupInfo var_info[]
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)