From df4622c8aa68493604f1e611eeb50c0960bb61a9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 13 Sep 2012 18:32:24 +0000 Subject: Email address change in nuttx/ git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5145 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/lm3s6965-ek/src/Makefile | 2 +- .../configs/lm3s6965-ek/src/lm3s6965ek_internal.h | 272 ++++++++--------- nuttx/configs/lm3s6965-ek/src/up_boot.c | 184 ++++++------ nuttx/configs/lm3s6965-ek/src/up_ethernet.c | 196 ++++++------ nuttx/configs/lm3s6965-ek/src/up_leds.c | 2 +- nuttx/configs/lm3s6965-ek/src/up_nsh.c | 2 +- nuttx/configs/lm3s6965-ek/src/up_oled.c | 2 +- nuttx/configs/lm3s6965-ek/src/up_ssi.c | 328 ++++++++++----------- 8 files changed, 494 insertions(+), 494 deletions(-) (limited to 'nuttx/configs/lm3s6965-ek/src') diff --git a/nuttx/configs/lm3s6965-ek/src/Makefile b/nuttx/configs/lm3s6965-ek/src/Makefile index bd9b4f9ca..90833fc31 100644 --- a/nuttx/configs/lm3s6965-ek/src/Makefile +++ b/nuttx/configs/lm3s6965-ek/src/Makefile @@ -2,7 +2,7 @@ # configs/lm3s6965-ek/src/Makefile # # Copyright (C) 2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions diff --git a/nuttx/configs/lm3s6965-ek/src/lm3s6965ek_internal.h b/nuttx/configs/lm3s6965-ek/src/lm3s6965ek_internal.h index fb3a8a4ea..621f00148 100644 --- a/nuttx/configs/lm3s6965-ek/src/lm3s6965ek_internal.h +++ b/nuttx/configs/lm3s6965-ek/src/lm3s6965ek_internal.h @@ -1,136 +1,136 @@ -/************************************************************************************ - * configs/lm3s6965-ek/src/lm3s6965ek_internal.h - * arch/arm/src/board/lm3s6965ek_internal.n - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 __CONFIGS_LM3S6965_EK_SRC_LM3S6965EK_INTERNAL_H -#define __CONFIGS_LM3S6965_EK_SRC_LM3S6965EK_INTERNAL_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include - -#include "chip.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* How many SSI modules does this chip support? The LM3S6965 supports 1 SSI - * module (others may support more than 2 -- in such case, the following must be - * expanded). - */ - -#if LM3S_NSSI == 0 -# undef CONFIG_SSI0_DISABLE -# define CONFIG_SSI0_DISABLE 1 -# undef CONFIG_SSI1_DISABLE -# define CONFIG_SSI1_DISABLE 1 -#elif LM3S_NSSI == 1 -# undef CONFIG_SSI1_DISABLE -# define CONFIG_SSI1_DISABLE 1 -#endif - -/* LM3S6965 Eval Kit ***************************************************************/ - -/* GPIO Usage - * - * PIN SIGNAL EVB Function - * --- ----------- --------------------------------------- - * 26 PA0/U0RX Virtual COM port receive - * 27 PA1/U0TX Virtual COM port transmit - * 10 PD0/IDX0 SD card chip select - * 11 PD1/PWM1 Sound - * 30 PA4/SSI0RX SD card data out - * 31 PA5/SSI0TX SD card and OLED display data in - * 28 PA2/SSI0CLK SD card and OLED display clock - * 22 PC7/PHB0 OLED display data/control select - * 29 PA3/SSI0FSS OLED display chip select - * 73 PE1/PWM5 Down switch - * 74 PE2/PHB1 Left switch - * 72 PE0/PWM4 Up switch - * 75 PE3/PHA1 Right switch - * 61 PF1/IDX1 Select switch - * 47 PF0/PWM0 User LED - * 23 PC6/CCP3 Enable +15 V - */ - -/* GPIO for microSD card chip select: - * - PD0: SD card chip select (CARDCSn) - */ - -#define SDCCS_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STDWPU | GPIO_STRENGTH_4MA | \ - GPIO_VALUE_ONE | GPIO_PORTD | 0) - -/* GPIO for single LED: - * - PF0: User LED - */ - -#define LED_GPIO (GPIO_FUNC_OUTPUT | GPIO_VALUE_ONE | GPIO_PORTF | 0) - -/* GPIOs for OLED: - * - PC7: OLED display data/control select (D/Cn) - * - PA3: OLED display chip select (CSn) - * - PC6: Enable +15V needed by OLED (EN+15V) - */ - -#define OLEDDC_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STD | GPIO_STRENGTH_8MA | \ - GPIO_VALUE_ONE | GPIO_PORTC | 7) -#define OLEDCS_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STDWPU | GPIO_STRENGTH_4MA | \ - GPIO_VALUE_ONE | GPIO_PORTA | 3) -#define OLEDEN_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STD | GPIO_STRENGTH_8MA | \ - GPIO_VALUE_ONE | GPIO_PORTC | 6) - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -/************************************************************************************ - * Name: lm3s_ssiinitialize - * - * Description: - * Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit. - * - ************************************************************************************/ - -extern void weak_function lm3s_ssiinitialize(void); - -#endif /* __ASSEMBLY__ */ -#endif /* __CONFIGS_LM3S6965_EK_SRC_LM3S6965EK_INTERNAL_H */ - +/************************************************************************************ + * configs/lm3s6965-ek/src/lm3s6965ek_internal.h + * arch/arm/src/board/lm3s6965ek_internal.n + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 __CONFIGS_LM3S6965_EK_SRC_LM3S6965EK_INTERNAL_H +#define __CONFIGS_LM3S6965_EK_SRC_LM3S6965EK_INTERNAL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include "chip.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* How many SSI modules does this chip support? The LM3S6965 supports 1 SSI + * module (others may support more than 2 -- in such case, the following must be + * expanded). + */ + +#if LM3S_NSSI == 0 +# undef CONFIG_SSI0_DISABLE +# define CONFIG_SSI0_DISABLE 1 +# undef CONFIG_SSI1_DISABLE +# define CONFIG_SSI1_DISABLE 1 +#elif LM3S_NSSI == 1 +# undef CONFIG_SSI1_DISABLE +# define CONFIG_SSI1_DISABLE 1 +#endif + +/* LM3S6965 Eval Kit ***************************************************************/ + +/* GPIO Usage + * + * PIN SIGNAL EVB Function + * --- ----------- --------------------------------------- + * 26 PA0/U0RX Virtual COM port receive + * 27 PA1/U0TX Virtual COM port transmit + * 10 PD0/IDX0 SD card chip select + * 11 PD1/PWM1 Sound + * 30 PA4/SSI0RX SD card data out + * 31 PA5/SSI0TX SD card and OLED display data in + * 28 PA2/SSI0CLK SD card and OLED display clock + * 22 PC7/PHB0 OLED display data/control select + * 29 PA3/SSI0FSS OLED display chip select + * 73 PE1/PWM5 Down switch + * 74 PE2/PHB1 Left switch + * 72 PE0/PWM4 Up switch + * 75 PE3/PHA1 Right switch + * 61 PF1/IDX1 Select switch + * 47 PF0/PWM0 User LED + * 23 PC6/CCP3 Enable +15 V + */ + +/* GPIO for microSD card chip select: + * - PD0: SD card chip select (CARDCSn) + */ + +#define SDCCS_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STDWPU | GPIO_STRENGTH_4MA | \ + GPIO_VALUE_ONE | GPIO_PORTD | 0) + +/* GPIO for single LED: + * - PF0: User LED + */ + +#define LED_GPIO (GPIO_FUNC_OUTPUT | GPIO_VALUE_ONE | GPIO_PORTF | 0) + +/* GPIOs for OLED: + * - PC7: OLED display data/control select (D/Cn) + * - PA3: OLED display chip select (CSn) + * - PC6: Enable +15V needed by OLED (EN+15V) + */ + +#define OLEDDC_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STD | GPIO_STRENGTH_8MA | \ + GPIO_VALUE_ONE | GPIO_PORTC | 7) +#define OLEDCS_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STDWPU | GPIO_STRENGTH_4MA | \ + GPIO_VALUE_ONE | GPIO_PORTA | 3) +#define OLEDEN_GPIO (GPIO_FUNC_OUTPUT | GPIO_PADTYPE_STD | GPIO_STRENGTH_8MA | \ + GPIO_VALUE_ONE | GPIO_PORTC | 6) + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Name: lm3s_ssiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit. + * + ************************************************************************************/ + +extern void weak_function lm3s_ssiinitialize(void); + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_LM3S6965_EK_SRC_LM3S6965EK_INTERNAL_H */ + diff --git a/nuttx/configs/lm3s6965-ek/src/up_boot.c b/nuttx/configs/lm3s6965-ek/src/up_boot.c index 3fb75cf54..7f887be62 100644 --- a/nuttx/configs/lm3s6965-ek/src/up_boot.c +++ b/nuttx/configs/lm3s6965-ek/src/up_boot.c @@ -1,92 +1,92 @@ -/************************************************************************************ - * configs/lm3s6965-ek/src/up_boot.c - * arch/arm/src/board/up_boot.c - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 "up_arch.h" -#include "up_internal.h" -#include "lm3s6965ek_internal.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: lm3s_boardinitialize - * - * Description: - * All LM3S architectures must provide the following entry point. This entry point - * is called early in the intitialization -- after all memory has been configured - * and mapped but before any devices have been initialized. - ************************************************************************************/ - -void lm3s_boardinitialize(void) -{ - /* Configure SPI chip selects if 1) SSI is not disabled, and 2) the weak function - * lm3s_ssiinitialize() has been brought into the link. - */ - - /* The LM3S6965 Eval Kit microSD CS and OLED are on SSI0 (Duh! There is no SSI1) */ - -#if !defined(CONFIG_SSI0_DISABLE) /* || !defined(CONFIG_SSI1_DISABLE) */ - if (lm3s_ssiinitialize) - { - lm3s_ssiinitialize(); - } -#endif - - /* Configure on-board LEDs if LED support has been selected. */ - -#ifdef CONFIG_ARCH_LEDS - up_ledinit(); -#endif -} +/************************************************************************************ + * configs/lm3s6965-ek/src/up_boot.c + * arch/arm/src/board/up_boot.c + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 "up_arch.h" +#include "up_internal.h" +#include "lm3s6965ek_internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: lm3s_boardinitialize + * + * Description: + * All LM3S architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + ************************************************************************************/ + +void lm3s_boardinitialize(void) +{ + /* Configure SPI chip selects if 1) SSI is not disabled, and 2) the weak function + * lm3s_ssiinitialize() has been brought into the link. + */ + + /* The LM3S6965 Eval Kit microSD CS and OLED are on SSI0 (Duh! There is no SSI1) */ + +#if !defined(CONFIG_SSI0_DISABLE) /* || !defined(CONFIG_SSI1_DISABLE) */ + if (lm3s_ssiinitialize) + { + lm3s_ssiinitialize(); + } +#endif + + /* Configure on-board LEDs if LED support has been selected. */ + +#ifdef CONFIG_ARCH_LEDS + up_ledinit(); +#endif +} diff --git a/nuttx/configs/lm3s6965-ek/src/up_ethernet.c b/nuttx/configs/lm3s6965-ek/src/up_ethernet.c index 1cea3d022..4f402cae7 100644 --- a/nuttx/configs/lm3s6965-ek/src/up_ethernet.c +++ b/nuttx/configs/lm3s6965-ek/src/up_ethernet.c @@ -1,98 +1,98 @@ -/************************************************************************************ - * configs/lm3s6965-ek/src/up_ethernet.c - * arch/arm/src/board/up_ethernet.c - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 "up_arch.h" -#include "chip.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: lm3s_ethernetmac - * - * Description: - * For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile - * USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function - * will obtain the MAC address from these registers. - * - ************************************************************************************/ - -#ifdef CONFIG_LM3S_BOARDMAC -void lm3s_ethernetmac(struct ether_addr *ethaddr) -{ - uint32_t user0; - uint32_t user1; - - /* Get the current value of the user registers */ - - user0 = getreg32(LM3S_FLASH_USERREG0); - user1 = getreg32(LM3S_FLASH_USERREG1); - - nlldbg("user: %06x:%06x\n", user1 & 0x00ffffff, user0 & 0x00ffffff); - DEBUGASSERT(user0 != 0xffffffff && user1 != 0xffffffff); - - /* Re-format that MAC address the way that uIP expects to see it */ - - ethaddr->ether_addr_octet[0] = ((user0 >> 0) & 0xff); - ethaddr->ether_addr_octet[1] = ((user0 >> 8) & 0xff); - ethaddr->ether_addr_octet[2] = ((user0 >> 16) & 0xff); - ethaddr->ether_addr_octet[3] = ((user1 >> 0) & 0xff); - ethaddr->ether_addr_octet[4] = ((user1 >> 8) & 0xff); - ethaddr->ether_addr_octet[5] = ((user1 >> 16) & 0xff); -} -#endif +/************************************************************************************ + * configs/lm3s6965-ek/src/up_ethernet.c + * arch/arm/src/board/up_ethernet.c + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 "up_arch.h" +#include "chip.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: lm3s_ethernetmac + * + * Description: + * For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile + * USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function + * will obtain the MAC address from these registers. + * + ************************************************************************************/ + +#ifdef CONFIG_LM3S_BOARDMAC +void lm3s_ethernetmac(struct ether_addr *ethaddr) +{ + uint32_t user0; + uint32_t user1; + + /* Get the current value of the user registers */ + + user0 = getreg32(LM3S_FLASH_USERREG0); + user1 = getreg32(LM3S_FLASH_USERREG1); + + nlldbg("user: %06x:%06x\n", user1 & 0x00ffffff, user0 & 0x00ffffff); + DEBUGASSERT(user0 != 0xffffffff && user1 != 0xffffffff); + + /* Re-format that MAC address the way that uIP expects to see it */ + + ethaddr->ether_addr_octet[0] = ((user0 >> 0) & 0xff); + ethaddr->ether_addr_octet[1] = ((user0 >> 8) & 0xff); + ethaddr->ether_addr_octet[2] = ((user0 >> 16) & 0xff); + ethaddr->ether_addr_octet[3] = ((user1 >> 0) & 0xff); + ethaddr->ether_addr_octet[4] = ((user1 >> 8) & 0xff); + ethaddr->ether_addr_octet[5] = ((user1 >> 16) & 0xff); +} +#endif diff --git a/nuttx/configs/lm3s6965-ek/src/up_leds.c b/nuttx/configs/lm3s6965-ek/src/up_leds.c index f817f8261..933c11446 100644 --- a/nuttx/configs/lm3s6965-ek/src/up_leds.c +++ b/nuttx/configs/lm3s6965-ek/src/up_leds.c @@ -3,7 +3,7 @@ * arch/arm/src/board/up_leds.c * * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/configs/lm3s6965-ek/src/up_nsh.c b/nuttx/configs/lm3s6965-ek/src/up_nsh.c index 952ee4298..409b351f0 100644 --- a/nuttx/configs/lm3s6965-ek/src/up_nsh.c +++ b/nuttx/configs/lm3s6965-ek/src/up_nsh.c @@ -3,7 +3,7 @@ * arch/arm/src/board/up_nsh.c * * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/configs/lm3s6965-ek/src/up_oled.c b/nuttx/configs/lm3s6965-ek/src/up_oled.c index 8a26e1eb2..586927d53 100644 --- a/nuttx/configs/lm3s6965-ek/src/up_oled.c +++ b/nuttx/configs/lm3s6965-ek/src/up_oled.c @@ -3,7 +3,7 @@ * arch/arm/src/board/up_oled.c * * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/configs/lm3s6965-ek/src/up_ssi.c b/nuttx/configs/lm3s6965-ek/src/up_ssi.c index 4dcd231c0..16111fcda 100644 --- a/nuttx/configs/lm3s6965-ek/src/up_ssi.c +++ b/nuttx/configs/lm3s6965-ek/src/up_ssi.c @@ -1,164 +1,164 @@ -/************************************************************************************ - * configs/lm3s6965-ek/src/up_ssi.c - * arch/arm/src/board/up_ssi.c - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 "up_arch.h" -#include "chip.h" -#include "lm3s_internal.h" -#include "lm3s6965ek_internal.h" - -/* The LM3S6965 Eval Kit microSD CS is on SSI0 */ - -#if !defined(CONFIG_SSI0_DISABLE) /* || !defined(CONFIG_SSI1_DISABLE) */ - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* Enables debug output from this file (needs CONFIG_DEBUG too) */ - -#undef SSI_DEBUG /* Define to enable debug */ -#undef SSI_VERBOSE /* Define to enable verbose debug */ - -#ifdef SSI_DEBUG -# define ssidbg lldbg -# ifdef SSI_VERBOSE -# define ssivdbg lldbg -# else -# define ssivdbg(x...) -# endif -#else -# undef SSI_VERBOSE -# define ssidbg(x...) -# define ssivdbg(x...) -#endif - -/* Dump GPIO registers */ - -#ifdef SSI_VERBOSE -# define ssi_dumpgpio(m) lm3s_dumpgpio(SDCCS_GPIO, m) -#else -# define ssi_dumpgpio(m) -#endif - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: lm3s_ssiinitialize - * - * Description: - * Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit. - * - ************************************************************************************/ - -void weak_function lm3s_ssiinitialize(void) -{ - /* Configure the SPI-based microSD CS GPIO */ - - ssi_dumpgpio("lm3s_ssiinitialize() Entry)"); - lm3s_configgpio(SDCCS_GPIO); -#ifdef CONFIG_NX_LCDDRIVER - lm3s_configgpio(OLEDCS_GPIO); -#endif - ssi_dumpgpio("lm3s_ssiinitialize() Exit"); -} - -/**************************************************************************** - * The external functions, lm3s_spiselect and lm3s_spistatus must be provided - * by board-specific logic. The are implementations of the select and status - * methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h). - * All othermethods (including up_spiinitialize()) are provided by common - * logic. To use this common SPI logic on your board: - * - * 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your - * board-specific logic. This function will perform chip selection and - * status operations using GPIOs in the way your board is configured. - * 2. Add a call to up_spiinitialize() in your low level initialization - * logic - * 3. The handle returned by up_spiinitialize() may then be used to bind the - * SPI driver to higher level logic (e.g., calling - * mmcsd_spislotinitialize(), for example, will bind the SPI driver to - * the SPI MMC/SD driver). - * - ****************************************************************************/ - -void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) -{ - ssidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); - ssi_dumpgpio("lm3s_spiselect() Entry"); - - if (devid == SPIDEV_MMCSD) - { - /* Assert the CS pin to the card */ - - lm3s_gpiowrite(SDCCS_GPIO, !selected); - } -#ifdef CONFIG_NX_LCDDRIVER - else if (devid == SPIDEV_DISPLAY) - { - /* Assert the CS pin to the display */ - - lm3s_gpiowrite(OLEDCS_GPIO, !selected); - } -#endif - ssi_dumpgpio("lm3s_spiselect() Exit"); -} - -uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) -{ - ssidbg("Returning SPI_STATUS_PRESENT\n"); - return SPI_STATUS_PRESENT; -} - -#endif /* !CONFIG_SSI0_DISABLE || !CONFIG_SSI1_DISABLE */ +/************************************************************************************ + * configs/lm3s6965-ek/src/up_ssi.c + * arch/arm/src/board/up_ssi.c + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 "up_arch.h" +#include "chip.h" +#include "lm3s_internal.h" +#include "lm3s6965ek_internal.h" + +/* The LM3S6965 Eval Kit microSD CS is on SSI0 */ + +#if !defined(CONFIG_SSI0_DISABLE) /* || !defined(CONFIG_SSI1_DISABLE) */ + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Enables debug output from this file (needs CONFIG_DEBUG too) */ + +#undef SSI_DEBUG /* Define to enable debug */ +#undef SSI_VERBOSE /* Define to enable verbose debug */ + +#ifdef SSI_DEBUG +# define ssidbg lldbg +# ifdef SSI_VERBOSE +# define ssivdbg lldbg +# else +# define ssivdbg(x...) +# endif +#else +# undef SSI_VERBOSE +# define ssidbg(x...) +# define ssivdbg(x...) +#endif + +/* Dump GPIO registers */ + +#ifdef SSI_VERBOSE +# define ssi_dumpgpio(m) lm3s_dumpgpio(SDCCS_GPIO, m) +#else +# define ssi_dumpgpio(m) +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: lm3s_ssiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit. + * + ************************************************************************************/ + +void weak_function lm3s_ssiinitialize(void) +{ + /* Configure the SPI-based microSD CS GPIO */ + + ssi_dumpgpio("lm3s_ssiinitialize() Entry)"); + lm3s_configgpio(SDCCS_GPIO); +#ifdef CONFIG_NX_LCDDRIVER + lm3s_configgpio(OLEDCS_GPIO); +#endif + ssi_dumpgpio("lm3s_ssiinitialize() Exit"); +} + +/**************************************************************************** + * The external functions, lm3s_spiselect and lm3s_spistatus must be provided + * by board-specific logic. The are implementations of the select and status + * methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h). + * All othermethods (including up_spiinitialize()) are provided by common + * logic. To use this common SPI logic on your board: + * + * 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your + * board-specific logic. This function will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 2. Add a call to up_spiinitialize() in your low level initialization + * logic + * 3. The handle returned by up_spiinitialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + ssidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + ssi_dumpgpio("lm3s_spiselect() Entry"); + + if (devid == SPIDEV_MMCSD) + { + /* Assert the CS pin to the card */ + + lm3s_gpiowrite(SDCCS_GPIO, !selected); + } +#ifdef CONFIG_NX_LCDDRIVER + else if (devid == SPIDEV_DISPLAY) + { + /* Assert the CS pin to the display */ + + lm3s_gpiowrite(OLEDCS_GPIO, !selected); + } +#endif + ssi_dumpgpio("lm3s_spiselect() Exit"); +} + +uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + ssidbg("Returning SPI_STATUS_PRESENT\n"); + return SPI_STATUS_PRESENT; +} + +#endif /* !CONFIG_SSI0_DISABLE || !CONFIG_SSI1_DISABLE */ -- cgit v1.2.3