Updates/fixes related to ENC28J60, Kconfigs, and fire-stm32v2

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5128 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-09-11 16:50:16 +00:00
parent 648420e67a
commit 64c8e5c7c3
19 changed files with 135 additions and 223 deletions

View File

@ -3315,4 +3315,11 @@
require DMA-capable memory. If CONFIG_FAT_DMAMEMORY is defined,
then the FAT FS will use platform-provided DMA memory allocators
to allocate the block driver I/O buffers.
* CONFIG_NET_ENC28J60 renamed CONFIG_ENC28J60 to be consistent
in all places.
* drivers/enc28j60.c, include/nuttx/net/enc28j60.h, and
olimex-strp711/src/up_enc28j60.c: No longer passes IRQ number
as a parameters. Instead now passes a call table to manage
ENC28J60 GPIO interrupts. That is because GPIO interrupts are
handled in different ways by different MCUs and some do not
support IRQ numbers for GPIO interrupts.

View File

@ -4963,7 +4963,7 @@ build
<h3>ENC28J60 Ethernet Driver Configuration Settings</h3>
<ul>
<li>
<code>CONFIG_NET_ENC28J60</code>: Enabled ENC28J60 support
<code>CONFIG_ENC28J60</code>: Enabled ENC28J60 support
</li>
<li>
<code>CONFIG_ENC28J60_SPIMODE</code>: Controls the SPI mode

View File

@ -950,7 +950,7 @@ defconfig -- This is a configuration file similar to the Linux
ENC28J60 Ethernet Driver Configuration Settings:
CONFIG_NET_ENC28J60 - Enabled ENC28J60 support
CONFIG_ENC28J60 - Enabled ENC28J60 support
CONFIG_ENC28J60_SPIMODE - Controls the SPI mode
CONFIG_ENC28J60_FREQUENCY - Define to use a different bus frequency
CONFIG_ENC28J60_NINTERFACES - Specifies the number of physical ENC28J60

View File

@ -256,14 +256,14 @@
* PIN NAME SIGNAL NOTES
* --- ------ -------------- -------------------------------------------------------------------
*
* 68 PA9 PA9-US1-TX MAX3232, DB9 D8, Requires CONFIG_STM32_USART1_REMAP
* 69 PA10 PA10-US1-RX MAX3232, DB9 D8, Requires CONFIG_STM32_USART1_REMAP
* 68 PA9 PA9-US1-TX MAX3232, DB9 D8, Requires !CONFIG_STM32_USART1_REMAP
* 69 PA10 PA10-US1-RX MAX3232, DB9 D8, Requires !CONFIG_STM32_USART1_REMAP
* 25 PA2 PA2-US2-TX MAX3232, DB9 D7, Requires !CONFIG_STM32_USART2_REMAP
* 26 PA3 PA3-US2-RX MAX3232, DB9 D7, Requires !CONFIG_STM32_USART2_REMAP
*/
#if defined(CONFIG_STM32_USART1) && !defined(CONFIG_STM32_USART1_REMAP)
# errror "USART1 requires CONFIG_STM32_USART1_REMAP=y"
#if defined(CONFIG_STM32_USART1) && defined(CONFIG_STM32_USART1_REMAP)
# errror "USART1 requires CONFIG_STM32_USART1_REMAP=n"
#endif
#if defined(CONFIG_STM32_USART2) && defined(CONFIG_STM32_USART2_REMAP)

View File

@ -131,7 +131,7 @@ CONFIG_STM32_I2C1=y
# CONFIG_STM32_IWDG is not set
CONFIG_STM32_PWR=y
CONFIG_STM32_SDIO=y
# CONFIG_STM32_SPI1 is not set
CONFIG_STM32_SPI1=y
# CONFIG_STM32_SPI2 is not set
# CONFIG_STM32_SPI4 is not set
# CONFIG_STM32_TIM1 is not set
@ -149,12 +149,14 @@ CONFIG_STM32_USART2=y
# CONFIG_STM32_UART5 is not set
CONFIG_STM32_USB=y
# CONFIG_STM32_WWDG is not set
CONFIG_STM32_SPI=y
#
# Alternate Pin Mapping
#
CONFIG_STM32_USART1_REMAP=y
# CONFIG_STM32_USART1_REMAP is not set
# CONFIG_STM32_USART2_REMAP is not set
# CONFIG_STM32_SPI1_REMAP is not set
# CONFIG_STM32_I2C1_REMAP is not set
# CONFIG_STM32_JTAG_DISABLE is not set
CONFIG_STM32_JTAG_FULL_ENABLE=y
@ -163,6 +165,12 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_STM32_FORCEPOWER is not set
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
#
# SPI Configuration
#
# CONFIG_STM32_SPI_INTERRUPTS is not set
# CONFIG_STM32_SPI_DMA is not set
#
# SDIO Configuration
#
@ -300,71 +308,27 @@ CONFIG_DEV_NULL=y
# CONFIG_DEV_ZERO is not set
# CONFIG_LOOP is not set
# CONFIG_RAMDISK is not set
#
# CAN Driver Options
#
# CONFIG_CAN is not set
#
# PWM Driver Options
#
# CONFIG_PWM is not set
#
# I2C Driver Options
#
CONFIG_I2C=y
# CONFIG_I2C_SLAVE is not set
CONFIG_I2C_TRANSFER=y
# CONFIG_I2C_WRITEREAD is not set
CONFIG_I2C_POLLED=y
# CONFIG_I2C_TRACE is not set
#
# SPI Driver Options
#
CONFIG_SPI=y
# CONFIG_SPI_OWNBUS is not set
CONFIG_SPI_EXCHANGE=y
CONFIG_SPI_CMDDATA=y
#
# RTC Driver Options
#
# CONFIG_SPI_CMDDATA is not set
CONFIG_RTC=y
# CONFIG_RTC_DATETIME is not set
# CONFIG_RTC_HIRES is not set
# CONFIG_RTC_ALARM is not set
#
# Watchdog Driver Options
#
# CONFIG_WATCHDOG is not set
#
# Analog Driver Options
#
# CONFIG_ANALOG is not set
#
# Block-to-Character Driver Support
#
# CONFIG_BCH is not set
#
# Input device Driver Options
#
# CONFIG_INPUT is not set
#
# LCD Driver Options
#
# CONFIG_LCD is not set
#
# MMCSD Driver Options
#
CONFIG_MMCSD=y
CONFIG_MMCSD_NSLOTS=1
# CONFIG_MMCSD_READONLY is not set
@ -375,42 +339,23 @@ CONFIG_MMCSD_SPI=y
CONFIG_MMCSD_SPICLOCK=20000000
CONFIG_MMCSD_SDIO=y
# CONFIG_SDIO_MUXBUS is not set
#
# I2C Driver Options
#
# CONFIG_MTD is not set
#
# Network Device Driver Options
#
# CONFIG_NETDEVICES is not set
CONFIG_NETDEVICES=y
# CONFIG_NET_DM90x0 is not set
CONFIG_ENC28J60=y
CONFIG_ENC28J60_NINTERFACES=1
CONFIG_ENC28J60_SPIMODE=2
CONFIG_ENC28J60_FREQUENCY=20000000
# CONFIG_ENC28J60_STATS is not set
# CONFIG_ENC28J60_HALFDUPPLEX is not set
# CONFIG_NET_E1000 is not set
# CONFIG_NET_SLIP is not set
#
# Pipe Options
#
# CONFIG_NET_VNET is not set
# CONFIG_PIPES is not set
#
# Power Management Options
#
# CONFIG_PM is not set
# CONFIG_POWER is not set
#
# Sensor Driver Options
#
# CONFIG_SENSORS is not set
#
# Osmocom-bb Sercomm Driver Options
#
# CONFIG_SERCOMM_CONSOLE is not set
#
# Serial Driver Options
#
CONFIG_SERIAL=y
# CONFIG_LOWLEVEL_CONSOLE is not set
# CONFIG_16550_UART is not set
@ -441,10 +386,6 @@ CONFIG_USART2_BAUD=115200
CONFIG_USART2_BITS=8
CONFIG_USART2_PARITY=0
CONFIG_USART2_2STOP=0
#
# USB Device Driver Options
#
CONFIG_USBDEV=y
# CONFIG_USBDEV_COMPOSITE is not set
# CONFIG_USBDEV_ISOCHRONOUS is not set
@ -468,15 +409,7 @@ CONFIG_USBMSC_PRODUCTID=0x5342
CONFIG_USBMSC_PRODUCTSTR="USBdev Storage"
CONFIG_USBMSC_VERSIONNO=0x0399
CONFIG_USBMSC_REMOVABLE=y
#
# USB Host Driver Options
#
# CONFIG_USBHOST is not set
#
# Wireless Device Driver Options
#
# CONFIG_WIRELESS is not set
#
@ -495,7 +428,7 @@ CONFIG_NET=y
# CONFIG_NET_NOINTS is not set
# CONFIG_NET_MULTIBUFFER is not set
# CONFIG_NET_IPv6 is not set
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NSOCKET_DESCRIPTORS=16
CONFIG_NET_NACTIVESOCKETS=16
CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFSIZE=562
@ -512,7 +445,7 @@ CONFIG_NET_UDP_CHECKSUMS=y
CONFIG_NET_UDP_CONNS=8
CONFIG_NET_BROADCAST=y
CONFIG_NET_ICMP=y
# CONFIG_NET_ICMP_PING is not set
CONFIG_NET_ICMP_PING=y
# CONFIG_NET_PINGADDRCONF is not set
# CONFIG_NET_IGMP is not set
CONFIG_NET_STATISTICS=y
@ -532,6 +465,7 @@ CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_MAXFNAME=32
# CONFIG_FS_FATTIME is not set
# CONFIG_FAT_DMAMEMORY is not set
# CONFIG_FS_RAMMAP is not set
# CONFIG_NFS is not set
# CONFIG_FS_NXFFS is not set

View File

@ -56,7 +56,7 @@ else
CSRCS += up_userleds.c
endif
ifeq ($(CONFIG_NET_ENC28J60),y)
ifeq ($(CONFIG_ENC28J60),y)
CSRCS += up_enc28j60.c
endif

View File

@ -191,7 +191,7 @@
* 32 PA7 PA7-SPI1-MOSI 2.4" TFT + Touchscreen, 10Mbit ENC28J60, SPI 2M FLASH
*/
#ifndef CONFIG_NET_ENC28J60
#ifndef CONFIG_ENC28J60
# define GPIO_ENC28J60_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
#endif
@ -210,11 +210,11 @@
* 4 PE5 (no name) 10Mbps ENC28J60 Interrupt
*/
#if defined(CONFIG_STM32_FSMC) && defined(CONFIG_NET_ENC28J60)
#if defined(CONFIG_STM32_FSMC) && defined(CONFIG_ENC28J60)
# warning "TFT LCD and ENCJ2860 shared PE1"
#endif
#ifdef CONFIG_NET_ENC28J60
#ifdef CONFIG_ENC28J60
# define GPIO_ENC28J60_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
# define GPIO_ENC28J60_RESET (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\

View File

@ -193,7 +193,8 @@ static struct pm_callback_s g_ledscb =
* Name: led_clrbits
*
* Description:
* Clear all LEDs to the bit encoded state
* Clear all LEDs to the bit encoded state. The LEDs are pulled up and,
* hence, active low.
*
****************************************************************************/
@ -201,17 +202,17 @@ static inline void led_clrbits(unsigned int clrbits)
{
if ((clrbits & FIRE_LED1) != 0)
{
stm32_gpiowrite(GPIO_LED1, false);
stm32_gpiowrite(GPIO_LED1, true);
}
if ((clrbits & FIRE_LED2) != 0)
{
stm32_gpiowrite(GPIO_LED2, false);
stm32_gpiowrite(GPIO_LED2, true);
}
if ((clrbits & FIRE_LED3) != 0)
{
stm32_gpiowrite(GPIO_LED3, false);
stm32_gpiowrite(GPIO_LED3, true);
}
}
@ -219,7 +220,8 @@ static inline void led_clrbits(unsigned int clrbits)
* Name: led_setbits
*
* Description:
* Set all LEDs to the bit encoded state
* Set all LEDs to the bit encoded state. The LEDs are pulled up and,
* hence, active low.
*
****************************************************************************/
@ -227,17 +229,17 @@ static inline void led_setbits(unsigned int setbits)
{
if ((setbits & FIRE_LED1) != 0)
{
stm32_gpiowrite(GPIO_LED1, true);
stm32_gpiowrite(GPIO_LED1, false);
}
if ((setbits & FIRE_LED2) != 0)
{
stm32_gpiowrite(GPIO_LED2, true);
stm32_gpiowrite(GPIO_LED2, false);
}
if ((setbits & FIRE_LED3) != 0)
{
stm32_gpiowrite(GPIO_LED3, true);
stm32_gpiowrite(GPIO_LED3, false);
}
}

View File

@ -63,9 +63,9 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "fire_internal.h"
#include "fire-internal.h"
#ifdef CONFIG_NET_ENC28J60
#ifdef CONFIG_ENC28J60
/****************************************************************************
* Definitions
@ -110,9 +110,9 @@ struct stm32_lower_s
* Private Function Prototypes
****************************************************************************/
static int up_attach(FAR struct enc_lower_s *lower, xcpt_t handler);
static void up_enable(FAR struct enc_lower_s *lower);
static void up_disable(FAR struct enc_lower_s *lower);
static int up_attach(FAR const struct enc_lower_s *lower, xcpt_t handler);
static void up_enable(FAR const struct enc_lower_s *lower);
static void up_disable(FAR const struct enc_lower_s *lower);
/****************************************************************************
* Private Data
@ -123,13 +123,15 @@ static void up_disable(FAR struct enc_lower_s *lower);
* the ENC28J60 GPIO interrupt.
*/
static const struct enc_lower_s g_enclower =
static struct stm32_lower_s g_enclower =
{
.lower =
{
.attach = up_attach,
.enable = up_enable,
.disable = up_disable
}
},
.handler = NULL,
};
/****************************************************************************
@ -140,25 +142,25 @@ static const struct enc_lower_s g_enclower =
* Name: struct enc_lower_s methods
****************************************************************************/
static int up_attach(FAR struct enc_lower_s *lower, xcpt_t handler)
static int up_attach(FAR const struct enc_lower_s *lower, xcpt_t handler)
{
FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)lower;
/* Just save the handler for use when the interrupt is enabled */
priv-handler = handler;
priv->handler = handler;
return OK;
}
static void up_enable(FAR struct enc_lower_s *lower)
static void up_enable(FAR const struct enc_lower_s *lower)
{
FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)lower;
DEBUGASSERT(priv->handler);
(void)stm32_gpiosetevent(GPIO_ENC28J60_INTR, true, true, true, priv-handler);
(void)stm32_gpiosetevent(GPIO_ENC28J60_INTR, true, true, true, priv->handler);
}
static void up_disable(FAR struct enc_lower_s *lower)
static void up_disable(FAR const struct enc_lower_s *lower)
{
(void)stm32_gpiosetevent(GPIO_ENC28J60_INTR, true, true, true, NULL);
}
@ -174,7 +176,6 @@ static void up_disable(FAR struct enc_lower_s *lower)
void up_netinitialize(void)
{
FAR struct spi_dev_s *spi;
uint16_t reg16;
int ret;
/* Assumptions:
@ -195,7 +196,7 @@ void up_netinitialize(void)
/* Bind the SPI port to the ENC28J60 driver */
ret = enc_initialize(spi, ENC28J60_DEVNO, &g_enclower);
ret = enc_initialize(spi, &g_enclower.lower, ENC28J60_DEVNO);
if (ret < 0)
{
nlldbg("Failed to bind SPI port %d ENC28J60 device %d: %d\n",
@ -207,4 +208,4 @@ void up_netinitialize(void)
ENC28J60_SPI_PORTNO, ENC28J60_DEVNO);
}
#endif /* CONFIG_NET_ENC28J60 */
#endif /* CONFIG_ENC28J60 */

View File

@ -111,7 +111,7 @@ void weak_function stm32_spiinitialize(void)
/* Configure ENC28J60 SPI1 CS (also RESET and interrupt pins) */
#ifdef CONFIG_NET_ENC28J60
#ifdef CONFIG_ENC28J60
stm32_configgpio(GPIO_ENC28J60_CS);
stm32_configgpio(GPIO_ENC28J60_RESET);
stm32_configgpio(GPIO_ENC28J60_INTR);
@ -171,7 +171,7 @@ void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele
}
else
#endif
#ifdef CONFIG_NET_ENC28J60
#ifdef CONFIG_ENC28J60
if (devid == SPIDEV_ETHERNET)
{
/* Set the GPIO low to select and high to de-select */

View File

@ -105,18 +105,28 @@ void stm32_ledinit(void)
/****************************************************************************
* Name: stm32_setled
*
* Description:
* Set one LED to the 'ledon' state. The LEDs are pulled up and, hence,
* active low.
*
****************************************************************************/
void stm32_setled(int led, bool ledon)
{
if ((unsigned)led < BOARD_NLEDS)
{
stm32_gpiowrite(g_ledcfg[led], ledon);
stm32_gpiowrite(g_ledcfg[led], !ledon);
}
}
/****************************************************************************
* Name: stm32_setleds
*
* Description:
* Set each LED to the bit encoded state. The LEDs are pulled up and,
* hence, active low.
*
****************************************************************************/
void stm32_setleds(uint8_t ledset)

View File

@ -2,7 +2,7 @@
# configs/olimes-strp711/nettest/defconfig
#
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -235,7 +235,7 @@ CONFIG_FS_ROMFS=n
#
# ENC28J60 configuration
#
CONFIG_NET_ENC28J60=y
CONFIG_ENC28J60=y
#CONFIG_ENC28J60_SPIMODE
CONFIG_ENC28J60_FREQUENCY=20000000
CONFIG_ENC28J60_NINTERFACES=1

View File

@ -1,8 +1,8 @@
############################################################################
# configs/olimex-strp711/src/Makefile
#
# Copyright (C) 2007-2008, 2010 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
# Copyright (C) 2007-2008, 2010, 2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -51,7 +51,7 @@ CSRCS = up_spi.c up_leds.c up_buttons.c
ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
ifeq ($(CONFIG_NET_ENC28J60),y)
ifeq ($(CONFIG_ENC28J60),y)
CSRCS += up_enc28j60.c
endif
COBJS = $(CSRCS:.c=$(OBJEXT))

View File

@ -95,7 +95,7 @@
#include "up_internal.h"
#include "str71x_internal.h"
#ifdef CONFIG_NET_ENC28J60
#ifdef CONFIG_ENC28J60
/****************************************************************************
* Definitions
@ -182,17 +182,17 @@ static const struct enc_lower_s g_enclower =
* Name: struct enc_lower_s methods
****************************************************************************/
static int up_attach(FAR struct enc_lower_s *lower, xcpt_t handler)
static int up_attach(FAR const struct enc_lower_s *lower, xcpt_t handler)
{
return irq_attach(ENC28J60_IRQ, handler)
}
static void up_enable(FAR struct enc_lower_s *lower)
static void up_enable(FAR const struct enc_lower_s *lower)
{
up_enable_irq(ENC28J60_IRQ);
}
static void up_disable(FAR struct enc_lower_s *lower)
static void up_disable(FAR const struct enc_lower_s *lower)
{
up_disable_irq(ENC28J60_IRQ);
}
@ -237,7 +237,7 @@ void up_netinitialize(void)
/* Bind the SPI port to the ENC28J60 driver */
ret = enc_initialize(spi, ENC28J60_DEVNO, &g_enclower);
ret = enc_initialize(spi, &g_enclower, ENC28J60_DEVNO);
if (ret < 0)
{
nlldbg("Failed to bind SPI port %d ENC28J60 device %d: %d\n",
@ -248,4 +248,4 @@ void up_netinitialize(void)
nllvdbg("Bound SPI port %d to ENC28J60 device %d\n",
ENC28J60_SPI_PORTNO, ENC28J60_DEVNO);
}
#endif /* CONFIG_NET_ENC28J60 */
#endif /* CONFIG_ENC28J60 */

View File

@ -1,8 +1,8 @@
/****************************************************************************
* config/olimex-strp711/src/up_spi.c
*
* Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Copyright (C) 2008-2010,2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -155,7 +155,7 @@
* P0.4/S1.MISO P0.4 output 6 5 NET RST
*/
#ifdef CONFIG_NET_ENC28J60
#ifdef CONFIG_ENC28J60
/* UART3, I2C cannot be used with SPI0. The GPIOs selected for the ENC28J60
* interrupt conflict with BSPI1
@ -981,7 +981,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
* reset (also active low)
*/
#ifdef CONFIG_NET_ENC28J60
#ifdef CONFIG_ENC28J60
reg16 = getreg16(STR71X_GPIO0_PD);
reg16 |= (ENC_GPIO0_CS | ENC_GPIO0_NETRST);
putreg16(reg16, STR71X_GPIO0_PD);

View File

@ -27,10 +27,8 @@ config RAMDISK
a block driver that can be mounted as a files system. See
include/nuttx/ramdisk.h.
comment "CAN Driver Options"
config CAN
bool "CAN Support"
menuconfig CAN
bool "CAN Driver Support"
default n
---help---
This selection enables building of the "upper-half" CAN driver.
@ -65,10 +63,8 @@ config CAN_LOOPBACK
endif
comment "PWM Driver Options"
config PWM
bool "PWM Support"
menuconfig PWM
bool "PWM Driver Support"
default n
---help---
This selection enables building of the "upper-half" PWM driver.
@ -86,10 +82,8 @@ config PWM_PULSECOUNT
endif
comment "I2C Driver Options"
config I2C
bool "I2C Support"
menuconfig I2C
bool "I2C Driver Support"
default n
---help---
This selection enables building of the "upper-half" I2C driver.
@ -125,10 +119,8 @@ config I2C_NTRACE
default n
depends on I2C_TRACE
comment "SPI Driver Options"
config SPI
bool "SPI Support"
menuconfig SPI
bool "SPI Driver Support"
default n
---help---
This selection enables building of the "upper-half" SPI driver.
@ -159,10 +151,8 @@ config SPI_CMDDATA
endif
comment "RTC Driver Options"
config RTC
bool "RTC Support"
menuconfig RTC
bool "RTC Driver Support"
default n
---help---
This selection enables configuration of a real time clock (RTCdriver.
@ -214,9 +204,7 @@ config RTC_ALARM
Enable if the RTC hardware supports setting of an alarm. A callback
function will be executed when the alarm goes off.
comment "Watchdog Driver Options"
config WATCHDOG
menuconfig WATCHDOG
bool "Watchdog Timer Support"
default n
---help---
@ -226,8 +214,6 @@ config WATCHDOG
if WATCHDOG
endif
comment "Analog Driver Options"
menuconfig ANALOG
bool "Analog Device(ADC/DAC) Support"
default n
@ -241,9 +227,7 @@ if ANALOG
source drivers/analog/Kconfig
endif
comment "Block-to-Character Driver Support"
config BCH
menuconfig BCH
bool "Block-to-Character (BCH) Support"
default n
---help---
@ -256,8 +240,6 @@ if BCH
source drivers/bch/Kconfig
endif
comment "Input device Driver Options"
menuconfig INPUT
bool "Input Device Support"
default n
@ -270,10 +252,8 @@ if INPUT
source drivers/input/Kconfig
endif
comment "LCD Driver Options"
menuconfig LCD
bool "LCD Support"
bool "LCD Driver Support"
default n
select NX_LCDDRIVER
---help---
@ -288,10 +268,8 @@ if LCD
source drivers/lcd/Kconfig
endif
comment "MMCSD Driver Options"
menuconfig MMCSD
bool "MMC/SD Support"
bool "MMC/SD Driver Support"
default n
---help---
Support for MMC/SD block drivers. MMC/SD block drivers based on
@ -302,8 +280,6 @@ if MMCSD
source drivers/mmcsd/Kconfig
endif
comment "I2C Driver Options"
menuconfig MTD
bool "Memory Technology Device (MTD) Support"
default n
@ -321,8 +297,6 @@ if MTD
source drivers/mtd/Kconfig
endif
comment "Network Device Driver Options"
menuconfig NETDEVICES
bool "Network Device Support"
default n
@ -333,8 +307,6 @@ if NETDEVICES
source drivers/net/Kconfig
endif
comment "Pipe Options"
menuconfig PIPES
bool "FIFO and named pipe drivers"
default n
@ -346,8 +318,6 @@ if PIPES
source drivers/pipes/Kconfig
endif
comment "Power Management Options"
config PM
bool "Power management (PM) driver interfaces"
default n
@ -367,10 +337,8 @@ if POWER
source drivers/power/Kconfig
endif
comment "Sensor Driver Options"
menuconfig SENSORS
bool "Sensors Support"
bool "Sensor Device Support"
default n
---help---
Drivers for various sensors
@ -379,10 +347,8 @@ if SENSORS
source drivers/sensors/Kconfig
endif
comment "Osmocom-bb Sercomm Driver Options"
menuconfig SERCOMM_CONSOLE
bool "Osmocom-bb serial console"
bool "Osmocom-bb Sercomm Driver Support"
default n
---help---
Sercomm is the transport used by osmocom-bb that runs on top of serial.
@ -398,10 +364,8 @@ if SERCOMM
source drivers/sercomm/Kconfig
endif
comment "Serial Driver Options"
menuconfig SERIAL
bool "Serial Support"
bool "Serial Driver Support"
default y
---help---
Front-end character drivers for chip-specific UARTs. This provide
@ -412,10 +376,8 @@ if SERIAL
source drivers/serial/Kconfig
endif
comment "USB Device Driver Options"
menuconfig USBDEV
bool "USB Device Support"
bool "USB Device Driver Support"
default n
---help---
USB device drivers. See also include/nuttx/usb/usbdev.h
@ -424,10 +386,8 @@ if USBDEV
source drivers/usbdev/Kconfig
endif
comment "USB Host Driver Options"
menuconfig USBHOST
bool "USB Host Support"
bool "USB Host Driver Support"
default n
---help---
USB host drivers. See also include/nuttx/usb/usbhost.h
@ -436,10 +396,8 @@ if USBHOST
source drivers/usbhost/Kconfig
endif
comment "Wireless Device Driver Options"
menuconfig WIRELESS
bool "Wireless Support"
bool "Wireless Device Support"
default n
---help---
Drivers for various wireless devices.

View File

@ -1,8 +1,8 @@
############################################################################
# drivers/net/Make.defs
#
# Copyright (C) 2007, 2010-2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
# Copyright (C) 2007, 2010-2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -47,7 +47,7 @@ ifeq ($(CONFIG_NET_CS89x0),y)
CSRCS += cs89x0.c
endif
ifeq ($(CONFIG_NET_ENC28J60),y)
ifeq ($(CONFIG_ENC28J60),y)
CSRCS += enc28j60.c
endif

View File

@ -42,7 +42,7 @@
****************************************************************************/
#include <nuttx/config.h>
#if defined(CONFIG_NET) && defined(CONFIG_NET_ENC28J60)
#if defined(CONFIG_NET) && defined(CONFIG_ENC28J60)
#include <stdint.h>
#include <stdbool.h>
@ -74,7 +74,7 @@
/* ENC28J60 Configuration Settings:
*
* CONFIG_NET_ENC28J60 - Enabled ENC28J60 support
* CONFIG_ENC28J60 - Enabled ENC28J60 support
* CONFIG_ENC28J60_SPIMODE - Controls the SPI mode
* CONFIG_ENC28J60_FREQUENCY - Define to use a different bus frequency
* CONFIG_ENC28J60_NINTERFACES - Specifies the number of physical ENC28J60
@ -172,36 +172,36 @@ struct enc_driver_s
{
/* Device control */
bool bifup; /* true:ifup false:ifdown */
uint8_t bank; /* Currently selected bank */
uint16_t nextpkt; /* Next packet address */
FAR struct enc_lower_s *lower; /* Low-level MCU-specific support */
bool bifup; /* true:ifup false:ifdown */
uint8_t bank; /* Currently selected bank */
uint16_t nextpkt; /* Next packet address */
FAR const struct enc_lower_s *lower; /* Low-level MCU-specific support */
/* Timing */
WDOG_ID txpoll; /* TX poll timer */
WDOG_ID txtimeout; /* TX timeout timer */
WDOG_ID txpoll; /* TX poll timer */
WDOG_ID txtimeout; /* TX timeout timer */
/* We 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 */
struct work_s work; /* Work queue support */
#endif
/* This is the contained SPI driver intstance */
FAR struct spi_dev_s *spi;
FAR struct spi_dev_s *spi;
/* This holds the information visible to uIP/NuttX */
struct uip_driver_s dev; /* Interface understood by uIP */
struct uip_driver_s dev; /* Interface understood by uIP */
/* Statistics */
#ifdef CONFIG_ENC28J60_STATS
struct enc_stats_s stats;
struct enc_stats_s stats;
#endif
};

View File

@ -51,7 +51,7 @@
/* ENC28J60 Configuration Settings:
*
* CONFIG_NET_ENC28J60 - Enabled ENC28J60 support
* CONFIG_ENC28J60 - Enabled ENC28J60 support
* CONFIG_ENC28J60_SPIMODE - Controls the SPI mode
* CONFIG_ENC28J60_FREQUENCY - Define to use a different bus frequency
* CONFIG_ENC28J60_NINTERFACES - Specifies the number of physical ENC28J60
@ -89,9 +89,9 @@ struct enc_stats_s
struct enc_lower_s
{
int (*attach)(FAR struct enc_lower_s *lower, xcpt_t handler);
void (*enable)(FAR struct enc_lower_s *lower);
void (*disable)(FAR struct enc_lower_s *lower);
int (*attach)(FAR const struct enc_lower_s *lower, xcpt_t handler);
void (*enable)(FAR const struct enc_lower_s *lower);
void (*disable)(FAR const struct enc_lower_s *lower);
};
/****************************************************************************