From 8c6ebe6f07cb81ab197850c2af4c75fb50e5f1cb Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 17 Jun 2011 22:03:20 +0000 Subject: Fix AVR clock setup; add SPI driver git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3721 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/avr/src/at90usb/Make.defs | 4 + nuttx/arch/avr/src/at90usb/at90usb_lowinit.c | 5 + nuttx/arch/avr/src/at90usb/at90usb_memorymap.h | 6 - nuttx/arch/avr/src/at90usb/chip.h | 2 +- nuttx/arch/avr/src/atmega/Make.defs | 4 + nuttx/arch/avr/src/atmega/atmega_lowinit.c | 5 + nuttx/arch/avr/src/atmega/atmega_memorymap.h | 6 - nuttx/arch/avr/src/atmega/chip.h | 2 +- nuttx/arch/avr/src/avr/avr_internal.h | 85 ++++ nuttx/arch/avr/src/avr/up_spi.c | 537 +++++++++++++++++++++++++ nuttx/arch/avr/src/avr32/avr32_internal.h | 45 +++ nuttx/arch/avr/src/common/up_assert.c | 9 + 12 files changed, 696 insertions(+), 14 deletions(-) create mode 100644 nuttx/arch/avr/src/avr/up_spi.c (limited to 'nuttx/arch') diff --git a/nuttx/arch/avr/src/at90usb/Make.defs b/nuttx/arch/avr/src/at90usb/Make.defs index e3559c0dc..706eca544 100644 --- a/nuttx/arch/avr/src/at90usb/Make.defs +++ b/nuttx/arch/avr/src/at90usb/Make.defs @@ -54,6 +54,10 @@ ifeq ($(CONFIG_ARCH_STACKDUMP),y) CMN_CSRCS += up_dumpstate.c endif +ifeq ($(CONFIG_AVR_SPI),y) +CMN_CSRCS += up_spi.c +endif + # Required AT90USB files CHIP_ASRCS = at90usb_exceptions.S diff --git a/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c b/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c index 5f8b2e432..e446fcf13 100644 --- a/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c +++ b/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c @@ -39,6 +39,7 @@ #include #include +#include #include "at90usb_config.h" #include "up_internal.h" @@ -127,6 +128,10 @@ void up_lowinit(void) up_wdtinit(); + /* Set the system clock divider to 1 */ + + clock_prescale_set(clock_div_1); + /* Initialize a console (probably a serial console) */ up_consoleinit(); diff --git a/nuttx/arch/avr/src/at90usb/at90usb_memorymap.h b/nuttx/arch/avr/src/at90usb/at90usb_memorymap.h index c312a7cca..71635d383 100644 --- a/nuttx/arch/avr/src/at90usb/at90usb_memorymap.h +++ b/nuttx/arch/avr/src/at90usb/at90usb_memorymap.h @@ -46,12 +46,6 @@ * Pre-processor Definitions ************************************************************************************/ -/* Physical memory map */ -# warning "Missing Definitions" - -/* Peripheral Address Map */ -# warning "Missing Definitions" - /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/nuttx/arch/avr/src/at90usb/chip.h b/nuttx/arch/avr/src/at90usb/chip.h index facc65ec1..c5f2c48b3 100644 --- a/nuttx/arch/avr/src/at90usb/chip.h +++ b/nuttx/arch/avr/src/at90usb/chip.h @@ -48,7 +48,7 @@ /* Define features for supported chip in the ATMEGA family */ -#if 0 +#if 1 #else # error "Unsupported AVR chip" #endif diff --git a/nuttx/arch/avr/src/atmega/Make.defs b/nuttx/arch/avr/src/atmega/Make.defs index a761b4938..16f0f5a62 100644 --- a/nuttx/arch/avr/src/atmega/Make.defs +++ b/nuttx/arch/avr/src/atmega/Make.defs @@ -54,6 +54,10 @@ ifeq ($(CONFIG_ARCH_STACKDUMP),y) CMN_CSRCS += up_dumpstate.c endif +ifeq ($(CONFIG_AVR_SPI),y) +CMN_CSRCS += up_spi.c +endif + # Required ATMEGA files CHIP_ASRCS = atmega_exceptions.S diff --git a/nuttx/arch/avr/src/atmega/atmega_lowinit.c b/nuttx/arch/avr/src/atmega/atmega_lowinit.c index 417f4e2eb..5802a22f0 100644 --- a/nuttx/arch/avr/src/atmega/atmega_lowinit.c +++ b/nuttx/arch/avr/src/atmega/atmega_lowinit.c @@ -39,6 +39,7 @@ #include #include +#include #include "atmega_config.h" #include "up_internal.h" @@ -127,6 +128,10 @@ void up_lowinit(void) up_wdtinit(); + /* Set the system clock divider to 1 */ + + clock_prescale_set(clock_div_1); + /* Initialize a console (probably a serial console) */ up_consoleinit(); diff --git a/nuttx/arch/avr/src/atmega/atmega_memorymap.h b/nuttx/arch/avr/src/atmega/atmega_memorymap.h index a509f7657..7b990754c 100644 --- a/nuttx/arch/avr/src/atmega/atmega_memorymap.h +++ b/nuttx/arch/avr/src/atmega/atmega_memorymap.h @@ -46,12 +46,6 @@ * Pre-processor Definitions ************************************************************************************/ -/* Physical memory map */ -# warning "Missing Definitions" - -/* Peripheral Address Map */ -# warning "Missing Definitions" - /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/nuttx/arch/avr/src/atmega/chip.h b/nuttx/arch/avr/src/atmega/chip.h index 7f114a604..0e3f779ab 100644 --- a/nuttx/arch/avr/src/atmega/chip.h +++ b/nuttx/arch/avr/src/atmega/chip.h @@ -48,7 +48,7 @@ /* Define features for supported chip in the ATMEGA family */ -#if 0 +#if 1 #else # error "Unsupported AVR chip" #endif diff --git a/nuttx/arch/avr/src/avr/avr_internal.h b/nuttx/arch/avr/src/avr/avr_internal.h index 21906c79d..841b8376a 100644 --- a/nuttx/arch/avr/src/avr/avr_internal.h +++ b/nuttx/arch/avr/src/avr/avr_internal.h @@ -42,6 +42,7 @@ #ifndef __ASSEMBLY__ # include +# include #endif /**************************************************************************** @@ -90,12 +91,96 @@ extern uint16_t g_heapbase; #ifndef __ASSEMBLY__ +/************************************************************************************ + * Name: up_copystate + * + * Description: + * Copy the contents of a register state save structure from one location to + * another. + * + ************************************************************************************/ + extern void up_copystate(uint8_t *dest, uint8_t *src); + +/************************************************************************************ + * Name: up_saveusercontext + * + * Description: + * Save the register context of the currently executing (user) thread. + * + ************************************************************************************/ + extern int up_saveusercontext(uint8_t *saveregs); + +/************************************************************************************ + * Name: up_fullcontextrestore + * + * Description: + * Restore the full context of a saved thread/task. + * + ************************************************************************************/ + extern void up_fullcontextrestore(uint8_t *restoreregs) __attribute__ ((noreturn)); + +/************************************************************************************ + * Name: up_switchcontext + * + * Description: + * Switch from one thread/task context to another. + * + ************************************************************************************/ + extern void up_switchcontext(uint8_t *saveregs, uint8_t *restoreregs); + +/************************************************************************************ + * Name: up_doirq + * + * Description: + * Dispatch an interrupt. + * + ************************************************************************************/ + extern uint8_t *up_doirq(uint8_t irq, uint8_t *regs); +/************************************************************************************ + * Name: avr_spiselect, avr_spitatus, and avr_spicmddata + * + * Description: + * These external functions must be provided by board-specific logic. They are + * implementations of the select, status, and cmddata methods of the SPI interface + * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods + * including up_spiinitialize()) are provided by common LPC17xx logic. To use + * this common SPI logic on your board: + * + * 1. Provide logic in up_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide avr_spiselect() and avr_spistatus() functions in your board-specific + * logic. These functions will perform chip selection and status operations + * using GPIOs in the way your board is configured. + * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide the + * avr_spicmddata() function in your board-specific logic. This functions will + * perform cmd/data selection operations using GPIOs in the way your board is + * configured. + * 3. Add a call 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 + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ************************************************************************************/ + +struct spi_dev_s; +enum spi_dev_e; + +#ifdef CONFIG_AVR_SPI +extern void avr_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +extern uint8_t avr_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +#ifdef CONFIG_SPI_CMDDATA +extern int avr_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +#endif +#endif + #endif /* __ASSEMBLY__ */ #endif /* __ARCH_AVR_SRC_AVR_AVR_INTERNAL_H */ diff --git a/nuttx/arch/avr/src/avr/up_spi.c b/nuttx/arch/avr/src/avr/up_spi.c new file mode 100644 index 000000000..7a38d5c97 --- /dev/null +++ b/nuttx/arch/avr/src/avr/up_spi.c @@ -0,0 +1,537 @@ +/**************************************************************************** + * arch/arm/src/avr/up_spi.c + * + * Copyright (C) 2011 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 + +#include +#include +#include + +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "avr_internal.h" + +#ifdef CONFIG_AVR_SPI + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Enables debug output from this file (needs CONFIG_DEBUG too) */ + +#undef SPI_DEBUG /* Define to enable debug */ +#undef SPI_VERBOSE /* Define to enable verbose debug */ + +#ifdef SPI_DEBUG +# define spidbg lldbg +# ifdef SPI_VERBOSE +# define spivdbg lldbg +# else +# define spivdbg(x...) +# endif +#else +# undef SPI_VERBOSE +# define spidbg(x...) +# define spivdbg(x...) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct avr_spidev_s +{ + struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ +#ifndef CONFIG_SPI_OWNBUS + sem_t exclsem; /* Held while chip is selected for mutual exclusion */ + uint32_t frequency; /* Requested clock frequency */ + uint32_t actual; /* Actual clock frequency */ + uint8_t mode; /* Mode 0,1,2,3 */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* SPI methods */ + +#ifndef CONFIG_SPI_OWNBUS +static int spi_lock(FAR struct spi_dev_s *dev, bool lock); +#endif +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t ch); +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords); +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct spi_ops_s g_spiops = +{ +#ifndef CONFIG_SPI_OWNBUS + .lock = spi_lock, +#endif + .select = avr_spiselect, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, + .status = avr_spistatus, +#ifdef CONFIG_SPI_CMDDATA + .cmddata = avr_spicmddata, +#endif + .send = spi_send, + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, + .registercallback = 0, /* Not implemented */ +}; + +static struct avr_spidev_s g_spidev = +{ + .spidev = { &g_spiops }, +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: spi_lock + * + * Description: + * On SPI busses where there are multiple devices, it will be necessary to + * lock SPI to have exclusive access to the busses for a sequence of + * transfers. The bus should be locked before the chip is selected. After + * locking the SPI bus, the caller should then also call the setfrequency, + * setbits, and setmode methods to make sure that the SPI is properly + * configured for the device. If the SPI buss is being shared, then it + * may have been left in an incompatible state. + * + * Input Parameters: + * dev - Device-specific state data + * lock - true: Lock spi bus, false: unlock SPI bus + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static int spi_lock(FAR struct spi_dev_s *dev, bool lock) +{ + FAR struct avr_spidev_s *priv = (FAR struct avr_spidev_s *)dev; + + if (lock) + { + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&priv->exclsem) != 0) + { + /* The only case that an error should occur here is if the wait was awakened + * by a signal. + */ + + ASSERT(errno == EINTR); + } + } + else + { + (void)sem_post(&priv->exclsem); + } + return OK; +} +#endif + +/**************************************************************************** + * Name: spi_setfrequency + * + * Description: + * Set the SPI frequency. + * + * Input Parameters: + * dev - Device-specific state data + * frequency - The SPI frequency requested + * + * Returned Value: + * Returns the actual frequency selected + * + ****************************************************************************/ + +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) +{ + uint32_t actual; +#ifndef CONFIG_SPI_OWNBUS + FAR struct avr_spidev_s *priv = (FAR struct avr_spidev_s *)dev; + + /* Has the request frequency changed? */ + + if (frequency != priv->frequency) + { +#endif + /* Read the SPI status and control registers, clearing all divider bits */ + + uint8_t spcr = SPCR & ~((1 << SPR0) | (1 << SPR1)); + uint8_t spsr = SPSR & ~(1 << SPI2X); + + /* Select the best divider bits */ + + if (frequency >= BOARD_CPU_CLOCK / 2) + { + spsr |= (1 << SPI2X); + actual = BOARD_CPU_CLOCK / 2; + } + else if (frequency >= BOARD_CPU_CLOCK / 4) + { + actual = BOARD_CPU_CLOCK / 4; + } + else if (frequency >= BOARD_CPU_CLOCK / 8) + { + spcr |= (1 << SPR0); + spsr |= (1 << SPI2X); + actual = BOARD_CPU_CLOCK / 8; + } + else if (frequency >= BOARD_CPU_CLOCK / 16) + { + spcr |= (1 << SPR0); + actual = BOARD_CPU_CLOCK / 16; + } + else if (frequency >= BOARD_CPU_CLOCK / 32) + { + spcr |= (1 << SPR1); + spsr |= (1 << SPI2X); + actual = BOARD_CPU_CLOCK / 32; + } + else if (frequency >= BOARD_CPU_CLOCK / 64) + { + spcr |= (1 << SPR1); + actual = BOARD_CPU_CLOCK / 64; + } + else /* if (frequency >= BOARD_CPU_CLOCK / 128) */ + { + spcr |= (1 << SPR0)|(1 << SPR1); + actual = BOARD_CPU_CLOCK / 128; + } + + /* Save the frequency setting */ + +#ifndef CONFIG_SPI_OWNBUS + priv->frequency = frequency; + priv->actual = actual; + } + else + { + actual = priv->actual; + } +#endif + + spidbg("Frequency %d->%d\n", frequency, actual); + return actual; +} + +/**************************************************************************** + * Name: spi_setmode + * + * Description: + * Set the SPI mode. Optional. See enum spi_mode_e for mode definitions + * + * Input Parameters: + * dev - Device-specific state data + * mode - The SPI mode requested + * + * Returned Value: + * none + * + ****************************************************************************/ + +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) +{ +#ifndef CONFIG_SPI_OWNBUS + FAR struct avr_spidev_s *priv = (FAR struct avr_spidev_s *)dev; + + /* Has the mode changed? */ + + if (mode != priv->mode) + { +#endif + uint8_t regval; + + /* Yes... Set SPI CR appropriately */ + + regval = SPCR; + regval &= ~((1 << CPOL) | (1 << CPHA)); + + switch (mode) + { + case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */ + break; + + case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */ + regval |= (1 << CPHA); + break; + + case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */ + regval |= (1 << CPOL); + break; + + case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */ + regval |= ((1 << CPOL) | (1 << CPHA)); + break; + + default: + DEBUGASSERT(FALSE); + return; + } + + SPSR = regval; + + /* Save the mode so that subsequent re-configuratins will be faster */ + +#ifndef CONFIG_SPI_OWNBUS + priv->mode = mode; + } +#endif +} + +/**************************************************************************** + * Name: spi_setbits + * + * Description: + * Set the number if bits per word. + * + * Input Parameters: + * dev - Device-specific state data + * nbits - The number of bits requests (only nbits == 8 is supported) + * + * Returned Value: + * none + * + ****************************************************************************/ + +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) +{ + DEBUGASSERT(dev && nbits == 8); +} + +/**************************************************************************** + * Name: spi_send + * + * Description: + * Exchange one word on SPI + * + * Input Parameters: + * dev - Device-specific state data + * wd - The word to send. the size of the data is determined by the + * number of bits selected for the SPI interface. + * + * Returned Value: + * response + * + ****************************************************************************/ + +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd) +{ + /* Write the data to transmitted to the SPI Data Register */ + + SPDR = (uint8_t)wd; + + /* Wait for transmission to complete */ + + while (!(SPSR & (1<8, the data is packed into + * uint16_t's + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords) +{ + FAR uint8_t *ptr = (FAR uint8_t*)buffer; + + spidbg("nwords: %d\n", nwords); + while (nwords-- > 0) + { + (void)spi_send(dev, (uint16_t)*ptr++); + } +} + +/**************************************************************************** + * Name: spi_recvblock + * + * Description: + * Revice a block of data from SPI + * + * Input Parameters: + * dev - Device-specific state data + * buffer - A pointer to the buffer in which to recieve data + * nwords - the length of data that can be received in the buffer in number + * of words. The wordsize is determined by the number of bits- + * per-wordselected for the SPI interface. If nbits <= 8, the + * data is packed into uint8_t's; if nbits >8, the data is packed + * into uint16_t's + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords) +{ + FAR uint8_t *ptr = (FAR uint8_t*)buffer; + + spidbg("nwords: %d\n", nwords); + while (nwords-- > 0) + { + *ptr++ = spi_send(dev, (uint16_t)0xff); + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_spiinitialize + * + * Description: + * Initialize the selected SPI port + * + * Input Parameter: + * Port number (for hardware that has mutiple SPI interfaces) + * + * Returned Value: + * Valid SPI device structure reference on succcess; a NULL on failure + * + ****************************************************************************/ + +FAR struct spi_dev_s *up_spiinitialize(int port) +{ + FAR struct avr_spidev_s *priv = &g_spidev; + irqstate_t flags; + uint8_t regval; + + /* Make sure that clocks are provided to the SPI module */ + + flags = irqsave(); + power_spi_enable(); + + /* Set MOSI and SCK as outputs, all others are inputs (default on reset): + * + * PB3: PDO/MISO/PCINT3 + * PB2: PDI/MOSI/PCINT2 + * PB1: SCK/PCINT1 + * PB0: SS/PCINT0 + */ + + DDRB |= (1 << 2) | (1 << 1); + + /* - Enable SPI + * - Set Master + * - Set clock rate oscillator/4 + * - Set CPOL for SPI clock mode 0 + */ + + SPCR = (1 << SPE) | (1 << MSTR); + + /* Set clock rate to f(osc)/8 */ + /* SPSR |= (1 << 0); */ + + /* Clear status flags by reading them */ + + regval = SPSR; + regval = SPDR; + + /* Set the initial SPI configuration */ + +#ifndef CONFIG_SPI_OWNBUS + priv->frequency = 0; + priv->mode = SPIDEV_MODE0; +#endif + + /* Select a default frequency of approx. 400KHz */ + + spi_setfrequency((FAR struct spi_dev_s *)priv, 400000); + + /* Initialize the SPI semaphore that enforces mutually exclusive access */ + +#ifndef CONFIG_SPI_OWNBUS + sem_init(&priv->exclsem, 0, 1); +#endif + return &priv->spidev; +} +#endif /* CONFIG_AVR_SPI */ + diff --git a/nuttx/arch/avr/src/avr32/avr32_internal.h b/nuttx/arch/avr/src/avr32/avr32_internal.h index 9cf714b01..58aa555aa 100644 --- a/nuttx/arch/avr/src/avr32/avr32_internal.h +++ b/nuttx/arch/avr/src/avr32/avr32_internal.h @@ -90,10 +90,55 @@ extern uint32_t g_heapbase; #ifndef __ASSEMBLY__ +/************************************************************************************ + * Name: up_copystate + * + * Description: + * Copy the contents of a register state save structure from one location to + * another. + * + ************************************************************************************/ + extern void up_copystate(uint32_t *dest, uint32_t *src); + +/************************************************************************************ + * Name: up_saveusercontext + * + * Description: + * Save the register context of the currently executing (user) thread. + * + ************************************************************************************/ + extern int up_saveusercontext(uint32_t *saveregs); + +/************************************************************************************ + * Name: up_fullcontextrestore + * + * Description: + * Restore the full context of a saved thread/task. + * + ************************************************************************************/ + extern void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn)); + +/************************************************************************************ + * Name: up_switchcontext + * + * Description: + * Switch from one thread/task context to another. + * + ************************************************************************************/ + extern void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs); + +/************************************************************************************ + * Name: up_doirq + * + * Description: + * Dispatch an interrupt. + * + ************************************************************************************/ + extern uint32_t *up_doirq(int irq, uint32_t *regs); #endif /* __ASSEMBLY__ */ diff --git a/nuttx/arch/avr/src/common/up_assert.c b/nuttx/arch/avr/src/common/up_assert.c index b2cd8ae86..a0ba2355e 100644 --- a/nuttx/arch/avr/src/common/up_assert.c +++ b/nuttx/arch/avr/src/common/up_assert.c @@ -69,6 +69,15 @@ # define CONFIG_PRINT_TASKNAME 1 #endif +/* If there is going to be stackdump output, then we should turn on output + * here unconditionally as well. + */ + +#ifdef CONFIG_ARCH_STACKDUMP +# undef lldbg +# define lldbg lib_lowprintf +#endif + /**************************************************************************** * Private Data ****************************************************************************/ -- cgit v1.2.3