From 53309f29bef36ec7f8807f96f3a5d720f2c2df9c Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 27 Sep 2012 19:26:18 +0000 Subject: STM32 fixes for DM9161 PHY; Enhancements for ADS7843e touchscreen controller git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5199 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/armv7-m/nvic.h | 22 +++++--- nuttx/arch/arm/src/armv7-m/up_systemreset.c | 79 +++++++++++++++++++++++++++++ nuttx/arch/arm/src/common/up_internal.h | 4 ++ nuttx/arch/arm/src/stm32/Kconfig | 1 + nuttx/arch/arm/src/stm32/Make.defs | 4 +- nuttx/arch/arm/src/stm32/stm32_eth.c | 79 +++++++++++++++++++++++++++++ 6 files changed, 179 insertions(+), 10 deletions(-) create mode 100644 nuttx/arch/arm/src/armv7-m/up_systemreset.c (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/src/armv7-m/nvic.h b/nuttx/arch/arm/src/armv7-m/nvic.h index ae56118c9..6bd842a76 100644 --- a/nuttx/arch/arm/src/armv7-m/nvic.h +++ b/nuttx/arch/arm/src/armv7-m/nvic.h @@ -175,7 +175,7 @@ #define NVIC_CPUID_BASE_OFFSET 0x0d00 /* CPUID base register */ #define NVIC_INTCTRL_OFFSET 0x0d04 /* Interrupt control state register */ #define NVIC_VECTAB_OFFSET 0x0d08 /* Vector table offset register */ -#define NVIC_AIRC_OFFSET 0x0d0c /* Application interrupt/reset contol registr */ +#define NVIC_AIRCR_OFFSET 0x0d0c /* Application interrupt/reset contol registr */ #define NVIC_SYSCON_OFFSET 0x0d10 /* System control register */ #define NVIC_CFGCON_OFFSET 0x0d14 /* Configuration control register */ #define NVIC_SYSH_PRIORITY_OFFSET(n) (0x0d14 + 4*((n) >> 2)) @@ -348,7 +348,7 @@ #define NVIC_CPUID_BASE (ARMV7M_NVIC_BASE + NVIC_CPUID_BASE_OFFSET) #define NVIC_INTCTRL (ARMV7M_NVIC_BASE + NVIC_INTCTRL_OFFSET) #define NVIC_VECTAB (ARMV7M_NVIC_BASE + NVIC_VECTAB_OFFSET) -#define NVIC_AIRC (ARMV7M_NVIC_BASE + NVIC_AIRC_OFFSET) +#define NVIC_AIRCR (ARMV7M_NVIC_BASE + NVIC_AIRCR_OFFSET) #define NVIC_SYSCON (ARMV7M_NVIC_BASE + NVIC_SYSCON_OFFSET) #define NVIC_CFGCON (ARMV7M_NVIC_BASE + NVIC_CFGCON_OFFSET) #define NVIC_SYSH_PRIORITY(n) (ARMV7M_NVIC_BASE + NVIC_SYSH_PRIORITY_OFFSET(n)) @@ -501,12 +501,18 @@ #define NVIC_SYSHCON_USGFAULTENA (1 << 18) /* Bit 18: UsageFault enabled */ /* Application Interrupt and Reset Control Register (AIRCR) */ - /* Bit 0: Reserved */ -#define NVIC_AIRC_VECTCLRACTIVE (1 << 1) /* Bit 1: Reserved for debug use */ -#define NVIC_AIRC_SYSRESETREQ (1 << 2) /* Bit 2: System reset */ - /* Bits 3-14: Reserved */ -#define NVIC_AIRC_ENDIANNESS (1 << 15) /* Bit 15: 1=Big endian */ - /* Bits 16-31: Reserved */ + +#define NVIC_AIRCR_VECTRESET (1 << 0) /* Bit 0: VECTRESET */ +#define NVIC_AIRCR_VECTCLRACTIVE (1 << 1) /* Bit 1: Reserved for debug use */ +#define NVIC_AIRCR_SYSRESETREQ (1 << 2) /* Bit 2: System reset */ + /* Bits 2-7: Reserved */ +#define NVIC_AIRCR_PRIGROUP_SHIFT (8) /* Bits 8-14: PRIGROUP */ +#define NVIC_AIRCR_PRIGROUP_MASK (7 << NVIC_AIRCR_PRIGROUP_SHIFT) +#define NVIC_AIRCR_ENDIANNESS (1 << 15) /* Bit 15: 1=Big endian */ +#define NVIC_AIRCR_VECTKEY_SHIFT (16) /* Bits 16-31: VECTKEY */ +#define NVIC_AIRCR_VECTKEY_MASK (0xffff << NVIC_AIRCR_VECTKEY_SHIFT) +#define NVIC_AIRCR_VECTKEYSTAT_SHIFT (16) /* Bits 16-31: VECTKEYSTAT */ +#define NVIC_AIRCR_VECTKEYSTAT_MASK (0xffff << NVIC_AIRCR_VECTKEYSTAT_SHIFT) /* Debug Exception and Monitor Control Register (DEMCR) */ diff --git a/nuttx/arch/arm/src/armv7-m/up_systemreset.c b/nuttx/arch/arm/src/armv7-m/up_systemreset.c new file mode 100644 index 000000000..0d7bd2736 --- /dev/null +++ b/nuttx/arch/arm/src/armv7-m/up_systemreset.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * arch/arm/src/armv7-m/up_systemreset.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Darcy Gong + * + * 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 "up_arch.h" +#include "nvic.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + + /**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public functions + ****************************************************************************/ + +void up_systemreset(void) +{ + uint32_t regval; + + /* Set up for the system reset, retaining the priority group from the + * the AIRCR register. + */ + + regval = getreg32(NVIC_AIRCR) & NVIC_AIRCR_PRIGROUP_MASK; + regval |= ((0x5fa << NVIC_AIRCR_VECTKEY_SHIFT) | NVIC_AIRCR_SYSRESETREQ); + putreg32(regval, NVIC_AIRCR); + + /* Ensure completion of memory accesses */ + + __asm volatile ("dsb"); + + /* Wait for the reset */ + + for (;;); +} diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h index 9f20775c0..42142c5e8 100644 --- a/nuttx/arch/arm/src/common/up_internal.h +++ b/nuttx/arch/arm/src/common/up_internal.h @@ -241,6 +241,10 @@ extern void up_pminitialize(void); # define up_pminitialize() #endif +#if defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4) +extern void up_systemreset(void) noreturn_function; +#endif + /* Interrupt handling *******************************************************/ extern void up_irqinitialize(void); diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index 8d93fb104..fe89119a4 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -269,6 +269,7 @@ config STM32_ETHMAC bool "Ethernet MAC" default n depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX + select ARCH_HAVE_PHY config STM32_FSMC bool "FSMC" diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index 24af16c95..e52962977 100644 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -45,8 +45,8 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \ up_initialize.c up_initialstate.c up_interruptcontext.c \ up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ up_releasepending.c up_releasestack.c up_reprioritizertr.c \ - up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \ - up_usestack.c up_doirq.c up_hardfault.c up_svcall.c + up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \ + up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y) CMN_ASRCS += up_exception.S diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c index 2e892c9e5..81345fabf 100644 --- a/nuttx/arch/arm/src/stm32/stm32_eth.c +++ b/nuttx/arch/arm/src/stm32/stm32_eth.c @@ -664,6 +664,9 @@ static void stm32_rxdescinit(FAR struct stm32_ethmac_s *priv); static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value); static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value); +#ifdef CONFIG_PHY_DM9161 +static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv); +#endif static int stm32_phyinit(FAR struct stm32_ethmac_s *priv); /* MAC/DMA Initialization */ @@ -2479,6 +2482,72 @@ static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t val return -ETIMEDOUT; } +/**************************************************************************** + * Function: stm32_dm9161 + * + * Description: + * Special workaround for the Davicom DM9161 PHY is required. On power, + * up, the PHY is not usually configured correctly but will work after + * a powered-up reset. This is really a workaround for some more + * fundamental issue with the PHY clocking initialization, but the + * root cause has not been studied (nor will it be with this workaround). + * + * Parameters: + * priv - A reference to the private driver state structure + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_PHY_DM9161 +static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv) +{ + uint16_t phyval; + int ret; + + /* Read the PHYID1 register; A failure to read the PHY ID is one + * indication that check if the DM9161 PHY CHIP is not ready. + */ + + ret = stm32_phyread(CONFIG_STM32_PHYADDR, MII_PHYID1, &phyval); + if (ret < 0) + { + ndbg("Failed to read the PHY ID1: %d\n", ret); + return ret; + } + + /* If we failed to read the PHY ID1 register, the reset the MCU to recover */ + + else if (phyval == 0xffff) + { + up_systemreset(); + } + + nvdbg("PHY ID1: 0x%04X\n", phyval); + + /* Now check the "DAVICOM Specified Configuration Register (DSCR)", Register 16 */ + + ret = stm32_phyread(CONFIG_STM32_PHYADDR, 16, &phyval); + if (ret < 0) + { + ndbg("Failed to read the PHY Register 0x10: %d\n", ret); + return ret; + } + + /* Bit 8 of the DSCR register is zero, the the DM9161 has not selected RMII. + * If RMII is not selected, then reset the MCU to recover. + */ + + else if ((phyval & (1 << 8)) == 0) + { + up_systemreset(); + } + + return OK; +} +#endif + /**************************************************************************** * Function: stm32_phyinit * @@ -2524,6 +2593,16 @@ static int stm32_phyinit(FAR struct stm32_ethmac_s *priv) } up_mdelay(PHY_RESET_DELAY); + /* Special workaround for the Davicom DM9161 PHY is required. */ + +#ifdef CONFIG_PHY_DM9161 + ret = stm32_dm9161(priv); + if (ret < 0) + { + return ret; + } +#endif + /* Perform auto-negotion if so configured */ #ifdef CONFIG_STM32_AUTONEG -- cgit v1.2.3