Merge branch 'NuttX/master'

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5163 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
px4dev 2012-09-16 16:42:10 -07:00
commit 2b82c733a9
21 changed files with 1577 additions and 129 deletions

View File

@ -3349,3 +3349,22 @@
* configs/*/nxwm/defconfig and sched/task_exithook.c: Fixes for
bugs that crept in during recent changes. (Submitted by Max
Holtzberg).
* arch/arm/include/armv7-m/irq.h: Fix a critical bug in irqsave().
It looks like sometimes the compile will re-order some instructions
inapproapriately. This end result is that interrupts will get
stuff off.
* drivers/mtd/w25.c: Beginning of a driver for the Windbond SPI
FLASH family (W25x16, W25x32, and W25x64). The initial check-in
is basically just the SST25 driver with some name changes.
* arch/arm/include/armv7-m/irq.h and arch/arm/src/stm32/stm32_spi.c:
Back out the last change in irq.h. It is (most likely) fine the
way it was. The really interrupt related problem was in stm32_spi.c:
When SPI3 is not enabled, then the irqrestore() falls in the
else clause.
* include/nuttx/compiler.h and other files: Moved always_inline
and noinline __attributes__ here. Also replaced all occurrences
of explicit __atributes__ in other files with definitions from
this header file.
* drivers/mtd/w25.c: The Windbond SPI FLASH W25 FLASH driver is
code complete (but still untested).

View File

@ -1,4 +1,4 @@
NuttX TODO List (Last updated August 12, 2012)
NuttX TODO List (Last updated September 16, 2012)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This file summarizes known NuttX bugs, limitations, inconsistencies with
@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements.
nuttx/
(5) Task/Scheduler (sched/)
(6) Task/Scheduler (sched/)
(1) On-demand paging (sched/)
(1) Memory Managment (mm/)
(2) Signals (sched/, arch/)
@ -110,6 +110,13 @@ o Task/Scheduler (sched/)
Status: Open
Priority: Low
Title: posix_spawn()
Description: This would be a good interface to add to NuttX. It is really
just a re-packaging of the existing, non-standard NuttX exec()
function.
Status: Open
Priority: Medium low.
o On-demand paging (sched/)
^^^^^^^^^^^^^^^^^^^^^^^^^
@ -541,13 +548,6 @@ o Network (net/, drivers/net)
Status: Open
Priority: Low... fix defconfig files as necessary.
Title: UNFINISHED ENC28J60 DRIVER
Description: So far, I have not come up with a usable hardware platform to
verify the ENC28J60 Ethernet driver (drivers/net/enc28j60.c).
So it is untested.
Status: Open
Priority: Low unless you need it.
o USB (drivers/usbdev, drivers/usbhost)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

View File

@ -153,13 +153,14 @@ config ARCH_HAVE_INTERRUPTSTACK
bool
config ARCH_INTERRUPTSTACK
bool "Use interrupt stack"
int "Interrupt Stack Size"
depends on ARCH_HAVE_INTERRUPTSTACK
default y
default 0
---help---
This architecture supports an interrupt stack. If defined, this symbol
is the size of the interrupt stack in bytes. If not defined, the user
task stacks will be used during interrupt handling.
will be the size of the interrupt stack in bytes. If not defined (or
defined to be zero), the user task stacks will be used during interrupt
handling.
comment "Boot options"

View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/include/armv7-m/irq.h
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -48,6 +48,7 @@
#include <nuttx/irq.h>
#ifndef __ASSEMBLY__
# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@ -131,8 +132,7 @@ struct xcptcontext
/* Disable IRQs */
static inline void irqdisable(void) __attribute__((always_inline, no_instrument_function));
static inline void irqdisable(void) inline_function;
static inline void irqdisable(void)
{
__asm__ __volatile__ ("\tcpsid i\n");
@ -140,8 +140,7 @@ static inline void irqdisable(void)
/* Save the current primask state & disable IRQs */
static inline irqstate_t irqsave(void) __attribute__((always_inline, no_instrument_function));
static inline irqstate_t irqsave(void) inline_function;
static inline irqstate_t irqsave(void)
{
unsigned short primask;
@ -157,13 +156,13 @@ static inline irqstate_t irqsave(void)
: "=r" (primask)
:
: "memory");
return primask;
}
/* Enable IRQs */
static inline void irqenable(void) __attribute__((always_inline, no_instrument_function));
static inline void irqenable(void) inline_function;
static inline void irqenable(void)
{
__asm__ __volatile__ ("\tcpsie i\n");
@ -171,8 +170,7 @@ static inline void irqenable(void)
/* Restore saved primask state */
static inline void irqrestore(irqstate_t primask) __attribute__((always_inline, no_instrument_function));
static inline void irqrestore(irqstate_t primask) inline_function;
static inline void irqrestore(irqstate_t primask)
{
/* If bit 0 of the primask is 0, then we need to restore
@ -192,6 +190,7 @@ static inline void irqrestore(irqstate_t primask)
/* Get/set the primask register */
static inline uint8_t getprimask(void) inline_function;
static inline uint8_t getprimask(void)
{
uint32_t primask;
@ -201,9 +200,11 @@ static inline uint8_t getprimask(void)
: "=r" (primask)
:
: "memory");
return (uint8_t)primask;
}
static inline void setprimask(uint32_t primask) inline_function;
static inline void setprimask(uint32_t primask)
{
__asm__ __volatile__
@ -216,18 +217,22 @@ static inline void setprimask(uint32_t primask)
/* Get/set the basepri register */
static inline uint8_t getbasepri(void) inline_function;
static inline uint8_t getbasepri(void)
{
uint32_t basepri;
__asm__ __volatile__
(
"\tmrs %0, basepri\n"
: "=r" (basepri)
:
: "memory");
return (uint8_t)basepri;
}
static inline void setbasepri(uint32_t basepri) inline_function;
static inline void setbasepri(uint32_t basepri)
{
__asm__ __volatile__
@ -240,6 +245,7 @@ static inline void setbasepri(uint32_t basepri)
/* Get/set IPSR */
static inline uint32_t getipsr(void) inline_function;
static inline uint32_t getipsr(void)
{
uint32_t ipsr;
@ -249,9 +255,11 @@ static inline uint32_t getipsr(void)
: "=r" (ipsr)
:
: "memory");
return ipsr;
}
static inline void setipsr(uint32_t ipsr) inline_function;
static inline void setipsr(uint32_t ipsr)
{
__asm__ __volatile__
@ -264,6 +272,7 @@ static inline void setipsr(uint32_t ipsr)
/* Get/set CONTROL */
static inline uint32_t getcontrol(void) inline_function;
static inline uint32_t getcontrol(void)
{
uint32_t control;
@ -273,9 +282,11 @@ static inline uint32_t getcontrol(void)
: "=r" (control)
:
: "memory");
return control;
}
static inline void setcontrol(uint32_t control) inline_function;
static inline void setcontrol(uint32_t control)
{
__asm__ __volatile__

View File

@ -74,7 +74,7 @@
/* SYS call 1:
*
* void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
* void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*/
#define SYS_restore_context (1)

View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_assert.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -262,7 +262,7 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */

View File

@ -69,7 +69,7 @@
* Description:
* Restore the current thread context. Full prototype is:
*
* void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
* void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
* Return:
* None

View File

@ -280,7 +280,7 @@ int up_svcall(int irq, FAR void *context)
/* R0=SYS_restore_context: This a restore context command:
*
* void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
* void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
* At this point, the following values are saved in context:
*

View File

@ -40,7 +40,10 @@
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <nuttx/compiler.h>
# include <sys/types.h>
# include <stdint.h>
#endif
@ -223,7 +226,7 @@ extern void up_boot(void);
extern void up_copystate(uint32_t *dest, uint32_t *src);
extern void up_decodeirq(uint32_t *regs);
extern int up_saveusercontext(uint32_t *saveregs);
extern void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
extern void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
extern void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
/* Signal handling **********************************************************/

View File

@ -49,7 +49,7 @@
* 3. Add a calls to up_spiinitialize() in your low level application
* initialization logic
* 4. The handle returned by up_spiinitialize() may then be used to bind the
* SPI driver to higher level logic (e.g., calling
* SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
@ -881,7 +881,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
else
{
/* Less than fPCLK/128. This is as slow as we can go */
setbits = SPI_CR1_FPCLCKd256; /* 111: fPCLK/256 */
actual = priv->spiclock >> 8;
}
@ -941,22 +941,22 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
setbits = 0;
clrbits = SPI_CR1_CPOL|SPI_CR1_CPHA;
break;
case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */
setbits = SPI_CR1_CPHA;
clrbits = SPI_CR1_CPOL;
break;
case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */
setbits = SPI_CR1_CPOL;
clrbits = SPI_CR1_CPHA;
break;
case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */
setbits = SPI_CR1_CPOL|SPI_CR1_CPHA;
clrbits = 0;
break;
default:
return;
}
@ -1008,7 +1008,7 @@ static void spi_setbits(FAR struct spi_dev_s *dev, int nbits)
setbits = 0;
clrbits = SPI_CR1_DFF;
break;
case 16:
setbits = SPI_CR1_DFF;
clrbits = 0;
@ -1111,7 +1111,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
}
/* Exchange one word */
word = spi_send(dev, word);
/* Is there a buffer to receive the return value? */
@ -1120,7 +1120,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
{
*dest++ = word;
}
}
}
}
else
{
@ -1144,7 +1144,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
}
/* Exchange one word */
word = (uint8_t)spi_send(dev, (uint16_t)word);
/* Is there a buffer to receive the return value? */
@ -1152,7 +1152,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
if (dest)
{
*dest++ = word;
}
}
}
}
}
@ -1331,7 +1331,7 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv)
priv->txdma = stm32_dmachannel(priv->txch);
DEBUGASSERT(priv->rxdma && priv->txdma);
#endif
/* Enable spi */
spi_modifycr1(priv, SPI_CR1_SPE, 0);
@ -1360,7 +1360,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
FAR struct stm32_spidev_s *priv = NULL;
irqstate_t flags = irqsave();
#ifdef CONFIG_STM32_SPI1
if (port == 1)
{
@ -1431,7 +1431,12 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
spi_portinitialize(priv);
}
}
else
#endif
{
spidbg("ERROR: Unsupported SPI port: %d\n", port);
return NULL;
}
irqrestore(flags);
return (FAR struct spi_dev_s *)priv;

View File

@ -36,19 +36,19 @@ config AT45DB_PWRSAVE
bool "enables power save"
default n
depends on MTD_AT45DB
config MTD_MP25P
bool "SPI-based M25P1 falsh"
bool "SPI-based M25P FLASH"
default n
select SPI
config MP25P_SPIMODE
int "mp25p spi mode"
int "MP25P SPI mode"
default 0
depends on MTD_MP25P
config MP25P_MANUFACTURER
hex "mp25p manufacturers ID"
hex "MP25P manufacturers ID"
default 0x20
depends on MTD_MP25P
---help---
@ -66,3 +66,68 @@ config MTD_RAMTRON
config MTD_RAM
bool "Memory bus ram"
default n
config MTD_SST25
bool "SPI-based SST25 FLASH"
default n
select SPI
config SST25_SPIMODE
int "SST25 SPI Mode"
default 0
depends on MTD_SST25
config SST25_SPIFREQUENCY
int "SST25 SPI Frequency"
default 20000000
depends on MTD_SST25
config SST25_READONLY
bool "SST25 Read-Only FLASH"
default n
depends on MTD_SST25
config SST25_SECTOR512
bool "Simulate 512 byte Erase Blocks"
default n
depends on MTD_SST25
config SST25_SLOWWRITE
bool
default y
depends on MTD_SST25
config SST25_SLOWREAD
bool
default n
depends on MTD_SST25
config MTD_W25
bool "SPI-based W25 FLASH"
default n
select SPI
config W25_SPIMODE
int "W25 SPI Mode"
default 0
depends on MTD_W25
config W25_SPIFREQUENCY
int "W25 SPI Frequency"
default 20000000
depends on MTD_W25
config W25_READONLY
bool "W25 Read-Only FLASH"
default n
depends on MTD_W25
config W25_SECTOR512
bool "Simulate 512 byte Erase Blocks"
default n
depends on MTD_W25
config W25_SLOWREAD
bool
default n
depends on MTD_W25

View File

@ -47,6 +47,10 @@ ifeq ($(CONFIG_MTD_SST25),y)
CSRCS += sst25.c
endif
ifeq ($(CONFIG_MTD_W25),y)
CSRCS += w25.c
endif
# Include MTD driver support
DEPPATH += --dep-path mtd

1188
nuttx/drivers/mtd/w25.c Normal file

File diff suppressed because it is too large Load Diff

View File

@ -25,6 +25,7 @@ config ENC28J60
References:
ENC28J60 Data Sheet, Stand-Alone Ethernet Controller with SPI Interface,
DS39662C, 2008 Microchip Technology Inc.
if ENC28J60
config ENC28J60_NINTERFACES
int "Number of physical ENC28J60"
@ -61,6 +62,14 @@ config ENC28J60_HALFDUPPLEX
default n
---help---
Default is full duplex
config ENC28J60_DUMPPACKET
bool "Dump Packets"
default n
---help---
If selected, the ENC28J60 driver will dump the contents of each
packet to the console.
endif
config NET_E1000

View File

@ -110,7 +110,7 @@
/* We need to have the work queue to handle SPI interrupts */
#if !defined(CONFIG_SCHED_WORKQUEUE) && !defined(CONFIG_SPI_OWNBUS)
#ifndef CONFIG_SCHED_WORKQUEUE
# error "Worker thread support is required (CONFIG_SCHED_WORKQUEUE)"
#endif
@ -122,6 +122,12 @@
# define enc_dumppacket(m,a,n)
#endif
/* The ENC28J60 will not do interrupt level processing */
#ifndef CONFIG_NET_NOINTS
# warrning "CONFIG_NET_NOINTS should be set"
#endif
/* Timing *******************************************************************/
/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
@ -144,7 +150,7 @@
#define ALIGNED_BUFSIZE ((CONFIG_NET_BUFSIZE + 255) & ~255)
#define PKTMEM_TX_START 0x0000 /* Start TX buffer at 0 */
#define PKTMEM_TX_ENDP1 ALIGNED_BUFSIZE /* Allow TX buffer for one frame + */
#define PKTMEM_TX_ENDP1 ALIGNED_BUFSIZE /* Allow TX buffer for one frame */
#define PKTMEM_RX_START PKTMEM_TX_ENDP1 /* Followed by RX buffer */
#define PKTMEM_RX_END PKTMEM_END /* RX buffer goes to the end of SRAM */
@ -171,7 +177,7 @@
enum enc_state_e
{
ENCSTATE_UNIT = 0, /* The interface is in an unknown state */
ENCSTATE_UNINIT = 0, /* The interface is in an uninitialized state */
ENCSTATE_DOWN, /* The interface is down */
ENCSTATE_UP /* The interface is up */
};
@ -200,10 +206,10 @@ struct enc_driver_s
/* If we don't own the SPI bus, then we cannot do SPI accesses from the
* interrupt handler.
*/
#ifndef CONFIG_SPI_OWNBUS
struct work_s work; /* Work queue support */
#endif
struct work_s irqwork; /* Interrupt continuation work queue support */
struct work_s towork; /* Tx timeout work queue support */
struct work_s pollwork; /* Poll timeout work queue support */
/* This is the contained SPI driver intstance */
@ -279,15 +285,17 @@ static void enc_txif(FAR struct enc_driver_s *priv);
static void enc_txerif(FAR struct enc_driver_s *priv);
static void enc_txerif(FAR struct enc_driver_s *priv);
static void enc_rxerif(FAR struct enc_driver_s *priv);
static void enc_rxdispath(FAR struct enc_driver_s *priv);
static void enc_rxdispatch(FAR struct enc_driver_s *priv);
static void enc_pktif(FAR struct enc_driver_s *priv);
static void enc_worker(FAR void *arg);
static void enc_irqworker(FAR void *arg);
static int enc_interrupt(int irq, FAR void *context);
/* Watchdog timer expirations */
static void enc_polltimer(int argc, uint32_t arg, ...);
static void enc_toworker(FAR void *arg);
static void enc_txtimeout(int argc, uint32_t arg, ...);
static void enc_pollworker(FAR void *arg);
static void enc_polltimer(int argc, uint32_t arg, ...);
/* NuttX callback functions */
@ -1026,6 +1034,7 @@ static int enc_transmit(FAR struct enc_driver_s *priv)
* OK on success; a negated errno on failure
*
* Assumptions:
* Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
@ -1095,6 +1104,7 @@ static void enc_linkstatus(FAR struct enc_driver_s *priv)
* None
*
* Assumptions:
* Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
@ -1195,7 +1205,7 @@ static void enc_rxerif(FAR struct enc_driver_s *priv)
}
/****************************************************************************
* Function: enc_rxdispath
* Function: enc_rxdispatch
*
* Description:
* Give the newly received packet to uIP.
@ -1207,10 +1217,11 @@ static void enc_rxerif(FAR struct enc_driver_s *priv)
* None
*
* Assumptions:
* Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
static void enc_rxdispath(FAR struct enc_driver_s *priv)
static void enc_rxdispatch(FAR struct enc_driver_s *priv)
{
/* We only accept IP packets of the configured type and ARP packets */
@ -1267,6 +1278,7 @@ static void enc_rxdispath(FAR struct enc_driver_s *priv)
* None
*
* Assumptions:
* Interrupts are enabled but the caller holds the uIP lock.
*
****************************************************************************/
@ -1326,7 +1338,7 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
nlldbg("Bad packet size dropped (%d)\n", pktlen);
#ifdef CONFIG_ENC28J60_STATS
priv->stats.rxpktlen++;
#endif
#endif
}
/* Otherwise, read and process the packet */
@ -1340,11 +1352,11 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
/* Copy the data data from the receive buffer to priv->dev.d_buf */
enc_rdbuffer(priv, priv->dev.d_buf, priv->dev.d_len);
enc_dumppacket("Received Packet", priv->ld_dev.d_buf, priv->ld_dev.d_len);
enc_dumppacket("Received Packet", priv->dev.d_buf, priv->dev.d_len);
/* Dispatch the packet to uIP */
enc_rxdispath(priv);
enc_rxdispatch(priv);
}
/* Move the RX read pointer to the start of the next received packet.
@ -1360,7 +1372,7 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
}
/****************************************************************************
* Function: enc_worker
* Function: enc_irqworker
*
* Description:
* Perform interrupt handling logic outside of the interrupt handler (on
@ -1376,13 +1388,18 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
*
****************************************************************************/
static void enc_worker(FAR void *arg)
static void enc_irqworker(FAR void *arg)
{
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
uip_lock_t lock;
uint8_t eir;
DEBUGASSERT(priv);
/* Get exclusive access to uIP. */
lock = uip_lock();
/* Disable further interrupts by clearing the global interrupt enable bit.
* "After an interrupt occurs, the host controller should clear the global
* enable bit for the interrupt pin before servicing the interrupt. Clearing
@ -1402,9 +1419,12 @@ static void enc_worker(FAR void *arg)
while ((eir = enc_rdgreg(priv, ENC_EIR) & EIR_ALLINTS) != 0)
{
/* Handle interrupts according to interrupt register register bit
* settings
*
* DMAIF: The DMA interrupt indicates that the DMA module has completed
* settings.
*/
nllvdbg("EIR: %02x\n", eir);
/* DMAIF: The DMA interrupt indicates that the DMA module has completed
* its memory copy or checksum calculation. Additionally, this interrupt
* will be caused if the host controller cancels a DMA operation by
* manually clearing the DMAST bit. Once set, DMAIF can only be cleared
@ -1521,6 +1541,8 @@ static void enc_worker(FAR void *arg)
uint8_t pktcnt = enc_rdbreg(priv, ENC_EPKTCNT);
if (pktcnt > 0)
{
nllvdbg("EPKTCNT: %02x\n", pktcnt);
#ifdef CONFIG_ENC28J60_STATS
if (pktcnt > priv->stats.maxpktcnt)
{
@ -1560,15 +1582,17 @@ static void enc_worker(FAR void *arg)
}
}
/* Release lock on uIP */
uip_unlock(lock);
/* Enable Ethernet interrupts */
enc_bfsgreg(priv, ENC_EIE, EIE_INTIE);
/* Enable GPIO interrupts if they were disbled in enc_interrupt */
/* Enable GPIO interrupts */
#ifndef CONFIG_SPI_OWNBUS
priv->lower->enable(priv->lower);
#endif
}
/****************************************************************************
@ -1592,15 +1616,6 @@ static int enc_interrupt(int irq, FAR void *context)
{
register FAR struct enc_driver_s *priv = &g_enc28j60[0];
#ifdef CONFIG_SPI_OWNBUS
/* In very simple environments, we own the SPI and can do data transfers
* from the interrupt handler. That is actually a very bad idea in any
* case because it keeps interrupts disabled for a long time.
*/
enc_worker((FAR void*)priv);
return OK;
#else
/* In complex environments, we cannot do SPI transfers from the interrupt
* handler because semaphores are probably used to lock the SPI bus. In
* this case, we will defer processing to the worker thread. This is also
@ -1608,16 +1623,69 @@ static int enc_interrupt(int irq, FAR void *context)
* a good thing to do in any event.
*/
DEBUGASSERT(work_available(&priv->work));
DEBUGASSERT(work_available(&priv->irqwork));
/* Notice that further GPIO interrupts are disabled until the work is
* actually performed. This is to prevent overrun of the worker thread.
* Interrupts are re-enabled in enc_worker() when the work is completed.
* Interrupts are re-enabled in enc_irqworker() when the work is completed.
*/
priv->lower->disable(priv->lower);
return work_queue(HPWORK, &priv->work, enc_worker, (FAR void *)priv, 0);
return work_queue(HPWORK, &priv->irqwork, enc_irqworker, (FAR void *)priv, 0);
}
/****************************************************************************
* Function: enc_toworker
*
* Description:
* Our TX watchdog timed out. This is the worker thread continuation of
* the watchdog timer interrupt. Reset the hardware and start again.
*
* Parameters:
* arg - The reference to the driver structure (case to void*)
*
* Returned Value:
* None
*
* Assumptions:
*
****************************************************************************/
static void enc_toworker(FAR void *arg)
{
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
uip_lock_t lock;
int ret;
nlldbg("Tx timeout\n");
DEBUGASSERT(priv);
/* Get exclusive access to uIP. */
lock = uip_lock();
/* Increment statistics and dump debug info */
#ifdef CONFIG_ENC28J60_STATS
priv->stats.txtimeouts++;
#endif
/* Then reset the hardware: Take the interface down, then bring it
* back up
*/
ret = enc_ifdown(&priv->dev);
DEBUGASSERT(ret == OK);
ret = enc_ifup(&priv->dev);
DEBUGASSERT(ret == OK);
/* Then poll uIP for new XMIT data */
(void)uip_poll(&priv->dev, enc_uiptxpoll);
/* Release lock on uIP */
uip_unlock(lock);
}
/****************************************************************************
@ -1625,7 +1693,7 @@ static int enc_interrupt(int irq, FAR void *context)
*
* Description:
* Our TX watchdog timed out. Called from the timer interrupt handler.
* The last TX never completed. Reset the hardware and start again.
* The last TX never completed. Perform work on the worker thread.
*
* Parameters:
* argc - The number of available arguments
@ -1643,25 +1711,74 @@ static void enc_txtimeout(int argc, uint32_t arg, ...)
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
int ret;
/* Increment statistics and dump debug info */
nlldbg("Tx timeout\n");
#ifdef CONFIG_ENC28J60_STATS
priv->stats.txtimeouts++;
#endif
/* Then reset the hardware: Take the interface down, then bring it
* back up
/* In complex environments, we cannot do SPI transfers from the timout
* handler because semaphores are probably used to lock the SPI bus. In
* this case, we will defer processing to the worker thread. This is also
* much kinder in the use of system resources and is, therefore, probably
* a good thing to do in any event.
*/
ret = enc_ifdown(&priv->dev);
DEBUGASSERT(ret == OK);
ret = enc_ifup(&priv->dev);
DEBUGASSERT(ret == OK);
/* Then poll uIP for new XMIT data */
DEBUGASSERT(priv && work_available(&priv->towork));
(void)uip_poll(&priv->dev, enc_uiptxpoll);
/* Notice that Tx timeout watchdog is not active so further Tx timeouts
* can occur until we restart the Tx timeout watchdog.
*/
ret = work_queue(HPWORK, &priv->towork, enc_toworker, (FAR void *)priv, 0);
DEBUGASSERT(ret == OK);
}
/****************************************************************************
* Function: enc_pollworker
*
* Description:
* Periodic timer handler continuation.
*
* Parameters:
* argc - The number of available arguments
* arg - The first argument
*
* Returned Value:
* None
*
* Assumptions:
*
****************************************************************************/
static void enc_pollworker(FAR void *arg)
{
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
uip_lock_t lock;
DEBUGASSERT(priv);
/* Get exclusive access to uIP. */
lock = uip_lock();
/* Verify that the hardware is ready to send another packet. The driver
* start a transmission process by setting ECON1.TXRTS. When the packet is
* finished transmitting or is aborted due to an error/cancellation, the
* ECON1.TXRTS bit will be cleared.
*/
if ((enc_rdgreg(priv, ENC_ECON1) & ECON1_TXRTS) == 0)
{
/* Yes.. update TCP timing states and poll uIP for new XMIT data. Hmmm..
* looks like a bug here to me. Does this mean if there is a transmit
* in progress, we will missing TCP time state updates?
*/
(void)uip_timer(&priv->dev, enc_uiptxpoll, ENC_POLLHSEC);
}
/* Release lock on uIP */
uip_unlock(lock);
/* Setup the watchdog poll timer again */
(void)wd_start(priv->txpoll, ENC_WDDELAY, enc_polltimer, 1, arg);
}
/****************************************************************************
@ -1684,26 +1801,23 @@ static void enc_txtimeout(int argc, uint32_t arg, ...)
static void enc_polltimer(int argc, uint32_t arg, ...)
{
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)arg;
int ret;
/* Verify that the hardware is ready to send another packet. The driver
* start a transmission process by setting ECON1.TXRTS. When the packet is
* finished transmitting or is aborted due to an error/cancellation, the
* ECON1.TXRTS bit will be cleared.
/* In complex environments, we cannot do SPI transfers from the timout
* handler because semaphores are probably used to lock the SPI bus. In
* this case, we will defer processing to the worker thread. This is also
* much kinder in the use of system resources and is, therefore, probably
* a good thing to do in any event.
*/
if ((enc_rdgreg(priv, ENC_ECON1) & ECON1_TXRTS) == 0)
{
/* Yes.. update TCP timing states and poll uIP for new XMIT data. Hmmm..
* looks like a bug here to me. Does this mean if there is a transmit
* in progress, we will missing TCP time state updates?
*/
DEBUGASSERT(priv && work_available(&priv->pollwork));
(void)uip_timer(&priv->dev, enc_uiptxpoll, ENC_POLLHSEC);
}
/* Notice that poll watchdog is not active so further poll timeouts can
* occur until we restart the poll timeout watchdog.
*/
/* Setup the watchdog poll timer again */
(void)wd_start(priv->txpoll, ENC_WDDELAY, enc_polltimer, 1, arg);
ret = work_queue(HPWORK, &priv->pollwork, enc_pollworker, (FAR void *)priv, 0);
DEBUGASSERT(ret == OK);
}
/****************************************************************************
@ -1747,11 +1861,9 @@ static int enc_ifup(struct uip_driver_s *dev)
*/
enc_wrphy(priv, ENC_PHIE, PHIE_PGEIE | PHIE_PLNKIE);
enc_bfsgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE);
enc_bfsgreg(priv, ENC_EIR, EIR_DMAIF | EIR_LINKIF | EIR_TXIF |
EIR_TXERIF | EIR_RXERIF | EIR_PKTIF);
enc_wrgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE | EIE_LINKIE |
EIE_TXIE | EIE_TXERIE | EIE_RXERIE);
enc_bfcgreg(priv, ENC_EIR, EIR_ALLINTS);
enc_wrgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE | EIE_LINKIE |
EIE_TXIE | EIE_TXERIE | EIE_RXERIE);
/* Enable the receiver */
@ -2180,7 +2292,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
enc_wrbreg(priv, ENC_MAIPGL, 0x12);
/* Set ack-to-Back Inter-Packet Gap */
/* Set Back-to-Back Inter-Packet Gap */
enc_wrbreg(priv, ENC_MABBIPG, 0x15);
#endif
@ -2265,7 +2377,7 @@ int enc_initialize(FAR struct spi_dev_s *spi,
* bringing the interface up.
*/
priv->ifstate = ENCSTATE_UNIT;
priv->ifstate = ENCSTATE_UNINIT;
/* Attach the interrupt to the driver (but don't enable it yet) */

View File

@ -131,10 +131,10 @@
#define ECON1_BSEL_SHIFT (0) /* Bits 0-1: Bank select */
#define ECON1_BSEL_MASK (3 << ECON1_BSEL_SHIFT)
# define ECON1_BSEL_BANK0 (0 << 0) /* Bank 0 */
# define ECON1_BSEL_BANK1 (1 << 1) /* Bank 1 */
# define ECON1_BSEL_BANK2 (2 << 0) /* Bank 2 */
# define ECON1_BSEL_BANK3 (3 << 0) /* Bank 3 */
# define ECON1_BSEL_BANK0 (0 << ECON1_BSEL_SHIFT) /* Bank 0 */
# define ECON1_BSEL_BANK1 (1 << ECON1_BSEL_SHIFT) /* Bank 1 */
# define ECON1_BSEL_BANK2 (2 << ECON1_BSEL_SHIFT) /* Bank 2 */
# define ECON1_BSEL_BANK3 (3 << ECON1_BSEL_SHIFT) /* Bank 3 */
#define ECON1_RXEN (1 << 2) /* Bit 2: Receive Enable */
#define ECON1_TXRTS (1 << 3) /* Bit 3: Transmit Request to Send */
#define ECON1_CSUMEN (1 << 4) /* Bit 4: DMA Checksum Enable */

View File

@ -47,6 +47,7 @@
************************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
#include <sys/types.h>
#include <stdint.h>
@ -78,7 +79,7 @@ struct adc_msg_s
{
uint8_t am_channel; /* The 8-bit ADC Channel */
int32_t am_data; /* ADC convert result (4 bytes) */
} __attribute__((__packed__));
} packed_struct;
struct adc_fifo_s
{

View File

@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/compiler.h
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -92,6 +92,14 @@
# define reentrant_function
# define naked_function
/* The inline_function attribute informs GCC that the function should always
* be inlined, regardless of the level of optimization. The noinline_function
* indicates that the function should never be inlined.
*/
# define inline_function __attribute__ ((always_inline))
# define noinline_function __attribute__ ((noinline))
/* GCC has does not use storage classes to qualify addressing */
# define FAR
@ -224,10 +232,15 @@
# define noreturn_function
# define packed_struct
/* SDCC does support "naked" function s*/
/* SDCC does support "naked" functions */
# define naked_function __naked
/* SDCC does not support forced inlining. */
# define inline_function
# define noinline_function
/* The reentrant attribute informs SDCC that the function
* must be reentrant. In this case, SDCC will store input
* arguments on the stack to support reentrancy.
@ -320,11 +333,13 @@
# define weak_function
# define weak_const_function
/* The Zilog compiler does not support the noreturn, packed, or naked attributes */
/* The Zilog compiler does not support the noreturn, packed, naked attributes */
# define noreturn_function
# define packed_struct
# define naked_function
# define inline_function
# define noinline_function
/* The Zilog compiler does not support the reentrant attribute */
@ -406,7 +421,8 @@
# define packed_struct
# define reentrant_function
# define naked_function
# define inline_function
# define noinline_function
# define FAR
# define NEAR

View File

@ -220,6 +220,19 @@ EXTERN FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
EXTERN FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
/****************************************************************************
* Name: w25_initialize
*
* Description:
* Create an initialized MTD device instance. MTD devices are not registered
* in the file system, but are created as instances that can be bound to
* other functions (such as a block or character driver front end).
*
****************************************************************************/
EXTERN FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *dev);
#undef EXTERN
#ifdef __cplusplus
}

View File

@ -34,7 +34,7 @@ config NET_NOINTS
bool "Not interrupt driven"
default n
---help---
NET_NOINT indicates that uIP not called from the interrupt level.
NET_NOINT indicates that uIP is not called from the interrupt level.
If NET_NOINTS is defined, critical sections will be managed with semaphores;
Otherwise, it assumed that uIP will be called from interrupt level handling
and critical sections will be managed by enabling and disabling interrupts.

View File

@ -39,6 +39,7 @@
#include <nuttx/config.h>
#include <unistd.h>
#include <semaphore.h>
#include <assert.h>
#include <errno.h>