From f127495caa2d45a1b1fff3be7a9d3756259d23e2 Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 11 Jan 2013 02:14:43 -0800 Subject: Manually fixup merge botches via direct comparison with NuttX r5447. --- nuttx/drivers/Kconfig | 76 ++- nuttx/drivers/Makefile | 27 +- nuttx/drivers/analog/adc.c | 15 +- nuttx/drivers/input/max11802.c | 1313 ++++++++++++++++++++++++++++++++++++ nuttx/drivers/input/max11802.h | 167 +++++ nuttx/drivers/lcd/Kconfig | 81 ++- nuttx/drivers/lcd/ug-9664hswag01.c | 15 +- nuttx/drivers/mmcsd/mmcsd_sdio.c | 5 + nuttx/drivers/mmcsd/mmcsd_spi.c | 11 +- nuttx/drivers/net/e1000.c | 307 ++++----- nuttx/drivers/net/e1000.h | 4 +- nuttx/drivers/net/vnet.c | 333 +++++---- nuttx/drivers/usbdev/pl2303.c | 2 +- nuttx/drivers/usbdev/usbmsc.h | 2 +- 14 files changed, 1963 insertions(+), 395 deletions(-) create mode 100644 nuttx/drivers/input/max11802.c create mode 100644 nuttx/drivers/input/max11802.h (limited to 'nuttx/drivers') diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig index 1d263ec14..8302d21b7 100644 --- a/nuttx/drivers/Kconfig +++ b/nuttx/drivers/Kconfig @@ -47,7 +47,8 @@ config CAN_EXTID bool "CAN extended IDs" default n ---help--- - Enables support for the 29-bit extended ID. Default Standard 11-bit IDs. + Enables support for the 29-bit extended ID. Default Standard 11-bit + IDs. config CAN_FIFOSIZE int "CAN driver I/O buffer size" @@ -83,10 +84,10 @@ config PWM_PULSECOUNT bool "PWM Pulse Count Support" default n ---help--- - Some hardware will support generation of a fixed number of pulses. This - might be used, for example to support a stepper motor. If the hardware - will support a fixed pulse count, then this configuration should be set to - enable the capability. + Some hardware will support generation of a fixed number of pulses. + This might be used, for example to support a stepper motor. If the + hardware will support a fixed pulse count, then this configuration + should be set to enable the capability. endif @@ -147,23 +148,25 @@ config SPI_OWNBUS bool "SPI single device" default n ---help--- - Set if there is only one active device on the SPI bus. No locking or SPI - configuration will be performed. It is not necessary for clients to lock, - re-configure, etc.. + Set if there is only one active device on the SPI bus. No locking or + SPI configuration will be performed. It is not necessary for clients to + lock, re-configure, etc.. config SPI_EXCHANGE bool "SPI exchange" default y ---help--- - Driver supports a single exchange method (vs a recvblock() and sndblock ()methods). + Driver supports a single exchange method (vs a recvblock() and + sndblock() methods). config SPI_CMDDATA bool "SPI CMD/DATA" default n ---help--- - Devices on the SPI bus require out-of-band support to distinguish command - transfers from data transfers. Such devices will often support either 9-bit - SPI (yech) or 8-bit SPI and a GPIO output that selects between command and data. + Devices on the SPI bus require out-of-band support to distinguish + command transfers from data transfers. Such devices will often support + either 9-bit SPI (yech) or 8-bit SPI and a GPIO output that selects + between command and data. endif @@ -173,35 +176,36 @@ menuconfig RTC ---help--- This selection enables configuration of a real time clock (RTCdriver. See include/nuttx/rtc.h for further watchdog timer driver information. - Most RTC drivers are MCU specific and may require other specific settings. + Most RTC drivers are MCU specific and may require other specific + settings. config RTC_DATETIME bool "Date/Time RTC Support" default n depends on RTC ---help--- - There are two general types of RTC: (1) A simple battery backed counter - that keeps the time when power is down, and (2) a full date / time RTC the - provides the date and time information, often in BCD format. If - RTC_DATETIME is selected, it specifies this second kind of RTC. In this - case, the RTC is used to "seed" the normal NuttX timer and the NuttX system - timer provides for higher resolution time. + There are two general types of RTC: (1) A simple battery backed + counter that keeps the time when power is down, and (2) a full + date / time RTC the provides the date and time information, often in + BCD format. If RTC_DATETIME is selected, it specifies this second kind + of RTC. In this case, the RTC is used to "seed" the normal NuttX timer + and the NuttX system timer provides for higher resolution time. config RTC_HIRES bool "Hi-Res RTC Support" default n depends on RTC && !RTC_DATETIME ---help--- - If RTC_DATETIME not selected, then the simple, battery backed counter is - used. There are two different implementations of such simple counters - based on the time resolution of the counter: The typical RTC keeps time - to resolution of 1 second, usually supporting a 32-bit time_t value. In - this case, the RTC is used to "seed" the normal NuttX timer and the NuttX - timer provides for higherresoution time. + If RTC_DATETIME not selected, then the simple, battery backed counter + is used. There are two different implementations of such simple + counters based on the time resolution of the counter: The typical RTC + keeps time to resolution of 1 second, usually supporting a 32-bit + time_t value. In this case, the RTC is used to "seed" the normal NuttX + timer and the NuttX timer provides for higherresoution time. - If RTC_HIRES is enabled in the NuttX configuration, then the RTC provides - higher resolution time and completely replaces the system timer for purpose - of date and time. + If RTC_HIRES is enabled in the NuttX configuration, then the RTC + provides higher resolution time and completely replaces the system + timer for purpose of date and time. config RTC_FREQUENCY int "Hi-Res RTC frequency" @@ -209,8 +213,8 @@ config RTC_FREQUENCY depends on RTC && !RTC_DATETIME && RTC_HIRES ---help--- If RTC_HIRES is defined, then the frequency of the high resolution RTC - must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is assumed - to be one Hz. + must be provided. If RTC_HIRES is not defined, RTC_FREQUENCY is + assumed to be one Hz. config RTC_ALARM bool "RTC Alarm Support" @@ -224,8 +228,9 @@ menuconfig WATCHDOG bool "Watchdog Timer Support" default n ---help--- - This selection enables building of the "upper-half" watchdog timer driver. - See include/nuttx/watchdog.h for further watchdog timer driver information. + This selection enables building of the "upper-half" watchdog timer + driver. See include/nuttx/watchdog.h for further watchdog timer driver + information. if WATCHDOG endif @@ -348,7 +353,8 @@ menuconfig POWER bool "Power Management Support" default n ---help--- - Enable building of power-related devices (battery monitors, chargers, etc). + Enable building of power-related devices (battery monitors, chargers, + etc). if POWER source drivers/power/Kconfig @@ -386,8 +392,8 @@ menuconfig SERIAL default y ---help--- Front-end character drivers for chip-specific UARTs. This provide - some TTY-like functionality and are commonly used (but not required for) - the NuttX system console. See also include/nuttx/serial/serial.h + some TTY-like functionality and are commonly used (but not required + for) the NuttX system console. See also include/nuttx/serial/serial.h if SERIAL source drivers/serial/Kconfig diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index 6d3b40b1f..aaaa67bd7 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -86,15 +86,15 @@ ifeq ($(CONFIG_WATCHDOG),y) endif endif -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -BIN = libdrivers$(LIBEXT) +BIN = libdrivers$(LIBEXT) -all: $(BIN) +all: $(BIN) $(AOBJS): %$(OBJEXT): %.S $(call ASSEMBLE, $<, $@) @@ -102,22 +102,21 @@ $(AOBJS): %$(OBJEXT): %.S $(COBJS): %$(OBJEXT): %.c $(call COMPILE, $<, $@) -$(BIN): $(OBJS) - @( for obj in $(OBJS) ; do \ - $(call ARCHIVE, $@, $${obj}); \ - done ; ) +$(BIN): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) .depend: Makefile $(SRCS) - @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep - @touch $@ + $(Q) $(MKDEP) $(DEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ depend: .depend clean: - @rm -f $(BIN) *~ .*.swp + $(call DELFILE, $(BIN)) $(call CLEAN) distclean: clean - @rm -f Make.dep .depend + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) -include Make.dep diff --git a/nuttx/drivers/analog/adc.c b/nuttx/drivers/analog/adc.c index 84070f162..72f19452a 100644 --- a/nuttx/drivers/analog/adc.c +++ b/nuttx/drivers/analog/adc.c @@ -143,7 +143,7 @@ static int adc_open(FAR struct file *filep) dev->ad_recv.af_head = 0; dev->ad_recv.af_tail = 0; - /* Finally, Enable the CAN RX interrupt */ + /* Finally, Enable the ADC RX interrupt */ dev->ad_ops->ao_rxint(dev, true); @@ -151,9 +151,11 @@ static int adc_open(FAR struct file *filep) dev->ad_ocount = tmp; } + irqrestore(flags); } } + sem_post(&dev->ad_closesem); } return ret; @@ -370,6 +372,10 @@ static int adc_ioctl(FAR struct file *filep, int cmd, unsigned long arg) * Public Functions ****************************************************************************/ +/**************************************************************************** + * Name: adc_receive + ****************************************************************************/ + int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) { FAR struct adc_fifo_s *fifo = &dev->ad_recv; @@ -390,7 +396,7 @@ int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) if (nexttail != fifo->af_head) { - /* Add the new, decoded CAN message at the tail of the FIFO */ + /* Add the new, decoded ADC sample at the tail of the FIFO */ fifo->af_buffer[fifo->af_tail].am_channel = ch; fifo->af_buffer[fifo->af_tail].am_data = data; @@ -403,11 +409,16 @@ int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data) { sem_post(&fifo->af_sem); } + err = OK; } return err; } +/**************************************************************************** + * Name: adc_register + ****************************************************************************/ + int adc_register(FAR const char *path, FAR struct adc_dev_s *dev) { /* Initialize the ADC device structure */ diff --git a/nuttx/drivers/input/max11802.c b/nuttx/drivers/input/max11802.c new file mode 100644 index 000000000..ea3883cd0 --- /dev/null +++ b/nuttx/drivers/input/max11802.c @@ -0,0 +1,1313 @@ +/**************************************************************************** + * drivers/input/max11802.c + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Petteri Aimonen + * + * References: + * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers + * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 + * + * 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 + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "max11802.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* This is a value for the threshold that guantees a big difference on the + * first pendown (but can't overflow). + */ + +#define INVALID_THRESHOLD 0x1000 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ +/* Low-level SPI helpers */ + +#ifdef CONFIG_SPI_OWNBUS +static inline void max11802_configspi(FAR struct spi_dev_s *spi); +# define max11802_lock(spi) +# define max11802_unlock(spi) +#else +# define max11802_configspi(spi); +static void max11802_lock(FAR struct spi_dev_s *spi); +static void max11802_unlock(FAR struct spi_dev_s *spi); +#endif + +static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, uint8_t cmd, int *tags); + +/* Interrupts and data sampling */ + +static void max11802_notify(FAR struct max11802_dev_s *priv); +static int max11802_sample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample); +static int max11802_waitsample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample); +static void max11802_worker(FAR void *arg); +static int max11802_interrupt(int irq, FAR void *context); + +/* Character driver methods */ + +static int max11802_open(FAR struct file *filep); +static int max11802_close(FAR struct file *filep); +static ssize_t max11802_read(FAR struct file *filep, FAR char *buffer, size_t len); +static int max11802_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int max11802_poll(FAR struct file *filep, struct pollfd *fds, bool setup); +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This the the vtable that supports the character driver interface */ + +static const struct file_operations max11802_fops = +{ + max11802_open, /* open */ + max11802_close, /* close */ + max11802_read, /* read */ + 0, /* write */ + 0, /* seek */ + max11802_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , max11802_poll /* poll */ +#endif +}; + +/* If only a single MAX11802 device is supported, then the driver state + * structure may as well be pre-allocated. + */ + +#ifndef CONFIG_MAX11802_MULTIPLE +static struct max11802_dev_s g_max11802; + +/* Otherwise, we will need to maintain allocated driver instances in a list */ + +#else +static struct max11802_dev_s *g_max11802list; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: max11802_lock + * + * Description: + * Lock the SPI bus and re-configure as necessary. This function must be + * to assure: (1) exclusive access to the SPI bus, and (2) to assure that + * the shared bus is properly configured for the touchscreen controller. + * + * Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static void max11802_lock(FAR struct spi_dev_s *spi) +{ + /* Lock the SPI bus because there are multiple devices competing for the + * SPI bus + */ + + (void)SPI_LOCK(spi, true); + + /* We have the lock. Now make sure that the SPI bus is configured for the + * MAX11802 (it might have gotten configured for a different device while + * unlocked) + */ + + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); + SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE); + SPI_SETBITS(spi, 8); + SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY); + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); +} +#endif + +/**************************************************************************** + * Function: max11802_unlock + * + * Description: + * If we are sharing the SPI bus with other devices (CONFIG_SPI_OWNBUS + * undefined) then we need to un-lock the SPI bus for each transfer, + * possibly losing the current configuration. + * + * Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static void max11802_unlock(FAR struct spi_dev_s *spi) +{ + /* Relinquish the SPI bus. */ + + (void)SPI_LOCK(spi, false); +} +#endif + +/**************************************************************************** + * Function: max11802_configspi + * + * Description: + * Configure the SPI for use with the MAX11802. This function should be + * called once during touchscreen initialization to configure the SPI + * bus. Note that if CONFIG_SPI_OWNBUS is not defined, then this function + * does nothing. + * + * Parameters: + * spi - Reference to the SPI driver structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_SPI_OWNBUS +static inline void max11802_configspi(FAR struct spi_dev_s *spi) +{ + /* Configure SPI for the MAX11802. But only if we own the SPI bus. Otherwise, don't + * bother because it might change. + */ + + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true); + SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE); + SPI_SETBITS(spi, 8); + SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY); + SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false); +} +#endif + +/**************************************************************************** + * Name: max11802_sendcmd + ****************************************************************************/ + +static uint16_t max11802_sendcmd(FAR struct max11802_dev_s *priv, uint8_t cmd, int *tags) +{ + uint8_t buffer[2]; + uint16_t result; + + /* Select the MAX11802 */ + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + + /* Send the command */ + + (void)SPI_SEND(priv->spi, cmd); + + /* Read the data */ + + SPI_RECVBLOCK(priv->spi, buffer, 2); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1]; + *tags = result & 0xF; + result >>= 4; // Get rid of tags + + ivdbg("cmd:%02x response:%04x\n", cmd, result); + return result; +} + +/**************************************************************************** + * Name: max11802_notify + ****************************************************************************/ + +static void max11802_notify(FAR struct max11802_dev_s *priv) +{ +#ifndef CONFIG_DISABLE_POLL + int i; +#endif + + /* If there are threads waiting for read data, then signal one of them + * that the read data is available. + */ + + if (priv->nwaiters > 0) + { + /* After posting this semaphore, we need to exit because the sample + * is no longer available. + */ + + sem_post(&priv->waitsem); + } + + /* If there are threads waiting on poll() for MAX11802 data to become available, + * then wake them up now. NOTE: we wake up all waiting threads because we + * do not know that they are going to do. If they all try to read the data, + * then some make end up blocking after all. + */ + +#ifndef CONFIG_DISABLE_POLL + for (i = 0; i < CONFIG_MAX11802_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + ivdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +#endif +} + +/**************************************************************************** + * Name: max11802_sample + ****************************************************************************/ + +static int max11802_sample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample) +{ + irqstate_t flags; + int ret = -EAGAIN; + + /* Interrupts must be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + */ + + flags = irqsave(); + + /* Is there new MAX11802 sample data available? */ + + if (priv->penchange) + { + /* Yes.. the state has changed in some way. Return a copy of the + * sampled data. + */ + + memcpy(sample, &priv->sample, sizeof(struct max11802_sample_s )); + + /* Now manage state transitions */ + + if (sample->contact == CONTACT_UP) + { + /* Next.. no contact. Increment the ID so that next contact ID + * will be unique. X/Y positions are no longer valid. + */ + + priv->sample.contact = CONTACT_NONE; + priv->sample.valid = false; + priv->id++; + } + else if (sample->contact == CONTACT_DOWN) + { + /* First report -- next report will be a movement */ + + priv->sample.contact = CONTACT_MOVE; + } + + priv->penchange = false; + ret = OK; + } + + irqrestore(flags); + return ret; +} + +/**************************************************************************** + * Name: max11802_waitsample + ****************************************************************************/ + +static int max11802_waitsample(FAR struct max11802_dev_s *priv, + FAR struct max11802_sample_s *sample) +{ + irqstate_t flags; + int ret; + + /* Interrupts must be disabled when this is called to (1) prevent posting + * of semaphores from interrupt handlers, and (2) to prevent sampled data + * from changing until it has been reported. + * + * In addition, we will also disable pre-emption to prevent other threads + * from getting control while we muck with the semaphores. + */ + + sched_lock(); + flags = irqsave(); + + /* Now release the semaphore that manages mutually exclusive access to + * the device structure. This may cause other tasks to become ready to + * run, but they cannot run yet because pre-emption is disabled. + */ + + sem_post(&priv->devsem); + + /* Try to get the a sample... if we cannot, then wait on the semaphore + * that is posted when new sample data is available. + */ + + while (max11802_sample(priv, sample) < 0) + { + /* Wait for a change in the MAX11802 state */ + + ivdbg("Waiting..\n"); + priv->nwaiters++; + ret = sem_wait(&priv->waitsem); + priv->nwaiters--; + + if (ret < 0) + { + /* If we are awakened by a signal, then we need to return + * the failure now. + */ + + idbg("sem_wait: %d\n", errno); + DEBUGASSERT(errno == EINTR); + ret = -EINTR; + goto errout; + } + } + + ivdbg("Sampled\n"); + + /* Re-acquire the the semaphore that manages mutually exclusive access to + * the device structure. We may have to wait here. But we have our sample. + * Interrupts and pre-emption will be re-enabled while we wait. + */ + + ret = sem_wait(&priv->devsem); + +errout: + /* Then re-enable interrupts. We might get interrupt here and there + * could be a new sample. But no new threads will run because we still + * have pre-emption disabled. + */ + + irqrestore(flags); + + /* Restore pre-emption. We might get suspended here but that is okay + * because we already have our sample. Note: this means that if there + * were two threads reading from the MAX11802 for some reason, the data + * might be read out of order. + */ + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: max11802_schedule + ****************************************************************************/ + +static int max11802_schedule(FAR struct max11802_dev_s *priv) +{ + FAR struct max11802_config_s *config; + int ret; + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* Disable further interrupts. MAX11802 interrupts will be re-enabled + * after the worker thread executes. + */ + + config->enable(config, false); + + /* Disable the watchdog timer. It will be re-enabled in the worker thread + * while the pen remains down. + */ + + wd_cancel(priv->wdog); + + /* Transfer processing to the worker thread. Since MAX11802 interrupts are + * disabled while the work is pending, no special action should be required + * to protected the work queue. + */ + + DEBUGASSERT(priv->work.worker == NULL); + ret = work_queue(HPWORK, &priv->work, max11802_worker, priv, 0); + if (ret != 0) + { + illdbg("Failed to queue work: %d\n", ret); + } + + return OK; +} + +/**************************************************************************** + * Name: max11802_wdog + ****************************************************************************/ + +static void max11802_wdog(int argc, uint32_t arg1, ...) +{ + FAR struct max11802_dev_s *priv = (FAR struct max11802_dev_s *)((uintptr_t)arg1); + (void)max11802_schedule(priv); +} + +/**************************************************************************** + * Name: max11802_worker + ****************************************************************************/ + +static void max11802_worker(FAR void *arg) +{ + FAR struct max11802_dev_s *priv = (FAR struct max11802_dev_s *)arg; + FAR struct max11802_config_s *config; + uint16_t x; + uint16_t y; + uint16_t xdiff; + uint16_t ydiff; + bool pendown; + int ret; + int tags, tags2; + + ASSERT(priv != NULL); + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* Disable the watchdog timer. This is safe because it is started only + * by this function and this function is serialized on the worker thread. + */ + + wd_cancel(priv->wdog); + + /* Lock the SPI bus so that we have exclusive access */ + + max11802_lock(priv->spi); + + /* Start coordinate measurement */ + (void)max11802_sendcmd(priv, MAX11802_CMD_MEASUREXY, &tags); + + /* Get exclusive access to the driver data structure */ + + do + { + ret = sem_wait(&priv->devsem); + + /* This should only fail if the wait was canceled by an signal + * (and the worker thread will receive a lot of signals). + */ + + DEBUGASSERT(ret == OK || errno == EINTR); + } + while (ret < 0); + + /* Check for pen up or down by reading the PENIRQ GPIO. */ + + pendown = config->pendown(config); + + /* Handle the change from pen down to pen up */ + + if (pendown) + ivdbg("\nPD\n"); + else + ivdbg("\nPU\n"); + + if (!pendown) + { + /* The pen is up.. reset thresholding variables. */ + + priv->threshx = INVALID_THRESHOLD; + priv->threshy = INVALID_THRESHOLD; + + /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up + * and already reported; CONTACT_UP == pen up, but not reported) + */ + + ivdbg("\nPC%d\n", priv->sample.contact); + + if (priv->sample.contact == CONTACT_NONE || + priv->sample.contact == CONTACT_UP) + + { + goto ignored; + } + + /* The pen is up. NOTE: We know from a previous test, that this is a + * loss of contact condition. This will be changed to CONTACT_NONE + * after the loss of contact is sampled. + */ + + priv->sample.contact = CONTACT_UP; + } + + /* It is a pen down event. If the last loss-of-contact event has not been + * processed yet, then we have to ignore the pen down event (or else it will + * look like a drag event) + */ + + else if (priv->sample.contact == CONTACT_UP) + { + /* If we have not yet processed the last pen up event, then we + * cannot handle this pen down event. We will have to discard it. That + * should be okay because we will set the timer to to sample again + * later. + */ + + ivdbg("Previous pen up event still in buffer\n"); + max11802_notify(priv); + wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, (uint32_t)priv); + goto ignored; + } + else + { + /* Wait for data ready */ + do { + /* Handle pen down events. First, sample positional values. */ + +#ifdef CONFIG_MAX11802_SWAPXY + x = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags); + y = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags2); +#else + x = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags); + y = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags2); +#endif + } while (tags == 0xF || tags2 == 0xF); + + /* Continue to sample the position while the pen is down */ + wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, (uint32_t)priv); + + /* Check if data is valid */ + if ((tags & 0x03) != 0) + { + ivdbg("Touch ended before measurement\n"); + goto ignored; + } + + /* Perform a thresholding operation so that the results will be more stable. + * If the difference from the last sample is small, then ignore the event. + * REVISIT: Should a large change in pressure also generate a event? + */ + + xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x); + ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y); + + /* Check the thresholds. Bail if there is no significant difference */ + + if (xdiff < CONFIG_MAX11802_THRESHX && ydiff < CONFIG_MAX11802_THRESHY) + { + /* Little or no change in either direction ... don't report anything. */ + + goto ignored; + } + + /* When we see a big difference, snap to the new x/y thresholds */ + + priv->threshx = x; + priv->threshy = y; + + /* Update the x/y position in the sample data */ + + priv->sample.x = priv->threshx; + priv->sample.y = priv->threshy; + + /* The X/Y positional data is now valid */ + + priv->sample.valid = true; + + /* If this is the first (acknowledged) pen down report, then report + * this as the first contact. If contact == CONTACT_DOWN, it will be + * set to set to CONTACT_MOVE after the contact is first sampled. + */ + + if (priv->sample.contact != CONTACT_MOVE) + { + /* First contact */ + + priv->sample.contact = CONTACT_DOWN; + } + } + + /* Indicate the availability of new sample data for this ID */ + + priv->sample.id = priv->id; + priv->penchange = true; + + /* Notify any waiters that new MAX11802 data is available */ + + max11802_notify(priv); + +ignored: + config->enable(config, true); + + /* Release our lock on the state structure and unlock the SPI bus */ + + sem_post(&priv->devsem); + max11802_unlock(priv->spi); +} + +/**************************************************************************** + * Name: max11802_interrupt + ****************************************************************************/ + +static int max11802_interrupt(int irq, FAR void *context) +{ + FAR struct max11802_dev_s *priv; + FAR struct max11802_config_s *config; + int ret; + + /* Which MAX11802 device caused the interrupt? */ + +#ifndef CONFIG_MAX11802_MULTIPLE + priv = &g_max11802; +#else + for (priv = g_max11802list; + priv && priv->configs->irq != irq; + priv = priv->flink); + + ASSERT(priv != NULL); +#endif + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* Schedule sampling to occur on the worker thread */ + + ret = max11802_schedule(priv); + + /* Clear any pending interrupts and return success */ + + config->clear(config); + return ret; +} + +/**************************************************************************** + * Name: max11802_open + ****************************************************************************/ + +static int max11802_open(FAR struct file *filep) +{ +#ifdef CONFIG_MAX11802_REFCNT + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + uint8_t tmp; + int ret; + + ivdbg("Opening\n"); + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Increment the reference count */ + + tmp = priv->crefs + 1; + if (tmp == 0) + { + /* More than 255 opens; uint8_t overflows to zero */ + + ret = -EMFILE; + goto errout_with_sem; + } + + /* When the reference increments to 1, this is the first open event + * on the driver.. and an opportunity to do any one-time initialization. + */ + + /* Save the new open count on success */ + + priv->crefs = tmp; + +errout_with_sem: + sem_post(&priv->devsem); + return ret; +#else + ivdbg("Opening\n"); + return OK; +#endif +} + +/**************************************************************************** + * Name: max11802_close + ****************************************************************************/ + +static int max11802_close(FAR struct file *filep) +{ +#ifdef CONFIG_MAX11802_REFCNT + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + int ret; + + ivdbg("Closing\n"); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Decrement the reference count unless it would decrement a negative + * value. When the count decrements to zero, there are no further + * open references to the driver. + */ + + if (priv->crefs >= 1) + { + priv->crefs--; + } + + sem_post(&priv->devsem); +#endif + ivdbg("Closing\n"); + return OK; +} + +/**************************************************************************** + * Name: max11802_read + ****************************************************************************/ + +static ssize_t max11802_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + FAR struct touch_sample_s *report; + struct max11802_sample_s sample; + int ret; + + ivdbg("buffer:%p len:%d\n", buffer, len); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Verify that the caller has provided a buffer large enough to receive + * the touch data. + */ + + if (len < SIZEOF_TOUCH_SAMPLE_S(1)) + { + /* We could provide logic to break up a touch report into segments and + * handle smaller reads... but why? + */ + + idbg("Unsupported read size: %d\n", len); + return -ENOSYS; + } + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + idbg("sem_wait: %d\n", errno); + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Try to read sample data. */ + + ret = max11802_sample(priv, &sample); + if (ret < 0) + { + /* Sample data is not available now. We would ave to wait to get + * receive sample data. If the user has specified the O_NONBLOCK + * option, then just return an error. + */ + + ivdbg("Sample data is not available\n"); + if (filep->f_oflags & O_NONBLOCK) + { + ret = -EAGAIN; + goto errout; + } + + /* Wait for sample data */ + + ret = max11802_waitsample(priv, &sample); + if (ret < 0) + { + /* We might have been awakened by a signal */ + + idbg("max11802_waitsample: %d\n", ret); + goto errout; + } + } + + /* In any event, we now have sampled MAX11802 data that we can report + * to the caller. + */ + + report = (FAR struct touch_sample_s *)buffer; + memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); + report->npoints = 1; + report->point[0].id = sample.id; + report->point[0].x = sample.x; + report->point[0].y = sample.y; + + /* Report the appropriate flags */ + + if (sample.contact == CONTACT_UP) + { + /* Pen is now up. Is the positional data valid? This is important to + * know because the release will be sent to the window based on its + * last positional data. + */ + + if (sample.valid) + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + else + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; + } + } + else if (sample.contact == CONTACT_DOWN) + { + /* First contact */ + + report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + else /* if (sample->contact == CONTACT_MOVE) */ + { + /* Movement of the same contact */ + + report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID; + } + + ivdbg(" id: %d\n", report->point[0].id); + ivdbg(" flags: %02x\n", report->point[0].flags); + ivdbg(" x: %d\n", report->point[0].x); + ivdbg(" y: %d\n", report->point[0].y); + + ret = SIZEOF_TOUCH_SAMPLE_S(1); + +errout: + sem_post(&priv->devsem); + ivdbg("Returning: %d\n", ret); + return ret; +} + +/**************************************************************************** + * Name:max11802_ioctl + ****************************************************************************/ + +static int max11802_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + int ret; + + ivdbg("cmd: %d arg: %ld\n", cmd, arg); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Process the IOCTL by command */ + + switch (cmd) + { + case TSIOC_SETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ + { + FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); + DEBUGASSERT(priv->config != NULL && ptr != NULL); + priv->config->frequency = SPI_SETFREQUENCY(priv->spi, *ptr); + } + break; + + case TSIOC_GETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ + { + FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); + DEBUGASSERT(priv->config != NULL && ptr != NULL); + *ptr = priv->config->frequency; + } + break; + + default: + ret = -ENOTTY; + break; + } + + sem_post(&priv->devsem); + return ret; +} + +/**************************************************************************** + * Name: max11802_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int max11802_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct max11802_dev_s *priv; + pollevent_t eventset; + int ndx; + int ret = OK; + int i; + + ivdbg("setup: %d\n", (int)setup); + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct max11802_dev_s *)inode->i_private; + + /* Are we setting up the poll? Or tearing it down? */ + + ret = sem_wait(&priv->devsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + if (setup) + { + /* Ignore waits that do not include POLLIN */ + + if ((fds->events & POLLIN) == 0) + { + ret = -EDEADLK; + goto errout; + } + + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_MAX11802_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!priv->fds[i]) + { + /* Bind the poll structure and this slot */ + + priv->fds[i] = fds; + fds->priv = &priv->fds[i]; + break; + } + } + + if (i >= CONFIG_MAX11802_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should we immediately notify on any of the requested events? */ + + if (priv->penchange) + { + max11802_notify(priv); + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot != NULL); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&priv->devsem); + return ret; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: max11802_register + * + * Description: + * Configure the MAX11802 to use the provided SPI device instance. This + * will register the driver as /dev/inputN where N is the minor device + * number + * + * Input Parameters: + * dev - An SPI driver instance + * config - Persistent board configuration data + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int max11802_register(FAR struct spi_dev_s *spi, + FAR struct max11802_config_s *config, int minor) +{ + FAR struct max11802_dev_s *priv; + char devname[DEV_NAMELEN]; +#ifdef CONFIG_MAX11802_MULTIPLE + irqstate_t flags; +#endif + int ret; + + ivdbg("spi: %p minor: %d\n", spi, minor); + + /* Debug-only sanity checks */ + + DEBUGASSERT(spi != NULL && config != NULL && minor >= 0 && minor < 100); + + /* Create and initialize a MAX11802 device driver instance */ + +#ifndef CONFIG_MAX11802_MULTIPLE + priv = &g_max11802; +#else + priv = (FAR struct max11802_dev_s *)kmalloc(sizeof(struct max11802_dev_s)); + if (!priv) + { + idbg("kmalloc(%d) failed\n", sizeof(struct max11802_dev_s)); + return -ENOMEM; + } +#endif + + /* Initialize the MAX11802 device driver instance */ + + memset(priv, 0, sizeof(struct max11802_dev_s)); + priv->spi = spi; /* Save the SPI device handle */ + priv->config = config; /* Save the board configuration */ + priv->wdog = wd_create(); /* Create a watchdog timer */ + priv->threshx = INVALID_THRESHOLD; /* Initialize thresholding logic */ + priv->threshy = INVALID_THRESHOLD; /* Initialize thresholding logic */ + + sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */ + sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */ + + /* Make sure that interrupts are disabled */ + + config->clear(config); + config->enable(config, false); + + /* Attach the interrupt handler */ + + ret = config->attach(config, max11802_interrupt); + if (ret < 0) + { + idbg("Failed to attach interrupt\n"); + goto errout_with_priv; + } + + idbg("Mode: %d Bits: 8 Frequency: %d\n", + CONFIG_MAX11802_SPIMODE, CONFIG_MAX11802_FREQUENCY); + + /* Lock the SPI bus so that we have exclusive access */ + + max11802_lock(spi); + + /* Configure the SPI interface */ + + max11802_configspi(spi); + + /* Configure MAX11802 registers */ + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_WR); + (void)SPI_SEND(priv->spi, MAX11802_MODE); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_AVG_WR); + (void)SPI_SEND(priv->spi, MAX11802_AVG); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_TIMING_WR); + (void)SPI_SEND(priv->spi, MAX11802_TIMING); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_DELAY_WR); + (void)SPI_SEND(priv->spi, MAX11802_DELAY); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + /* Test that the device access was successful. */ + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true); + (void)SPI_SEND(priv->spi, MAX11802_CMD_MODE_RD); + ret = SPI_SEND(priv->spi, 0); + SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false); + + /* Unlock the bus */ + max11802_unlock(spi); + + if (ret != MAX11802_MODE) + { + idbg("max11802 mode readback failed: %02x\n", ret); + goto errout_with_priv; + } + + /* Register the device as an input device */ + + (void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); + ivdbg("Registering %s\n", devname); + + ret = register_driver(devname, &max11802_fops, 0666, priv); + if (ret < 0) + { + idbg("register_driver() failed: %d\n", ret); + goto errout_with_priv; + } + + /* If multiple MAX11802 devices are supported, then we will need to add + * this new instance to a list of device instances so that it can be + * found by the interrupt handler based on the recieved IRQ number. + */ + +#ifdef CONFIG_MAX11802_MULTIPLE + priv->flink = g_max11802list; + g_max11802list = priv; + irqrestore(flags); +#endif + + /* Schedule work to perform the initial sampling and to set the data + * availability conditions. + */ + + ret = work_queue(HPWORK, &priv->work, max11802_worker, priv, 0); + if (ret != 0) + { + idbg("Failed to queue work: %d\n", ret); + goto errout_with_priv; + } + + /* And return success (?) */ + + return OK; + +errout_with_priv: + sem_destroy(&priv->devsem); +#ifdef CONFIG_MAX11802_MULTIPLE + kfree(priv); +#endif + return ret; +} diff --git a/nuttx/drivers/input/max11802.h b/nuttx/drivers/input/max11802.h new file mode 100644 index 000000000..b6beec045 --- /dev/null +++ b/nuttx/drivers/input/max11802.h @@ -0,0 +1,167 @@ +/******************************************************************************************** + * drivers/input/max11802.h + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Petteri Aimonen + * + * References: + * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers + * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010 + * + * 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. + * + ********************************************************************************************/ + +#ifndef __DRIVERS_INPUT_MAX11802_H +#define __DRIVERS_INPUT_MAX11802_H + +/******************************************************************************************** + * Included Files + ********************************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +/******************************************************************************************** + * Pre-Processor Definitions + ********************************************************************************************/ +/* Configuration ****************************************************************************/ + +/* MAX11802 Interfaces *********************************************************************/ + +/* LSB of register addresses specifies read (1) or write (0). */ +#define MAX11802_CMD_XPOSITION ((0x52 << 1) | 1) +#define MAX11802_CMD_YPOSITION ((0x54 << 1) | 1) +#define MAX11802_CMD_MEASUREXY (0x70 << 1) +#define MAX11802_CMD_MODE_WR (0x0B << 1) +#define MAX11802_CMD_MODE_RD ((0x0B << 1) | 1) +#define MAX11802_CMD_AVG_WR (0x03 << 1) +#define MAX11802_CMD_TIMING_WR (0x05 << 1) +#define MAX11802_CMD_DELAY_WR (0x06 << 1) + +/* Register values to set */ +#define MAX11802_MODE 0x0E +#define MAX11802_AVG 0x55 +#define MAX11802_TIMING 0x77 +#define MAX11802_DELAY 0x55 + +/* Driver support **************************************************************************/ +/* This format is used to construct the /dev/input[n] device driver path. It + * defined here so that it will be used consistently in all places. + */ + +#define DEV_FORMAT "/dev/input%d" +#define DEV_NAMELEN 16 + +/* Poll the pen position while the pen is down at this rate (50MS): */ + +#define MAX11802_WDOG_DELAY ((50 + (MSEC_PER_TICK-1))/ MSEC_PER_TICK) + +/******************************************************************************************** + * Public Types + ********************************************************************************************/ + +/* This describes the state of one contact */ + +enum max11802_contact_3 +{ + CONTACT_NONE = 0, /* No contact */ + CONTACT_DOWN, /* First contact */ + CONTACT_MOVE, /* Same contact, possibly different position */ + CONTACT_UP, /* Contact lost */ +}; + +/* This structure describes the results of one MAX11802 sample */ + +struct max11802_sample_s +{ + uint8_t id; /* Sampled touch point ID */ + uint8_t contact; /* Contact state (see enum ads7843e_contact_e) */ + bool valid; /* True: x,y contain valid, sampled data */ + uint16_t x; /* Measured X position */ + uint16_t y; /* Measured Y position */ +}; + +/* This structure describes the state of one MAX11802 driver instance */ + +struct max11802_dev_s +{ +#ifdef CONFIG_ADS7843E_MULTIPLE + FAR struct ads7843e_dev_s *flink; /* Supports a singly linked list of drivers */ +#endif + uint8_t nwaiters; /* Number of threads waiting for MAX11802 data */ + uint8_t id; /* Current touch point ID */ + volatile bool penchange; /* An unreported event is buffered */ + uint16_t threshx; /* Thresholding X value */ + uint16_t threshy; /* Thresholding Y value */ + sem_t devsem; /* Manages exclusive access to this structure */ + sem_t waitsem; /* Used to wait for the availability of data */ + + FAR struct max11802_config_s *config; /* Board configuration data */ + FAR struct spi_dev_s *spi; /* Saved SPI driver instance */ + struct work_s work; /* Supports the interrupt handling "bottom half" */ + struct max11802_sample_s sample; /* Last sampled touch point data */ + WDOG_ID wdog; /* Poll the position while the pen is down */ + + /* The following is a list if poll structures of threads waiting for + * driver events. The 'struct pollfd' reference for each open is also + * retained in the f_priv field of the 'struct file'. + */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_ADS7843E_NPOLLWAITERS]; +#endif +}; + +/******************************************************************************************** + * Public Function Prototypes + ********************************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __DRIVERS_INPUT_ADS7843E_H */ diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig index 640239e63..2d20003ac 100644 --- a/nuttx/drivers/lcd/Kconfig +++ b/nuttx/drivers/lcd/Kconfig @@ -183,12 +183,85 @@ config NOKIA6100_RGBORD endif config LCD_UG9664HSWAG01 - bool "9664HSWAG01 OLED Display Module" + bool "UG-9664HSWAG01 OLED Display Module" default n ---help--- - ug-9664hswag01.c. OLED Display Module, UG-9664HSWAG01", Univision - Technology Inc. Used with the LPC Xpresso and Embedded Artists - base board. + OLED Display Module, UG-9664HSWAG01, Univision Technology Inc. Used + with the LPCXpresso and Embedded Artists base board. + + Required LCD driver settings: + LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + LCD_MAXPOWER should be 1: 0=off, 1=on + + Required SPI driver settings: + SPI_CMDDATA - Include support for cmd/data selection. + +if LCD_UG9664HSWAG01 + +config UG9664HSWAG01_SPIMODE + int "UG-9664HSWAG01 SPI Mode" + default 0 + ---help--- + Controls the SPI mode + +config UG9664HSWAG01_FREQUENCY + int "UG-9664HSWAG01 SPI Frequency" + default 3500000 + ---help--- + Define to use a different bus frequency + +config UG9664HSWAG01_NINTERFACES + int "Number of UG-9664HSWAG01 Devices" + default 1 + ---help--- + Specifies the number of physical UG-9664HSWAG01 devices that will be + supported. NOTE: At present, this must be undefined or defined to be 1. + +config UG9664HSWAG01_POWER + bool "Power control" + default n + ---help--- + If the hardware supports a controllable OLED a power supply, this + configuration should be defined. In this case the system must + provide an interface ug_power(). + +endif + +config LCD_UG2864AMBAG01 + bool "UG-2864AMBAG01 OLED Display Module" + default n + ---help--- + OLED Display Module, UG-2864AMBAG01, Univision Technology Inc. + + Required LCD driver settings: + LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted. + LCD_MAXPOWER should be 1: 0=off, 1=on + + Required SPI driver settings: + SPI_CMDDATA - Include support for cmd/data selection. + +if LCD_UG2864AMBAG01 + + config UG2864AMBAG01_SPIMODE + int "UG-2864AMBAG01 SPI Mode" + default 3 + ---help--- + Controls the SPI mode + +config UG2864AMBAG01_FREQUENCY + int "UG-2864AMBAG01 SPI Frequency" + default 3500000 + ---help--- + Define to use a different bus frequency + +config UG2864AMBAG01_NINTERFACES + int "Number of UG-2864AMBAG01 Devices" + default 1 + ---help--- + Specifies the number of physical UG-9664HSWAG01 devices that will be + supported. NOTE: At present, this must be undefined or defined to be 1. + +endif config LCD_SSD1289 bool "LCD Based on SSD1289 Controller" diff --git a/nuttx/drivers/lcd/ug-9664hswag01.c b/nuttx/drivers/lcd/ug-9664hswag01.c index e0e8e8e3a..6ef78fca6 100644 --- a/nuttx/drivers/lcd/ug-9664hswag01.c +++ b/nuttx/drivers/lcd/ug-9664hswag01.c @@ -73,8 +73,6 @@ * CONFIG_UG9664HSWAG01_POWER * If the hardware supports a controllable OLED a power supply, this * configuration shold be defined. (See ug_power() below). - * CONFIG_LCD_UGDEBUG - Enable detailed UG-9664HSWAG01 debug output - * (CONFIG_DEBUG and CONFIG_VERBOSE must also be enabled). * * Required LCD driver settings: * CONFIG_LCD_UG9664HSWAG01 - Enable UG-9664HSWAG01 support @@ -119,11 +117,10 @@ #ifndef CONFIG_DEBUG # undef CONFIG_DEBUG_VERBOSE -# undef CONFIG_DEBUG_GRAPHICS #endif #ifndef CONFIG_DEBUG_VERBOSE -# undef CONFIG_LCD_UGDEBUG +# undef CONFIG_DEBUG_LCD #endif /* Check contrast selection */ @@ -182,7 +179,7 @@ #define UG_BPP 1 #define UG_COLORFMT FB_FMT_Y1 -/* Bytes per logical row andactual device row */ +/* Bytes per logical row and actual device row */ #define UG_XSTRIDE (UG_XRES >> 3) /* Pixels arrange "horizontally for user" */ #define UG_YSTRIDE (UG_YRES >> 3) /* But actual device arrangement is "vertical" */ @@ -198,10 +195,10 @@ /* Debug ******************************************************************************/ -#ifdef CONFIG_LCD_UGDEBUG -# define ugdbg(format, arg...) vdbg(format, ##arg) +#ifdef CONFIG_DEBUG_LCD +# define lcddbg(format, arg...) vdbg(format, ##arg) #else -# define ugdbg(x...) +# define lcddbg(x...) #endif /************************************************************************************** @@ -997,7 +994,7 @@ FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devn SPI_CMDDATA(spi, SPIDEV_DISPLAY, true); - /* Set the starting position for the run */ + /* Configure the device */ (void)SPI_SEND(spi, SSD1305_SETCOLL + 2); /* Set low column address */ (void)SPI_SEND(spi, SSD1305_SETCOLH + 2); /* Set high column address */ diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c index b17ae077d..3caa61583 100644 --- a/nuttx/drivers/mmcsd/mmcsd_sdio.c +++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c @@ -38,6 +38,9 @@ ****************************************************************************/ #include + +#if defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SDIO) + #include #include @@ -3179,3 +3182,5 @@ errout_with_alloc: kfree(priv); return ret; } + +#endif /* defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SDIO) */ diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c index 7dbadc55f..d437b7fea 100644 --- a/nuttx/drivers/mmcsd/mmcsd_spi.c +++ b/nuttx/drivers/mmcsd/mmcsd_spi.c @@ -38,6 +38,9 @@ ****************************************************************************/ #include + +#if defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SPI) + #include #include @@ -508,7 +511,7 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, } break; - /* The R3 response is 5 bytes long */ + /* The R3 response is 5 bytes long. The first byte is identical to R1. */ case MMCSD_CMDRESP_R3: { @@ -520,8 +523,10 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, fvdbg("CMD%d[%08x] R1=%02x OCR=%08x\n", cmd->cmd & 0x3f, arg, response, slot->ocr); } + break; + + /* The R7 response is 5 bytes long. The first byte is identical to R1. */ - /* The R7 response is 5 bytes long */ case MMCSD_CMDRESP_R7: default: { @@ -1876,3 +1881,5 @@ int mmcsd_spislotinitialize(int minor, int slotno, FAR struct spi_dev_s *spi) (void)SPI_REGISTERCALLBACK(spi, mmcsd_mediachanged, (void*)slot); return OK; } + +#endif /* defined (CONFIG_MMCSD) && defined (CONFIG_MMCSD_SPI) */ diff --git a/nuttx/drivers/net/e1000.c b/nuttx/drivers/net/e1000.c index ec2b29b6a..cae6f39b4 100644 --- a/nuttx/drivers/net/e1000.c +++ b/nuttx/drivers/net/e1000.c @@ -60,6 +60,7 @@ #include #include #include +#include #include #include #include "e1000.h" @@ -104,9 +105,9 @@ struct e1000_dev { uint32_t io_mem_base; uint32_t mem_size; int pci_dev_id; + uint16_t pci_addr; unsigned char src_mac[6]; unsigned char dst_mac[6]; - int irq; struct irq_action int_desc; struct tx_ring tx_ring; struct rx_ring rx_ring; @@ -308,16 +309,16 @@ void e1000_init(struct e1000_dev *dev) e1000_outl(dev, E1000_FCRTH, pba*9/10); // setup tx rings - txd_phys = PADDR(dev->tx_ring.desc); - kmem_phys = PADDR(dev->tx_ring.buf); + txd_phys = PADDR((uintptr_t)dev->tx_ring.desc); + kmem_phys = PADDR((uintptr_t)dev->tx_ring.buf); for (i=0; itx_ring.desc[i].base_address = kmem_phys; - dev->tx_ring.desc[i].packet_length = 0; - dev->tx_ring.desc[i].cksum_offset = 0; - dev->tx_ring.desc[i].cksum_origin = 0; - dev->tx_ring.desc[i].desc_status = 1; - dev->tx_ring.desc[i].desc_command = (1<<0)|(1<<1)|(1<<3); - dev->tx_ring.desc[i].special_info = 0; + dev->tx_ring.desc[i].base_address = kmem_phys; + dev->tx_ring.desc[i].packet_length = 0; + dev->tx_ring.desc[i].cksum_offset = 0; + dev->tx_ring.desc[i].cksum_origin = 0; + dev->tx_ring.desc[i].desc_status = 1; + dev->tx_ring.desc[i].desc_command = (1<<0)|(1<<1)|(1<<3); + dev->tx_ring.desc[i].special_info = 0; } dev->tx_ring.tail = 0; e1000_outl(dev, E1000_TDT, 0); @@ -329,15 +330,15 @@ void e1000_init(struct e1000_dev *dev) e1000_outl(dev, E1000_TXDCTL, 0x01010000); // setup rx rings - rxd_phys = PADDR(dev->rx_ring.desc); - kmem_phys = PADDR(dev->rx_ring.buf); + rxd_phys = PADDR((uintptr_t)dev->rx_ring.desc); + kmem_phys = PADDR((uintptr_t)dev->rx_ring.buf); for (i=0; irx_ring.desc[i].base_address = kmem_phys; - dev->rx_ring.desc[i].packet_length = 0; - dev->rx_ring.desc[i].packet_cksum = 0; - dev->rx_ring.desc[i].desc_status = 0; - dev->rx_ring.desc[i].desc_errors = 0; - dev->rx_ring.desc[i].vlan_tag = 0; + dev->rx_ring.desc[i].base_address = kmem_phys; + dev->rx_ring.desc[i].packet_length = 0; + dev->rx_ring.desc[i].packet_cksum = 0; + dev->rx_ring.desc[i].desc_status = 0; + dev->rx_ring.desc[i].desc_errors = 0; + dev->rx_ring.desc[i].vlan_tag = 0; } dev->rx_ring.head = 0; dev->rx_ring.tail = CONFIG_E1000_N_RX_DESC-1; @@ -378,7 +379,7 @@ static int e1000_transmit(struct e1000_dev *e1000) { int tail = e1000->tx_ring.tail; unsigned char *cp = (unsigned char *) - (e1000->tx_ring.buf + tail * CONFIG_E1000_BUFF_SIZE); + (e1000->tx_ring.buf + tail * CONFIG_E1000_BUFF_SIZE); int count = e1000->uip_dev.d_len; /* Verify that the hardware is ready to send another packet. If we get @@ -387,7 +388,7 @@ static int e1000_transmit(struct e1000_dev *e1000) */ if (!e1000->tx_ring.desc[tail].desc_status) - return -1; + return -1; /* Increment statistics */ @@ -445,14 +446,14 @@ static int e1000_uiptxpoll(struct uip_driver_s *dev) */ if (e1000->uip_dev.d_len > 0) { - uip_arp_out(&e1000->uip_dev); - e1000_transmit(e1000); - - /* Check if there is room in the device to hold another packet. If not, - * return a non-zero value to terminate the poll. - */ - if (!e1000->tx_ring.desc[tail].desc_status) - return -1; + uip_arp_out(&e1000->uip_dev); + e1000_transmit(e1000); + + /* Check if there is room in the device to hold another packet. If not, + * return a non-zero value to terminate the poll. + */ + if (!e1000->tx_ring.desc[tail].desc_status) + return -1; } /* If zero is returned, the polling will continue until all connections have @@ -483,75 +484,75 @@ static void e1000_receive(struct e1000_dev *e1000) { int head = e1000->rx_ring.head; unsigned char *cp = (unsigned char *) - (e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); + (e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); int cnt; while (e1000->rx_ring.desc[head].desc_status) { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - // Here we do not handle packets that exceed packet-buffer size - if ((e1000->rx_ring.desc[head].desc_status & 3) == 1) { - cprintf("NIC READ: Oversized packet\n"); - goto next; - } + // Here we do not handle packets that exceed packet-buffer size + if ((e1000->rx_ring.desc[head].desc_status & 3) == 1) { + cprintf("NIC READ: Oversized packet\n"); + goto next; + } - /* Check if the packet is a valid size for the uIP buffer configuration */ + /* Check if the packet is a valid size for the uIP buffer configuration */ - // get the number of actual data-bytes in this packet - cnt = e1000->rx_ring.desc[head].packet_length; + // get the number of actual data-bytes in this packet + cnt = e1000->rx_ring.desc[head].packet_length; - if (cnt > CONFIG_NET_BUFSIZE || cnt < 14) { - cprintf("NIC READ: invalid package size\n"); - goto next; - } + if (cnt > CONFIG_NET_BUFSIZE || cnt < 14) { + cprintf("NIC READ: invalid package size\n"); + goto next; + } - /* Copy the data data from the hardware to e1000->uip_dev.d_buf. Set - * amount of data in e1000->uip_dev.d_len - */ + /* Copy the data data from the hardware to e1000->uip_dev.d_buf. Set + * amount of data in e1000->uip_dev.d_len + */ - // now we try to copy these data-bytes to the UIP buffer - memcpy(e1000->uip_dev.d_buf, cp, cnt); - e1000->uip_dev.d_len = cnt; + // now we try to copy these data-bytes to the UIP buffer + memcpy(e1000->uip_dev.d_buf, cp, cnt); + e1000->uip_dev.d_len = cnt; - /* We only accept IP packets of the configured type and ARP packets */ + /* We only accept IP packets of the configured type and ARP packets */ #ifdef CONFIG_NET_IPv6 - if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) #else - if (BUF->type == HTONS(UIP_ETHTYPE_IP)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP)) #endif - { - uip_arp_ipin(&e1000->uip_dev); - uip_input(&e1000->uip_dev); - - /* If the above function invocation resulted in data that should be - * sent out on the network, the field d_len will set to a value > 0. - */ - - if (e1000->uip_dev.d_len > 0) { - uip_arp_out(&e1000->uip_dev); - e1000_transmit(e1000); - } - } - else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { - uip_arp_arpin(&e1000->uip_dev); - - /* If the above function invocation resulted in data that should be - * sent out on the network, the field d_len will set to a value > 0. - */ - - if (e1000->uip_dev.d_len > 0) { - e1000_transmit(e1000); - } - } + { + uip_arp_ipin(&e1000->uip_dev); + uip_input(&e1000->uip_dev); + + /* If the above function invocation resulted in data that should be + * sent out on the network, the field d_len will set to a value > 0. + */ + + if (e1000->uip_dev.d_len > 0) { + uip_arp_out(&e1000->uip_dev); + e1000_transmit(e1000); + } + } + else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { + uip_arp_arpin(&e1000->uip_dev); + + /* If the above function invocation resulted in data that should be + * sent out on the network, the field d_len will set to a value > 0. + */ + + if (e1000->uip_dev.d_len > 0) { + e1000_transmit(e1000); + } + } next: - e1000->rx_ring.desc[head].desc_status = 0; - e1000->rx_ring.head = (head + 1) % CONFIG_E1000_N_RX_DESC; - e1000->rx_ring.free++; - head = e1000->rx_ring.head; - cp = (unsigned char *)(e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); + e1000->rx_ring.desc[head].desc_status = 0; + e1000->rx_ring.head = (head + 1) % CONFIG_E1000_N_RX_DESC; + e1000->rx_ring.free++; + head = e1000->rx_ring.head; + cp = (unsigned char *)(e1000->rx_ring.buf + head * CONFIG_E1000_BUFF_SIZE); } } @@ -615,7 +616,7 @@ static void e1000_polltimer(int argc, uint32_t arg, ...) * the TX poll if he are unable to accept another packet for transmission. */ if (!e1000->tx_ring.desc[tail].desc_status) - return; + return; /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. * might be bug here. Does this mean if there is a transmit in progress, @@ -651,8 +652,8 @@ static int e1000_ifup(struct uip_driver_s *dev) struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; ndbg("Bringing up: %d.%d.%d.%d\n", - dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, - (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); + dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, + (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ e1000_init(e1000); @@ -662,9 +663,9 @@ static int e1000_ifup(struct uip_driver_s *dev) (void)wd_start(e1000->txpoll, E1000_WDDELAY, e1000_polltimer, 1, (uint32_t)e1000); if (e1000_inl(e1000, E1000_STATUS) & 2) - e1000->bifup = true; + e1000->bifup = true; else - e1000->bifup = false; + e1000->bifup = false; return OK; } @@ -749,9 +750,9 @@ static int e1000_txavail(struct uip_driver_s *dev) /* Ignore the notification if the interface is not yet up */ if (e1000->bifup) { - /* Check if there is room in the hardware to hold another outgoing packet. */ - if (e1000->tx_ring.desc[tail].desc_status) - (void)uip_poll(&e1000->uip_dev, e1000_uiptxpoll); + /* Check if there is room in the hardware to hold another outgoing packet. */ + if (e1000->tx_ring.desc[tail].desc_status) + (void)uip_poll(&e1000->uip_dev, e1000_uiptxpoll); } irqrestore(flags); @@ -779,11 +780,11 @@ static int e1000_txavail(struct uip_driver_s *dev) #ifdef CONFIG_NET_IGMP static int e1000_addmac(struct uip_driver_s *dev, const uint8_t *mac) { - struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; + struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -808,15 +809,15 @@ static int e1000_addmac(struct uip_driver_s *dev, const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int e1000_rmmac(struct uip_driver_s *dev, const uint8_t *mac) { - struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; + struct e1000_dev *e1000 = (struct e1000_dev *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif -irqreturn_t e1000_interrupt_handler(struct Trapframe *tf, void *dev_id) +static irqreturn_t e1000_interrupt_handler(int irq, void *dev_id) { struct e1000_dev *e1000 = (struct e1000_dev *)dev_id; @@ -826,27 +827,27 @@ irqreturn_t e1000_interrupt_handler(struct Trapframe *tf, void *dev_id) // not for me if (intr_cause == 0) - return IRQ_NONE; + return IRQ_NONE; /* Handle interrupts according to status bit settings */ // Link status change if (intr_cause & (1<<2)) { - if (e1000_inl(e1000, E1000_STATUS) & 2) - e1000->bifup = true; - else - e1000->bifup = false; + if (e1000_inl(e1000, E1000_STATUS) & 2) + e1000->bifup = true; + else + e1000->bifup = false; } /* Check if we received an incoming packet, if so, call skel_receive() */ // Rx-descriptor Timer expired if (intr_cause & (1<<7)) - e1000_receive(e1000); + e1000_receive(e1000); // Tx queue empty if (intr_cause & (1<<1)) - wd_cancel(e1000->txtimeout); + wd_cancel(e1000->txtimeout); /* Check is a packet transmission just completed. If so, call skel_txdone. * This may disable further Tx interrupts if there are no pending @@ -855,17 +856,17 @@ irqreturn_t e1000_interrupt_handler(struct Trapframe *tf, void *dev_id) // Tx-descriptor Written back if (intr_cause & (1<<0)) - uip_poll(&e1000->uip_dev, e1000_uiptxpoll); + uip_poll(&e1000->uip_dev, e1000_uiptxpoll); // Rx-Descriptors Low if (intr_cause & (1<<4)) { - int tail; - tail = e1000->rx_ring.tail + e1000->rx_ring.free; - tail %= CONFIG_E1000_N_RX_DESC; - e1000->rx_ring.tail = tail; - e1000->rx_ring.free = 0; - e1000_outl(e1000, E1000_RDT, tail); + int tail; + tail = e1000->rx_ring.tail + e1000->rx_ring.free; + tail %= CONFIG_E1000_N_RX_DESC; + e1000->rx_ring.tail = tail; + e1000->rx_ring.free = 0; + e1000_outl(e1000, E1000_RDT, tail); } return IRQ_HANDLED; @@ -885,20 +886,21 @@ static pci_id_t e1000_id_table[] = { static int e1000_probe(uint16_t addr, pci_id_t id) { uint32_t mmio_base, mmio_size; - uint32_t pci_cmd, size; - int err, irq, flags; + uint32_t size; + int err; void *kmem, *omem; struct e1000_dev *dev; // alloc e1000_dev memory - dev = kzalloc(sizeof(struct e1000_dev)); - if (dev == NULL) - return -1; + if ((dev = kzalloc(sizeof(struct e1000_dev))) == NULL) + return -1; + + // save pci addr + dev->pci_addr = addr; // enable device - err = pci_enable_device(addr, PCI_RESOURCE_MEM); - if (err) - goto error; + if ((err = pci_enable_device(addr, PCI_BUS_MASTER)) < 0) + goto error; // get e1000 device type dev->pci_dev_id = id.join; @@ -908,33 +910,20 @@ static int e1000_probe(uint16_t addr, pci_id_t id) mmio_size = pci_resource_len(addr, 0); err = rgmp_memmap_nocache(mmio_base, mmio_size, mmio_base); if (err) - goto error; + goto error; dev->phy_mem_base = mmio_base; dev->io_mem_base = mmio_base; dev->mem_size = mmio_size; - // make sure the controller's Bus Master capability is enabled - pci_cmd = pci_config_readl(addr, PCI_COMMAND); - pci_cmd |= (1<<2); - pci_config_writel(addr, PCI_COMMAND, pci_cmd); - // MAC address memset(dev->dst_mac, 0xFF, 6); memcpy(dev->src_mac, (void *)(dev->io_mem_base+E1000_RA), 6); - // get e1000 IRQ - flags = 0; - irq = pci_enable_msi(addr); - if (irq == 0) { - irq = pci_read_irq(addr); - flags |= IDC_SHARE; - } - dev->irq = irq; + // IRQ setup dev->int_desc.handler = e1000_interrupt_handler; dev->int_desc.dev_id = dev; - err = rgmp_request_irq(irq, &dev->int_desc, flags); - if (err) - goto err0; + if ((err = pci_request_irq(addr, &dev->int_desc, 0)) < 0) + goto err0; // Here we alloc a big block of memory once and make it // aligned to page boundary and multiple of page size. This @@ -942,15 +931,19 @@ static int e1000_probe(uint16_t addr, pci_id_t id) // should be mapped no-cache which will hugely reduce memory // access performance. The page size alloc will restrict // this bad effect only within the memory we alloc here. + // + // NEED FIX: the memalign may alloc memory continous in + // virtual address but dis-continous in physical address + // due to RGMP memory setup. size = CONFIG_E1000_N_TX_DESC * sizeof(struct tx_desc) + - CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + - CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + - CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; + CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + + CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + + CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; size = ROUNDUP(size, PGSIZE); omem = kmem = memalign(PGSIZE, size); if (kmem == NULL) { - err = -ENOMEM; - goto err1; + err = -ENOMEM; + goto err1; } rgmp_memremap_nocache((uintptr_t)kmem, size); @@ -991,7 +984,7 @@ static int e1000_probe(uint16_t addr, pci_id_t id) /* Register the device with the OS so that socket IOCTLs can be performed */ err = netdev_register(&dev->uip_dev); if (err) - goto err2; + goto err2; // insert into e1000_list dev->next = e1000_list.next; @@ -1000,14 +993,14 @@ static int e1000_probe(uint16_t addr, pci_id_t id) return 0; - err2: +err2: rgmp_memremap((uintptr_t)omem, size); free(omem); - err1: - rgmp_free_irq(irq, &dev->int_desc); - err0: +err1: + pci_free_irq(addr); +err0: rgmp_memunmap(mmio_base, mmio_size); - error: +error: kfree(dev); cprintf("e1000 device probe fail: %d\n", err); return err; @@ -1028,21 +1021,21 @@ void e1000_mod_exit(void) struct e1000_dev *dev; size = CONFIG_E1000_N_TX_DESC * sizeof(struct tx_desc) + - CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + - CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + - CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; + CONFIG_E1000_N_TX_DESC * CONFIG_E1000_BUFF_SIZE + + CONFIG_E1000_N_RX_DESC * sizeof(struct rx_desc) + + CONFIG_E1000_N_RX_DESC * CONFIG_E1000_BUFF_SIZE; size = ROUNDUP(size, PGSIZE); for (dev=e1000_list.next; dev!=NULL; dev=dev->next) { - netdev_unregister(&dev->uip_dev); - e1000_reset(dev); - wd_delete(dev->txpoll); - wd_delete(dev->txtimeout); - rgmp_memremap((uintptr_t)dev->tx_ring.desc, size); - free(dev->tx_ring.desc); - rgmp_free_irq(dev->irq, &dev->int_desc); - rgmp_memunmap((uintptr_t)dev->io_mem_base, dev->mem_size); - kfree(dev); + netdev_unregister(&dev->uip_dev); + e1000_reset(dev); + wd_delete(dev->txpoll); + wd_delete(dev->txtimeout); + rgmp_memremap((uintptr_t)dev->tx_ring.desc, size); + free(dev->tx_ring.desc); + pci_free_irq(dev->pci_addr); + rgmp_memunmap((uintptr_t)dev->io_mem_base, dev->mem_size); + kfree(dev); } e1000_list.next = NULL; diff --git a/nuttx/drivers/net/e1000.h b/nuttx/drivers/net/e1000.h index 6614ad77e..63ff53e3c 100644 --- a/nuttx/drivers/net/e1000.h +++ b/nuttx/drivers/net/e1000.h @@ -44,9 +44,7 @@ * Included Files ****************************************************************************/ -#include -#include -#include +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/drivers/net/vnet.c b/nuttx/drivers/net/vnet.c index f1e2465b9..e05a39675 100644 --- a/nuttx/drivers/net/vnet.c +++ b/nuttx/drivers/net/vnet.c @@ -168,30 +168,30 @@ static int vnet_transmit(FAR struct vnet_driver_s *vnet) { int err; - /* Verify that the hardware is ready to send another packet. If we get - * here, then we are committed to sending a packet; Higher level logic - * must have assured that there is not transmission in progress. - */ + /* Verify that the hardware is ready to send another packet. If we get + * here, then we are committed to sending a packet; Higher level logic + * must have assured that there is not transmission in progress. + */ - /* Increment statistics */ + /* Increment statistics */ - /* Send the packet: address=vnet->sk_dev.d_buf, length=vnet->sk_dev.d_len */ + /* Send the packet: address=vnet->sk_dev.d_buf, length=vnet->sk_dev.d_len */ err = vnet_xmit(vnet->vnet, (char *)vnet->sk_dev.d_buf, vnet->sk_dev.d_len); if (err) { - /* Setup the TX timeout watchdog (perhaps restarting the timer) */ - //(void)wd_start(vnet->sk_txtimeout, VNET_TXTIMEOUT, vnet_txtimeout, 1, (uint32_t)vnet); + /* Setup the TX timeout watchdog (perhaps restarting the timer) */ + //(void)wd_start(vnet->sk_txtimeout, VNET_TXTIMEOUT, vnet_txtimeout, 1, (uint32_t)vnet); - // When vnet_xmit fail, it means TX buffer is full. Watchdog - // is of no use here because no TX done INT will happen. So - // we reset the TX buffer directly. + // When vnet_xmit fail, it means TX buffer is full. Watchdog + // is of no use here because no TX done INT will happen. So + // we reset the TX buffer directly. #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - return ERROR; + return ERROR; } else { - // this step may be unnecessary here - vnet_txdone(vnet); + // this step may be unnecessary here + vnet_txdone(vnet); } return OK; @@ -223,29 +223,29 @@ static int vnet_transmit(FAR struct vnet_driver_s *vnet) static int vnet_uiptxpoll(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* If the polling resulted in data that should be sent out on the network, - * the field d_len is set to a value > 0. - */ + /* If the polling resulted in data that should be sent out on the network, + * the field d_len is set to a value > 0. + */ - if (vnet->sk_dev.d_len > 0) + if (vnet->sk_dev.d_len > 0) { - uip_arp_out(&vnet->sk_dev); - vnet_transmit(vnet); - - /* Check if there is room in the device to hold another packet. If not, - * return a non-zero value to terminate the poll. - */ - if (vnet_is_txbuff_full(vnet->vnet)) - return 1; + uip_arp_out(&vnet->sk_dev); + vnet_transmit(vnet); + + /* Check if there is room in the device to hold another packet. If not, + * return a non-zero value to terminate the poll. + */ + if (vnet_is_txbuff_full(vnet->vnet)) + return 1; } - /* If zero is returned, the polling will continue until all connections have - * been examined. - */ + /* If zero is returned, the polling will continue until all connections have + * been examined. + */ - return 0; + return 0; } /**************************************************************************** @@ -265,54 +265,53 @@ static int vnet_uiptxpoll(struct uip_driver_s *dev) * ****************************************************************************/ -void rtos_vnet_recv(struct rgmp_vnet *vnet_dummy, char *data, int len) +void rtos_vnet_recv(struct rgmp_vnet *rgmp_vnet, char *data, int len) { - // now only support 1 vnet - struct vnet_driver_s *vnet = &g_vnet[0]; + struct vnet_driver_s *vnet = rgmp_vnet->priv; do { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - /* Check if the packet is a valid size for the uIP buffer configuration */ - if (len > CONFIG_NET_BUFSIZE || len < 14) { + /* Check if the packet is a valid size for the uIP buffer configuration */ + if (len > CONFIG_NET_BUFSIZE || len < 14) { #ifdef CONFIG_DEBUG - cprintf("VNET: receive invalid packet of size %d\n", len); + cprintf("VNET: receive invalid packet of size %d\n", len); #endif - return; - } + return; + } - // Copy the data data from the hardware to vnet->sk_dev.d_buf. Set - // amount of data in vnet->sk_dev.d_len - memcpy(vnet->sk_dev.d_buf, data, len); - vnet->sk_dev.d_len = len; + // Copy the data data from the hardware to vnet->sk_dev.d_buf. Set + // amount of data in vnet->sk_dev.d_len + memcpy(vnet->sk_dev.d_buf, data, len); + vnet->sk_dev.d_len = len; - /* We only accept IP packets of the configured type and ARP packets */ + /* We only accept IP packets of the configured type and ARP packets */ #ifdef CONFIG_NET_IPv6 - if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP6)) #else - if (BUF->type == HTONS(UIP_ETHTYPE_IP)) + if (BUF->type == HTONS(UIP_ETHTYPE_IP)) #endif - { - uip_arp_ipin(&vnet->sk_dev); - uip_input(&vnet->sk_dev); - - // If the above function invocation resulted in data that should be - // sent out on the network, the field d_len will set to a value > 0. - if (vnet->sk_dev.d_len > 0) { - uip_arp_out(&vnet->sk_dev); - vnet_transmit(vnet); - } - } - else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { - uip_arp_arpin(&vnet->sk_dev); - - // If the above function invocation resulted in data that should be - // sent out on the network, the field d_len will set to a value > 0. - if (vnet->sk_dev.d_len > 0) { - vnet_transmit(vnet); - } - } + { + uip_arp_ipin(&vnet->sk_dev); + uip_input(&vnet->sk_dev); + + // If the above function invocation resulted in data that should be + // sent out on the network, the field d_len will set to a value > 0. + if (vnet->sk_dev.d_len > 0) { + uip_arp_out(&vnet->sk_dev); + vnet_transmit(vnet); + } + } + else if (BUF->type == htons(UIP_ETHTYPE_ARP)) { + uip_arp_arpin(&vnet->sk_dev); + + // If the above function invocation resulted in data that should be + // sent out on the network, the field d_len will set to a value > 0. + if (vnet->sk_dev.d_len > 0) { + vnet_transmit(vnet); + } + } } while (0); /* While there are more packets to be processed */ } @@ -336,17 +335,17 @@ void rtos_vnet_recv(struct rgmp_vnet *vnet_dummy, char *data, int len) static void vnet_txdone(FAR struct vnet_driver_s *vnet) { - /* Check for errors and update statistics */ + /* Check for errors and update statistics */ - /* If no further xmits are pending, then cancel the TX timeout and - * disable further Tx interrupts. - */ + /* If no further xmits are pending, then cancel the TX timeout and + * disable further Tx interrupts. + */ - //wd_cancel(vnet->sk_txtimeout); + //wd_cancel(vnet->sk_txtimeout); - /* Then poll uIP for new XMIT data */ + /* Then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } /**************************************************************************** @@ -370,15 +369,15 @@ static void vnet_txdone(FAR struct vnet_driver_s *vnet) static void vnet_txtimeout(int argc, uint32_t arg, ...) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; - /* Increment statistics and dump debug info */ + /* Increment statistics and dump debug info */ - /* Then reset the hardware */ + /* Then reset the hardware */ - /* Then poll uIP for new XMIT data */ + /* Then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } /**************************************************************************** @@ -401,28 +400,28 @@ static void vnet_txtimeout(int argc, uint32_t arg, ...) static void vnet_polltimer(int argc, uint32_t arg, ...) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)arg; - /* Check if there is room in the send another TX packet. We cannot perform - * the TX poll if he are unable to accept another packet for transmission. - */ - if (vnet_is_txbuff_full(vnet->vnet)) { + /* Check if there is room in the send another TX packet. We cannot perform + * the TX poll if he are unable to accept another packet for transmission. + */ + if (vnet_is_txbuff_full(vnet->vnet)) { #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - return; - } + return; + } - /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. - * might be bug here. Does this mean if there is a transmit in progress, - * we will missing TCP time state updates? - */ + /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm.. + * might be bug here. Does this mean if there is a transmit in progress, + * we will missing TCP time state updates? + */ - (void)uip_timer(&vnet->sk_dev, vnet_uiptxpoll, VNET_POLLHSEC); + (void)uip_timer(&vnet->sk_dev, vnet_uiptxpoll, VNET_POLLHSEC); - /* Setup the watchdog poll timer again */ + /* Setup the watchdog poll timer again */ - (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, arg); + (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, arg); } /**************************************************************************** @@ -444,20 +443,20 @@ static void vnet_polltimer(int argc, uint32_t arg, ...) static int vnet_ifup(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - ndbg("Bringing up: %d.%d.%d.%d\n", - dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, - (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); + ndbg("Bringing up: %d.%d.%d.%d\n", + dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, + (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); - /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ + /* Initialize PHYs, the Ethernet interface, and setup up Ethernet interrupts */ - /* Set and activate a timer process */ + /* Set and activate a timer process */ - (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, (uint32_t)vnet); + (void)wd_start(vnet->sk_txpoll, VNET_WDDELAY, vnet_polltimer, 1, (uint32_t)vnet); - vnet->sk_bifup = true; - return OK; + vnet->sk_bifup = true; + return OK; } /**************************************************************************** @@ -478,28 +477,28 @@ static int vnet_ifup(struct uip_driver_s *dev) static int vnet_ifdown(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - irqstate_t flags; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + irqstate_t flags; - /* Disable the Ethernet interrupt */ + /* Disable the Ethernet interrupt */ - flags = irqsave(); + flags = irqsave(); - /* Cancel the TX poll timer and TX timeout timers */ + /* Cancel the TX poll timer and TX timeout timers */ - wd_cancel(vnet->sk_txpoll); - //wd_cancel(vnet->sk_txtimeout); + wd_cancel(vnet->sk_txpoll); + //wd_cancel(vnet->sk_txtimeout); - /* Put the the EMAC is its reset, non-operational state. This should be - * a known configuration that will guarantee the vnet_ifup() always - * successfully brings the interface back up. - */ + /* Put the the EMAC is its reset, non-operational state. This should be + * a known configuration that will guarantee the vnet_ifup() always + * successfully brings the interface back up. + */ - /* Mark the device "down" */ + /* Mark the device "down" */ - vnet->sk_bifup = false; - irqrestore(flags); - return OK; + vnet->sk_bifup = false; + irqrestore(flags); + return OK; } /**************************************************************************** @@ -523,35 +522,35 @@ static int vnet_ifdown(struct uip_driver_s *dev) static int vnet_txavail(struct uip_driver_s *dev) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - irqstate_t flags; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + irqstate_t flags; - /* Disable interrupts because this function may be called from interrupt - * level processing. - */ + /* Disable interrupts because this function may be called from interrupt + * level processing. + */ - flags = irqsave(); + flags = irqsave(); - /* Ignore the notification if the interface is not yet up */ + /* Ignore the notification if the interface is not yet up */ - if (vnet->sk_bifup) + if (vnet->sk_bifup) { - /* Check if there is room in the hardware to hold another outgoing packet. */ - if (vnet_is_txbuff_full(vnet->vnet)) { + /* Check if there is room in the hardware to hold another outgoing packet. */ + if (vnet_is_txbuff_full(vnet->vnet)) { #ifdef CONFIG_DEBUG - cprintf("VNET: TX buffer is full\n"); + cprintf("VNET: TX buffer is full\n"); #endif - goto out; - } + goto out; + } - /* If so, then poll uIP for new XMIT data */ + /* If so, then poll uIP for new XMIT data */ - (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); + (void)uip_poll(&vnet->sk_dev, vnet_uiptxpoll); } - out: - irqrestore(flags); - return OK; +out: + irqrestore(flags); + return OK; } /**************************************************************************** @@ -575,11 +574,11 @@ static int vnet_txavail(struct uip_driver_s *dev) #ifdef CONFIG_NET_IGMP static int vnet_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -604,11 +603,11 @@ static int vnet_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac) #ifdef CONFIG_NET_IGMP static int vnet_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac) { - FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; + FAR struct vnet_driver_s *vnet = (FAR struct vnet_driver_s *)dev->d_private; - /* Add the MAC address to the hardware multicast routing table */ + /* Add the MAC address to the hardware multicast routing table */ - return OK; + return OK; } #endif @@ -633,41 +632,41 @@ static int vnet_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac) * ****************************************************************************/ -void vnet_initialize(void) +int vnet_init(struct rgmp_vnet *vnet) { - struct vnet_driver_s *priv; - struct rgmp_vnet *vnet = vnet_list.next; - int i; + struct vnet_driver_s *priv; + static int i = 0; - for (i=0; i= CONFIG_VNET_NINTERFACES) + return -1; - /* Initialize the driver structure */ + priv = &g_vnet[i++]; - memset(priv, 0, sizeof(struct vnet_driver_s)); - priv->sk_dev.d_ifup = vnet_ifup; /* I/F down callback */ - priv->sk_dev.d_ifdown = vnet_ifdown; /* I/F up (new IP address) callback */ - priv->sk_dev.d_txavail = vnet_txavail; /* New TX data callback */ + /* Initialize the driver structure */ + + memset(priv, 0, sizeof(struct vnet_driver_s)); + priv->sk_dev.d_ifup = vnet_ifup; /* I/F down callback */ + priv->sk_dev.d_ifdown = vnet_ifdown; /* I/F up (new IP address) callback */ + priv->sk_dev.d_txavail = vnet_txavail; /* New TX data callback */ #ifdef CONFIG_NET_IGMP - priv->sk_dev.d_addmac = vnet_addmac; /* Add multicast MAC address */ - priv->sk_dev.d_rmmac = vnet_rmmac; /* Remove multicast MAC address */ + priv->sk_dev.d_addmac = vnet_addmac; /* Add multicast MAC address */ + priv->sk_dev.d_rmmac = vnet_rmmac; /* Remove multicast MAC address */ #endif - priv->sk_dev.d_private = (void*)g_vnet; /* Used to recover private state from dev */ + priv->sk_dev.d_private = (void*)priv; /* Used to recover private state from dev */ + + /* Create a watchdog for timing polling for and timing of transmisstions */ - /* Create a watchdog for timing polling for and timing of transmisstions */ + priv->sk_txpoll = wd_create(); /* Create periodic poll timer */ + //priv->sk_txtimeout = wd_create(); /* Create TX timeout timer */ - priv->sk_txpoll = wd_create(); /* Create periodic poll timer */ - //priv->sk_txtimeout = wd_create(); /* Create TX timeout timer */ + priv->vnet = vnet; + vnet->priv = priv; - priv->vnet = vnet; + /* Register the device with the OS */ - /* Register the device with the OS */ + (void)netdev_register(&priv->sk_dev); - (void)netdev_register(&priv->sk_dev); - vnet = vnet->next; - } + return 0; } #endif /* CONFIG_NET && CONFIG_NET_VNET */ diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c index 69bf87965..95f26c185 100644 --- a/nuttx/drivers/usbdev/pl2303.c +++ b/nuttx/drivers/usbdev/pl2303.c @@ -132,7 +132,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER #else # define SELFPOWERED (0) #endif diff --git a/nuttx/drivers/usbdev/usbmsc.h b/nuttx/drivers/usbdev/usbmsc.h index 6a5530d9d..883a49951 100644 --- a/nuttx/drivers/usbdev/usbmsc.h +++ b/nuttx/drivers/usbdev/usbmsc.h @@ -227,7 +227,7 @@ /* USB Controller */ #ifndef CONFIG_USBDEV_SELFPOWERED -# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER +# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER #else # define SELFPOWERED (0) #endif -- cgit v1.2.3