aboutsummaryrefslogtreecommitdiff
path: root/apps/px4io/px4io.h
diff options
context:
space:
mode:
Diffstat (limited to 'apps/px4io/px4io.h')
-rw-r--r--apps/px4io/px4io.h40
1 files changed, 23 insertions, 17 deletions
diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h
index d90f7e36b..4889036b6 100644
--- a/apps/px4io/px4io.h
+++ b/apps/px4io/px4io.h
@@ -32,10 +32,18 @@
****************************************************************************/
/**
- * @file General defines and structures for the PX4IO module firmware.
+ * @file px4io.h
+ *
+ * General defines and structures for the PX4IO module firmware.
*/
-#include <arch/board/drv_gpio.h>
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdint.h>
+
+#include <drivers/boards/px4io/px4io_internal.h>
+
#include "protocol.h"
/*
@@ -102,21 +110,19 @@ extern volatile int timers[TIMER_NUM_TIMERS];
/*
* GPIO handling.
*/
-extern int gpio_fd;
-
-#define POWER_SERVO(_s) ioctl(gpio_fd, GPIO_SET(GPIO_SERVO_POWER), (_s))
-#define POWER_ACC1(_s) ioctl(gpio_fd, GPIO_SET(GPIO_SERVO_ACC1), (_s))
-#define POWER_ACC2(_s) ioctl(gpio_fd, GPIO_SET(GPIO_SERVO_ACC2), (_s))
-#define POWER_RELAY1(_s) ioctl(gpio_fd, GPIO_SET(GPIO_RELAY1, (_s))
-#define POWER_RELAY2(_s) ioctl(gpio_fd, GPIO_SET(GPIO_RELAY2, (_s))
-
-#define LED_AMBER(_s) ioctl(gpio_fd, GPIO_SET(GPIO_LED_AMBER), !(_s))
-#define LED_BLUE(_s) ioctl(gpio_fd, GPIO_SET(GPIO_LED_BLUE), !(_s))
-#define LED_SAFETY(_s) ioctl(gpio_fd, GPIO_SET(GPIO_LED_SAFETY), !(_s))
-
-#define OVERCURRENT_ACC ioctl(gpio_fd, GPIO_GET(GPIO_ACC_OVERCURRENT), 0)
-#define OVERCURRENT_SERVO ioctl(gpio_fd, GPIO_GET(GPIO_SERVO_OVERCURRENT), 0)
-#define BUTTON_SAFETY ioctl(gpio_fd, GPIO_GET(GPIO_SAFETY_BUTTON), 0)
+#define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED1, !(_s))
+#define LED_BLUE(_s) stm32_gpiowrite(GPIO_LED2, !(_s))
+#define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s))
+
+#define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s))
+#define POWER_ACC1(_s) stm32_gpiowrite(GPIO_SERVO_ACC1_EN, (_s))
+#define POWER_ACC2(_s) stm32_gpiowrite(GPIO_SERVO_ACC2_EN, (_s))
+#define POWER_RELAY1(_s) stm32_gpiowrite(GPIO_RELAY1_EN, (_s))
+#define POWER_RELAY2(_s) stm32_gpiowrite(GPIO_RELAY2_EN, (_s))
+
+#define OVERCURRENT_ACC stm32_gpioread(GPIO_ACC_OC_DETECT)
+#define OVERCURRENT_SERVO stm32_gpioread(GPIO_SERVO_OC_DETECT
+#define BUTTON_SAFETY stm32_gpioread(GPIO_BTN_SAFETY)
/*
* Mixer