tiva(stellaris)/lpc: Use directory structure as stm32

EDIT: Whitespace changes to the files stripped out.
This commit is contained in:
Uwe Bonnes
2014-01-20 13:03:58 +01:00
committed by Frantisek Burian
parent 3af1f8d43d
commit 1740fee230
64 changed files with 5 additions and 5 deletions

View File

@@ -0,0 +1,48 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
## Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.com>
##
## This library is free software: you can redistribute it and/or modify
## it undebipr 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 = opencm3_lm4f
DEFS = -DLM4F
FP_FLAGS ?= -mfloat-abi=hard -mfpu=fpv4-sp-d16
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 $(FP_FLAGS)
################################################################################
# OpenOCD specific variables
# Support for ICDI is available starting with openocd 0.7.0
OOCD ?= openocd
OOCD_INTERFACE ?= flossjtag
OOCD_BOARD ?= ek-lm4f120xl
################################################################################
# Black Magic Probe specific variables
# Set the BMP_PORT to a serial port and then BMP is used for flashing
BMP_PORT ?=
################################################################################
# texane/stlink specific variables
#STLINK_PORT ?= :4242
include ../../../../Makefile.rules

View File

@@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Uwe Hermann <uwe@hermann-uwe.de>
*
* 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/>.
*/
/* Linker script for TI Stellaris EX-LM4F120XL evaluation board. */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x00000000, LENGTH = 256K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K
}
/* Include the common ld script. */
INCLUDE libopencm3_lm4f.ld

View File

@@ -0,0 +1,25 @@
##
## 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/>.
##
BINARY = miniblink
LDSCRIPT = ../ek-lm4f120xl.ld
include ../../Makefile.include

View File

@@ -0,0 +1,22 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example demonstrates the following:
* Configuriong GPIO pins
* Toggling GPIO pins
* Setting up and using GPIO interrupts
* Unlocking protected GPIO pins
* Controlling the system clock
* Changing the system clock on the fly
Flashes the Red, Green and Blue diodes on the board, in order. The system clock
starts at 80MHz.
Pressing SW2 toggles the system clock between 80MHz, 57MHz, 40MHz ,20MHz, and
16MHz by changing the PLL divisor.
Pressing SW1 bypasses the PLL completely, and runs off the raw 16MHz clock
provided by the external crystal oscillator.
The LEDs will toggle at different speeds, depending on the system clock. The
system clock changes are handled within the interrupt service routine.

View File

@@ -0,0 +1,206 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
* Copyright (C) 2012-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/>.
*/
/**
* \addtogroup Examples
*
* Flashes the Red, Green and Blue diodes on the board, in order.
*
* RED controlled by PF1
* Green controlled by PF3
* Blue controlled by PF2
*/
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/lm4f/systemcontrol.h>
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/lm4f/nvic.h>
#include <stdbool.h>
#include <stdio.h>
/* This is how the RGB LED is connected on the stellaris launchpad */
#define RGB_PORT GPIOF
enum {
LED_R = GPIO1,
LED_G = GPIO3,
LED_B = GPIO2,
};
/* This is how the user switches are connected to GPIOF */
enum {
USR_SW1 = GPIO4,
USR_SW2 = GPIO0,
};
/* The divisors we loop through when the user presses SW2 */
enum {
PLL_DIV_80MHZ = 5,
PLL_DIV_57MHZ = 7,
PLL_DIV_40MHZ = 10,
PLL_DIV_20MHZ = 20,
PLL_DIV_16MHZ = 25,
};
static const uint8_t plldiv[] = {
PLL_DIV_80MHZ,
PLL_DIV_57MHZ,
PLL_DIV_40MHZ,
PLL_DIV_20MHZ,
PLL_DIV_16MHZ,
0
};
/* The PLL divisor we are currently on */
static size_t ipll = 0;
/* Are we bypassing the PLL, or not? */
static bool bypass = false;
/*
* Clock setup:
* Take the main crystal oscillator at 16MHz, run it through the PLL, and divide
* the 400MHz PLL clock to get a system clock of 80MHz.
*/
static void clock_setup(void)
{
rcc_sysclk_config(OSCSRC_MOSC, XTAL_16M, PLL_DIV_80MHZ);
}
/*
* GPIO setup:
* Enable the pins driving the RGB LED as outputs.
*/
static void gpio_setup(void)
{
/*
* Configure GPIOF
* This port is used to control the RGB LED
*/
periph_clock_enable(RCC_GPIOF);
const uint32_t outpins = (LED_R | LED_G | LED_B);
gpio_mode_setup(RGB_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, outpins);
gpio_set_output_config(RGB_PORT, GPIO_OTYPE_PP, GPIO_DRIVE_2MA, outpins);
/*
* Now take care of our buttons
*/
const uint32_t btnpins = USR_SW1 | USR_SW2;
/*
* PF0 is a locked by default. We need to unlock it before we can
* re-purpose it as a GPIO pin.
*/
gpio_unlock_commit(GPIOF, USR_SW2);
/* Configure pins as inputs, with pull-up. */
gpio_mode_setup(GPIOF, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, btnpins);
}
/*
* IRQ setup:
* Trigger an interrupt whenever a button is depressed.
*/
static void irq_setup(void)
{
const uint32_t btnpins = USR_SW1 | USR_SW2;
/* Trigger interrupt on rising-edge (when button is depressed) */
gpio_configure_trigger(GPIOF, GPIO_TRIG_EDGE_RISE, btnpins);
/* Finally, Enable interrupt */
gpio_enable_interrupts(GPIOF, btnpins);
/* Enable the interrupt in the NVIC as well */
nvic_enable_irq(NVIC_GPIOF_IRQ);
}
#define FLASH_DELAY 800000
static void delay(void)
{
int i;
for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
__asm__("nop");
}
int main(void)
{
gpio_enable_ahb_aperture();
clock_setup();
gpio_setup();
irq_setup();
/* Blink each color of the RGB LED in order. */
while (1) {
/*
* Flash the Red diode
*/
gpio_set(RGB_PORT, LED_R);
delay(); /* Wait a bit. */
gpio_clear(RGB_PORT, LED_R);
delay(); /* Wait a bit. */
/*
* Flash the Green diode
*/
gpio_set(RGB_PORT, LED_G);
delay(); /* Wait a bit. */
gpio_clear(RGB_PORT, LED_G);
delay(); /* Wait a bit. */
/*
* Flash the Blue diode
*/
gpio_set(RGB_PORT, LED_B);
delay(); /* Wait a bit. */
gpio_clear(RGB_PORT, LED_B);
delay(); /* Wait a bit. */
}
return 0;
}
void gpiof_isr(void)
{
if (gpio_is_interrupt_source(GPIOF, USR_SW1)) {
/* SW1 was just depressed */
bypass = !bypass;
if (bypass) {
rcc_pll_bypass_enable();
/*
* The divisor is still applied to the raw clock.
* Disable the divisor, or we'll divide the raw clock.
*/
SYSCTL_RCC &= ~SYSCTL_RCC_USESYSDIV;
}
else
{
rcc_change_pll_divisor(plldiv[ipll]);
}
/* Clear interrupt source */
gpio_clear_interrupt_flag(GPIOF, USR_SW1);
}
if (gpio_is_interrupt_source(GPIOF, USR_SW2)) {
/* SW2 was just depressed */
if (!bypass) {
if (plldiv[++ipll] == 0)
ipll = 0;
rcc_change_pll_divisor(plldiv[ipll]);
}
/* Clear interrupt source */
gpio_clear_interrupt_flag(GPIOF, USR_SW2);
}
}

View File

@@ -0,0 +1,25 @@
##
## 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/>.
##
BINARY = uart_echo_interrupt
LDSCRIPT = ../ek-lm4f120xl.ld
include ../../Makefile.include

View File

@@ -0,0 +1,18 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example demonstrates the ease of setting up the UART with libopencm3, and
using UART interrupts. UART echo is achieved by echoing back received characters
from within the interrupt service routine. This has the advantage over using
blocking reads and writes that the main program loop is freed for other tasks.
The UART is set up as 921600-8N1.
PA0 is the Rx pin, and PA1 is the Tx pin (from the LM4F perspective). These
pins are connected to the CDCACM interface on the debug chip, so no hardware is
necessary to test this example. Just connect the debug USB cable and use a
terminal program to open the ACM port with 921600-8N1.
For example:
$ picocom /dev/ttyACM0 -b921600

View File

@@ -0,0 +1,90 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
* 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>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/lm4f/uart.h>
#include <libopencm3/lm4f/nvic.h>
static void uart_setup(void)
{
/* Enable GPIOA in run mode. */
periph_clock_enable(RCC_GPIOA);
/* Mux PA0 and PA1 to UART0 (alternate function 1) */
gpio_set_af(GPIOA, 1, GPIO0 | GPIO1);
/* Enable the UART clock */
periph_clock_enable(RCC_UART0);
/* We need a brief delay before we can access UART config registers */
__asm__("nop");
/* Disable the UART while we mess with its setings */
uart_disable(UART0);
/* Configure the UART clock source as precision internal oscillator */
uart_clock_from_piosc(UART0);
/* Set communication parameters */
uart_set_baudrate(UART0, 921600);
uart_set_databits(UART0, 8);
uart_set_parity(UART0, UART_PARITY_NONE);
uart_set_stopbits(UART0, 1);
/* Now that we're done messing with the settings, enable the UART */
uart_enable(UART0);
}
static void uart_irq_setup(void)
{
/* Gimme and RX interrupt */
uart_enable_rx_interrupt(UART0);
/* Make sure the interrupt is routed through the NVIC */
nvic_enable_irq(NVIC_UART0_IRQ);
}
/*
* uart0_isr is declared as a weak function. When we override it here, the
* libopencm3 build system takes care that it becomes our UART0 ISR.
*/
void uart0_isr(void)
{
uint8_t rx;
uint32_t irq_clear = 0;
if (uart_is_interrupt_source(UART0, UART_INT_RX)) {
rx = uart_recv(UART0);
uart_send(UART0, rx);
irq_clear |= UART_INT_RX;
}
uart_clear_interrupt_flag(UART0, irq_clear);
}
int main(void)
{
gpio_enable_ahb_aperture();
uart_setup();
uart_irq_setup();
/*
* Not worrying about the UART here.
*/
while (1) {
/* Do some other task */
}
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## 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/>.
##
BINARY = uart_echo_simple
LDSCRIPT = ../ek-lm4f120xl.ld
include ../../Makefile.include

View File

@@ -0,0 +1,14 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example demonstrates the ease of setting up the UART with libopencm3.
Basic UART echo is achieved by using blocking reads and writes. The UART is set
up as 921600-8N1.
PA0 is the Rx pin, and PA1 is the Tx pin (from the LM4F perspective). These
pins are connected to the CDCACM interface on the debug chip, so no hardware is
necessary to test this example. Just connect the debug USB cable and use a
terminal program to open the ACM port with 921600-8N1.
For example:
$ picocom /dev/ttyACM0 -b921600

View File

@@ -0,0 +1,66 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
* 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>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/lm4f/uart.h>
static void uart_setup(void)
{
/* Enable GPIOA in run mode. */
periph_clock_enable(RCC_GPIOA);
/* Mux PA0 and PA1 to UART0 (alternate function 1) */
gpio_set_af(GPIOA, 1, GPIO0 | GPIO1);
/* Enable the UART clock */
periph_clock_enable(RCC_UART0);
/* We need a brief delay before we can access UART config registers */
__asm__("nop");
/* Disable the UART while we mess with its setings */
uart_disable(UART0);
/* Configure the UART clock source as precision internal oscillator */
uart_clock_from_piosc(UART0);
/* Set communication parameters */
uart_set_baudrate(UART0, 921600);
uart_set_databits(UART0, 8);
uart_set_parity(UART0, UART_PARITY_NONE);
uart_set_stopbits(UART0, 1);
/* Now that we're done messing with the settings, enable the UART */
uart_enable(UART0);
}
int main(void)
{
uint8_t rx;
gpio_enable_ahb_aperture();
uart_setup();
/*
* Yes, it's that simple !
*/
while(1) {
rx = uart_recv_blocking(UART0);
uart_send_blocking(UART0, rx);
}
return 0;
}

View File

@@ -0,0 +1,24 @@
##
## 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/>.
##
BINARY = usb_bulk_dev
LDSCRIPT = ../ek-lm4f120xl.ld
include ../../Makefile.include

View File

@@ -0,0 +1,61 @@
usb_bulk_dev
============
This example demonstrates the following:
* Setting up polled USB endpoints
* Setting up interrupt driven USB endpoints
* Using the UART as a debug tool
USB module
----------
Several USB endpoints are being set up:
* EP1 OUT - interrupt driven RX endpoint
* EP2 IN - interrupt driven TX endpoint
* EP3 OUT - polled RX endpoint
* EP4 IN - polled TX endpoint
* EP5 OUT - polled RX endpoint with unaligned buffer
* EP6 IN - polled TX endpoint with unaligned buffer
These endpoints do not transfer any meaningful data. Instead, they try to push
data in and out as fast as possible by writing it to the FIFOs or reading it
from the FIFOs.
The interrupt driven endpoints only read or write a packet during a callback
from the USB driver. Since the USB driver is run entirely from the USB ISR,
these callbacks are essentially interrupt driven.
The polled endpoints try to continuously read and write data. Even though
usbd_ep_read/write_packet is called continuously for these endpoints, the USB
driver will only write a packet to the TX FIFO if it is empty, and only read
a packet from the FIFO if one has arrived.
The endpoints with a misaligned buffer show the performance drop when the buffer
is not aligned to a 4 byte boundary. 32-bit memory accesses to the buffer are
downgraded to 8-bit accesses by the hardware.
Clock change module
-------------------
Pressing SW2 toggles the system clock between 80MHz, 57MHz, 40MHz, 30MHz, 20MHz,
and 16MHz by changing the PLL divisor.
Pressing SW1 bypasses the PLL completely, and runs off the raw 16MHz clock
provided by the external crystal oscillator.
Changing the system clock on-the-fly does not affect the USB peripheral. It is
possible to change the system clock while benchmarking the USB endpoint.
The current system clock is printed on the debug interface. This allows testing
the performance of the USB endpoints under different clocks.
Debug module
------------
printf() support is provided via UART0. The UART0 pins are connected to the
CDCACM interface on the ICDI chip, so no extra hardware is necessary to check
the debug output. Just connect the debug USB cable and use a terminal program to
open the ACM port with 921600-8N1.
For example:
> $ picocom /dev/ttyACM0 -b921600

View File

@@ -0,0 +1,475 @@
/*
* 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/>.
*/
/**
* \addtogroup Examples
*
* Establishes a basic USB devices with interrupt-driven and polled IN and OUT
* bulk endpoints.
*/
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/lm4f/nvic.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/lm4f/usb.h>
#include<stdio.h>
int _write(int file, char *ptr, int len);
void uart_setup(void);
/* =============================================================================
* = Clock control definitions
* ---------------------------------------------------------------------------*/
/* This is how the RGB LED is connected on the stellaris launchpad */
#define RGB_PORT GPIOF
enum {
LED_R = GPIO1,
LED_G = GPIO3,
LED_B = GPIO2,
};
/* This is how the user switches are connected to GPIOF */
enum {
USR_SW1 = GPIO4,
USR_SW2 = GPIO0,
};
/* The divisors we loop through when the user presses SW2 */
enum {
PLL_DIV_80MHZ = 5,
PLL_DIV_57MHZ = 7,
PLL_DIV_40MHZ = 10,
PLL_DIV_30MHZ = 13,
PLL_DIV_20MHZ = 20,
PLL_DIV_16MHZ = 25,
};
static const uint8_t plldiv[] = {
PLL_DIV_80MHZ,
PLL_DIV_57MHZ,
PLL_DIV_40MHZ,
PLL_DIV_30MHZ,
PLL_DIV_20MHZ,
PLL_DIV_16MHZ,
0
};
/* The PLL divisor we are currently on */
static size_t ipll = 0;
/* Are we bypassing the PLL, or not? */
static bool bypass = false;
/* =============================================================================
* = USB descriptors
* ---------------------------------------------------------------------------*/
static const struct usb_device_descriptor dev_descr = {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x0110,
.bDeviceClass = 0xff,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = 64,
.idVendor = 0xc03e,
.idProduct = 0xb007,
.bcdDevice = 0x0110,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
};
static const struct usb_endpoint_descriptor bulk_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x01,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x82,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x03,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x84,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x05,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x86,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}};
static const struct usb_interface_descriptor bulk_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 6,
.bInterfaceClass = 0xff,
.bInterfaceSubClass = 0xff,
.bInterfaceProtocol = 0xff,
.iInterface = 0,
.endpoint = bulk_endp,
.extra = NULL,
.extralen = 0,
}};
static const struct usb_interface ifaces[] = {{
.num_altsetting = 1,
.altsetting = bulk_iface,
}};
static const struct usb_config_descriptor config_descr = {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
.bNumInterfaces = 1,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0x80,
.bMaxPower = 0x32,
.interface = ifaces,
};
extern usbd_driver lm4f_usb_driver;
static usbd_device *bulk_dev;
static uint8_t usbd_control_buffer[128];
static uint8_t config_set = 0;
static const char *usb_strings[] = {
"libopencm3",
"usb_dev_bulk",
"none",
"DEMO",
};
/* =============================================================================
* = USB Module
* ---------------------------------------------------------------------------*/
/*
* Mux the USB pins to their analog function
*/
static void usb_setup(void)
{
/* USB pins are connected to port D */
periph_clock_enable(RCC_GPIOD);
/* Mux USB pins to their analog function */
gpio_mode_setup(GPIOD, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO4 | GPIO5);
}
/*
* Enable USB interrupts
*
* We don't enable the USB peripheral clock here, but we need it on in order to
* acces USB registers. Hence, this must be called after usbd_init().
*/
static void usb_ints_setup(void)
{
uint8_t usbints;
/* Gimme some interrupts */
usbints = USB_INT_RESET | USB_INT_DISCON | USB_INT_RESUME |
USB_INT_SUSPEND | USB_INT_SOF;
usb_enable_interrupts(usbints, 0xff, 0xff);
nvic_enable_irq(NVIC_USB0_IRQ);
}
/*
* Callback for the interrupt-driven OUT endpoint
*
* This gets called whenever a new OUT packet has arrived.
*/
static void bulk_rx_cb(usbd_device * usbd_dev, uint8_t ep)
{
char buf[64] __attribute__ ((aligned(4)));
(void)ep;
/* Read the packet to clear the FIFO and make room for a new packet */
usbd_ep_read_packet(usbd_dev, 0x01, buf, 64);
}
/*
* Callback for the interrupt-driven IN endpoint
*
* This gets called whenever an IN packet has been successfully transmitted.
*/
static void bulk_tx_cb(usbd_device * usbd_dev, uint8_t ep)
{
char buf[64] __attribute__ ((aligned(4)));
(void)ep;
/* Keep sending packets */
usbd_ep_write_packet(usbd_dev, 0x82, buf, 64);
}
/*
* Initialize the USB configuration
*
* Called after the host issues a SetConfiguration request.
*/
static void set_config(usbd_device * usbd_dev, uint16_t wValue)
{
uint8_t data[64] __attribute__ ((aligned(4)));
(void)wValue;
printf("Configuring endpoints.\n\r");
usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, 64, bulk_rx_cb);
usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, 64, bulk_tx_cb);
usbd_ep_setup(usbd_dev, 0x03, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(usbd_dev, 0x84, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(usbd_dev, 0x05, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(usbd_dev, 0x86, USB_ENDPOINT_ATTR_BULK, 64, NULL);
/* The main loop will not touch the EPs until this is set */
config_set = 1;
/*
* "Bootstrap" the callback-based endpoint
* Data will stay in the FIFO until the host reads it. Once it's sent
* our callback kicks in and writes another packet in the FIFO.
*/
usbd_ep_write_packet(bulk_dev, 0x82, data, 64);
printf("Done.\n\r");
}
/* =============================================================================
* = Clock control module
* ---------------------------------------------------------------------------*/
/*
* Setup the buttons and interrupts
*/
static void button_setup(void)
{
/*
* Configure GPIOF
* This port is used to control the RGB LED
*/
periph_clock_enable(RCC_GPIOF);
/*
* Now take care of our buttons
*/
const uint32_t btnpins = USR_SW1 | USR_SW2;
/*
* PF0 is a locked by default. We need to unlock it before we can
* re-purpose it as a GPIO pin.
*/
gpio_unlock_commit(GPIOF, USR_SW2);
/* Configure pins as inputs, with pull-up. */
gpio_mode_setup(GPIOF, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, btnpins);
/* Trigger interrupt on rising-edge (when button is depressed) */
gpio_configure_trigger(GPIOF, GPIO_TRIG_EDGE_RISE, btnpins);
/* Finally, Enable interrupt */
gpio_enable_interrupts(GPIOF, btnpins);
/* Enable the interrupt in the NVIC as well */
nvic_enable_irq(NVIC_GPIOF_IRQ);
}
/* =============================================================================
* = A main() function which does not need to do too much
* ---------------------------------------------------------------------------*/
int main(void)
{
uint8_t data[65] __attribute__ ((aligned(4)));
gpio_enable_ahb_aperture();
rcc_sysclk_config(OSCSRC_MOSC, XTAL_16M, PLL_DIV_80MHZ);
/* We use the UART for debugging */
uart_setup();
/* And the buttons for changing the system clock on-the-fly */
button_setup();
/* Mux the GPIO pins to the USB peripheral */
usb_setup();
/* Let the stack take care of the rest */
bulk_dev = usbd_init(&lm4f_usb_driver, &dev_descr, &config_descr,
usb_strings, 4,
usbd_control_buffer, sizeof(usbd_control_buffer));
usbd_register_set_config_callback(bulk_dev, set_config);
/* Enable the interrupts. */
usb_ints_setup();
/* HALT! Don't touch the EP's until we configure them */
while (!config_set) ;
/*
* For our polled endpoints, we just read and write continuously. The
* driver will only move data in or out of the FIFOs if it is safe to
* do so.
*/
while (1) {
usbd_ep_read_packet(bulk_dev, 0x03, data, 64);
usbd_ep_write_packet(bulk_dev, 0x84, data, 64);
/*
* On endpoints 5 and 6, we deliberately misalign the buffer.
* This degrades the endpoint performance.
*/
usbd_ep_read_packet(bulk_dev, 0x05, data + 1, 64);
usbd_ep_write_packet(bulk_dev, 0x86, data + 1, 64);
}
/* Never reached */
return 0;
}
/* =============================================================================
* = USB interrupt service routine. All the magic happens here
* ---------------------------------------------------------------------------*/
void usb0_isr(void)
{
usbd_poll(bulk_dev);
}
/* =============================================================================
* = GPIO interrupt service routine. Pressing a button gets us here.
* ---------------------------------------------------------------------------*/
void gpiof_isr(void)
{
uint8_t serviced_irqs = 0;
if (gpio_is_interrupt_source(GPIOF, USR_SW1)) {
/* SW1 was just depressed */
bypass = !bypass;
if (bypass) {
rcc_pll_bypass_enable();
/*
* The divisor is still applied to the raw clock.
* Disable the divisor, or we'll divide the raw clock.
*/
SYSCTL_RCC &= ~SYSCTL_RCC_USESYSDIV;
printf("Changing system clock to 16MHz MOSC\n\r");
} else {
rcc_change_pll_divisor(plldiv[ipll]);
printf("Changing system clock to %iMHz\n\r",
400 / plldiv[ipll]);
}
/* Clear interrupt source */
serviced_irqs |= USR_SW1;
}
if (gpio_is_interrupt_source(GPIOF, USR_SW2)) {
/* SW2 was just depressed */
if (!bypass) {
if (plldiv[++ipll] == 0)
ipll = 0;
printf("Changing system clock to %iMHz\n\r",
400 / plldiv[ipll]);
rcc_change_pll_divisor(plldiv[ipll]);
}
/* Clear interrupt source */
serviced_irqs |= USR_SW2;
}
gpio_clear_interrupt_flag(GPIOF, serviced_irqs);
}
/* =============================================================================
* = Debug module
* ---------------------------------------------------------------------------*/
#include <libopencm3/lm4f/uart.h>
#include <errno.h>
/*
* Initialize the UART
*/
void uart_setup(void)
{
/* Enable GPIOA in run mode. */
periph_clock_enable(RCC_GPIOA);
/* Configure PA0 and PA1 as alternate function pins */
gpio_set_af(GPIOA, 1, GPIO0 | GPIO1);
/* Enable the UART clock */
periph_clock_enable(RCC_UART0);
/* Slight delay before we can access the UART registers */
__asm__("nop");
__asm__("nop");
__asm__("nop");
/* Disable the UART while we mess with its setings */
uart_disable(UART0);
/* Configure the UART clock source */
uart_clock_from_piosc(UART0);
/* Set communication parameters */
uart_set_baudrate(UART0, 921600);
/* Set 8N1 */
uart_set_databits(UART0, 8);
uart_set_parity(UART0, UART_PARITY_NONE);
uart_set_stopbits(UART0, 1);
/* Enable FIFOs */
UART_LCRH(UART0) |= UART_LCRH_FEN;
/* Now that we're done messing with the settings, enable the UART */
uart_enable(UART0);
}
/*
* Write to the debug port
*
* This is called whenever printf is used. We write stdio to the UART.
*/
int _write(int file, char *ptr, int len)
{
int i;
if (file == 1) {
for (i = 0; i < len; i++)
uart_send_blocking(UART0, ptr[i]);
return i;
}
errno = EIO;
return -1;
}

View File

@@ -0,0 +1,27 @@
##
## 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/>.
##
BINARY = usb_to_serial_cdcacm
LDSCRIPT = ../ek-lm4f120xl.ld
OBJS += uart.o usb_cdcacm.o
include ../../Makefile.include

View File

@@ -0,0 +1,68 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example demonstrates the following:
* Using the USB controller
* Setting up a simple usb to serial converter (CDCACM)
File list:
* usb_cdcacm.c - implementation of the CDCACM subclass
* uart.c - implementation of UART peripheral
* usb_to_serial_cdcacm.c - glue logic between UART and CDCACM device
* usb_to_serial_cdcacm.h - common definitions
Implements a USB-to-serial adapter, compliant to the CDCACM subclass. UART1 is
used for the TX/RX lines. Although UART1 also has lines for flow control, they
are not used. Instead, the control lines are implemented in software via GPIOA.
The following pinout is used:
Tx <- PB1
Rx -> PB0
DCD -> PA2
DSR -> PA3
RI -> PA4
CTS -> PA5 (UNUSED)
DTR <- PA6
RTS <- PA7
Note that the CTS pin is unused. The CDCACM specification does not define a way
to control this pin, nor does it define a way to switch between flow control
mechanisms.
The glue logic in usb_to_serial_cdcacm.c receives requests from both the UART
and CDCACM interface, and forward them to their destination, while also
controlling the LEDs
The green LED is lit as long as either DTR or RTS are high.
The red LED is lit while the UART is sending data.
The blue LED is lit while data is read from the UART.
The red and blue LEDs will only be lit for very short periods of time, thus they
may be difficult to notice.
------------------------------------------------------------------------------
Windows Quirks
------------------------------------------------------------------------------
On openening the CDCACM port Windows send a SET_LINE_CODING request with the
desired baud rate but without valid databits. To run this example CDDACM device
under Windows you have to return always 1 when a SET_LINE_CODING request is
received. The following code should work:
File: usb_cdcacm.c
Function: cdcacm_control_request()
case USB_CDC_REQ_SET_LINE_CODING:{
struct usb_cdc_line_coding *coding;
if (*len < sizeof(struct usb_cdc_line_coding))
{
return 0;
}
coding = (struct usb_cdc_line_coding *)*buf;
glue_set_line_coding_cb(coding->dwDTERate,
coding->bDataBits,
coding->bParityType,
coding->bCharFormat);
return 1;

View File

@@ -0,0 +1,99 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012-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/>.
*/
/**
* \addtogroup Examples
*
*/
/*
* Pins handled by hw peripheral:
* Tx <-> PB1
* Rx <-> PB0
* Input pins handled manually via interrupts:
* DCD <-> PA2
* DSR <-> PA3
* RI <-> PA4
* CTS <-> PA5 (UNUSED)
* Output pins handled via commands from the host:
* DTR <-> PA6
* RTS <-> PA7
*/
#include "usb_to_serial_cdcacm.h"
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/lm4f/uart.h>
#include <libopencm3/lm4f/nvic.h>
static void uart_ctl_line_setup(void)
{
uint32_t inpins, outpins;
inpins = PIN_DCD | PIN_DSR | PIN_RI | PIN_CTS;
outpins = PIN_DTR | PIN_RTS;
gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, outpins);
gpio_mode_setup(GPIOA, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, inpins);
}
void uart_init(void)
{
/* Enable GPIOA and GPIOB in run mode. */
periph_clock_enable(RCC_GPIOB);
periph_clock_enable(RCC_GPIOA);
uart_ctl_line_setup();
/* Mux PB0 and PB1 to AF1 (UART1 in this case) */
gpio_set_af(GPIOB, 1, GPIO0 | GPIO1);
/* Enable the UART clock */
periph_clock_enable(RCC_UART1);
/* Disable the UART while we mess with its setings */
uart_disable(UART1);
/* Configure the UART clock source */
uart_clock_from_piosc(UART1);
/* We don't make any other settings here. */
uart_enable(UART1);
/* Ping us when something comes in */
uart_enable_rx_interrupt(UART1);
nvic_enable_irq(NVIC_UART1_IRQ);
}
uint8_t uart_get_ctl_line_state(void)
{
return gpio_read(GPIOA, PIN_RI | PIN_DSR | PIN_DCD);
}
void uart_set_ctl_line_state(uint8_t dtr, uint8_t rts)
{
uint8_t val = 0;
val |= dtr ? PIN_DTR : 0;
val |= rts ? PIN_RTS : 0;
gpio_write(GPIOA, PIN_DTR | PIN_RTS, val);
}
void uart1_isr(void)
{
uint8_t rx;
rx = uart_recv(UART1);
glue_data_received_cb(&rx, 1);
uart_clear_interrupt_flag(UART1, UART_INT_RX);
}

View File

@@ -0,0 +1,303 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 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/>.
*/
#include "usb_to_serial_cdcacm.h"
#include <stdlib.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/cdc.h>
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/cm3/scb.h>
#include <libopencm3/lm4f/nvic.h>
#include <libopencm3/lm4f/usb.h>
static const struct usb_device_descriptor dev = {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x2000,
.bDeviceClass = USB_CLASS_CDC,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = 64,
.idVendor = 0xc03e,
.idProduct = 0xb007,
.bcdDevice = 0x2000,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
};
/*
* This notification endpoint isn't implemented. According to CDC spec it's
* optional, but its absence causes a NULL pointer dereference in the
* Linux cdc_acm driver.
*/
static const struct usb_endpoint_descriptor comm_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x83,
.bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
.wMaxPacketSize = 16,
.bInterval = 1,
}};
static const struct usb_endpoint_descriptor data_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x01,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x82,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}};
static const struct {
struct usb_cdc_header_descriptor header;
struct usb_cdc_call_management_descriptor call_mgmt;
struct usb_cdc_acm_descriptor acm;
struct usb_cdc_union_descriptor cdc_union;
} __attribute__ ((packed)) cdcacm_functional_descriptors = {
.header = {
.bFunctionLength = sizeof(struct usb_cdc_header_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_HEADER,
.bcdCDC = 0x0110,
},
.call_mgmt = {
.bFunctionLength =
sizeof(struct usb_cdc_call_management_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
.bmCapabilities = 0,
.bDataInterface = 1,
},
.acm = {
.bFunctionLength = sizeof(struct usb_cdc_acm_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_ACM,
.bmCapabilities = (1 << 1),
},
.cdc_union = {
.bFunctionLength = sizeof(struct usb_cdc_union_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_UNION,
.bControlInterface = 0,
.bSubordinateInterface0 = 1,
}
};
static const struct usb_interface_descriptor comm_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_CDC,
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
.bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
.iInterface = 0,
.endpoint = comm_endp,
.extra = &cdcacm_functional_descriptors,
.extralen = sizeof(cdcacm_functional_descriptors)
}};
static const struct usb_interface_descriptor data_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 1,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
.endpoint = data_endp,
}};
static const struct usb_interface ifaces[] = {{
.num_altsetting = 1,
.altsetting = comm_iface,
}, {
.num_altsetting = 1,
.altsetting = data_iface,
}};
static const struct usb_config_descriptor config = {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
.bNumInterfaces = 2,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0x80,
.bMaxPower = 0x32,
.interface = ifaces,
};
static const char *usb_strings[] = {
"libopencm3",
"usb_to_serial_cdcacm",
"none",
"DEMO",
};
usbd_device *acm_dev;
uint8_t usbd_control_buffer[128];
extern usbd_driver lm4f_usb_driver;
static int cdcacm_control_request(usbd_device * usbd_dev,
struct usb_setup_data *req, uint8_t ** buf,
uint16_t * len,
void (**complete) (usbd_device * usbd_dev,
struct usb_setup_data *
req))
{
uint8_t dtr, rts;
(void)complete;
(void)buf;
(void)usbd_dev;
switch (req->bRequest) {
case USB_CDC_REQ_SET_CONTROL_LINE_STATE:{
/*
* This Linux cdc_acm driver requires this to be implemented
* even though it's optional in the CDC spec, and we don't
* advertise it in the ACM functional descriptor.
*/
dtr = (req->wValue & (1 << 0)) ? 1 : 0;
rts = (req->wValue & (1 << 1)) ? 1 : 0;
glue_set_line_state_cb(dtr, rts);
return 1;
}
case USB_CDC_REQ_SET_LINE_CODING:{
struct usb_cdc_line_coding *coding;
if (*len < sizeof(struct usb_cdc_line_coding))
return 0;
coding = (struct usb_cdc_line_coding *)*buf;
return glue_set_line_coding_cb(coding->dwDTERate,
coding->bDataBits,
coding->bParityType,
coding->bCharFormat);
}
}
return 0;
}
static void cdcacm_data_rx_cb(usbd_device * usbd_dev, uint8_t ep)
{
uint8_t buf[64];
(void)ep;
int len = usbd_ep_read_packet(usbd_dev, 0x01, buf, 64);
glue_send_data_cb(buf, len);
}
void cdcacm_send_data(uint8_t * buf, uint16_t len)
{
usbd_ep_write_packet(acm_dev, 0x82, buf, len);
}
static void cdcacm_set_config(usbd_device * usbd_dev, uint16_t wValue)
{
(void)wValue;
usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, 64,
cdcacm_data_rx_cb);
usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
usbd_register_control_callback(usbd_dev,
USB_REQ_TYPE_CLASS |
USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE |
USB_REQ_TYPE_RECIPIENT,
cdcacm_control_request);
}
void cdcacm_line_state_changed_cb(uint8_t linemask)
{
const int size = sizeof(struct usb_cdc_notification) + 2;
uint8_t buf[size];
struct usb_cdc_notification *notify = (void *)buf;
notify->bmRequestType = 0xa1;
notify->bNotification = USB_CDC_NOTIFY_SERIAL_STATE;
notify->wValue = 0;
notify->wIndex = 1;
notify->wLength = 2;
uint16_t *data = (void *)&buf[sizeof(struct usb_cdc_notification)];
*data = linemask;
while (usbd_ep_write_packet(acm_dev, 0x83, buf, size) == size) ;
}
static void usb_pins_setup(void)
{
/* USB pins are connected to port D */
periph_clock_enable(RCC_GPIOD);
/* Mux USB pins to their analog function */
gpio_mode_setup(GPIOD, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, GPIO4 | GPIO5);
}
static void usb_ints_setup(void)
{
uint8_t usbints;
/* Gimme some interrupts */
usbints = USB_INT_RESET | USB_INT_DISCON | USB_INT_RESUME | USB_INT_SUSPEND; //| USB_IM_SOF;
usb_enable_interrupts(usbints, 0xff, 0xff);
nvic_enable_irq(NVIC_USB0_IRQ);
}
void cdcacm_init(void)
{
usbd_device *usbd_dev;
usb_pins_setup();
usbd_dev = usbd_init(&lm4f_usb_driver, &dev, &config, usb_strings, 4,
usbd_control_buffer, sizeof(usbd_control_buffer));
acm_dev = usbd_dev;
usbd_register_set_config_callback(usbd_dev, cdcacm_set_config);
usb_ints_setup();
}
void usb0_isr(void)
{
usbd_poll(acm_dev);
}

View File

@@ -0,0 +1,206 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
* Copyright (C) 2012-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/>.
*/
/**
* \addtogroup Examples
*
* Flashes the Red, Green and Blue diodes on the board, in order.
*
* RED controlled by PF1
* Green controlled by PF3
* Blue controlled by PF2
*/
#include "usb_to_serial_cdcacm.h"
#include <libopencm3/lm4f/systemcontrol.h>
#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/lm4f/uart.h>
#include <libopencm3/lm4f/nvic.h>
#include <libopencm3/cm3/scb.h>
#define PLL_DIV_80MHZ 5
/* This is how the RGB LED is connected on the stellaris launchpad */
#define RGB_PORT GPIOF
enum {
LED_R = GPIO1,
LED_G = GPIO3,
LED_B = GPIO2,
};
/*
* Clock setup:
* Take the main crystal oscillator at 16MHz, run it through the PLL, and divide
* the 400MHz PLL clock to get a system clock of 80MHz.
*/
static void clock_setup(void)
{
rcc_sysclk_config(OSCSRC_MOSC, XTAL_16M, PLL_DIV_80MHZ);
}
/*
* GPIO setup:
* Enable the pins driving the RGB LED as outputs.
*/
static void gpio_setup(void)
{
/*
* Configure GPIOF
* This port is used to control the RGB LED
*/
periph_clock_enable(RCC_GPIOF);
const uint32_t opins = (LED_R | LED_G | LED_B);
gpio_mode_setup(RGB_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, opins);
gpio_set_output_config(RGB_PORT, GPIO_OTYPE_PP, GPIO_DRIVE_2MA, opins);
}
static void cm4f_enable_fpu(void)
{
/* Enable FPU */
SCB_CPACR |= SCB_CPACR_FULL * (SCB_CPACR_CP10 | SCB_CPACR_CP11);
/* Wait for store to complete */
__asm__("DSB");
/* Reset pipeline. Now the FPU is enabled */
__asm__("ISB");
}
void glue_data_received_cb(uint8_t * buf, uint16_t len)
{
/* Blue LED indicates data coming in */
gpio_set(RGB_PORT, LED_B);
cdcacm_send_data(buf, len);
gpio_clear(RGB_PORT, LED_B);
}
void glue_set_line_state_cb(uint8_t dtr, uint8_t rts)
{
/* Green LED indicated one of the control lines are active */
if (dtr || rts)
gpio_set(RGB_PORT, LED_G);
else
gpio_clear(RGB_PORT, LED_G);
uart_set_ctl_line_state(dtr, rts);
}
int glue_set_line_coding_cb(uint32_t baud, uint8_t databits,
enum usb_cdc_line_coding_bParityType cdc_parity,
enum usb_cdc_line_coding_bCharFormat cdc_stopbits)
{
enum uart_parity parity;
uint8_t uart_stopbits;
if (databits < 5 || databits > 8)
return 0;
switch (cdc_parity) {
case USB_CDC_NO_PARITY:
parity = UART_PARITY_NONE;
break;
case USB_CDC_ODD_PARITY:
parity = UART_PARITY_ODD;
break;
case USB_CDC_EVEN_PARITY:
parity = UART_PARITY_EVEN;
break;
default:
return 0;
}
switch (cdc_stopbits) {
case USB_CDC_1_STOP_BITS:
uart_stopbits = 1;
break;
case USB_CDC_2_STOP_BITS:
uart_stopbits = 2;
break;
default:
return 0;
}
/* Disable the UART while we mess with its settings */
uart_disable(UART1);
/* Set communication parameters */
uart_set_baudrate(UART1, baud);
uart_set_databits(UART1, databits);
uart_set_parity(UART1, parity);
uart_set_stopbits(UART1, uart_stopbits);
/* Back to work. */
uart_enable(UART1);
return 1;
}
void glue_send_data_cb(uint8_t * buf, uint16_t len)
{
int i;
/* Red LED indicates data going out */
gpio_set(RGB_PORT, LED_R);
for (i = 0; i < len; i++) {
uart_send_blocking(UART1, buf[i]);
}
gpio_clear(RGB_PORT, LED_R);
}
static void mainloop(void)
{
uint8_t linestate, cdcacmstate;
static uint8_t oldlinestate = 0;
/* See if the state of control lines has changed */
linestate = uart_get_ctl_line_state();
if (oldlinestate != linestate) {
/* Inform host of state change */
cdcacmstate = 0;
if (linestate & PIN_RI)
cdcacmstate |= CDCACM_RI;
if (linestate & PIN_DSR)
cdcacmstate |= CDCACM_DSR;
if (linestate & PIN_DCD)
cdcacmstate |= CDCACM_DCD;
cdcacm_line_state_changed_cb(cdcacmstate);
}
oldlinestate = linestate;
}
int main(void)
{
gpio_enable_ahb_aperture();
clock_setup();
gpio_setup();
cdcacm_init();
uart_init();
cm4f_enable_fpu();
while (1)
mainloop();
return 0;
}

View File

@@ -0,0 +1,69 @@
/*
* 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/>.
*/
/**@{*/
#ifndef __STELLARIS_EK_LM4F120XL_USB_TO_SERIAL_CDCACM_H
#define __STELLARIS_EK_LM4F120XL_USB_TO_SERIAL_CDCACM_H
#include <libopencm3/cm3/common.h>
#include <libopencm3/lm4f/gpio.h>
#include <libopencm3/usb/cdc.h>
/* =============================================================================
* UART control
* ---------------------------------------------------------------------------*/
enum rs232pin {
PIN_DCD = GPIO2,
PIN_DSR = GPIO3,
PIN_RI = GPIO4,
PIN_CTS = GPIO5,
PIN_DTR = GPIO6,
PIN_RTS = GPIO7,
};
void uart_init(void);
uint8_t uart_get_ctl_line_state(void);
void uart_set_ctl_line_state(uint8_t dtr, uint8_t rts);
/* =============================================================================
* CDCACM control
* ---------------------------------------------------------------------------*/
enum cdc_serial_state_line {
CDCACM_DCD = (1 << 0),
CDCACM_DSR = (1 << 1),
CDCACM_RI = (1 << 3),
};
void cdcacm_init(void);
void cdcacm_line_state_changed_cb(uint8_t linemask);
void cdcacm_send_data(uint8_t *buf, uint16_t len);
/* =============================================================================
* CDCACM <-> UART glue
* ---------------------------------------------------------------------------*/
void glue_data_received_cb(uint8_t *buf, uint16_t len);
void glue_set_line_state_cb(uint8_t dtr, uint8_t rts);
int glue_set_line_coding_cb(uint32_t baud, uint8_t databits,
enum usb_cdc_line_coding_bParityType cdc_parity,
enum usb_cdc_line_coding_bCharFormat cdc_stopbits);
void glue_send_data_cb(uint8_t *buf, uint16_t len);
#endif /* __STELLARIS_EK_LM4F120XL_USB_TO_SERIAL_CDCACM_H */
/**@}*/