Add software
This commit is contained in:
@ -0,0 +1,42 @@
|
||||
##
|
||||
## This file is part of the libopencm3 project.
|
||||
##
|
||||
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
|
||||
## Copyright (C) 2013 Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
##
|
||||
## This library is free software: you can redistribute it and/or modify
|
||||
## it under the terms of the GNU Lesser General Public License as published by
|
||||
## the Free Software Foundation, either version 3 of the License, or
|
||||
## (at your option) any later version.
|
||||
##
|
||||
## This library is distributed in the hope that it will be useful,
|
||||
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
## GNU Lesser General Public License for more details.
|
||||
##
|
||||
## You should have received a copy of the GNU Lesser General Public License
|
||||
## along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
##
|
||||
|
||||
LIBNAME = libopencm3_lm4f
|
||||
|
||||
FP_FLAGS ?= -mfloat-abi=hard -mfpu=fpv4-sp-d16
|
||||
PREFIX ?= arm-none-eabi
|
||||
|
||||
CC = $(PREFIX)-gcc
|
||||
AR = $(PREFIX)-ar
|
||||
CFLAGS = -Os -g \
|
||||
-Wall -Wextra -Wimplicit-function-declaration \
|
||||
-Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes \
|
||||
-Wundef -Wshadow \
|
||||
-I../../include -fno-common \
|
||||
-mcpu=cortex-m4 -mthumb $(FP_FLAGS) -Wstrict-prototypes \
|
||||
-ffunction-sections -fdata-sections -MD -DLM4F
|
||||
# ARFLAGS = rcsv
|
||||
ARFLAGS = rcs
|
||||
OBJS = gpio.o vector.o assert.o systemcontrol.o rcc.o uart.o \
|
||||
usb_lm4f.o usb.o usb_control.o usb_standard.o
|
||||
|
||||
VPATH += ../usb:../cm3
|
||||
|
||||
include ../Makefile.include
|
@ -0,0 +1,598 @@
|
||||
/*
|
||||
* This file is part of the libopencm3 project.
|
||||
*
|
||||
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
|
||||
* Copyright (C) 2013 Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* This library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU Lesser General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public License
|
||||
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/** @defgroup gpio_file GPIO
|
||||
*
|
||||
*
|
||||
* @ingroup LM4Fxx
|
||||
*
|
||||
* @version 1.0.0
|
||||
*
|
||||
* @author @htmlonly © @endhtmlonly 2011
|
||||
* Gareth McMullin <gareth@blacksphere.co.nz>
|
||||
* @author @htmlonly © @endhtmlonly 2013
|
||||
* Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* @date 16 March 2013
|
||||
*
|
||||
* LGPL License Terms @ref lgpl_license
|
||||
*
|
||||
* @brief <b>libopencm3 LM4F General Purpose I/O</b>
|
||||
*
|
||||
* The LM4F GPIO API provides functionality for accessing the GPIO pins of the
|
||||
* LM4F.
|
||||
*
|
||||
* @attention @code An important aspect to consider is that libopencm3 uses the
|
||||
* AHB aperture for accessing the GPIO registers on the LM4F. The AHB must be
|
||||
* explicitly enabled with a call to gpio_enable_ahb_aperture() before accessing
|
||||
* any GPIO functionality.
|
||||
* @endcode
|
||||
*
|
||||
* Please see the individual GPIO modules for more details. To use the GPIO, the
|
||||
* gpio.h header needs to be included:
|
||||
* @code{.c}
|
||||
* #include <libopencm3/lm4f/gpio.h>
|
||||
* @endcode
|
||||
*/
|
||||
|
||||
/**@{*/
|
||||
|
||||
#include <libopencm3/lm4f/gpio.h>
|
||||
#include <libopencm3/lm4f/systemcontrol.h>
|
||||
|
||||
/* Value we need to write to unlock the GPIO commit register */
|
||||
#define GPIO_LOCK_UNLOCK_CODE 0x4C4F434B
|
||||
|
||||
|
||||
/** @defgroup gpio_config GPIO pin configuration
|
||||
* @ingroup gpio_file
|
||||
*
|
||||
* \brief <b>Enabling and configuring GPIO pins</b>
|
||||
*
|
||||
* @section gpio_api_enable Enabling GPIO ports
|
||||
* @attention
|
||||
* Before accessing GPIO functionality through this API, the AHB aperture for
|
||||
* GPIO ports must be enabled via a call to @ref gpio_enable_ahb_aperture().
|
||||
* Failing to do so will cause a hard fault.
|
||||
*
|
||||
* @note
|
||||
* Once the AHB aperture is enabled, GPIO registers can no longer be accessed
|
||||
* via the APB aperture. The two apertures are mutually exclusive.
|
||||
*
|
||||
* Enabling the AHB aperture only needs to be done once. However, in order to
|
||||
* access a certain GPIO port, its clock must also be enabled. Enabling the
|
||||
* GPIO clock needs to be done for every port that will be used.
|
||||
*
|
||||
* For example, to enable GPIOA and GPIOD:
|
||||
* @code{.c}
|
||||
* // Make sure we can access the GPIO via the AHB aperture
|
||||
* gpio_enable_ahb_aperture();
|
||||
* ...
|
||||
* // Enable GPIO ports A and D
|
||||
* periph_clock_enable(RCC_GPIOA);
|
||||
* periph_clock_enable(RCC_GPIOD);
|
||||
* @endcode
|
||||
*
|
||||
* On reset all ports are configured as digital floating inputs (no pull-up or
|
||||
* pull-down), except for special function pins.
|
||||
*
|
||||
*
|
||||
* @section gpio_api_in Configuring pins as inputs
|
||||
*
|
||||
* Configuring GPIO pins as inputs is done with @ref gpio_mode_setup(), with
|
||||
* @ref GPIO_MODE_INPUT for the mode parameter. The direction of the pull-up
|
||||
* must be specified with the same call
|
||||
*
|
||||
* For example, PA2, PA3, and PA4 as inputs, with pull-up on PA4:
|
||||
* @code{.c}
|
||||
* gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO2 | GPIO3);
|
||||
* gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_PULLUP, GPIO4);
|
||||
* @endcode
|
||||
*
|
||||
*
|
||||
* @section gpio_api_out Configuring pins as outputs
|
||||
*
|
||||
* Output pins have more configuration options than input pins. LM4F pins can be
|
||||
* configured as either push-pull, or open drain. The drive strength of each pin
|
||||
* can be adjusted between 2mA, 4mA, or 8mA. Slew-rate control is available when
|
||||
* the pins are configured to drive 8mA. These extra options can be specified
|
||||
* with @ref gpio_set_output_config().
|
||||
* The default is push-pull configuration with 2mA drive capability.
|
||||
*
|
||||
* @note
|
||||
* @ref gpio_set_output_config() controls different capabilities than the
|
||||
* similar sounding gpio_set_output_options() from the STM GPIO API. They are
|
||||
* intentionally named differently to prevent confusion between the two. They
|
||||
* are API incompatible.
|
||||
*
|
||||
* For example, to set PA2 to output push-pull with a drive strength of 8mA:
|
||||
* @code{.c}
|
||||
* gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO2);
|
||||
* gpio_set_output_config(GPIOA, GPIO_OTYPE_PP, GPIO_DRIVE_8MA, GPIO2);
|
||||
* @endcode
|
||||
*
|
||||
*
|
||||
* @section gpio_api_analog Configuring pins as analog function
|
||||
*
|
||||
* Configuring GPIO pins to their analog function is done with
|
||||
* @ref gpio_mode_setup(), with @ref GPIO_MODE_ANALOG for the mode parameter.
|
||||
*
|
||||
* Suppose PD4 and PD5 are the USB pins. To enable their analog functionality
|
||||
* (USB D+ and D- in this case), use:
|
||||
* @code
|
||||
* // Mux USB pins to their analog function
|
||||
* gpio_mode_setup(GPIOD, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO4 | GPIO5);
|
||||
* @endcode
|
||||
*
|
||||
* @section gpio_api_alf_func Configuring pins as alternate functions
|
||||
*
|
||||
* Most pins have alternate functions associated with them. When a pin is set to
|
||||
* an alternate function, it is multiplexed to one of the dedicated hardware
|
||||
* peripheral in the chip. The alternate function mapping can be found in the
|
||||
* part's datasheet, and usually varies between arts of the same family.
|
||||
*
|
||||
* Multiplexing a pin, or group of pins to an alternate function is done with
|
||||
* @ref gpio_set_af(). Because AF0 is not used on the LM4F, passing 0 as the
|
||||
* alt_func_num parameter will disable the alternate function of the given pins.
|
||||
*
|
||||
* @code
|
||||
* // Mux PB0 and PB1 to AF1 (UART1 TX/RX in this case)
|
||||
* gpio_set_af(GPIOB, 1, GPIO0 | GPIO1);
|
||||
* @endcode
|
||||
*
|
||||
* @section gpio_api_sfpins Changing configuration of special function pins
|
||||
*
|
||||
* On the LM4F, the NMI and JTAG/SWD default to their alternate function. These
|
||||
* pins cannot normally be committed to GPIO usage. To enable these special
|
||||
* function pins to be used as GPIO, they must be unlocked. This may be achieved
|
||||
* via @ref gpio_unlock_commit. Once a special function pin is unlocked, its
|
||||
* settings may be altered in the usual way.
|
||||
*
|
||||
* For example, to unlock the PF0 pin (NMI on the LM4F120):
|
||||
* @code
|
||||
* // PF0 is an NMI pin, and needs to be unlocked
|
||||
* gpio_unlock_commit(GPIOF, GPIO0);
|
||||
* // Now the pin can be configured
|
||||
* gpio_mode_setup(RGB_PORT, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, btnpins);
|
||||
* @endcode
|
||||
*/
|
||||
/**@{*/
|
||||
|
||||
/**
|
||||
* \brief Enable access to GPIO registers via the AHB aperture
|
||||
*
|
||||
* All GPIO registers are accessed in libopencm3 via the AHB aperture. It
|
||||
* provides faster control over the older APB aperture. This aperture must be
|
||||
* enabled before calling any other gpio_*() function.
|
||||
*
|
||||
*/
|
||||
void gpio_enable_ahb_aperture(void)
|
||||
{
|
||||
SYSCTL_GPIOHBCTL = 0xffffffff;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Configure a group of pins
|
||||
*
|
||||
* Sets the Pin direction, analog/digital mode, and pull-up configuration of
|
||||
* or a set of GPIO pins on a given GPIO port.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] mode Pin mode (@ref gpio_mode) \n
|
||||
* - GPIO_MODE_OUTPUT -- Configure pin as output \n
|
||||
* - GPIO_MODE_INPUT -- Configure pin as input \n
|
||||
* - GPIO_MODE_ANALOG -- Configure pin as analog function
|
||||
* @param[in] pullup Pin pullup/pulldown configuration (@ref gpio_pullup) \n
|
||||
* - GPIO_PUPD_NONE -- Do not pull the pin high or low \n
|
||||
* - GPIO_PUPD_PULLUP -- Pull the pin high \n
|
||||
* - GPIO_PUPD_PULLDOWN -- Pull the pin low
|
||||
* @param[in] gpios @ref gpio_pin_id. Any combination of pins may be specified
|
||||
* by OR'ing then together
|
||||
*/
|
||||
void gpio_mode_setup(uint32_t gpioport, enum gpio_mode mode,
|
||||
enum gpio_pullup pullup, uint8_t gpios)
|
||||
{
|
||||
switch (mode) {
|
||||
case GPIO_MODE_OUTPUT:
|
||||
GPIO_DIR(gpioport) |= gpios;
|
||||
GPIO_DEN(gpioport) |= gpios;
|
||||
GPIO_AMSEL(gpioport) &= ~gpios;
|
||||
break;
|
||||
case GPIO_MODE_INPUT:
|
||||
GPIO_DIR(gpioport) &= ~gpios;
|
||||
GPIO_DEN(gpioport) |= gpios;
|
||||
GPIO_AMSEL(gpioport) &= ~gpios;
|
||||
break;
|
||||
case GPIO_MODE_ANALOG:
|
||||
GPIO_DEN(gpioport) &= ~gpios;
|
||||
GPIO_AMSEL(gpioport) |= gpios;
|
||||
break;
|
||||
default:
|
||||
/* Don't do anything */
|
||||
break;
|
||||
}
|
||||
|
||||
/*
|
||||
* Setting a bit in the GPIO_PDR register clears the corresponding bit
|
||||
* in the GPIO_PUR register, and vice-versa.
|
||||
*/
|
||||
switch (pullup) {
|
||||
case GPIO_PUPD_PULLUP:
|
||||
GPIO_PUR(gpioport) |= gpios;
|
||||
break;
|
||||
case GPIO_PUPD_PULLDOWN:
|
||||
GPIO_PDR(gpioport) |= gpios;
|
||||
break;
|
||||
case GPIO_PUPD_NONE: /* Fall through */
|
||||
default:
|
||||
GPIO_PUR(gpioport) &= ~gpios;
|
||||
GPIO_PDR(gpioport) &= ~gpios;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Configure output parameters of a group of pins
|
||||
*
|
||||
* Sets the output configuration and drive strength, of or a set of GPIO pins
|
||||
* for a set of GPIO pins in output mode.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] otype Output driver configuration (@ref gpio_output_type) \n
|
||||
* - GPIO_OTYPE_PP -- Configure pin driver as push-pull \n
|
||||
* - GPIO_OTYPE_OD -- Configure pin driver as open drain
|
||||
* @param[in] drive Pin drive strength (@ref gpio_drive_strength) \n
|
||||
* - GPIO_DRIVE_2MA -- 2mA drive \n
|
||||
* - GPIO_DRIVE_4MA -- 4mA drive \n
|
||||
* - GPIO_DRIVE_8MA -- 8mA drive \n
|
||||
* - GPIO_DRIVE_8MA_SLEW_CTL -- 8mA drive with slew rate
|
||||
* control
|
||||
* @param[in] gpios @ref gpio_pin_id. Any combination of pins may be specified
|
||||
* by OR'ing then together
|
||||
*/
|
||||
void gpio_set_output_config(uint32_t gpioport, enum gpio_output_type otype,
|
||||
enum gpio_drive_strength drive, uint8_t gpios)
|
||||
{
|
||||
if (otype == GPIO_OTYPE_OD) {
|
||||
GPIO_ODR(gpioport) |= gpios;
|
||||
} else {
|
||||
GPIO_ODR(gpioport) &= ~gpios;
|
||||
}
|
||||
|
||||
/*
|
||||
* Setting a bit in the GPIO_DRxR register clears the corresponding bit
|
||||
* in the other GPIO_DRyR registers, and vice-versa.
|
||||
*/
|
||||
switch (drive) {
|
||||
case GPIO_DRIVE_8MA_SLEW_CTL:
|
||||
GPIO_DR8R(gpioport) |= gpios;
|
||||
GPIO_SLR(gpioport) |= gpios;
|
||||
break;
|
||||
case GPIO_DRIVE_8MA:
|
||||
GPIO_DR8R(gpioport) |= gpios;
|
||||
GPIO_SLR(gpioport) &= ~gpios;
|
||||
break;
|
||||
case GPIO_DRIVE_4MA:
|
||||
GPIO_DR4R(gpioport) |= gpios;
|
||||
break;
|
||||
case GPIO_DRIVE_2MA: /* Fall through */
|
||||
default:
|
||||
GPIO_DR2R(gpioport) |= gpios;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#define PCTL_AF(pin, af) (af << (pin << 2))
|
||||
#define PCTL_MASK(pin) PCTL_AF(pin, 0xf)
|
||||
/**
|
||||
* \brief Multiplex group of pins to the given alternate function
|
||||
*
|
||||
* Mux the pin or group of pins to the given alternate function. Note that a
|
||||
* number of pins may be set but only with a single AF number. This is useful
|
||||
* when one or more of a peripheral's pins are assigned to the same alternate
|
||||
* function.
|
||||
*
|
||||
* Because AF0 is not used on the LM4F, passing 0 as the alt_func_num parameter
|
||||
* will disable the alternate function of the given pins.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] alt_func_num Pin alternate function number or 0 to disable the
|
||||
* alternate function multiplexing.
|
||||
* @param[in] gpios @ref gpio_pin_id. Any combination of pins may be specified
|
||||
* by OR'ing then together
|
||||
*/
|
||||
void gpio_set_af(uint32_t gpioport, uint8_t alt_func_num, uint8_t gpios)
|
||||
{
|
||||
uint32_t pctl32;
|
||||
uint8_t pin_mask;
|
||||
int i;
|
||||
|
||||
/* Did we mean to disable the alternate function? */
|
||||
if (alt_func_num == 0) {
|
||||
GPIO_AFSEL(gpioport) &= ~gpios;
|
||||
return;
|
||||
}
|
||||
|
||||
/* Enable the alternate function */
|
||||
GPIO_AFSEL(gpioport) |= gpios;
|
||||
/* Alternate functions are digital */
|
||||
GPIO_DEN(gpioport) |= gpios;
|
||||
|
||||
/* Now take care of the actual multiplexing */
|
||||
pctl32 = GPIO_PCTL(gpioport);
|
||||
for (i = 0; i < 8; i++) {
|
||||
pin_mask = (1 << i);
|
||||
|
||||
if (!(gpios & pin_mask)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
pctl32 &= ~PCTL_MASK(i);
|
||||
pctl32 |= PCTL_AF(i, (alt_func_num & 0xf));
|
||||
}
|
||||
|
||||
GPIO_PCTL(gpioport) = pctl32;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Unlock the commit control of a special function pin
|
||||
*
|
||||
* Unlocks the commit control of the given pin or group of pins. If a pin is a
|
||||
* JTAG/SWD or NMI, the pin may then be reconfigured as a GPIO pin. If the pin
|
||||
* is not locked by default, this has no effect.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] gpios @ref gpio_pin_id. Any combination of pins may be specified
|
||||
* by OR'ing then together.
|
||||
*/
|
||||
void gpio_unlock_commit(uint32_t gpioport, uint8_t gpios)
|
||||
{
|
||||
/* Unlock the GPIO_CR register */
|
||||
GPIO_LOCK(gpioport) = GPIO_LOCK_UNLOCK_CODE;
|
||||
/* Enable committing changes */
|
||||
GPIO_CR(gpioport) |= gpios;
|
||||
/* Lock the GPIO_CR register */
|
||||
GPIO_LOCK(gpioport) = ~GPIO_LOCK_UNLOCK_CODE;
|
||||
}
|
||||
/**@}*/
|
||||
|
||||
/** @defgroup gpio_control GPIO pin control
|
||||
* @ingroup gpio_file
|
||||
*
|
||||
* \brief <b>Controlling GPIO pins</b>
|
||||
*
|
||||
* Each I/O port has 8 individually configurable bits. When reading and writing
|
||||
* data to the GPIO ports, address bits [9:2] mask the pins to be read or
|
||||
* written. This mechanism makes all GPIO port reads and writes on the LM4F
|
||||
* atomic operations. The GPIO API takes full advantage of this fact to preserve
|
||||
* the atomicity of these operations.
|
||||
*
|
||||
* Setting or clearing a group of bits can be accomplished with @ref gpio_set()
|
||||
* and @ref gpio_clear() respectively. These operation use the masking mechanism
|
||||
* described above to only affect the specified pins.
|
||||
*
|
||||
* Sometimes it is more appropriate to read or set the level of a group of pins
|
||||
* on a port, in one atomic operation. Reading the status can be accomplished
|
||||
* with @ref gpio_read(). The result is equivalent to reading all the pins, then
|
||||
* masking only the desired pins; however, the masking is done in hardware, and
|
||||
* does not require an extra hardware operation.
|
||||
*
|
||||
* Writing a group of pins can be accomplished with @ref gpio_write(). The mask
|
||||
* ('gpios' parameter) is applied in hardware, and the masked pins are not
|
||||
* affected, regardless of the value of the respective bits written to the GPIO
|
||||
* port.
|
||||
*
|
||||
* Two extra functions are provided, @ref gpio_port_read() and
|
||||
* @ref gpio_port_write(). They are functionally identical to
|
||||
* @ref gpio_read (port, GPIO_ALL) and @ref gpio_write (port, GPIO_ALL, val)
|
||||
* respectively. Hence, they are also atomic.
|
||||
*
|
||||
* GPIO pins may be toggled with @ref gpio_toggle(). This function does not
|
||||
* translate to an atomic operation.
|
||||
*
|
||||
* @note
|
||||
* The @ref gpio_toggle() operation is the only GPIO port operation which is not
|
||||
* atomic. It involves a read-modify-write cycle.
|
||||
*
|
||||
* Suppose PA0, PA1, PA2, and PA3 are to be modified without affecting the other
|
||||
* pins on port A. This is common when controlling, for example, a 4-bit bus:
|
||||
* @code{.c}
|
||||
* // Pins 4,5,6, and 7 are unaffected, regardless of the bits in val
|
||||
* gpio_write(GPIOA, GPIO0 | GPIO1 | GPIO2 | GPIO3, val);
|
||||
* // Wait a bit then send the other 4 bits
|
||||
* wait_a_bit();
|
||||
* gpio_write(GPIOA, GPIO0 | GPIO1 | GPIO2 | GPIO3, val >> 4);
|
||||
* @endcode
|
||||
*
|
||||
* Suppose a LED is connected to PD4, and we want to flash the LED for a brief
|
||||
* period of time:
|
||||
* @code
|
||||
* gpio_set(GPIOD, GPIO4);
|
||||
* wait_a_bit();
|
||||
* gpio_set(GPIOD, GPIO4);
|
||||
* @endcode
|
||||
*/
|
||||
/**@{*/
|
||||
/**
|
||||
* \brief Toggle a Group of Pins
|
||||
*
|
||||
* Toggle one or more pins of the given GPIO port.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] gpios Pin identifiers. @ref gpio_pin_id
|
||||
*/
|
||||
void gpio_toggle(uint32_t gpioport, uint8_t gpios)
|
||||
{
|
||||
/* The mask makes sure we only toggle the GPIOs we want to */
|
||||
GPIO_DATA(gpioport)[gpios] ^= GPIO_ALL;
|
||||
}
|
||||
/**@}*/
|
||||
|
||||
|
||||
/** @defgroup gpio_irq GPIO Interrupt control
|
||||
* @ingroup gpio_file
|
||||
*
|
||||
* \brief <b>Configuring interrupts from GPIO pins</b>
|
||||
*
|
||||
* GPIO pins can trigger interrupts on either edges or levels. The type of
|
||||
* trigger can be configured with @ref gpio_configure_int_trigger(). To have an
|
||||
* event on the given pin generate an interrupt, its interrupt source must be
|
||||
* unmasked. This can be achieved with @ref gpio_enable_interrupts(). Interrupts
|
||||
* which are no longer needed can be disabled through
|
||||
* @ref gpio_disable_interrupts().
|
||||
*
|
||||
* In order for the interrupt to generate an IRQ and a call to the interrupt
|
||||
* service routine, the interrupt for the GPIO port must be routed through the
|
||||
* NVIC with @ref nvic_enable_irq(). For this last step, the nvic.h header is
|
||||
* needed:
|
||||
* @code{.c}
|
||||
* #include <libopencm3/lm4f/nvic.h>
|
||||
* @endcode
|
||||
*
|
||||
* Enabling an interrupt is as simple as configuring the desired trigger,
|
||||
* unmasking the desired interrupt, and routing the desired GPIO port's
|
||||
* interrupt through the NVIC.
|
||||
* @code{.c}
|
||||
* // Trigger interrupt on each rising edge
|
||||
* gpio_configure_trigger(GPIOF, GPIO_TRIG_EDGE_RISE, GPIO0 | GPIO4);
|
||||
* // Unmask the interrupt on those pins
|
||||
* gpio_enable_interrupts(GPIOF, GPIO0 | GPIO4);
|
||||
* // Enable the interrupt in the NVIC as well
|
||||
* nvic_enable_irq(NVIC_GPIOF_IRQ);
|
||||
* @endcode
|
||||
*
|
||||
* After interrupts are properly enabled and routed through the NVIC, when an
|
||||
* event occurs, the appropriate IRQ flag is set by hardware, and execution
|
||||
* jumps to the GPIO ISR. The ISR should query the IRQ flags to determine which
|
||||
* event caused the interrupt. For this, use @ref gpio_is_interrupt_source(),
|
||||
* with the desired GPIO flag. After one or more interrupt sources are
|
||||
* serviced, the IRQ flags must be cleared by the ISR. This can be done with
|
||||
* @ref gpio_clear_interrupt_flag().
|
||||
*
|
||||
* A typical GPIO ISR may look like the following:
|
||||
* @code{.c}
|
||||
* void gpiof_isr(void)
|
||||
* {
|
||||
* uint8_t serviced_irqs = 0;
|
||||
*
|
||||
* // Process individual IRQs
|
||||
* if (gpio_is_interrupt_source(GPIOF, GPIO0)) {
|
||||
* process_gpio0_event();
|
||||
* serviced_irq |= GPIO0;
|
||||
* }
|
||||
* if (gpio_is_interrupt_source(GPIOF, GPIO4)) {
|
||||
* process_gpio4_event();
|
||||
* serviced_irq |= GPIO4;
|
||||
* }
|
||||
*
|
||||
* // Clear the interupt flag for the processed IRQs
|
||||
* gpio_clear_interrupt_flag(GPIOF, serviced_irqs);
|
||||
* }
|
||||
* @endcode
|
||||
*/
|
||||
/**@{*/
|
||||
/**
|
||||
* \brief Configure the interrupt trigger on the given GPIO pins
|
||||
*
|
||||
* Sets the Pin direction, analog/digital mode, and pull-up configuration of
|
||||
* or a set of GPIO pins on a given GPIO port.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] trigger Trigger configuration (@ref gpio_trigger) \n
|
||||
* - GPIO_TRIG_LVL_LOW -- Trigger on low level \n
|
||||
* - GPIO_TRIG_LVL_HIGH -- Trigger on high level \n
|
||||
* - GPIO_TRIG_EDGE_FALL -- Trigger on falling edges \n
|
||||
* - GPIO_TRIG_EDGE_RISE -- Trigger on rising edges \n
|
||||
* - GPIO_TRIG_EDGE_BOTH -- Trigger on all edges
|
||||
* @param[in] gpios @ref gpio_pin_id. Any combination of pins may be specified
|
||||
* by OR'ing then together
|
||||
*/
|
||||
void gpio_configure_trigger(uint32_t gpioport, enum gpio_trigger trigger,
|
||||
uint8_t gpios)
|
||||
{
|
||||
switch (trigger) {
|
||||
case GPIO_TRIG_LVL_LOW:
|
||||
GPIO_IS(gpioport) |= gpios;
|
||||
GPIO_IEV(gpioport) &= ~gpios;
|
||||
break;
|
||||
case GPIO_TRIG_LVL_HIGH:
|
||||
GPIO_IS(gpioport) |= gpios;
|
||||
GPIO_IEV(gpioport) |= gpios;
|
||||
break;
|
||||
case GPIO_TRIG_EDGE_FALL:
|
||||
GPIO_IS(gpioport) &= ~gpios;
|
||||
GPIO_IBE(gpioport) &= ~gpios;
|
||||
GPIO_IEV(gpioport) &= ~gpios;
|
||||
break;
|
||||
case GPIO_TRIG_EDGE_RISE:
|
||||
GPIO_IS(gpioport) &= ~gpios;
|
||||
GPIO_IBE(gpioport) &= ~gpios;
|
||||
GPIO_IEV(gpioport) |= gpios;
|
||||
break;
|
||||
case GPIO_TRIG_EDGE_BOTH:
|
||||
GPIO_IS(gpioport) &= ~gpios;
|
||||
GPIO_IBE(gpioport) |= gpios;
|
||||
break;
|
||||
default:
|
||||
/* Don't do anything */
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable interrupts on specified GPIO pins
|
||||
*
|
||||
* Enable interrupts on the specified GPIO pins
|
||||
*
|
||||
* Note that the NVIC must be enabled and properly configured for the interrupt
|
||||
* to be routed to the CPU.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] gpios @ref gpio_pin_id. Pins whose interrupts to enable. Any
|
||||
* combination of pins may be specified by OR'ing them
|
||||
* together.
|
||||
*/
|
||||
void gpio_enable_interrupts(uint32_t gpioport, uint8_t gpios)
|
||||
{
|
||||
GPIO_IM(gpioport) |= gpios;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable interrupts on specified GPIO pins
|
||||
*
|
||||
* Disable interrupts on the specified GPIO pins
|
||||
*
|
||||
* Note that the NVIC must be enabled and properly configured for the interrupt
|
||||
* to be routed to the CPU.
|
||||
*
|
||||
* @param[in] gpioport GPIO block register address base @ref gpio_reg_base
|
||||
* @param[in] gpios @ref gpio_pin_id. Pins whose interrupts to disable. Any
|
||||
* combination of pins may be specified by OR'ing them
|
||||
* together.
|
||||
*/
|
||||
void gpio_disable_interrupts(uint32_t gpioport, uint8_t gpios)
|
||||
{
|
||||
GPIO_IM(gpioport) |= gpios;
|
||||
}
|
||||
|
||||
/**@}*/
|
||||
|
||||
/**@}*/
|
||||
|
@ -0,0 +1,2 @@
|
||||
/* Yes, we can simply use the lm3s linker script */
|
||||
INCLUDE "libopencm3_lm3s.ld"
|
@ -0,0 +1,499 @@
|
||||
/*
|
||||
* This file is part of the libopencm3 project.
|
||||
*
|
||||
* Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* This library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU Lesser General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public License
|
||||
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup rcc_file RCC
|
||||
*
|
||||
* @ingroup LM4Fxx
|
||||
*
|
||||
@author @htmlonly © @endhtmlonly 2012
|
||||
Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
|
||||
* \brief <b>libopencm3 LM4F Clock control API</b>
|
||||
*
|
||||
* The LM$F clock API provides functionaliity for manipulating the system clock,
|
||||
* oscillator, and PLL. Functions are provided for fine-grained control of clock
|
||||
* control registers, while also providing higher level functionality to easily
|
||||
* configure the main system clock source.
|
||||
*
|
||||
* The following code snippet uses fine-grained mechanisms to configures the
|
||||
* chip to run off an external 16MHz crystal, and use the PLL to derive a clock
|
||||
* frequency of 80MHz.
|
||||
* @code{.c}
|
||||
* // A divisor of 5 gives us a clock of 400/5 = 80MHz
|
||||
* #define PLLDIV_80MHZ 5
|
||||
*
|
||||
* // Enable the main oscillator
|
||||
* rcc_enable_main_osc();
|
||||
*
|
||||
* // Make RCC2 override RCC
|
||||
* rcc_enable_rcc2();
|
||||
*
|
||||
* // Set XTAL value to 16MHz
|
||||
* rcc_configure_xtal(XTAL_16M);
|
||||
* // Set the oscillator source as the main oscillator
|
||||
* rcc_set_osc_source(OSCSRC_MOSC);
|
||||
* // Enable the PLL
|
||||
* rcc_pll_on();
|
||||
*
|
||||
* // Change the clock divisor
|
||||
* rcc_set_pll_divisor(PLLDIV_80MHZ);
|
||||
*
|
||||
* // We cannot use the PLL as a clock source until it locks
|
||||
* rcc_wait_for_pll_ready();
|
||||
* // Disable PLL bypass to derive the system clock from the PLL clock
|
||||
* rcc_pll_bypass_disable();
|
||||
*
|
||||
* // Keep track of frequency
|
||||
* lm4f_rcc_sysclk_freq = 80E6;
|
||||
* @endcode
|
||||
*
|
||||
* The same can be achieved by a simple call to high-level routines:
|
||||
* @code
|
||||
* // A divisor of 5 gives us a clock of 400/5 = 80MHz
|
||||
* #define PLLDIV_80MHZ 5
|
||||
*
|
||||
* rcc_sysclk_config(OSCSRC_MOSC, XTAL_16M, PLLDIV_80MHZ);
|
||||
* @endcode
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include <libopencm3/lm4f/rcc.h>
|
||||
|
||||
/**
|
||||
* @defgroup rcc_low_level Low-level clock control API
|
||||
@ingroup rcc_file
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* \brief System clock frequency
|
||||
*
|
||||
* This variable is provided to keep track of the system clock frequency. It
|
||||
* should be updated every time the system clock is changed via the fine-grained
|
||||
* mechanisms. The initial value is 16MHz, which corresponds to the clock of the
|
||||
* internal 16MHz oscillator.
|
||||
*
|
||||
* High-level routines update the system clock automatically.
|
||||
* For read access, it is recommended to acces this variable via
|
||||
* @code
|
||||
* rcc_get_system_clock_frequency();
|
||||
* @endcode
|
||||
*
|
||||
* If write access is desired (i.e. when changing the system clock via the
|
||||
* fine-grained mechanisms), then include the following line in your code:
|
||||
* @code
|
||||
* extern uint32_t lm4f_rcc_sysclk_freq;
|
||||
* @endcode
|
||||
*/
|
||||
uint32_t lm4f_rcc_sysclk_freq = 16000000;
|
||||
|
||||
|
||||
/**
|
||||
* \brief Configure the crystal type connected to the device.
|
||||
*
|
||||
* Configure the crystal type connected between the OSCO and OSCI pins by
|
||||
* writing the appropriate value to the XTAL field in SYSCTL_RCC. The PLL
|
||||
* parameters are automatically adjusted in hardware to provide a PLL clock of
|
||||
* 400MHz.
|
||||
*
|
||||
* @param[in] xtal predefined crystal type @see xtal_t
|
||||
*/
|
||||
void rcc_configure_xtal(enum xtal_t xtal)
|
||||
{
|
||||
uint32_t reg32;
|
||||
|
||||
reg32 = SYSCTL_RCC;
|
||||
reg32 &= ~SYSCTL_RCC_XTAL_MASK;
|
||||
reg32 |= (xtal & SYSCTL_RCC_XTAL_MASK);
|
||||
SYSCTL_RCC = reg32;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the main oscillator
|
||||
*
|
||||
* Sets the IOSCDIS bit in SYSCTL_RCC, disabling the main oscillator.
|
||||
*/
|
||||
void rcc_disable_main_osc(void)
|
||||
{
|
||||
SYSCTL_RCC |= SYSCTL_RCC_MOSCDIS;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the internal oscillator
|
||||
*
|
||||
* Sets the IOSCDIS bit in SYSCTL_RCC, disabling the internal oscillator.
|
||||
*/
|
||||
void rcc_disable_interal_osc(void)
|
||||
{
|
||||
SYSCTL_RCC |= SYSCTL_RCC_IOSCDIS;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable the main oscillator
|
||||
*
|
||||
* Clears the MOSCDIS bit in SYSCTL_RCC, enabling the main oscillator.
|
||||
*/
|
||||
void rcc_enable_main_osc(void)
|
||||
{
|
||||
SYSCTL_RCC &= ~SYSCTL_RCC_MOSCDIS;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable the internal oscillator
|
||||
*
|
||||
* Clears the IOSCDIS bit in SYSCTL_RCC, enabling the internal oscillator.
|
||||
*/
|
||||
void rcc_enable_interal_osc(void)
|
||||
{
|
||||
SYSCTL_RCC &= ~SYSCTL_RCC_IOSCDIS;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable the use of SYSCTL_RCC2 register for clock control
|
||||
*
|
||||
* Enables the USERCC2 bit in SYSCTTL_RCC2. Settings in SYSCTL_RCC2 will
|
||||
* override settings in SYSCTL_RCC.
|
||||
* This function must be called before other calls to manipulate the clock, as
|
||||
* libopencm3 uses the SYSCTL_RCC2 register.
|
||||
*/
|
||||
void rcc_enable_rcc2(void)
|
||||
{
|
||||
SYSCTL_RCC2 |= SYSCTL_RCC2_USERCC2;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Power down the main PLL
|
||||
*
|
||||
* Sets the SYSCTL_RCC2_PWRDN2 in SYSCTL_RCC2 to power down the PLL.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*/
|
||||
void rcc_pll_off(void)
|
||||
{
|
||||
SYSCTL_RCC2 |= SYSCTL_RCC2_PWRDN2;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Power up the main PLL
|
||||
*
|
||||
* Clears the PWRDN2 in SYSCTL_RCC2 to power on the PLL.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*/
|
||||
void rcc_pll_on(void)
|
||||
{
|
||||
SYSCTL_RCC2 &= ~SYSCTL_RCC2_PWRDN2;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set the oscillator source to be used by the system clock
|
||||
*
|
||||
* Set the clock source for the system clock.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*/
|
||||
void rcc_set_osc_source(enum osc_src src)
|
||||
{
|
||||
uint32_t reg32;
|
||||
|
||||
reg32 = SYSCTL_RCC2;
|
||||
reg32 &= ~SYSCTL_RCC2_OSCSRC2_MASK;
|
||||
reg32 |= (src & SYSCTL_RCC2_OSCSRC2_MASK);
|
||||
SYSCTL_RCC2 = reg32;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the PLL bypass and use the PLL clock
|
||||
*
|
||||
* Clear BYPASS2 in SYSCTL_RCC2. The system clock is derived from the PLL
|
||||
* clock divided by the divisor specified in SYSDIV2.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*/
|
||||
void rcc_pll_bypass_disable(void)
|
||||
{
|
||||
SYSCTL_RCC2 &= ~SYSCTL_RCC2_BYPASS2;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable the PLL bypass and use the oscillator clock
|
||||
*
|
||||
* Set BYPASS2 in SYSCTL_RCC2. The system clock is derived from the oscillator
|
||||
* clock divided by the divisor specified in SYSDIV2.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*/
|
||||
void rcc_pll_bypass_enable(void)
|
||||
{
|
||||
SYSCTL_RCC2 |= SYSCTL_RCC2_BYPASS2;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set the PLL clock divisor (from 400MHz)
|
||||
*
|
||||
* Set the binary divisor used to predivide the system clock down for use as the
|
||||
* timing reference for the PWM module. The divisor is expected to be a divisor
|
||||
* from 400MHz, not 200MHz. The DIV400 is also set.
|
||||
*
|
||||
* Specifies the divisor that used to generate the system clock from either the
|
||||
* PLL output or the oscillator source (depending on the BYPASS2 bit in
|
||||
* SYSCTL_RCC2). SYSDIV2 is used for the divisor when both the USESYSDIV bit in
|
||||
* SYSCTL_RCC is set.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*
|
||||
* @param[in] div clock divisor to apply to the 400MHz PLL clock. It is the
|
||||
* caller's responsibility to ensure that the divisor will not create
|
||||
* a system clock that is out of spec.
|
||||
*/
|
||||
void rcc_set_pll_divisor(uint8_t div400)
|
||||
{
|
||||
uint32_t reg32;
|
||||
|
||||
SYSCTL_RCC |= SYSCTL_RCC_USESYSDIV;
|
||||
|
||||
reg32 = SYSCTL_RCC2;
|
||||
reg32 &= ~SYSCTL_RCC2_SYSDIV400_MASK;
|
||||
reg32 |= ((div400 - 1) << 22) & SYSCTL_RCC2_SYSDIV400_MASK;
|
||||
/* We are expecting a divider from 400MHz */
|
||||
reg32 |= SYSCTL_RCC2_DIV400;
|
||||
SYSCTL_RCC2 = reg32;
|
||||
}
|
||||
/**
|
||||
* \brief Set the PWM unit clock divisor
|
||||
*
|
||||
* Set the binary divisor used to predivide the system clock down for use as the
|
||||
* timing reference for the PWM module.
|
||||
*
|
||||
* @param[in] div clock divisor to use @see pwm_clkdiv_t
|
||||
*/
|
||||
void rcc_set_pwm_divisor(enum pwm_clkdiv div)
|
||||
{
|
||||
uint32_t reg32;
|
||||
|
||||
reg32 = SYSCTL_RCC;
|
||||
reg32 &= ~SYSCTL_RCC_PWMDIV_MASK;
|
||||
reg32 |= (div & SYSCTL_RCC_PWMDIV_MASK);
|
||||
SYSCTL_RCC = reg32;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Power down the USB PLL
|
||||
*
|
||||
* Sets the USBPWRDN in SYSCTL_RCC2 to power down the USB PLL.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*/
|
||||
void rcc_usb_pll_off(void)
|
||||
{
|
||||
SYSCTL_RCC2 |= SYSCTL_RCC2_USBPWRDN;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Power up the USB PLL
|
||||
*
|
||||
* Clears the USBPWRDN in SYSCTL_RCC2 to power on the USB PLL.
|
||||
*
|
||||
* USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
|
||||
* function.
|
||||
*/
|
||||
void rcc_usb_pll_on(void)
|
||||
{
|
||||
SYSCTL_RCC2 &= ~SYSCTL_RCC2_USBPWRDN;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Wait for main PLL to lock
|
||||
*
|
||||
* Waits until the LOCK bit in SYSCTL_PLLSTAT is set. This guarantees that the
|
||||
* PLL is locked, and ready to use.
|
||||
*/
|
||||
void rcc_wait_for_pll_ready(void)
|
||||
{
|
||||
while (!(SYSCTL_PLLSTAT & SYSCTL_PLLSTAT_LOCK));
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup rcc_high_level High-level clock control API
|
||||
@ingroup rcc_file
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \brief Change the PLL divisor
|
||||
*
|
||||
* Changes the divisor applied to the 400MHz PLL clock. The PLL must have
|
||||
* previously been configured by selecting an appropriate XTAL value, and
|
||||
* turning on the PLL. This function does not reconfigure the XTAL value or
|
||||
* oscillator source. It only changes the PLL divisor.
|
||||
*
|
||||
* The PLL is bypassed before modifying the divisor, and the function blocks
|
||||
* until the PLL is locked, then the bypass is disabled, before returning.
|
||||
*
|
||||
* @param [in] pll_div400 The clock divisor to apply to the 400MHz PLL clock.
|
||||
*/
|
||||
void rcc_change_pll_divisor(uint8_t pll_div400)
|
||||
{
|
||||
/* Bypass the PLL while its settings are modified */
|
||||
rcc_pll_bypass_enable();
|
||||
/* Change the clock divisor */
|
||||
rcc_set_pll_divisor(pll_div400);
|
||||
/* We cannot use the PLL as a clock source until it locks */
|
||||
rcc_wait_for_pll_ready();
|
||||
/* Disable PLL bypass to derive the system clock from the PLL clock */
|
||||
rcc_pll_bypass_disable();
|
||||
/* Update the system clock frequency for housekeeping */
|
||||
lm4f_rcc_sysclk_freq = (uint32_t)400E6 / pll_div400;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Get the system clock frequency
|
||||
*
|
||||
* @return System clock frequency in Hz
|
||||
*/
|
||||
uint32_t rcc_get_system_clock_frequency(void)
|
||||
{
|
||||
return lm4f_rcc_sysclk_freq;
|
||||
}
|
||||
|
||||
/* Get the clock frequency corresponding to a given XTAL value */
|
||||
static uint32_t xtal_to_freq(enum xtal_t xtal)
|
||||
{
|
||||
const uint32_t freqs[] = {
|
||||
4000000, /* XTAL_4M */
|
||||
4096000, /* XTAL_4M_096 */
|
||||
4915200, /* XTAL_4M_9152 */
|
||||
5000000, /* ,XTAL_5M */
|
||||
5120000, /* XTAL_5M_12 */
|
||||
6000000, /* XTAL_6M */
|
||||
6144000, /* XTAL_6M_144 */
|
||||
7372800, /* XTAL_7M_3728 */
|
||||
8000000, /* XTAL_8M */
|
||||
8192000, /* XTAL_8M_192 */
|
||||
10000000, /* XTAL_10M */
|
||||
12000000, /* XTAL_12M */
|
||||
12288000, /* XTAL_12M_288 */
|
||||
13560000, /* XTAL_13M_56 */
|
||||
14318180, /* XTAL_14M_31818 */
|
||||
16000000, /* XTAL_16M */
|
||||
16384000, /* XTAL_16M_384 */
|
||||
18000000, /* XTAL_18M */
|
||||
20000000, /* XTAL_20M */
|
||||
24000000, /* XTAL_24M */
|
||||
25000000, /* XTAL_25M */
|
||||
};
|
||||
|
||||
return freqs[xtal - XTAL_4M];
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Configure the system clock source
|
||||
*
|
||||
* Sets up the system clock, including configuring the oscillator source, and
|
||||
* PLL to acheve the desired system clock frequency. Where applicable, The LM4F
|
||||
* clock API uses the new RCC2 register to configure clock parameters.
|
||||
*
|
||||
* Enables the main oscillator if the clock source is OSCSRC_MOSC. If the main
|
||||
* oscillator was previously enabled, it will not be disabled. If desired, it
|
||||
* can be separately disabled by a call to rcc_disable_main_osc().
|
||||
*
|
||||
* Configures the system clock to run from the 400MHz PLL with a divisor of
|
||||
* pll_div400 applied. If pll_div400 is 0, then the PLL is disabled, and the
|
||||
* system clock is configured to run off a "raw" clock. If the PLL was
|
||||
* previously powered on, it will not be disabled. If desired, it can de powered
|
||||
* off by a call to rcc_pll_off().
|
||||
*
|
||||
* @param [in] osc_src Oscillator from where to derive the system clock.
|
||||
* @param [in] xtal Type of crystal connected to the OSCO/OSCI pins
|
||||
* @param [in] pll_div400 The clock divisor to apply to the 400MHz PLL clock.
|
||||
* If 0, then the PLL is disabled, and the system runs
|
||||
* off a "raw" clock.
|
||||
*
|
||||
* @return System clock frequency in Hz
|
||||
*/
|
||||
void rcc_sysclk_config(enum osc_src src, enum xtal_t xtal, uint8_t pll_div400)
|
||||
{
|
||||
/*
|
||||
* We could be using the PLL at this point, or we could be running of a
|
||||
* raw clock. Either way, it is safer to bypass the PLL now.
|
||||
*/
|
||||
rcc_pll_bypass_enable();
|
||||
|
||||
/* Enable the main oscillator, if needed */
|
||||
if (src == OSCSRC_MOSC) {
|
||||
rcc_enable_main_osc();
|
||||
}
|
||||
|
||||
/* Make RCC2 override RCC */
|
||||
rcc_enable_rcc2();
|
||||
|
||||
/* Set XTAL value to 16MHz */
|
||||
rcc_configure_xtal(xtal);
|
||||
/* Set the oscillator source */
|
||||
rcc_set_osc_source(src);
|
||||
if (pll_div400) {
|
||||
/* Enable the PLL */
|
||||
rcc_pll_on();
|
||||
/* Configure the PLL to the divisor we want */
|
||||
rcc_change_pll_divisor(pll_div400);
|
||||
} else {
|
||||
/* We are running off a raw clock */
|
||||
switch (src) {
|
||||
case OSCSRC_PIOSC:
|
||||
lm4f_rcc_sysclk_freq = 16000000;
|
||||
break;
|
||||
case OSCSRC_PIOSC_D4:
|
||||
lm4f_rcc_sysclk_freq = 4000000;
|
||||
break;
|
||||
case OSCSRC_MOSC:
|
||||
lm4f_rcc_sysclk_freq = xtal_to_freq(xtal);
|
||||
break;
|
||||
case OSCSRC_32K_EXT:
|
||||
lm4f_rcc_sysclk_freq = 32768;
|
||||
break;
|
||||
case OSCSRC_30K_INT: /* Fall through. */
|
||||
default:
|
||||
/*
|
||||
* We either are running off the internal 30KHz
|
||||
* oscillator, which is +- 50% imprecise, or we got a
|
||||
* bad osc_src parameter.
|
||||
*/
|
||||
lm4f_rcc_sysclk_freq = 0;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -0,0 +1,40 @@
|
||||
/*
|
||||
* This file is part of the libopencm3 project.
|
||||
*
|
||||
* Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* This library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU Lesser General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public License
|
||||
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <libopencm3/lm4f/systemcontrol.h>
|
||||
|
||||
/**
|
||||
* \brief Enable the clock source for the peripheral
|
||||
*
|
||||
* @param[in] periph peripheral and clock type to enable @see lm4f_clken
|
||||
*/
|
||||
void periph_clock_enable(enum lm4f_clken periph)
|
||||
{
|
||||
MMIO32(SYSCTL_BASE + (periph >> 5)) |= 1 << (periph & 0x1f);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the clock source for the peripheral
|
||||
*
|
||||
* @param[in] periph peripheral and clock type to enable @see lm4f_clken
|
||||
*/
|
||||
void periph_clock_disable(enum lm4f_clken periph)
|
||||
{
|
||||
MMIO32(SYSCTL_BASE + (periph >> 5)) &= ~(1 << (periph & 0x1f));
|
||||
}
|
@ -0,0 +1,627 @@
|
||||
/*
|
||||
* This file is part of the libopencm3 project.
|
||||
*
|
||||
* Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* This library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU Lesser General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public License
|
||||
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup uart_file UART
|
||||
*
|
||||
* @ingroup LM4Fxx
|
||||
*
|
||||
* @author @htmlonly © @endhtmlonly 2013 Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* \brief <b>libopencm3 LM4F Universal Asynchronous Receiver Transmitter</b>
|
||||
*
|
||||
* The LM4F UART API provides functionality for accessing the UART hardware of
|
||||
* the LM4F.
|
||||
*
|
||||
* Please see the individual UART modules for more details. To use the UART, the
|
||||
* uart.h header needs to be included:
|
||||
* @code{.c}
|
||||
* #include <libopencm3/lm4f/uart.h>
|
||||
* @endcode
|
||||
*
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include <libopencm3/lm4f/uart.h>
|
||||
#include <libopencm3/lm4f/systemcontrol.h>
|
||||
#include <libopencm3/lm4f/rcc.h>
|
||||
|
||||
/** @defgroup uart_config UART configuration
|
||||
* @ingroup uart_file
|
||||
*
|
||||
* \brief <b>Enabling and configuring the UART</b>
|
||||
*
|
||||
* Enabling the UART is a two step process. The GPIO on which the UART resides
|
||||
* must be enabled, and the UART pins must be configured as alternate function,
|
||||
* digital pins. Pins must also be muxed to the appropriate alternate function.
|
||||
* This is done with the GPIO API.
|
||||
*
|
||||
* The second step involves enabling and the UART itself. The UART should be
|
||||
* disabled while it is being configured.
|
||||
* -# The UART clock must be enabled with @ref periph_clock_enable().
|
||||
* -# The UART must be disabled with @ref uart_disable().
|
||||
* -# The UART clock source should be chosen before setting the baudrate.
|
||||
* -# Baudrate, data bits, stop bit length, and parity can be configured.
|
||||
* -# If needed, enable CTS or RTS lines via the @ref uart_set_flow_control().
|
||||
* -# The UART can now be enabled with @ref uart_enable().
|
||||
*
|
||||
* For example, to enable UART1 at 115200 8n1 with hardware flow control:
|
||||
* @code{.c}
|
||||
* // Enable the UART clock
|
||||
* periph_clock_enable(RCC_UART1);
|
||||
* // We need a brief delay before we can access UART config registers
|
||||
* __asm__("nop"); __asm__("nop"); __asm__("nop");
|
||||
* // Disable the UART while we mess with its settings
|
||||
* uart_disable(UART1);
|
||||
* // Configure the UART clock source as precision internal oscillator
|
||||
* uart_clock_from_piosc();
|
||||
* // Set communication parameters
|
||||
* uart_set_baudrate(UART1, 115200);
|
||||
* uart_set_databits(UART1, 8);
|
||||
* uart_set_parity(UART1, UART_PARITY_NONE);
|
||||
* uart_set_stopbits(UART1, 1);
|
||||
* // Enable RTC and CTS lines
|
||||
* uart_set_flow_control(UART1, UART_FLOWCTL_HARD_RTS_CTS);
|
||||
* // Now that we're done messing with the settings, enable the UART
|
||||
* uart_enable(UART1);
|
||||
* @endcode
|
||||
*/
|
||||
/**@{*/
|
||||
/**
|
||||
* \brief Enable the UART
|
||||
*
|
||||
* Enable the UART. The Rx and Tx lines are also enabled.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_enable(uint32_t uart)
|
||||
{
|
||||
UART_CTL(uart) |= (UART_CTL_UARTEN | UART_CTL_RXE | UART_CTL_TXE);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the UART
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_disable(uint32_t uart)
|
||||
{
|
||||
UART_CTL(uart) &= ~UART_CTL_UARTEN;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set UART baudrate
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] baud Baud rate in bits per second (bps).*
|
||||
*/
|
||||
void uart_set_baudrate(uint32_t uart, uint32_t baud)
|
||||
{
|
||||
uint32_t clock;
|
||||
|
||||
/* Are we running off the internal clock or system clock? */
|
||||
if (UART_CC(uart) == UART_CC_CS_PIOSC) {
|
||||
clock = 16000000;
|
||||
} else {
|
||||
clock = rcc_get_system_clock_frequency();
|
||||
}
|
||||
|
||||
/* Find the baudrate divisor */
|
||||
uint32_t div = (((clock * 8) / baud) + 1) / 2;
|
||||
|
||||
/* Set the baudrate divisors */
|
||||
UART_IBRD(uart) = div / 64;
|
||||
UART_FBRD(uart) = div % 64;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set UART databits
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] databits number of data bits per transmission.
|
||||
*/
|
||||
void uart_set_databits(uint32_t uart, uint8_t databits)
|
||||
{
|
||||
uint32_t reg32, bitint32_t;
|
||||
|
||||
/* This has the same effect as using UART_LCRH_WLEN_5/6/7/8 directly */
|
||||
bitint32_t = (databits - 5) << 5;
|
||||
|
||||
/* TODO: What about 9 data bits? */
|
||||
|
||||
reg32 = UART_LCRH(uart);
|
||||
reg32 &= ~UART_LCRH_WLEN_MASK;
|
||||
reg32 |= bitint32_t;
|
||||
UART_LCRH(uart) = reg32;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set UART stopbits
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] bits the requested number of stopbits, either 1 or 2.
|
||||
*/
|
||||
void uart_set_stopbits(uint32_t uart, uint8_t stopbits)
|
||||
{
|
||||
if (stopbits == 2) {
|
||||
UART_LCRH(uart) |= UART_LCRH_STP2;
|
||||
} else {
|
||||
UART_LCRH(uart) &= ~UART_LCRH_STP2;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set UART parity
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] bits the requested parity scheme.
|
||||
*/
|
||||
void uart_set_parity(uint32_t uart, enum uart_parity parity)
|
||||
{
|
||||
uint32_t reg32;
|
||||
|
||||
reg32 = UART_LCRH(uart);
|
||||
reg32 |= UART_LCRH_PEN;
|
||||
reg32 &= ~(UART_LCRH_SPS | UART_LCRH_EPS);
|
||||
|
||||
switch (parity) {
|
||||
case UART_PARITY_NONE:
|
||||
/* Once we disable parity the other bits are meaningless */
|
||||
UART_LCRH(uart) &= ~UART_LCRH_PEN;
|
||||
return;
|
||||
case UART_PARITY_ODD:
|
||||
break;
|
||||
case UART_PARITY_EVEN:
|
||||
reg32 |= UART_LCRH_EPS;
|
||||
break;
|
||||
case UART_PARITY_STICK_0:
|
||||
reg32 |= (UART_LCRH_SPS | UART_LCRH_EPS);
|
||||
break;
|
||||
case UART_PARITY_STICK_1:
|
||||
reg32 |= UART_LCRH_SPS;
|
||||
break;
|
||||
}
|
||||
|
||||
UART_LCRH(uart) = reg32;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set the flow control scheme
|
||||
*
|
||||
* Set the flow control scheme by enabling or disabling RTS and CTS lines. This
|
||||
* will only have effect if the given UART supports the RTS and CTS lines.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] flow The flow control scheme to use (none, RTS, CTS or both) \n
|
||||
* UART_FLOWCTL_RTS -- enable the RTS line \n
|
||||
* UART_FLOWCTL_CTS -- enable the CTS line \n
|
||||
* UART_FLOWCTL_RTS_CTS -- enable both RTS and CTS lines
|
||||
*/
|
||||
void uart_set_flow_control(uint32_t uart, enum uart_flowctl flow)
|
||||
{
|
||||
uint32_t reg32 = UART_CTL(uart);
|
||||
|
||||
reg32 &= ~(UART_CTL_RTSEN | UART_CTL_CTSEN);
|
||||
|
||||
if (flow == UART_FLOWCTL_RTS) {
|
||||
reg32 |= UART_CTL_RTSEN;
|
||||
} else if (flow == UART_FLOWCTL_CTS) {
|
||||
reg32 |= UART_CTL_CTSEN;
|
||||
} else if (flow == UART_FLOWCTL_RTS_CTS) {
|
||||
reg32 |= (UART_CTL_RTSEN | UART_CTL_CTSEN);
|
||||
}
|
||||
|
||||
UART_CTL(uart) = reg32;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Clock the UART module from the internal oscillator
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_clock_from_piosc(uint32_t uart)
|
||||
{
|
||||
UART_CC(uart) = UART_CC_CS_PIOSC;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Clock the UART module from the system clock
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_clock_from_sysclk(uint32_t uart)
|
||||
{
|
||||
UART_CC(uart) = UART_CC_CS_SYSCLK;
|
||||
}
|
||||
/**@}*/
|
||||
|
||||
/** @defgroup uart_send_recv UART transmission and reception
|
||||
* @ingroup uart_file
|
||||
*
|
||||
* \brief <b>Sending and receiving data through the UART</b>
|
||||
*
|
||||
* Primitives for sending and recieving data are provided, @ref uart_send() and
|
||||
* @ref uart_recv(). These primitives do not check if data can be transmitted
|
||||
* or wait for data. If waiting until data is available or can be transmitted is
|
||||
* desired, blocking primitives are also available, @ref uart_send_blocking()
|
||||
* and @ref uart_recv_blocking().
|
||||
*
|
||||
* These primitives only handle one byte at at time, and thus may be unsuited
|
||||
* for some applications. You may also consider using @ref uart_dma.
|
||||
*/
|
||||
/**@{*/
|
||||
/**
|
||||
* \brief UART Send a Data Word.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] data data to send.
|
||||
*/
|
||||
void uart_send(uint32_t uart, uint16_t data)
|
||||
{
|
||||
data &= 0xFF;
|
||||
UART_DR(uart) = data;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief UART Read a Received Data Word.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @return data from the Rx FIFO.
|
||||
*/
|
||||
uint16_t uart_recv(uint32_t uart)
|
||||
{
|
||||
return UART_DR(uart) & UART_DR_DATA_MASK;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief UART Wait for Transmit Data Buffer Not Full
|
||||
*
|
||||
* Blocks until the transmit data FIFO is not empty and can accept the next data
|
||||
* word.
|
||||
* \n
|
||||
* Even if the FIFO is not empty, this function will return as long as there is
|
||||
* room for at least one more word.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_wait_send_ready(uint32_t uart)
|
||||
{
|
||||
/* Wait until the Tx FIFO is no longer full */
|
||||
while (UART_FR(uart) & UART_FR_TXFF);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief UART Wait for Received Data Available
|
||||
*
|
||||
* Blocks until the receive data FIFO holds a at least valid received data word.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_wait_recv_ready(uint32_t uart)
|
||||
{
|
||||
/* Wait until the Tx FIFO is no longer empty */
|
||||
while (UART_FR(uart) & UART_FR_RXFE);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief UART Send Data Word with Blocking
|
||||
*
|
||||
* Blocks until the transmit data FIFO can accept the next data word for
|
||||
* transmission.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_send_blocking(uint32_t uart, uint16_t data)
|
||||
{
|
||||
uart_wait_send_ready(uart);
|
||||
uart_send(uart, data);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief UART Read a Received Data Word with Blocking.
|
||||
*
|
||||
* Wait until a data word has been received then return the word.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @return data from the Rx FIFO.
|
||||
*/
|
||||
uint16_t uart_recv_blocking(uint32_t uart)
|
||||
{
|
||||
uart_wait_recv_ready(uart);
|
||||
return uart_recv(uart);
|
||||
}
|
||||
/**@}*/
|
||||
|
||||
/** @defgroup uart_irq UART Interrupt control
|
||||
* @ingroup uart_file
|
||||
*
|
||||
* \brief <b>Configuring interrupts from the UART</b>
|
||||
*
|
||||
* To have an event generate an interrupt, its interrupt source must be
|
||||
* unmasked. This can be achieved with @ref uart_enable_interrupts(). Interrupts
|
||||
* which are no longer needed can be disabled through
|
||||
* @ref uart_disable_interrupts().
|
||||
*
|
||||
* In order for the interrupt to generate an IRQ and a call to the interrupt
|
||||
* service routine, the interrupt for the target UART must be routed through the
|
||||
* NVIC with @ref nvic_enable_irq(). For this last step, the nvic.h header is
|
||||
* needed:
|
||||
* @code{.c}
|
||||
* #include <libopencm3/lm4f/nvic.h>
|
||||
* @endcode
|
||||
*
|
||||
* Enabling an interrupt is as simple as unmasking the desired interrupt, and
|
||||
* routing the desired UART's interrupt through the NVIC.
|
||||
* @code{.c}
|
||||
* // Unmask receive interrupt
|
||||
* uart_enable_rx_interrupt(UART0);
|
||||
* // Make sure the interrupt is routed through the NVIC
|
||||
* nvic_enable_irq(NVIC_UART0_IRQ);
|
||||
* @endcode
|
||||
*
|
||||
* If a more than one interrupt is to be enabled at one time, the interrupts
|
||||
* can be enabled by a single call to @ref uart_enable_interrupts().
|
||||
* For example:
|
||||
* @code{.c}
|
||||
* // Unmask receive, CTS, and RI, interrupts
|
||||
* uart_enable_interrupts(UART0, UART_INT_RX | UART_INT_RI | UART_INT_CTS);
|
||||
* @endcode
|
||||
*
|
||||
* After interrupts are properly enabled and routed through the NVIC, when an
|
||||
* event occurs, the appropriate IRQ flag is set by hardware, and execution
|
||||
* jumps to the UART ISR. The ISR should query the IRQ flags to determine which
|
||||
* event caused the interrupt. For this, use @ref uart_is_interrupt_source(),
|
||||
* with the desired UART_INT flag. After one or more interrupt sources are
|
||||
* serviced, the IRQ flags must be cleared by the ISR. This can be done with
|
||||
* @ref uart_clear_interrupt_flag().
|
||||
*
|
||||
* A typical UART ISR may look like the following:
|
||||
* @code{.c}
|
||||
* void uart0_isr(void)
|
||||
* {
|
||||
* uint32_t serviced_irqs = 0;
|
||||
*
|
||||
* // Process individual IRQs
|
||||
* if (uart_is_interrupt_source(UART0, UART_INT_RX)) {
|
||||
* process_rx_event();
|
||||
* serviced_irq |= UART_INT_RX;
|
||||
* }
|
||||
* if (uart_is_interrupt_source(UART0, UART_INT_CTS)) {
|
||||
* process_cts_event();
|
||||
* serviced_irq |= UART_INT_CTS;
|
||||
* }
|
||||
*
|
||||
* // Clear the interupt flag for the processed IRQs
|
||||
* uart_clear_interrupt_flag(UART0, serviced_irqs);
|
||||
* }
|
||||
* @endcode
|
||||
*/
|
||||
/**@{*/
|
||||
/**
|
||||
* \brief Enable Specific UART Interrupts
|
||||
*
|
||||
* Enable any combination of interrupts. Interrupts may be OR'ed together to
|
||||
* enable them with one call. For example, to enable both the RX and CTS
|
||||
* interrupts, pass (UART_INT_RX | UART_INT_CTS)
|
||||
*
|
||||
* Note that the NVIC must be enabled and properly configured for the interrupt
|
||||
* to be routed to the CPU.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] ints Interrupts which to enable. Any combination of interrupts may
|
||||
* be specified by OR'ing then together
|
||||
*/
|
||||
void uart_enable_interrupts(uint32_t uart, enum uart_interrupt_flag ints)
|
||||
{
|
||||
UART_IM(uart) |= ints;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable Specific UART Interrupts
|
||||
*
|
||||
* Disabe any combination of interrupts. Interrupts may be OR'ed together to
|
||||
* disable them with one call. For example, to disable both the RX and CTS
|
||||
* interrupts, pass (UART_INT_RX | UART_INT_CTS)
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] ints Interrupts which to disable. Any combination of interrupts
|
||||
* may be specified by OR'ing then together
|
||||
*/
|
||||
void uart_disable_interrupts(uint32_t uart, enum uart_interrupt_flag ints)
|
||||
{
|
||||
UART_IM(uart) &= ~ints;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable the UART Receive Interrupt.
|
||||
*
|
||||
* Note that the NVIC must be enabled and properly configured for the interrupt
|
||||
* to be routed to the CPU.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_enable_rx_interrupt(uint32_t uart)
|
||||
{
|
||||
uart_enable_interrupts(uart, UART_INT_RX);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the UART Receive Interrupt.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_disable_rx_interrupt(uint32_t uart)
|
||||
{
|
||||
uart_disable_interrupts(uart, UART_INT_RX);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable the UART Transmit Interrupt.
|
||||
*
|
||||
* Note that the NVIC must be enabled and properly configured for the interrupt
|
||||
* to be routed to the CPU.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_enable_tx_interrupt(uint32_t uart)
|
||||
{
|
||||
uart_enable_interrupts(uart, UART_INT_TX);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the UART Transmit Interrupt.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_disable_tx_interrupt(uint32_t uart)
|
||||
{
|
||||
uart_disable_interrupts(uart, UART_INT_TX);
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Mark interrupt as serviced
|
||||
*
|
||||
* After an interrupt is services, its flag must be cleared. If the flag is not
|
||||
* cleared, then execution will jump back to the start of the ISR after the ISR
|
||||
* returns.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] ints Interrupts which to clear. Any combination of interrupts may
|
||||
* be specified by OR'ing then together
|
||||
*/
|
||||
void uart_clear_interrupt_flag(uint32_t uart, enum uart_interrupt_flag ints)
|
||||
{
|
||||
UART_ICR(uart) |= ints;
|
||||
}
|
||||
/**@}*/
|
||||
|
||||
/** @defgroup uart_dma UART DMA control
|
||||
* @ingroup uart_file
|
||||
*
|
||||
* \brief <b>Enabling Direct Memory Access transfers for the UART</b>
|
||||
*
|
||||
*/
|
||||
/**@{*/
|
||||
|
||||
/**
|
||||
* \brief Enable the UART Receive DMA.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_enable_rx_dma(uint32_t uart)
|
||||
{
|
||||
UART_DMACTL(uart) |= UART_DMACTL_RXDMAE;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the UART Receive DMA.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_disable_rx_dma(uint32_t uart)
|
||||
{
|
||||
UART_DMACTL(uart) &= ~UART_DMACTL_RXDMAE;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Enable the UART Transmit DMA.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_enable_tx_dma(uint32_t uart)
|
||||
{
|
||||
UART_DMACTL(uart) |= UART_DMACTL_TXDMAE;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable the UART Transmit DMA.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_disable_tx_dma(uint32_t uart)
|
||||
{
|
||||
UART_DMACTL(uart) &= ~UART_DMACTL_TXDMAE;
|
||||
}
|
||||
/**@}*/
|
||||
|
||||
/** @defgroup uart_fifo UART FIFO control
|
||||
* @ingroup uart_file
|
||||
*
|
||||
* \brief <b>Enabling and controlling UART FIFO</b>
|
||||
*
|
||||
* The UART on the LM4F can either be used with a single character TX and RX
|
||||
* buffer, or with a 8 character TX and RX FIFO. In order to use the FIFO it
|
||||
* must be enabled, this is done with uart_enable_fifo() and can be disabled
|
||||
* again with uart_disable_fifo(). On reset the FIFO is disabled, and it must
|
||||
* be explicitly be enabled.
|
||||
*
|
||||
* When enabling the UART FIFOs, RX and TX interrupts are triggered according
|
||||
* to the amount of data in the FIFOs. For the RX FIFO the trigger level is
|
||||
* defined by how full the FIFO is. The TX FIFO trigger level is defined by
|
||||
* how empty the FIFO is instead.
|
||||
*
|
||||
* For example, to enable the FIFOs and trigger interrupts for a single
|
||||
* received and single transmitted character:
|
||||
* @code{.c}
|
||||
* uart_enable_fifo(UART0);
|
||||
* uart_set_fifo_trigger_levels(UART0, UART_FIFO_RX_TRIG_1_8,
|
||||
* UART_FIFO_TX_TRIG_7_8);
|
||||
* @endcode
|
||||
*/
|
||||
/**@{*/
|
||||
|
||||
/**
|
||||
* \brief Enable FIFO for the UART.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_enable_fifo(uint32_t uart)
|
||||
{
|
||||
UART_LCRH(uart) |= UART_LCRH_FEN;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable FIFO for the UART.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
*/
|
||||
void uart_disable_fifo(uint32_t uart)
|
||||
{
|
||||
UART_LCRH(uart) &= ~UART_LCRH_FEN;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Set the FIFO trigger levels.
|
||||
*
|
||||
* @param[in] uart UART block register address base @ref uart_reg_base
|
||||
* @param[in] rx_level Trigger level for RX FIFO
|
||||
* @param[in] tx_level Trigger level for TX FIFO
|
||||
*/
|
||||
void uart_set_fifo_trigger_levels(uint32_t uart,
|
||||
enum uart_fifo_rx_trigger_level rx_level,
|
||||
enum uart_fifo_tx_trigger_level tx_level)
|
||||
{
|
||||
UART_IFLS(uart) = rx_level | tx_level;
|
||||
}
|
||||
/**@}*/
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
@ -0,0 +1,651 @@
|
||||
/*
|
||||
* This file is part of the libopencm3 project.
|
||||
*
|
||||
* Copyright (C) 2013 Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* This library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU Lesser General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public License
|
||||
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup usb_file USB
|
||||
*
|
||||
* @ingroup LM4Fxx
|
||||
*
|
||||
* @author @htmlonly © @endhtmlonly 2013
|
||||
* Alexandru Gagniuc <mr.nuke.me@gmail.com>
|
||||
*
|
||||
* \brief <b>libopencm3 LM4F Universal Serial Bus controller </b>
|
||||
*
|
||||
* The LM4F USB driver is integrated with the libopencm3 USB stack. You should
|
||||
* use the generic stack.
|
||||
*
|
||||
* To use this driver, tell the linker to look for it:
|
||||
* @code{.c}
|
||||
* extern usbd_driver lm4f_usb_driver;
|
||||
* @endcode
|
||||
*
|
||||
* And pass this driver as an argument when initializing the USB stack:
|
||||
* @code{.c}
|
||||
* usbd_device *usbd_dev;
|
||||
* usbd_dev = usbd_init(&lm4f_usb_driver, ...);
|
||||
* @endcode
|
||||
*
|
||||
* <b>Polling or interrupt-driven? </b>
|
||||
*
|
||||
* The LM4F USB driver will work fine regardless of whether it is called from an
|
||||
* interrupt service routine, or from the main program loop.
|
||||
*
|
||||
* Polling USB from the main loop requires calling @ref usbd_poll() from the
|
||||
* main program loop.
|
||||
* For example:
|
||||
* @code{.c}
|
||||
* // Main program loop
|
||||
* while(1) {
|
||||
* usbd_poll(usb_dev);
|
||||
* do_other_stuff();
|
||||
* ...
|
||||
* @endcode
|
||||
*
|
||||
* Running @ref usbd_poll() from an interrupt has the advantage that it is only
|
||||
* called when needed, saving CPU cycles for the main program.
|
||||
*
|
||||
* RESET, DISCON, RESUME, and SUSPEND interrupts must be enabled, along with the
|
||||
* interrupts for any endpoint that is used. The EP0_TX interrupt must be
|
||||
* enabled for the control endpoint to function correctly.
|
||||
* For example, if EP1IN and EP2OUT are used, then the EP0_TX, EP1_TX, and
|
||||
* EP2_RX interrupts should be enabled:
|
||||
* @code{.c}
|
||||
* // Enable USB interrupts for EP0, EP1IN, and EP2OUT
|
||||
* ints = USB_INT_RESET | USB_INT_DISCON | USB_INT_RESUME |
|
||||
* USB_INT_SUSPEND;
|
||||
* usb_enable_interrupts(ints, USB_EP2_INT, USB_EP0_INT | USB_EP1_INT);
|
||||
* // Route the interrupts through the NVIC
|
||||
* nvic_enable_irq(NVIC_USB0_IRQ);
|
||||
* @endcode
|
||||
*
|
||||
* The USB ISR only has to call @ref usbd_poll().
|
||||
*
|
||||
* @code{.c}
|
||||
* void usb0_isr(void)
|
||||
* {
|
||||
* usbd_poll(usb_dev);
|
||||
* }
|
||||
* @endcode
|
||||
* @{
|
||||
*/
|
||||
|
||||
/*
|
||||
* TODO list:
|
||||
*
|
||||
* 1) Driver works by reading and writing to the FIFOs one byte at a time. It
|
||||
* has no knowledge of DMA.
|
||||
* 2) Double-buffering is supported. How can we take advantage of it to speed
|
||||
* up endpoint transfers.
|
||||
* 3) No benchmarks as to the endpoint's performance has been done.
|
||||
*/
|
||||
/*
|
||||
* The following are resources referenced in comments:
|
||||
* [1] http://e2e.ti.com/support/microcontrollers/tiva_arm/f/908/t/238784.aspx
|
||||
*/
|
||||
|
||||
#include <libopencm3/cm3/common.h>
|
||||
#include <libopencm3/lm4f/usb.h>
|
||||
#include <libopencm3/lm4f/rcc.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include "../../lib/usb/usb_private.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
||||
#define MAX_FIFO_RAM (4 * 1024)
|
||||
|
||||
const struct _usbd_driver lm4f_usb_driver;
|
||||
|
||||
/**
|
||||
* \brief Enable Specific USB Interrupts
|
||||
*
|
||||
* Enable any combination of interrupts. Interrupts may be OR'ed together to
|
||||
* enable them with one call. For example, to enable both the RESUME and RESET
|
||||
* interrupts, pass (USB_INT_RESUME | USB_INT_RESET)
|
||||
*
|
||||
* Note that the NVIC must be enabled and properly configured for the interrupt
|
||||
* to be routed to the CPU.
|
||||
*
|
||||
* @param[in] ints Interrupts which to enable. Any combination of interrupts may
|
||||
* be specified by OR'ing then together
|
||||
* @param[in] rx_ints Endpoints for which to generate an interrupt when a packet
|
||||
* packet is received.
|
||||
* @param[in] tx_ints Endpoints for which to generate an interrupt when a packet
|
||||
* packet is finished transmitting.
|
||||
*/
|
||||
void usb_enable_interrupts(enum usb_interrupt ints,
|
||||
enum usb_ep_interrupt rx_ints,
|
||||
enum usb_ep_interrupt tx_ints)
|
||||
{
|
||||
USB_IE |= ints;
|
||||
USB_RXIE |= rx_ints;
|
||||
USB_TXIE |= tx_ints;
|
||||
}
|
||||
|
||||
/**
|
||||
* \brief Disable Specific USB Interrupts
|
||||
*
|
||||
* Disable any combination of interrupts. Interrupts may be OR'ed together to
|
||||
* enable them with one call. For example, to disable both the RESUME and RESET
|
||||
* interrupts, pass (USB_INT_RESUME | USB_INT_RESET)
|
||||
*
|
||||
* Note that the NVIC must be enabled and properly configured for the interrupt
|
||||
* to be routed to the CPU.
|
||||
*
|
||||
* @param[in] ints Interrupts which to disable. Any combination of interrupts
|
||||
* may be specified by OR'ing then together
|
||||
* @param[in] rx_ints Endpoints for which to stop generating an interrupt when a
|
||||
* packet packet is received.
|
||||
* @param[in] tx_ints Endpoints for which to stop generating an interrupt when a
|
||||
* packet packet is finished transmitting.
|
||||
*/
|
||||
void usb_disable_interrupts(enum usb_interrupt ints,
|
||||
enum usb_ep_interrupt rx_ints,
|
||||
enum usb_ep_interrupt tx_ints)
|
||||
{
|
||||
USB_IE &= ~ints;
|
||||
USB_RXIE &= ~rx_ints;
|
||||
USB_TXIE &= ~tx_ints;
|
||||
}
|
||||
|
||||
/**
|
||||
* @cond private
|
||||
*/
|
||||
static inline void lm4f_usb_soft_disconnect(void)
|
||||
{
|
||||
USB_POWER &= ~USB_POWER_SOFTCONN;
|
||||
}
|
||||
|
||||
static inline void lm4f_usb_soft_connect(void)
|
||||
{
|
||||
USB_POWER |= USB_POWER_SOFTCONN;
|
||||
}
|
||||
|
||||
static void lm4f_set_address(usbd_device *usbd_dev, uint8_t addr)
|
||||
{
|
||||
(void)usbd_dev;
|
||||
|
||||
USB_FADDR = addr & USB_FADDR_FUNCADDR_MASK;
|
||||
}
|
||||
|
||||
static void lm4f_ep_setup(usbd_device *usbd_dev, uint8_t addr, uint8_t type,
|
||||
uint16_t max_size,
|
||||
void (*callback) (usbd_device *usbd_dev, uint8_t ep))
|
||||
{
|
||||
(void)usbd_dev;
|
||||
(void)type;
|
||||
|
||||
uint8_t reg8;
|
||||
uint16_t fifo_size;
|
||||
|
||||
const bool dir_tx = addr & 0x80;
|
||||
const uint8_t ep = addr & 0x0f;
|
||||
|
||||
/*
|
||||
* We do not mess with the maximum packet size, but we can only allocate
|
||||
* the FIFO in power-of-two increments.
|
||||
*/
|
||||
if (max_size > 1024) {
|
||||
fifo_size = 2048;
|
||||
reg8 = USB_FIFOSZ_SIZE_2048;
|
||||
} else if (max_size > 512) {
|
||||
fifo_size = 1024;
|
||||
reg8 = USB_FIFOSZ_SIZE_1024;
|
||||
} else if (max_size > 256) {
|
||||
fifo_size = 512;
|
||||
reg8 = USB_FIFOSZ_SIZE_512;
|
||||
} else if (max_size > 128) {
|
||||
fifo_size = 256;
|
||||
reg8 = USB_FIFOSZ_SIZE_256;
|
||||
} else if (max_size > 64) {
|
||||
fifo_size = 128;
|
||||
reg8 = USB_FIFOSZ_SIZE_128;
|
||||
} else if (max_size > 32) {
|
||||
fifo_size = 64;
|
||||
reg8 = USB_FIFOSZ_SIZE_64;
|
||||
} else if (max_size > 16) {
|
||||
fifo_size = 32;
|
||||
reg8 = USB_FIFOSZ_SIZE_32;
|
||||
} else if (max_size > 8) {
|
||||
fifo_size = 16;
|
||||
reg8 = USB_FIFOSZ_SIZE_16;
|
||||
} else {
|
||||
fifo_size = 8;
|
||||
reg8 = USB_FIFOSZ_SIZE_8;
|
||||
}
|
||||
|
||||
/* Endpoint 0 is more special */
|
||||
if (addr == 0) {
|
||||
USB_EPIDX = 0;
|
||||
|
||||
if (reg8 > USB_FIFOSZ_SIZE_64) {
|
||||
reg8 = USB_FIFOSZ_SIZE_64;
|
||||
}
|
||||
|
||||
/* The RX and TX FIFOs are shared for EP0 */
|
||||
USB_RXFIFOSZ = reg8;
|
||||
USB_TXFIFOSZ = reg8;
|
||||
|
||||
/*
|
||||
* Regardless of how much we allocate, the first 64 bytes
|
||||
* are always reserved for EP0.
|
||||
*/
|
||||
usbd_dev->fifo_mem_top_ep0 = 64;
|
||||
return;
|
||||
}
|
||||
|
||||
/* Are we out of FIFO space? */
|
||||
if (usbd_dev->fifo_mem_top + fifo_size > MAX_FIFO_RAM) {
|
||||
return;
|
||||
}
|
||||
|
||||
USB_EPIDX = addr & USB_EPIDX_MASK;
|
||||
|
||||
/* FIXME: What about double buffering? */
|
||||
if (dir_tx) {
|
||||
USB_TXMAXP(ep) = max_size;
|
||||
USB_TXFIFOSZ = reg8;
|
||||
USB_TXFIFOADD = ((usbd_dev->fifo_mem_top) >> 3);
|
||||
if (callback) {
|
||||
usbd_dev->user_callback_ctr[ep][USB_TRANSACTION_IN] =
|
||||
(void *)callback;
|
||||
}
|
||||
if (type == USB_ENDPOINT_ATTR_ISOCHRONOUS) {
|
||||
USB_TXCSRH(ep) |= USB_TXCSRH_ISO;
|
||||
} else {
|
||||
USB_TXCSRH(ep) &= ~USB_TXCSRH_ISO;
|
||||
}
|
||||
} else {
|
||||
USB_RXMAXP(ep) = max_size;
|
||||
USB_RXFIFOSZ = reg8;
|
||||
USB_RXFIFOADD = ((usbd_dev->fifo_mem_top) >> 3);
|
||||
if (callback) {
|
||||
usbd_dev->user_callback_ctr[ep][USB_TRANSACTION_OUT] =
|
||||
(void *)callback;
|
||||
}
|
||||
if (type == USB_ENDPOINT_ATTR_ISOCHRONOUS) {
|
||||
USB_RXCSRH(ep) |= USB_RXCSRH_ISO;
|
||||
} else {
|
||||
USB_RXCSRH(ep) &= ~USB_RXCSRH_ISO;
|
||||
}
|
||||
}
|
||||
|
||||
usbd_dev->fifo_mem_top += fifo_size;
|
||||
}
|
||||
|
||||
static void lm4f_endpoints_reset(usbd_device *usbd_dev)
|
||||
{
|
||||
/*
|
||||
* The core resets the endpoints automatically on reset.
|
||||
* The first 64 bytes are always reserved for EP0
|
||||
*/
|
||||
usbd_dev->fifo_mem_top = 64;
|
||||
}
|
||||
|
||||
static void lm4f_ep_stall_set(usbd_device *usbd_dev, uint8_t addr,
|
||||
uint8_t stall)
|
||||
{
|
||||
(void)usbd_dev;
|
||||
|
||||
const uint8_t ep = addr & 0x0f;
|
||||
const bool dir_tx = addr & 0x80;
|
||||
|
||||
if (ep == 0) {
|
||||
if (stall) {
|
||||
USB_CSRL0 |= USB_CSRL0_STALL;
|
||||
} else {
|
||||
USB_CSRL0 &= ~USB_CSRL0_STALL;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (dir_tx) {
|
||||
if (stall) {
|
||||
(USB_TXCSRL(ep)) |= USB_TXCSRL_STALL;
|
||||
} else {
|
||||
(USB_TXCSRL(ep)) &= ~USB_TXCSRL_STALL;
|
||||
}
|
||||
} else {
|
||||
if (stall) {
|
||||
(USB_RXCSRL(ep)) |= USB_RXCSRL_STALL;
|
||||
} else {
|
||||
(USB_RXCSRL(ep)) &= ~USB_RXCSRL_STALL;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t lm4f_ep_stall_get(usbd_device *usbd_dev, uint8_t addr)
|
||||
{
|
||||
(void)usbd_dev;
|
||||
|
||||
const uint8_t ep = addr & 0x0f;
|
||||
const bool dir_tx = addr & 0x80;
|
||||
|
||||
if (ep == 0) {
|
||||
return USB_CSRL0 & USB_CSRL0_STALLED;
|
||||
}
|
||||
|
||||
if (dir_tx) {
|
||||
return USB_TXCSRL(ep) & USB_TXCSRL_STALLED;
|
||||
} else {
|
||||
return USB_RXCSRL(ep) & USB_RXCSRL_STALLED;
|
||||
}
|
||||
}
|
||||
|
||||
static void lm4f_ep_nak_set(usbd_device *usbd_dev, uint8_t addr, uint8_t nak)
|
||||
{
|
||||
(void)usbd_dev;
|
||||
(void)addr;
|
||||
(void)nak;
|
||||
|
||||
/* NAK's are handled automatically by hardware. Move along. */
|
||||
}
|
||||
|
||||
static uint16_t lm4f_ep_write_packet(usbd_device *usbd_dev, uint8_t addr,
|
||||
const void *buf, uint16_t len)
|
||||
{
|
||||
const uint8_t ep = addr & 0xf;
|
||||
uint16_t i;
|
||||
|
||||
(void)usbd_dev;
|
||||
|
||||
/* Don't touch the FIFO if there is still a packet being transmitted */
|
||||
if (ep == 0 && (USB_CSRL0 & USB_CSRL0_TXRDY)) {
|
||||
return 0;
|
||||
} else if (USB_TXCSRL(ep) & USB_TXCSRL_TXRDY) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* We don't need to worry about buf not being aligned. If it's not,
|
||||
* the reads are downgraded to 8-bit in hardware. We lose a bit of
|
||||
* performance, but we don't crash.
|
||||
*/
|
||||
for (i = 0; i < (len & ~0x3); i += 4) {
|
||||
USB_FIFO32(ep) = *((uint32_t *)(buf + i));
|
||||
}
|
||||
if (len & 0x2) {
|
||||
USB_FIFO16(ep) = *((uint16_t *)(buf + i));
|
||||
i += 2;
|
||||
}
|
||||
if (len & 0x1) {
|
||||
USB_FIFO8(ep) = *((uint8_t *)(buf + i));
|
||||
i += 1;
|
||||
}
|
||||
|
||||
if (ep == 0) {
|
||||
/*
|
||||
* EP0 is very special. We should only set DATAEND when we
|
||||
* transmit the last packet in the transaction. A transaction
|
||||
* that is a multiple of 64 bytes will end with a zero-length
|
||||
* packet, so our check is sane.
|
||||
*/
|
||||
if (len != 64) {
|
||||
USB_CSRL0 |= USB_CSRL0_TXRDY | USB_CSRL0_DATAEND;
|
||||
} else {
|
||||
USB_CSRL0 |= USB_CSRL0_TXRDY;
|
||||
}
|
||||
} else {
|
||||
USB_TXCSRL(ep) |= USB_TXCSRL_TXRDY;
|
||||
}
|
||||
|
||||
return i;
|
||||
}
|
||||
|
||||
static uint16_t lm4f_ep_read_packet(usbd_device *usbd_dev, uint8_t addr,
|
||||
void *buf, uint16_t len)
|
||||
{
|
||||
(void)usbd_dev;
|
||||
|
||||
uint16_t rlen;
|
||||
uint8_t ep = addr & 0xf;
|
||||
|
||||
uint16_t fifoin = USB_RXCOUNT(ep);
|
||||
|
||||
rlen = (fifoin > len) ? len : fifoin;
|
||||
|
||||
/*
|
||||
* We don't need to worry about buf not being aligned. If it's not,
|
||||
* the writes are downgraded to 8-bit in hardware. We lose a bit of
|
||||
* performance, but we don't crash.
|
||||
*/
|
||||
for (len = 0; len < (rlen & ~0x3); len += 4) {
|
||||
*((uint32_t *)(buf + len)) = USB_FIFO32(ep);
|
||||
}
|
||||
if (rlen & 0x2) {
|
||||
*((uint16_t *)(buf + len)) = USB_FIFO16(ep);
|
||||
len += 2;
|
||||
}
|
||||
if (rlen & 0x1) {
|
||||
*((uint8_t *)(buf + len)) = USB_FIFO8(ep);
|
||||
}
|
||||
|
||||
if (ep == 0) {
|
||||
/*
|
||||
* Clear RXRDY
|
||||
* Datasheet says that DATAEND must also be set when clearing
|
||||
* RXRDY. We don't do that. If did this when transmitting a
|
||||
* packet larger than 64 bytes, only the first 64 bytes would
|
||||
* be transmitted, followed by a handshake. The host would only
|
||||
* get 64 bytes, seeing it as a malformed packet. Usually, we
|
||||
* would not get past enumeration.
|
||||
*/
|
||||
USB_CSRL0 |= USB_CSRL0_RXRDYC;
|
||||
|
||||
} else {
|
||||
USB_RXCSRL(ep) &= ~USB_RXCSRL_RXRDY;
|
||||
}
|
||||
|
||||
return rlen;
|
||||
}
|
||||
|
||||
static void lm4f_poll(usbd_device *usbd_dev)
|
||||
{
|
||||
void (*tx_cb)(usbd_device *usbd_dev, uint8_t ea);
|
||||
void (*rx_cb)(usbd_device *usbd_dev, uint8_t ea);
|
||||
int i;
|
||||
|
||||
/*
|
||||
* The initial state of these registers might change, as we process the
|
||||
* interrupt, but we need the initial state in order to decide how to
|
||||
* handle events.
|
||||
*/
|
||||
const uint8_t usb_is = USB_IS;
|
||||
const uint8_t usb_rxis = USB_RXIS;
|
||||
const uint8_t usb_txis = USB_TXIS;
|
||||
const uint8_t usb_csrl0 = USB_CSRL0;
|
||||
|
||||
if ((usb_is & USB_IM_SUSPEND) && (usbd_dev->user_callback_suspend)) {
|
||||
usbd_dev->user_callback_suspend();
|
||||
}
|
||||
|
||||
if ((usb_is & USB_IM_RESUME) && (usbd_dev->user_callback_resume)) {
|
||||
usbd_dev->user_callback_resume();
|
||||
}
|
||||
|
||||
if (usb_is & USB_IM_RESET) {
|
||||
_usbd_reset(usbd_dev);
|
||||
}
|
||||
|
||||
if ((usb_is & USB_IM_SOF) && (usbd_dev->user_callback_sof)) {
|
||||
usbd_dev->user_callback_sof();
|
||||
}
|
||||
|
||||
if (usb_txis & USB_EP0) {
|
||||
/*
|
||||
* The EP0 bit in USB_TXIS is special. It tells us that
|
||||
* something happened on EP0, but does not tell us what. This
|
||||
* bit does not necessarily tell us that a packet was
|
||||
* transmitted, so we have to go through all the possibilities
|
||||
* to figure out exactly what did. Only after we've exhausted
|
||||
* all other possibilities, can we assume this is a EPO
|
||||
* "transmit complete" interrupt.
|
||||
*/
|
||||
if (usb_csrl0 & USB_CSRL0_RXRDY) {
|
||||
enum _usbd_transaction type;
|
||||
type = (usbd_dev->control_state.state != DATA_OUT &&
|
||||
usbd_dev->control_state.state != LAST_DATA_OUT)
|
||||
? USB_TRANSACTION_SETUP :
|
||||
USB_TRANSACTION_OUT;
|
||||
|
||||
if (usbd_dev->user_callback_ctr[0][type]) {
|
||||
usbd_dev->
|
||||
user_callback_ctr[0][type](usbd_dev, 0);
|
||||
}
|
||||
|
||||
|
||||
} else {
|
||||
tx_cb = usbd_dev->user_callback_ctr[0]
|
||||
[USB_TRANSACTION_IN];
|
||||
|
||||
/*
|
||||
* EP0 bit in TXIS is set not only when a packet is
|
||||
* finished transmitting, but also when RXRDY is set, or
|
||||
* when we set TXRDY to transmit a packet. If any of
|
||||
* those are the case, then we do not want to call our
|
||||
* IN callback, since the state machine will be in the
|
||||
* wrong state, and we'll just stall our control
|
||||
* endpoint.
|
||||
* In fact, the only way to know if it's time to call
|
||||
* our TX callback is to know what to expect. The
|
||||
* hardware does not tell us what sort of transaction
|
||||
* this is. We need to work with the state machine to
|
||||
* figure it all out. See [1] for details.
|
||||
*/
|
||||
if ((usbd_dev->control_state.state != DATA_IN) &&
|
||||
(usbd_dev->control_state.state != LAST_DATA_IN) &&
|
||||
(usbd_dev->control_state.state != STATUS_IN)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (tx_cb) {
|
||||
tx_cb(usbd_dev, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* See which interrupt occurred */
|
||||
for (i = 1; i < 8; i++) {
|
||||
tx_cb = usbd_dev->user_callback_ctr[i][USB_TRANSACTION_IN];
|
||||
rx_cb = usbd_dev->user_callback_ctr[i][USB_TRANSACTION_OUT];
|
||||
|
||||
if ((usb_txis & (1 << i)) && tx_cb) {
|
||||
tx_cb(usbd_dev, i);
|
||||
}
|
||||
|
||||
if ((usb_rxis & (1 << i)) && rx_cb) {
|
||||
rx_cb(usbd_dev, i);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
static void lm4f_disconnect(usbd_device *usbd_dev, bool disconnected)
|
||||
{
|
||||
(void)usbd_dev;
|
||||
|
||||
/*
|
||||
* This is all it takes:
|
||||
* usbd_disconnect(dev, 1) followed by usbd_disconnect(dev, 0)
|
||||
* causes the device to re-enumerate and re-configure properly.
|
||||
*/
|
||||
if (disconnected) {
|
||||
lm4f_usb_soft_disconnect();
|
||||
} else {
|
||||
lm4f_usb_soft_connect();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* A static struct works as long as we have only one USB peripheral. If we
|
||||
* meet LM4Fs with more than one USB, then we need to rework this approach.
|
||||
*/
|
||||
static struct _usbd_device usbd_dev;
|
||||
|
||||
/** Initialize the USB device controller hardware of the LM4F. */
|
||||
static usbd_device *lm4f_usbd_init(void)
|
||||
{
|
||||
int i;
|
||||
|
||||
/* Start the USB clock */
|
||||
periph_clock_enable(RCC_USB0);
|
||||
/* Enable the USB PLL interrupts - used to assert PLL lock */
|
||||
SYSCTL_IMC |= (SYSCTL_IMC_USBPLLLIM | SYSCTL_IMC_PLLLIM);
|
||||
rcc_usb_pll_on();
|
||||
|
||||
/* Make sure we're disconnected. We'll reconnect later */
|
||||
lm4f_usb_soft_disconnect();
|
||||
|
||||
/* Software reset USB */
|
||||
SYSCTL_SRUSB = 1;
|
||||
for (i = 0; i < 1000; i++) {
|
||||
__asm__("nop");
|
||||
}
|
||||
SYSCTL_SRUSB = 0;
|
||||
|
||||
/*
|
||||
* Wait for the PLL to lock before soft connecting
|
||||
* This will result in a deadlock if the system clock is not setup
|
||||
* correctly (clock from main oscillator).
|
||||
*/
|
||||
/* Wait for it */
|
||||
i = 0;
|
||||
while ((SYSCTL_RIS & SYSCTL_RIS_USBPLLLRIS) == 0) {
|
||||
i++;
|
||||
if (i > 0xffff) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/* Now connect to USB */
|
||||
lm4f_usb_soft_connect();
|
||||
|
||||
/* No FIFO allocated yet, but the first 64 bytes are still reserved */
|
||||
usbd_dev.fifo_mem_top = 64;
|
||||
|
||||
return &usbd_dev;
|
||||
}
|
||||
|
||||
/* What is this thing even good for */
|
||||
#define RX_FIFO_SIZE 512
|
||||
|
||||
const struct _usbd_driver lm4f_usb_driver = {
|
||||
.init = lm4f_usbd_init,
|
||||
.set_address = lm4f_set_address,
|
||||
.ep_setup = lm4f_ep_setup,
|
||||
.ep_reset = lm4f_endpoints_reset,
|
||||
.ep_stall_set = lm4f_ep_stall_set,
|
||||
.ep_stall_get = lm4f_ep_stall_get,
|
||||
.ep_nak_set = lm4f_ep_nak_set,
|
||||
.ep_write_packet = lm4f_ep_write_packet,
|
||||
.ep_read_packet = lm4f_ep_read_packet,
|
||||
.poll = lm4f_poll,
|
||||
.disconnect = lm4f_disconnect,
|
||||
.base_address = USB_BASE,
|
||||
.set_address_before_status = false,
|
||||
.rx_fifo_size = RX_FIFO_SIZE,
|
||||
};
|
||||
/**
|
||||
* @endcond
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
Reference in New Issue
Block a user