summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/shenzhou/include/board.h16
-rw-r--r--nuttx/configs/shenzhou/src/shenzhou-internal.h4
-rw-r--r--nuttx/configs/shenzhou/src/up_relays.c13
3 files changed, 27 insertions, 6 deletions
diff --git a/nuttx/configs/shenzhou/include/board.h b/nuttx/configs/shenzhou/include/board.h
index b0fc1b52d..efc15c73d 100644
--- a/nuttx/configs/shenzhou/include/board.h
+++ b/nuttx/configs/shenzhou/include/board.h
@@ -49,6 +49,8 @@
#include "stm32_sdio.h"
#include "stm32_internal.h"
+#include <nuttx/arch.h>
+
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
@@ -174,6 +176,10 @@
#define BUTTON_TAMPER_BIT BUTTON_KEY3_BIT
#define BUTTON_WAKEUP_BIT BUTTON_KEY4_BIT
+/* Relays */
+
+#define NUM_RELAYS 2
+
/* Pin selections ******************************************************************/
/* Ethernet
*
@@ -426,18 +432,20 @@ EXTERN void stm32_lcdclear(uint16_t color);
* Relay control functions
*
* Description:
- * Non-standard fucntions for relay control from the Shenzhou board.
+ * Non-standard functions for relay control from the Shenzhou board.
+ *
+ * NOTE: These must match the prototypes in include/nuttx/arch.h
*
************************************************************************************/
#ifdef CONFIG_ARCH_RELAYS
EXTERN void up_relaysinit(void);
-EXTERN void relays_setstat(int relays,bool stat);
+EXTERN void relays_setstat(int relays, bool stat);
EXTERN bool relays_getstat(int relays);
EXTERN void relays_setstats(uint32_t relays_stat);
EXTERN uint32_t relays_getstats(void);
-EXTERN void relays_onoff(int relays,uint32_t mdelay);
-EXTERN void relays_onoffs(uint32_t relays_stat,uint32_t mdelay);
+EXTERN void relays_onoff(int relays, uint32_t mdelay);
+EXTERN void relays_onoffs(uint32_t relays_stat, uint32_t mdelay);
EXTERN void relays_resetmode(int relays);
EXTERN void relays_powermode(int relays);
EXTERN void relays_resetmodes(uint32_t relays_stat);
diff --git a/nuttx/configs/shenzhou/src/shenzhou-internal.h b/nuttx/configs/shenzhou/src/shenzhou-internal.h
index 862a0250d..f28abcf60 100644
--- a/nuttx/configs/shenzhou/src/shenzhou-internal.h
+++ b/nuttx/configs/shenzhou/src/shenzhou-internal.h
@@ -393,9 +393,11 @@
/* Relays */
-#define NUM_RELAYS 1
+#define NUM_RELAYS 2
#define GPIO_RELAYS_R00 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN0)
+#define GPIO_RELAYS_R01 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN1)
/****************************************************************************************************
* Public Types
diff --git a/nuttx/configs/shenzhou/src/up_relays.c b/nuttx/configs/shenzhou/src/up_relays.c
index 075c7d590..6916ee455 100644
--- a/nuttx/configs/shenzhou/src/up_relays.c
+++ b/nuttx/configs/shenzhou/src/up_relays.c
@@ -42,10 +42,12 @@
#include <stdint.h>
#include <unistd.h>
+#include <debug.h>
+#include <nuttx/arch.h>
#include <arch/board/board.h>
+
#include "shenzhou-internal.h"
-#include <debug.h>
#ifdef CONFIG_ARCH_RELAYS
@@ -62,6 +64,7 @@
****************************************************************************/
static uint32_t g_relays_stat = 0;
+static bool g_relays_init = false;
static const uint16_t g_relays[NUM_RELAYS] =
{
@@ -173,6 +176,11 @@ void up_relaysinit(void)
{
int i;
+ if (g_relays_init)
+ {
+ return;
+ }
+
/* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are
* configured for some pins but NOT used in this file
*/
@@ -180,7 +188,10 @@ void up_relaysinit(void)
for (i = 0; i < NUM_RELAYS; i++)
{
stm32_configgpio(g_relays[i]);
+ stm32_gpiowrite(g_relays[i], false);
}
+
+ g_relays_init = true;
}
void relays_setstat(int relays,bool stat)