summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-12-03 12:24:23 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-12-03 12:24:23 -0600
commit650d4e21398fadd04d11e3d194270c32a26e4fbc (patch)
tree77b918030b66bbccdabbe7a23efacd3e4faae8c8 /nuttx
parentdda109af3ba6d932763a4099730cc82c676cac0d (diff)
downloadpx4-nuttx-650d4e21398fadd04d11e3d194270c32a26e4fbc.tar.gz
px4-nuttx-650d4e21398fadd04d11e3d194270c32a26e4fbc.tar.bz2
px4-nuttx-650d4e21398fadd04d11e3d194270c32a26e4fbc.zip
SAMA5D3 Xplained: Add support for the Itead Joystick shield
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/sama5/sam_adc.c2
-rw-r--r--nuttx/configs/sama5d3-xplained/README.txt101
-rw-r--r--nuttx/configs/sama5d3-xplained/src/Makefile3
-rw-r--r--nuttx/configs/sama5d3-xplained/src/sam_adc.c34
-rw-r--r--nuttx/configs/sama5d3-xplained/src/sam_ajoystick.c461
-rw-r--r--nuttx/configs/sama5d3-xplained/src/sam_nsh.c13
-rw-r--r--nuttx/configs/sama5d3-xplained/src/sama5d3-xplained.h96
-rw-r--r--nuttx/drivers/input/ajoystick.c2
8 files changed, 698 insertions, 14 deletions
diff --git a/nuttx/arch/arm/src/sama5/sam_adc.c b/nuttx/arch/arm/src/sama5/sam_adc.c
index 24d49e139..1c739d103 100644
--- a/nuttx/arch/arm/src/sama5/sam_adc.c
+++ b/nuttx/arch/arm/src/sama5/sam_adc.c
@@ -2023,7 +2023,7 @@ struct adc_dev_s *sam_adc_initialize(void)
regval |= PMC_PCR_PID(SAM_PID_ADC) | PMC_PCR_CMD | PMC_PCR_EN;
sam_adc_putreg(priv, SAM_PMC_PCR, regval);
- /* Enable the ADC peripheral clock*/
+ /* Enable the ADC peripheral clock */
sam_adc_enableclk();
diff --git a/nuttx/configs/sama5d3-xplained/README.txt b/nuttx/configs/sama5d3-xplained/README.txt
index 838061f7e..e5417c22c 100644
--- a/nuttx/configs/sama5d3-xplained/README.txt
+++ b/nuttx/configs/sama5d3-xplained/README.txt
@@ -79,6 +79,7 @@ Contents
- TRNG and /dev/random
- Tickless OS
- I2S Audio Support
+ - Shields
- SAMA5D3-Xplained Configuration Options
- Configurations
- To-Do List
@@ -2577,6 +2578,106 @@ I2S Audio Support
Library Routines
CONFIG_SCHED_WORKQUEUE=y : Driver needs work queue support
+Shields
+=======
+
+ Support is built in for the following shields:
+
+ Itead Joystick Shield
+ ---------------------
+ See http://imall.iteadstudio.com/im120417014.html for more information
+ about this joystick.
+
+ Itead Joystick Connection:
+
+ --------- ----------------- ---------------------------------
+ ARDUINO ITEAD SAMA5D3 XPLAINED
+ PIN NAME SIGNAL CONNECTOR SIGNAL
+ --------- ----------------- ---------- ----------------------
+ D3 Button E Output J18 pin 4 PC8
+ D4 Button D Output J18 pin 5 PC28
+ D5 Button C Output J18 pin 6 PC7
+ D6 Button B Output J18 pin 7 PC6
+ D7 Button A Output J18 pin 8 PC5
+ D8 Button F Output J15 pin 1 PC4
+ D9 Button G Output J15 pin 2 PC3
+ A0 Joystick Y Output J17 pin 1 PC18 AD0 (function 4)
+ A1 Joystick X Output J17 pin 2 PD21 AD1 (function 1)
+ --------- ----------------- ---------- ----------------------
+
+ Possible conflicts:
+
+ ---- ----- --------------------------------------------------
+ ARDU SAMA5 SAMA5D3 XPLAINED
+ PIN GPIO SIGNAL FUNCTION
+ ---- ----- ----------------- --------------------------------
+ D3 PC8 EMDC 10/100Mbit Ethernet MAC
+ D4 PC28 SPI1_NPCS3/ISI_D9 SPI1/ISI
+ D5 PC7 EREFCK 10/100Mbit Ethernet MAC
+ D6 PC6 ECRSDV 10/100Mbit Ethernet MAC
+ D7 PC5 ECRSDV 10/100Mbit Ethernet MAC
+ D8 PC4 ETXEN 10/100Mbit Ethernet MAC
+ D9 PC3 ERX1 10/100Mbit Ethernet MAC
+ A0 PC18 RK0 SSC/Audio
+ A1 PC21 RD0 SSC/Audio
+ ---- ----- ----------------- --------------------------------
+
+ Itead Joystick Signal interpretation:
+
+ --------- ----------------------- ---------------------------
+ BUTTON TYPE NUTTX ALIAS
+ --------- ----------------------- ---------------------------
+ Button A Large button A JUMP/BUTTON 3
+ Button B Large button B FIRE/BUTTON 2
+ Button C Joystick select button SELECT/BUTTON 1
+ Button D Tiny Button D BUTTON 6
+ Button E Tiny Button E BUTTON 7
+ Button F Large Button F BUTTON 4
+ Button G Large Button G BUTTON 5
+ --------- ----------------------- ---------------------------
+
+ Itead Joystick configuration settings:
+
+ System Type -> SAMA5 Peripheral Support
+ CONFIG_SAMA5_ADC=y : Enable ADC driver support
+ CONFIG_SAMA5_TC0=y : Enable the Timer/counter library need for periodic sampling
+ CONFIG_SAMA5_EMACA=n : 10/100Mbit Ethernet MAC conflicts
+ CONFIG_SAMA5_SSC0=n : SSC0 Audio conflicts
+ CONFIG_SAMA5_SPI1=? : SPI1 might conflict if PCS3 is used
+ CONFIG_SAMA5_ISI=? : ISIS conflics if bit 9 is used
+
+ System Type -> PIO Interrupts
+ CONFIG_SAMA5_PIO_IRQ=y : PIO interrupt support is required
+ CONFIG_SAMA5_PIOC_IRQ=y : PIOC interrupt support is required
+
+ Drivers
+ CONFIG_ANALOG=y : Should be automatically selected
+ CONFIG_ADC=y : Should be automatically selected
+ CONFIG_INPUT=y : Select input device support
+ CONFIG_AJOYSTICK=y : Select analog joystick support
+
+ System Type -> ADC Configuration
+ CONFIG_SAMA5_ADC_CHAN0=y : These settings enable the sequencer to collect
+ CONFIG_SAMA5_ADC_CHAN1=y : Samples from ADC channels 0-1 on each trigger
+ CONFIG_SAMA5_ADC_SEQUENCER=y
+ CONFIG_SAMA5_ADC_TIOA0TRIG=y : Trigger on the TC0, channel 0 output A
+ CONFIG_SAMA5_ADC_TIOAFREQ=10 : At a frequency of 10Hz
+ CONFIG_SAMA5_ADC_TIOA_RISING=y : Trigger on the rising edge
+
+ Default ADC settings (like gain and offset) may also be set if desired.
+
+ System Type -> Timer/counter Configuration
+ CONFIG_SAMA5_TC0_TIOA0=y : Should be automatically selected
+
+ Library routines
+ CONFIG_SCHED_WORKQUEUE=y : Work queue support is needed
+
+ This enables the analog joystick example at apps/examples/ajoystick:
+
+ CONFIG_EXAMPLES_AJOYSTICK=y
+ CONFIG_EXAMPLES_AJOYSTICK_DEVNAME="/dev/ajoy0"
+ CONFIG_EXAMPLES_AJOYSTICK_SIGNO=13
+
SAMA5D3-Xplained Configuration Options
=================================
diff --git a/nuttx/configs/sama5d3-xplained/src/Makefile b/nuttx/configs/sama5d3-xplained/src/Makefile
index 56ad6277a..ac03e09f6 100644
--- a/nuttx/configs/sama5d3-xplained/src/Makefile
+++ b/nuttx/configs/sama5d3-xplained/src/Makefile
@@ -98,6 +98,9 @@ endif
ifeq ($(CONFIG_ADC),y)
CSRCS += sam_adc.c
+ifeq ($(CONFIG_AJOYSTICK),y)
+CSRCS += sam_ajoystick.c
+endif
endif
ifeq ($(CONFIG_PWM),y)
diff --git a/nuttx/configs/sama5d3-xplained/src/sam_adc.c b/nuttx/configs/sama5d3-xplained/src/sam_adc.c
index 89203555f..2d091745b 100644
--- a/nuttx/configs/sama5d3-xplained/src/sam_adc.c
+++ b/nuttx/configs/sama5d3-xplained/src/sam_adc.c
@@ -47,12 +47,9 @@
#include "sam_adc.h"
#include "sama5d3-xplained.h"
-#ifdef CONFIG_ADC
-
/************************************************************************************
- * Definitions
+ * Pre-processor Definitions
************************************************************************************/
-/* Configuration ********************************************************************/
/************************************************************************************
* Private Data
@@ -67,17 +64,16 @@
************************************************************************************/
/************************************************************************************
- * Name: adc_devinit
+ * Name: board_adc_initialize
*
* Description:
- * All STM32 architectures must provide the following interface to work with
- * examples/adc.
+ * Initialize and register the ADC driver
*
************************************************************************************/
-int adc_devinit(void)
-{
#ifdef CONFIG_SAMA5_ADC
+int board_adc_initialize(void)
+{
static bool initialized = false;
struct adc_dev_s *adc;
int ret;
@@ -110,9 +106,25 @@ int adc_devinit(void)
}
return OK;
+}
+#endif /* CONFIG_ADC */
+
+/************************************************************************************
+ * Name: adc_devinit
+ *
+ * Description:
+ * All SAMA5 architectures must provide the following interface to work with
+ * examples/adc.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_EXAMPLES_ADC
+int adc_devinit(void)
+{
+#ifdef CONFIG_SAMA5_ADC
+ return board_adc_initialize();
#else
return -ENOSYS;
#endif
}
-
-#endif /* CONFIG_ADC */
+#endif /* CONFIG_EXAMPLES_ADC */
diff --git a/nuttx/configs/sama5d3-xplained/src/sam_ajoystick.c b/nuttx/configs/sama5d3-xplained/src/sam_ajoystick.c
new file mode 100644
index 000000000..4be9aef0a
--- /dev/null
+++ b/nuttx/configs/sama5d3-xplained/src/sam_ajoystick.c
@@ -0,0 +1,461 @@
+/****************************************************************************
+ * configs/sam10e-eval/src/sam_ajoystick.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/input/ajoystick.h>
+
+#include "sam_pio.h"
+#include "sam_adc.h"
+#include "chip/sam_adc.h"
+#include "sama5d3-xplained.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Check for pre-requisites and pin conflicts */
+
+#ifdef CONFIG_AJOYSTICK
+# if !defined(CONFIG_ADC)
+# error CONFIG_ADC is required for the Itead joystick
+# undef CONFIG_AJOYSTICK
+# elif !defined(CONFIG_SAMA5_ADC_CHAN0) || !defined(CONFIG_SAMA5_ADC_CHAN1)
+# error CONFIG_SAMA5_ADC_CHAN0 and 1 are required for Itead joystick
+# elif !defined(CONFIG_SAMA5_PIOC_IRQ)
+# error CONFIG_SAMA5_PIOC_IRQ is required for the Itead joystick
+# undef CONFIG_AJOYSTICK
+# elif defined(CONFIG_SAMA5_EMACA)
+# error EMAC conflicts with the Itead PIO usage
+# undef CONFIG_AJOYSTICK
+# elif defined(CONFIG_SAMA5_SSC0)
+# error SSC0 conflicts with the Itead PIO usage
+# undef CONFIG_AJOYSTICK
+# elif defined(CONFIG_SAMA5_SPI1)
+# warning SPI1 may conflict with the Itead PIO usage
+# elif defined(CONFIG_SAMA5_ISI)
+# warning ISI may conflict with the Itead PIO usage
+# endif
+#endif /* CONFIG_AJOYSTICK */
+
+#ifdef CONFIG_AJOYSTICK
+
+/* Number of Joystick buttons */
+
+#define AJOY_NGPIOS 7
+
+/* Bitset of supported Joystick buttons */
+
+#define AJOY_SUPPORTED (AJOY_BUTTON_1_BIT | AJOY_BUTTON_2_BIT | \
+ AJOY_BUTTON_3_BIT | AJOY_BUTTON_4_BIT | \
+ AJOY_BUTTON_5_BIT | AJOY_BUTTON_6_BIT | \
+ AJOY_BUTTON_7_BIT )
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static ajoy_buttonset_t ajoy_supported(FAR const struct ajoy_lowerhalf_s *lower);
+static int ajoy_sample(FAR const struct ajoy_lowerhalf_s *lower,
+ FAR struct ajoy_sample_s *sample);
+static ajoy_buttonset_t ajoy_buttons(FAR const struct ajoy_lowerhalf_s *lower);
+static void ajoy_enable(FAR const struct ajoy_lowerhalf_s *lower,
+ ajoy_buttonset_t press, ajoy_buttonset_t release,
+ ajoy_handler_t handler, FAR void *arg);
+
+static void ajoy_disable(void);
+static int ajoy_interrupt(int irq, FAR void *context);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Pin configuration for each Itead joystick button. Index using AJOY_*
+ * button definitions in include/nuttx/input/ajoystick.h.
+ */
+
+static const pio_pinset_t g_joypio[AJOY_NGPIOS] =
+{
+ PIO_BUTTON_1, PIO_BUTTON_2, PIO_BUTTON_3, PIO_BUTTON_4,
+ PIO_BUTTON_5, PIO_BUTTON_6, PIO_BUTTON_6
+};
+
+static const uint8_t g_joyirq[AJOY_NGPIOS] =
+{
+ IRQ_BUTTON_1, IRQ_BUTTON_2, IRQ_BUTTON_3, IRQ_BUTTON_4,
+ IRQ_BUTTON_5, IRQ_BUTTON_6, IRQ_BUTTON_6
+};
+
+/* This is the button joystick lower half driver interface */
+
+static const struct ajoy_lowerhalf_s g_ajoylower =
+{
+ .al_supported = ajoy_supported,
+ .al_sample = ajoy_sample,
+ .al_buttons = ajoy_buttons,
+ .al_enable = ajoy_enable,
+};
+
+/* Descriptor for the open ADC driver */
+
+static int g_adcfd = -1;
+
+/* Current interrupt handler and argument */
+
+static ajoy_handler_t g_ajoyhandler;
+static FAR void *g_ajoyarg;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: ajoy_supported
+ *
+ * Description:
+ * Return the set of buttons supported on the button joystick device
+ *
+ ****************************************************************************/
+
+static ajoy_buttonset_t ajoy_supported(FAR const struct ajoy_lowerhalf_s *lower)
+{
+ ivdbg("Supported: %02x\n", AJOY_SUPPORTED);
+ return (ajoy_buttonset_t)AJOY_SUPPORTED;
+}
+
+/****************************************************************************
+ * Name: ajoy_sample
+ *
+ * Description:
+ * Return the current state of all button joystick buttons
+ *
+ ****************************************************************************/
+
+static int ajoy_sample(FAR const struct ajoy_lowerhalf_s *lower,
+ FAR struct ajoy_sample_s *sample)
+{
+ struct adc_msg_s adcmsg[SAM_ADC_NCHANNELS];
+ FAR struct adc_msg_s *ptr;
+ ssize_t nread;
+ ssize_t offset;
+ int have;
+ int i;
+
+ /* Read all of the available samples (handling the case where additional
+ * channels are enabled).
+ */
+
+ nread = read(g_adcfd, adcmsg, SAM_ADC_NCHANNELS * sizeof(struct adc_msg_s));
+ if (nread < 0)
+ {
+ int errcode = get_errno();
+ if (errcode != EINTR)
+ {
+ idbg("ERROR: read failed: %d\n", errcode);
+ }
+
+ return -errcode;
+ }
+ else if (nread < 2 * sizeof(struct adc_msg_s))
+ {
+ idbg("ERROR: read too small: %ld\n", (long)nread);
+ return -EIO;
+ }
+
+ /* Sample and the raw analog inputs */
+
+ for (i = 0, offset = 0, have = 0;
+ i < SAM_ADC_NCHANNELS && offset < nread && have != 3;
+ i++, offset += sizeof(struct adc_msg_s))
+ {
+ ptr = &adcmsg[i];
+
+ /* Is this one of the channels that we need? */
+
+ if ((have & 1) == 0 && ptr->am_channel == 0)
+ {
+ int32_t tmp = ptr->am_data;
+ sample->as_x = (int16_t)tmp;
+ have |= 1;
+
+ ivdbg("X sample: %ld -> %d\n", (long)tmp, (int)sample->as_x);
+ }
+
+ if ((have & 2) == 0 && ptr->am_channel == 1)
+ {
+ int32_t tmp = ptr->am_data;
+ sample->as_y = (int16_t)tmp;
+ have |= 2;
+
+ ivdbg("Y sample: %ld -> %d\n", (long)tmp, (int)sample->as_y);
+ }
+ }
+
+ if (have != 3)
+ {
+ idbg("ERROR: Could not find joystack channels\n");
+ return -EIO;
+ }
+
+
+ /* Sample the discrete button inputs */
+
+ sample->as_buttons = ajoy_buttons(lower);
+ ivdbg("Returning: %02x\n", AJOY_SUPPORTED);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: ajoy_buttons
+ *
+ * Description:
+ * Return the current state of button data (only)
+ *
+ ****************************************************************************/
+
+static ajoy_buttonset_t ajoy_buttons(FAR const struct ajoy_lowerhalf_s *lower)
+{
+ ajoy_buttonset_t ret = 0;
+ ajoy_buttonset_t bit;
+ bool released;
+ int i;
+
+ /* Read each joystick GPIO value */
+
+ for (i = 0; i < AJOY_NGPIOS; i++)
+ {
+ bit = (1 << i);
+ if ((bit & AJOY_SUPPORTED) != 0)
+ {
+ released = sam_pioread(g_joypio[i]);
+ if (!released)
+ {
+ ret |= bit;
+ }
+ }
+ }
+
+ ivdbg("Returning: %02x\n", ret);
+ return ret;
+}
+
+/****************************************************************************
+ * Name: ajoy_enable
+ *
+ * Description:
+ * Enable interrupts on the selected set of joystick buttons. And empty
+ * set will disable all interrupts.
+ *
+ ****************************************************************************/
+
+static void ajoy_enable(FAR const struct ajoy_lowerhalf_s *lower,
+ ajoy_buttonset_t press, ajoy_buttonset_t release,
+ ajoy_handler_t handler, FAR void *arg)
+{
+ irqstate_t flags;
+ ajoy_buttonset_t either = press | release;
+ ajoy_buttonset_t bit;
+ int i;
+
+ /* Start with all interrupts disabled */
+
+ flags = irqsave();
+ ajoy_disable();
+
+ illvdbg("press: %02x release: %02x handler: %p arg: %p\n",
+ press, release, handler, arg);
+
+ /* If no events are indicated or if no handler is provided, then this
+ * must really be a request to disable interrupts.
+ */
+
+ if (either && handler)
+ {
+ /* Save the new the handler and argument */
+
+ g_ajoyhandler = handler;
+ g_ajoyarg = arg;
+
+ /* Check each GPIO. */
+
+ for (i = 0; i < AJOY_NGPIOS; i++)
+ {
+ /* Enable interrupts on each pin that has either a press or
+ * release event associated with it.
+ */
+
+ bit = (1 << i);
+ if ((either & bit) != 0)
+ {
+ /* REVISIT: It would be better if we reconfigured for
+ * the edges of interest so that we do not get spurious
+ * interrupts.
+ */
+
+ sam_pioirqenable(g_joypio[i]);
+ }
+ }
+ }
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: ajoy_disable
+ *
+ * Description:
+ * Disable all joystick interrupts
+ *
+ ****************************************************************************/
+
+static void ajoy_disable(void)
+{
+ irqstate_t flags;
+ int i;
+
+ /* Disable each joystick interrupt */
+
+ flags = irqsave();
+ for (i = 0; i < AJOY_NGPIOS; i++)
+ {
+ sam_pioirqdisable(g_joyirq[i]);
+ }
+
+ irqrestore(flags);
+
+ /* Nullify the handler and argument */
+
+ g_ajoyhandler = NULL;
+ g_ajoyarg = NULL;
+}
+
+/****************************************************************************
+ * Name: ajoy_interrupt
+ *
+ * Description:
+ * Discrete joystick interrupt handler
+ *
+ ****************************************************************************/
+
+static int ajoy_interrupt(int irq, FAR void *context)
+{
+ DEBUGASSERT(g_ajoyhandler);
+ if (g_ajoyhandler)
+ {
+ g_ajoyhandler(&g_ajoylower, g_ajoyarg);
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_ajoy_initialization
+ *
+ * Description:
+ * Initialize and register the button joystick driver
+ *
+ ****************************************************************************/
+
+int sam_ajoy_initialization(void)
+{
+ int ret;
+ int i;
+
+ /* Initialize ADC. We will need this to read the ADC inputs */
+
+ ret = board_adc_initialize();
+ if (ret < 0)
+ {
+ idbg("ERROR: board_adc_initialize() failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Open the ADC driver for reading */
+
+ g_adcfd = open("/dev/adc0", O_RDONLY);
+ if (g_adcfd < 0)
+ {
+ int errcode = get_errno();
+ idbg("ERROR: Failed to open /dev/adc0: %d\n", errcode);
+ return -errcode;
+ }
+
+ /* Configure the GPIO pins as interrupting inputs. */
+
+ for (i = 0; i < AJOY_NGPIOS; i++)
+ {
+ /* Configure the PIO as an input */
+
+ sam_configpio(g_joypio[i]);
+
+ /* Configure PIO interrupts, attach the interrupt handler, but leave
+ * the interrupt disabled.
+ */
+
+ sam_pioirq(g_joypio[i]);
+ (void)irq_attach(g_joyirq[i], ajoy_interrupt);
+ sam_pioirqdisable(g_joyirq[i]);
+ }
+
+ /* Register the joystick device as /dev/ajoy0 */
+
+ ret = ajoy_register("/dev/ajoy0", &g_ajoylower);
+ if (ret < 0)
+ {
+ idbg("ERROR: ajoy_register failed: %d\n", ret);
+ close(g_adcfd);
+ g_adcfd = -1;
+ }
+
+ return ret;
+}
+
+#endif /* CONFIG_AJOYSTICK */
diff --git a/nuttx/configs/sama5d3-xplained/src/sam_nsh.c b/nuttx/configs/sama5d3-xplained/src/sam_nsh.c
index 842d807ae..aad5b8ad2 100644
--- a/nuttx/configs/sama5d3-xplained/src/sam_nsh.c
+++ b/nuttx/configs/sama5d3-xplained/src/sam_nsh.c
@@ -71,7 +71,7 @@
int nsh_archinitialize(void)
{
#if defined(HAVE_NAND) || defined(HAVE_AT25) || defined(HAVE_HSMCI) || \
- defined(HAVE_USBHOST) || defined(HAVE_USBMONITOR)
+ defined(HAVE_USBHOST) || defined(HAVE_USBMONITOR) || defined(CONFIG_AJOYSTICK)
int ret;
#endif
@@ -146,5 +146,16 @@ int nsh_archinitialize(void)
}
#endif
+#ifdef CONFIG_AJOYSTICK
+ /* Initialize and register the joystick driver */
+
+ ret = sam_ajoy_initialization();
+ if (ret != OK)
+ {
+ syslog(LOG_ERR, "ERROR: Failed to register the joystick driver: %d\n", ret);
+ return ret;
+ }
+#endif
+
return OK;
}
diff --git a/nuttx/configs/sama5d3-xplained/src/sama5d3-xplained.h b/nuttx/configs/sama5d3-xplained/src/sama5d3-xplained.h
index 6d24bc53e..154fc564f 100644
--- a/nuttx/configs/sama5d3-xplained/src/sama5d3-xplained.h
+++ b/nuttx/configs/sama5d3-xplained/src/sama5d3-xplained.h
@@ -487,6 +487,90 @@
PIO_PORT_PIOD | PIO_PIN13)
#define AT25_PORT SPI0_CS0
+/* Itead Joystick Shield
+ *
+ * See http://imall.iteadstudio.com/im120417014.html for more information
+ * about this joystick.
+ *
+ * --------- ----------------- ---------------------------------
+ * ARDUINO ITEAD SAMA5D3 XPLAINED
+ * PIN NAME SIGNAL CONNECTOR SIGNAL
+ * --------- ----------------- ---------- ----------------------
+ * D3 Button E Output J18 pin 4 PC8
+ * D4 Button D Output J18 pin 5 PC28
+ * D5 Button C Output J18 pin 6 PC7
+ * D6 Button B Output J18 pin 7 PC6
+ * D7 Button A Output J18 pin 8 PC5
+ * D8 Button F Output J15 pin 1 PC4
+ * D9 Button G Output J15 pin 2 PC3
+ * A0 Joystick Y Output J17 pin 1 PC18 AD0 (function 4)
+ * A1 Joystick X Output J17 pin 2 PD21 AD1 (function 1)
+ * --------- ----------------- ---------- ----------------------
+ */
+
+#define ADC_XOUPUT 1 /* X output is on ADC channel 1 */
+#define ADC_YOUPUT 0 /* Y output is on ADC channel 0 */
+
+#define PIO_BUTTON_A (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \
+ PIO_INT_BOTHEDGES | PIO_PORT_PIOC | PIO_PIN5)
+#define IRQ_BUTTON_A SAM_IRQ_PC5
+#define PIO_BUTTON_B (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \
+ PIO_INT_BOTHEDGES | PIO_PORT_PIOC | PIO_PIN6)
+#define IRQ_BUTTON_B SAM_IRQ_PC6
+#define PIO_BUTTON_C (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \
+ PIO_INT_BOTHEDGES | PIO_PORT_PIOC | PIO_PIN7)
+#define IRQ_BUTTON_C SAM_IRQ_PC7
+#define PIO_BUTTON_D (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \
+ PIO_INT_BOTHEDGES | PIO_PORT_PIOC | PIO_PIN28)
+#define IRQ_BUTTON_D SAM_IRQ_PC28
+#define PIO_BUTTON_E (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \
+ PIO_INT_BOTHEDGES | PIO_PORT_PIOC | PIO_PIN8)
+#define IRQ_BUTTON_E SAM_IRQ_PC8
+#define PIO_BUTTON_F (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \
+ PIO_INT_BOTHEDGES | PIO_PORT_PIOC | PIO_PIN4)
+#define IRQ_BUTTON_F SAM_IRQ_PC4
+#define PIO_BUTTON_G (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \
+ PIO_INT_BOTHEDGES | PIO_PORT_PIOC | PIO_PIN3)
+#define IRQ_BUTTON_G SAM_IRQ_PC3
+
+/* Itead Joystick Signal interpretation:
+ *
+ * --------- ----------------------- ---------------------------
+ * BUTTON TYPE NUTTX ALIAS
+ * --------- ----------------------- ---------------------------
+ * Button A Large button A JUMP/BUTTON 3
+ * Button B Large button B FIRE/BUTTON 2
+ * Button C Joystick select button SELECT/BUTTON 1
+ * Button D Tiny Button D BUTTON 6
+ * Button E Tiny Button E BUTTON 7
+ * Button F Large Button F BUTTON 4
+ * Button G Large Button G BUTTON 5
+ * --------- ----------------------- ---------------------------
+ */
+
+#define PIO_BUTTON_1 PIO_BUTTON_C
+#define IRQ_BUTTON_1 IRQ_BUTTON_C
+#define PIO_BUTTON_2 PIO_BUTTON_B
+#define IRQ_BUTTON_2 IRQ_BUTTON_B
+#define PIO_BUTTON_3 PIO_BUTTON_A
+#define IRQ_BUTTON_3 IRQ_BUTTON_A
+#define PIO_BUTTON_4 PIO_BUTTON_F
+#define IRQ_BUTTON_4 IRQ_BUTTON_F
+#define PIO_BUTTON_5 PIO_BUTTON_G
+#define IRQ_BUTTON_5 IRQ_BUTTON_G
+#define PIO_BUTTON_6 PIO_BUTTON_D
+#define IRQ_BUTTON_6 IRQ_BUTTON_D
+#define PIO_BUTTON_7 PIO_BUTTON_E
+#define IRQ_BUTTON_7 IRQ_BUTTON_E
+
+#define PIO_SELECT PIO_BUTTON_1
+#define IRQ_SELECT IRQ_BUTTON_1
+#define PIO_FIRE PIO_BUTTON_2
+#define IRQ_FIRE IRQ_BUTTON_2
+#define PIO_JUMP PIO_BUTTON_3
+#define IRQ_JUMP IRQ_BUTTON_3
+
+
/************************************************************************************
* Public Types
************************************************************************************/
@@ -673,6 +757,18 @@ void board_led_initialize(void);
int nsh_archinitialize(void);
#endif
+/************************************************************************************
+ * Name: board_adc_initialize
+ *
+ * Description:
+ * Initialize and register the ADC driver
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_SAMA5_ADC
+int board_adc_initialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_SAMA5D3_XPLAINED_SRC_SAMA5D3_XPLAINED_H */
diff --git a/nuttx/drivers/input/ajoystick.c b/nuttx/drivers/input/ajoystick.c
index 1054b8ca3..9f2416c46 100644
--- a/nuttx/drivers/input/ajoystick.c
+++ b/nuttx/drivers/input/ajoystick.c
@@ -396,9 +396,9 @@ static int ajoy_open(FAR struct file *filep)
{
FAR struct inode *inode;
FAR struct ajoy_upperhalf_s *priv;
- FAR const struct ajoy_lowerhalf_s *lower;
FAR struct ajoy_open_s *opriv;
#ifndef CONFIG_DISABLE_POLL
+ FAR const struct ajoy_lowerhalf_s *lower;
ajoy_buttonset_t supported;
#endif
int ret;