ChibiOS 2.6.8, until I can figure out where to get it from git.

This commit is contained in:
Jared Boone
2015-07-08 08:40:23 -07:00
parent dc6fee8370
commit e1eea8e08a
1929 changed files with 575326 additions and 0 deletions

View File

@@ -0,0 +1,248 @@
/*
ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/**
* @file stm32_usb.h
* @brief STM32 USB registers layout header.
* @note This file requires definitions from the ST STM32 header files
* stm32f10x.h or stm32l1xx.h.
*
* @addtogroup USB
* @{
*/
#ifndef _STM32_USB_H_
#define _STM32_USB_H_
/**
* @brief Number of the available endpoints.
* @details This value does not include the endpoint 0 which is always present.
*/
#define USB_ENDOPOINTS_NUMBER 7
/**
* @brief USB registers block.
*/
typedef struct {
/**
* @brief Endpoint registers.
*/
volatile uint32_t EPR[USB_ENDOPOINTS_NUMBER + 1];
/*
* @brief Reserved space.
*/
volatile uint32_t _r20[8];
/*
* @brief Control Register.
*/
volatile uint32_t CNTR;
/*
* @brief Interrupt Status Register.
*/
volatile uint32_t ISTR;
/*
* @brief Frame Number Register.
*/
volatile uint32_t FNR;
/*
* @brief Device Address Register.
*/
volatile uint32_t DADDR;
/*
* @brief Buffer Table Address.
*/
volatile uint32_t BTABLE;
} stm32_usb_t;
/**
* @brief USB descriptor registers block.
*/
typedef struct {
/**
* @brief TX buffer offset register.
*/
volatile uint32_t TXADDR0;
/**
* @brief TX counter register 0.
*/
volatile uint16_t TXCOUNT0;
/**
* @brief TX counter register 1.
*/
volatile uint16_t TXCOUNT1;
/**
* @brief RX buffer offset register.
*/
volatile uint32_t RXADDR0;
/**
* @brief RX counter register 0.
*/
volatile uint16_t RXCOUNT0;
/**
* @brief RX counter register 1.
*/
volatile uint16_t RXCOUNT1;
} stm32_usb_descriptor_t;
/**
* @name Register aliases
* @{
*/
#define RXADDR1 TXADDR0
#define TXADDR1 RXADDR0
/** @} */
/**
* @brief USB registers block numeric address.
*/
#define STM32_USB_BASE (APB1PERIPH_BASE + 0x5C00)
/**
* @brief USB RAM numeric address.
*/
#define STM32_USBRAM_BASE (APB1PERIPH_BASE + 0x6000)
/**
* @brief Pointer to the USB registers block.
*/
#define STM32_USB ((stm32_usb_t *)STM32_USB_BASE)
/**
* @brief Pointer to the USB RAM.
*/
#define STM32_USBRAM ((uint32_t *)STM32_USBRAM_BASE)
/**
* @brief Size of the dedicated packet memory.
*/
#define USB_PMA_SIZE 512
/**
* @brief Mask of all the toggling bits in the EPR register.
*/
#define EPR_TOGGLE_MASK (EPR_STAT_TX_MASK | EPR_DTOG_TX | \
EPR_STAT_RX_MASK | EPR_DTOG_RX | \
EPR_SETUP)
#define EPR_EA_MASK 0x000F
#define EPR_STAT_TX_MASK 0x0030
#define EPR_STAT_TX_DIS 0x0000
#define EPR_STAT_TX_STALL 0x0010
#define EPR_STAT_TX_NAK 0x0020
#define EPR_STAT_TX_VALID 0x0030
#define EPR_DTOG_TX 0x0040
#define EPR_SWBUF_RX EPR_DTOG_TX
#define EPR_CTR_TX 0x0080
#define EPR_EP_KIND 0x0100
#define EPR_EP_DBL_BUF EPR_EP_KIND
#define EPR_EP_STATUS_OUT EPR_EP_KIND
#define EPR_EP_TYPE_MASK 0x0600
#define EPR_EP_TYPE_BULK 0x0000
#define EPR_EP_TYPE_CONTROL 0x0200
#define EPR_EP_TYPE_ISO 0x0400
#define EPR_EP_TYPE_INTERRUPT 0x0600
#define EPR_SETUP 0x0800
#define EPR_STAT_RX_MASK 0x3000
#define EPR_STAT_RX_DIS 0x0000
#define EPR_STAT_RX_STALL 0x1000
#define EPR_STAT_RX_NAK 0x2000
#define EPR_STAT_RX_VALID 0x3000
#define EPR_DTOG_RX 0x4000
#define EPR_SWBUF_TX EPR_DTOG_RX
#define EPR_CTR_RX 0x8000
#define CNTR_FRES 0x0001
#define CNTR_PDWN 0x0002
#define CNTR_LP_MODE 0x0004
#define CNTR_FSUSP 0x0008
#define CNTR_RESUME 0x0010
#define CNTR_ESOFM 0x0100
#define CNTR_SOFM 0x0200
#define CNTR_RESETM 0x0400
#define CNTR_SUSPM 0x0800
#define CNTR_WKUPM 0x1000
#define CNTR_ERRM 0x2000
#define CNTR_PMAOVRM 0x4000
#define CNTR_CTRM 0x8000
#define ISTR_EP_ID_MASK 0x000F
#define ISTR_DIR 0x0010
#define ISTR_ESOF 0x0100
#define ISTR_SOF 0x0200
#define ISTR_RESET 0x0400
#define ISTR_SUSP 0x0800
#define ISTR_WKUP 0x1000
#define ISTR_ERR 0x2000
#define ISTR_PMAOVR 0x4000
#define ISTR_CTR 0x8000
#define FNR_FN_MASK 0x07FF
#define FNR_LSOF 0x1800
#define FNR_LCK 0x2000
#define FNR_RXDM 0x4000
#define FNR_RXDP 0x8000
#define DADDR_ADD_MASK 0x007F
#define DADDR_EF 0x0080
#define RXCOUNT_COUNT_MASK 0x03FF
#define TXCOUNT_COUNT_MASK 0x03FF
#define EPR_CTR_MASK (EPR_CTR_TX | EPR_CTR_RX)
#define EPR_SET(ep, epr) \
STM32_USB->EPR[ep] = ((epr) & ~EPR_TOGGLE_MASK) | EPR_CTR_MASK
#define EPR_TOGGLE(ep, epr) \
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] ^ ((epr) & EPR_TOGGLE_MASK)) \
| EPR_CTR_MASK
#define EPR_SET_STAT_RX(ep, epr) \
STM32_USB->EPR[ep] = ((STM32_USB->EPR[ep] & \
~(EPR_TOGGLE_MASK & ~EPR_STAT_RX_MASK)) ^ \
(epr)) | EPR_CTR_MASK
#define EPR_SET_STAT_TX(ep, epr) \
STM32_USB->EPR[ep] = ((STM32_USB->EPR[ep] & \
~(EPR_TOGGLE_MASK & ~EPR_STAT_TX_MASK)) ^ \
(epr)) | EPR_CTR_MASK
#define EPR_CLEAR_CTR_RX(ep) \
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] & ~EPR_CTR_RX & ~EPR_TOGGLE_MASK)\
| EPR_CTR_TX
#define EPR_CLEAR_CTR_TX(ep) \
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] & ~EPR_CTR_TX & ~EPR_TOGGLE_MASK)\
| EPR_CTR_RX
/**
* @brief Returns an endpoint descriptor pointer.
*/
#define USB_GET_DESCRIPTOR(ep) \
((stm32_usb_descriptor_t *)((uint32_t)STM32_USBRAM_BASE + \
(uint32_t)STM32_USB->BTABLE * 2 + \
(uint32_t)(ep) * \
sizeof(stm32_usb_descriptor_t)))
/**
* @brief Converts from a PMA address to a physical address.
*/
#define USB_ADDR2PTR(addr) \
((uint32_t *)((addr) * 2 + STM32_USBRAM_BASE))
#endif /* _STM32_USB_H_ */
/** @} */

View File

@@ -0,0 +1,830 @@
/*
ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/**
* @file STM32/USBv1/usb_lld.c
* @brief STM32 USB subsystem low level driver source.
*
* @addtogroup USB
* @{
*/
#include <string.h>
#include "ch.h"
#include "hal.h"
#if HAL_USE_USB || defined(__DOXYGEN__)
/*===========================================================================*/
/* Driver local definitions. */
/*===========================================================================*/
#define BTABLE_ADDR 0x0000
/*===========================================================================*/
/* Driver exported variables. */
/*===========================================================================*/
/** @brief USB1 driver identifier.*/
#if STM32_USB_USE_USB1 || defined(__DOXYGEN__)
USBDriver USBD1;
#endif
/*===========================================================================*/
/* Driver local variables and types. */
/*===========================================================================*/
/**
* @brief EP0 state.
* @note It is an union because IN and OUT endpoints are never used at the
* same time for EP0.
*/
static union {
/**
* @brief IN EP0 state.
*/
USBInEndpointState in;
/**
* @brief OUT EP0 state.
*/
USBOutEndpointState out;
} ep0_state;
/**
* @brief Buffer for the EP0 setup packets.
*/
static uint8_t ep0setup_buffer[8];
/**
* @brief EP0 initialization structure.
*/
static const USBEndpointConfig ep0config = {
USB_EP_MODE_TYPE_CTRL,
_usb_ep0setup,
_usb_ep0in,
_usb_ep0out,
0x40,
0x40,
&ep0_state.in,
&ep0_state.out,
1,
ep0setup_buffer
};
/*===========================================================================*/
/* Driver local functions. */
/*===========================================================================*/
/**
* @brief Resets the packet memory allocator.
*
* @param[in] usbp pointer to the @p USBDriver object
*/
static void usb_pm_reset(USBDriver *usbp) {
/* The first 64 bytes are reserved for the descriptors table. The effective
available RAM for endpoint buffers is just 448 bytes.*/
usbp->pmnext = 64;
}
/**
* @brief Resets the packet memory allocator.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] size size of the packet buffer to allocate
*/
static uint32_t usb_pm_alloc(USBDriver *usbp, size_t size) {
uint32_t next;
next = usbp->pmnext;
usbp->pmnext += size;
chDbgAssert(usbp->pmnext <= USB_PMA_SIZE, "usb_pm_alloc(), #1", "PMA overflow");
return next;
}
/**
* @brief Reads from a dedicated packet buffer.
*
* @param[in] udp pointer to a @p stm32_usb_descriptor_t
* @param[out] buf buffer where to copy the packet data
* @param[in] n maximum number of bytes to copy. This value must
* not exceed the maximum packet size for this endpoint.
*
* @notapi
*/
static void usb_packet_read_to_buffer(stm32_usb_descriptor_t *udp,
uint8_t *buf, size_t n) {
uint32_t *pmap= USB_ADDR2PTR(udp->RXADDR0);
n = (n + 1) / 2;
while (n > 0) {
/* Note, this line relies on the Cortex-M3/M4 ability to perform
unaligned word accesses.*/
*(uint16_t *)buf = (uint16_t)*pmap++;
buf += 2;
n--;
}
}
/**
* @brief Reads from a dedicated packet buffer.
*
* @param[in] udp pointer to a @p stm32_usb_descriptor_t
* @param[in] iqp pointer to an @p InputQueue object
* @param[in] n maximum number of bytes to copy. This value must
* not exceed the maximum packet size for this endpoint.
*
* @notapi
*/
static void usb_packet_read_to_queue(stm32_usb_descriptor_t *udp,
InputQueue *iqp, size_t n) {
size_t nhw;
uint32_t *pmap= USB_ADDR2PTR(udp->RXADDR0);
nhw = n / 2;
while (nhw > 0) {
uint32_t w;
w = *pmap++;
*iqp->q_wrptr++ = (uint8_t)w;
if (iqp->q_wrptr >= iqp->q_top)
iqp->q_wrptr = iqp->q_buffer;
*iqp->q_wrptr++ = (uint8_t)(w >> 8);
if (iqp->q_wrptr >= iqp->q_top)
iqp->q_wrptr = iqp->q_buffer;
nhw--;
}
/* Last byte for odd numbers.*/
if ((n & 1) != 0) {
*iqp->q_wrptr++ = (uint8_t)*pmap;
if (iqp->q_wrptr >= iqp->q_top)
iqp->q_wrptr = iqp->q_buffer;
}
/* Updating queue.*/
chSysLockFromIsr();
iqp->q_counter += n;
while (notempty(&iqp->q_waiting))
chSchReadyI(fifo_remove(&iqp->q_waiting))->p_u.rdymsg = Q_OK;
chSysUnlockFromIsr();
}
/**
* @brief Writes to a dedicated packet buffer.
*
* @param[in] udp pointer to a @p stm32_usb_descriptor_t
* @param[in] buf buffer where to fetch the packet data
* @param[in] n maximum number of bytes to copy. This value must
* not exceed the maximum packet size for this endpoint.
*
* @notapi
*/
static void usb_packet_write_from_buffer(stm32_usb_descriptor_t *udp,
const uint8_t *buf,
size_t n) {
uint32_t *pmap = USB_ADDR2PTR(udp->TXADDR0);
udp->TXCOUNT0 = (uint16_t)n;
n = (n + 1) / 2;
while (n > 0) {
/* Note, this line relies on the Cortex-M3/M4 ability to perform
unaligned word accesses.*/
*pmap++ = *(uint16_t *)buf;
buf += 2;
n--;
}
}
/**
* @brief Writes to a dedicated packet buffer.
*
* @param[in] udp pointer to a @p stm32_usb_descriptor_t
* @param[in] buf buffer where to fetch the packet data
* @param[in] n maximum number of bytes to copy. This value must
* not exceed the maximum packet size for this endpoint.
*
* @notapi
*/
static void usb_packet_write_from_queue(stm32_usb_descriptor_t *udp,
OutputQueue *oqp, size_t n) {
size_t nhw;
uint32_t *pmap = USB_ADDR2PTR(udp->TXADDR0);
udp->TXCOUNT0 = (uint16_t)n;
nhw = n / 2;
while (nhw > 0) {
uint32_t w;
w = (uint32_t)*oqp->q_rdptr++;
if (oqp->q_rdptr >= oqp->q_top)
oqp->q_rdptr = oqp->q_buffer;
w |= (uint32_t)*oqp->q_rdptr++ << 8;
if (oqp->q_rdptr >= oqp->q_top)
oqp->q_rdptr = oqp->q_buffer;
*pmap++ = w;
nhw--;
}
/* Last byte for odd numbers.*/
if ((n & 1) != 0) {
*pmap = (uint32_t)*oqp->q_rdptr++;
if (oqp->q_rdptr >= oqp->q_top)
oqp->q_rdptr = oqp->q_buffer;
}
/* Updating queue. Note, the lock is done in this unusual way because this
function can be called from both ISR and thread context so the kind
of lock function to be invoked cannot be decided beforehand.*/
port_lock();
dbg_enter_lock();
oqp->q_counter += n;
while (notempty(&oqp->q_waiting))
chSchReadyI(fifo_remove(&oqp->q_waiting))->p_u.rdymsg = Q_OK;
dbg_leave_lock();
port_unlock();
}
/*===========================================================================*/
/* Driver interrupt handlers. */
/*===========================================================================*/
#if STM32_USB_USE_USB1 || defined(__DOXYGEN__)
#if !defined(STM32_USB1_HP_HANDLER)
#error "STM32_USB1_HP_HANDLER not defined"
#endif
/**
* @brief USB high priority interrupt handler.
*
* @isr
*/
CH_IRQ_HANDLER(STM32_USB1_HP_HANDLER) {
CH_IRQ_PROLOGUE();
CH_IRQ_EPILOGUE();
}
#if !defined(STM32_USB1_LP_HANDLER)
#error "STM32_USB1_LP_HANDLER not defined"
#endif
/**
* @brief USB low priority interrupt handler.
*
* @isr
*/
CH_IRQ_HANDLER(STM32_USB1_LP_HANDLER) {
uint32_t istr;
USBDriver *usbp = &USBD1;
CH_IRQ_PROLOGUE();
istr = STM32_USB->ISTR;
/* USB bus reset condition handling.*/
if (istr & ISTR_RESET) {
_usb_reset(usbp);
_usb_isr_invoke_event_cb(usbp, USB_EVENT_RESET);
STM32_USB->ISTR = ~ISTR_RESET;
}
/* USB bus SUSPEND condition handling.*/
if (istr & ISTR_SUSP) {
STM32_USB->CNTR |= CNTR_FSUSP;
_usb_isr_invoke_event_cb(usbp, USB_EVENT_SUSPEND);
#if STM32_USB_LOW_POWER_ON_SUSPEND
STM32_USB->CNTR |= CNTR_LP_MODE;
#endif
STM32_USB->ISTR = ~ISTR_SUSP;
}
/* USB bus WAKEUP condition handling.*/
if (istr & ISTR_WKUP) {
uint32_t fnr = STM32_USB->FNR;
if (!(fnr & FNR_RXDP)) {
STM32_USB->CNTR &= ~CNTR_FSUSP;
_usb_isr_invoke_event_cb(usbp, USB_EVENT_WAKEUP);
}
#if STM32_USB_LOW_POWER_ON_SUSPEND
else {
/* Just noise, going back in SUSPEND mode, reference manual 22.4.5,
table 169.*/
STM32_USB->CNTR |= CNTR_LP_MODE;
}
#endif
STM32_USB->ISTR = ~ISTR_WKUP;
}
/* SOF handling.*/
if (istr & ISTR_SOF) {
_usb_isr_invoke_sof_cb(usbp);
STM32_USB->ISTR = ~ISTR_SOF;
}
/* Endpoint events handling.*/
while (istr & ISTR_CTR) {
size_t n;
uint32_t ep;
uint32_t epr = STM32_USB->EPR[ep = istr & ISTR_EP_ID_MASK];
const USBEndpointConfig *epcp = usbp->epc[ep];
if (epr & EPR_CTR_TX) {
size_t transmitted;
/* IN endpoint, transmission.*/
EPR_CLEAR_CTR_TX(ep);
transmitted = (size_t)USB_GET_DESCRIPTOR(ep)->TXCOUNT0;
epcp->in_state->txcnt += transmitted;
n = epcp->in_state->txsize - epcp->in_state->txcnt;
if (n > 0) {
/* Transfer not completed, there are more packets to send.*/
if (n > epcp->in_maxsize)
n = epcp->in_maxsize;
if (epcp->in_state->txqueued)
usb_packet_write_from_queue(USB_GET_DESCRIPTOR(ep),
epcp->in_state->mode.queue.txqueue,
n);
else {
epcp->in_state->mode.linear.txbuf += transmitted;
usb_packet_write_from_buffer(USB_GET_DESCRIPTOR(ep),
epcp->in_state->mode.linear.txbuf,
n);
}
chSysLockFromIsr();
usb_lld_start_in(usbp, ep);
chSysUnlockFromIsr();
}
else {
/* Transfer completed, invokes the callback.*/
_usb_isr_invoke_in_cb(usbp, ep);
}
}
if (epr & EPR_CTR_RX) {
EPR_CLEAR_CTR_RX(ep);
/* OUT endpoint, receive.*/
if (epr & EPR_SETUP) {
/* Setup packets handling, setup packets are handled using a
specific callback.*/
_usb_isr_invoke_setup_cb(usbp, ep);
}
else {
stm32_usb_descriptor_t *udp = USB_GET_DESCRIPTOR(ep);
n = (size_t)udp->RXCOUNT0 & RXCOUNT_COUNT_MASK;
/* Reads the packet into the defined buffer.*/
if (epcp->out_state->rxqueued)
usb_packet_read_to_queue(udp,
epcp->out_state->mode.queue.rxqueue,
n);
else {
usb_packet_read_to_buffer(udp,
epcp->out_state->mode.linear.rxbuf,
n);
epcp->out_state->mode.linear.rxbuf += n;
}
/* Transaction data updated.*/
epcp->out_state->rxcnt += n;
epcp->out_state->rxsize -= n;
epcp->out_state->rxpkts -= 1;
/* The transaction is completed if the specified number of packets
has been received or the current packet is a short packet.*/
if ((n < epcp->out_maxsize) || (epcp->out_state->rxpkts == 0)) {
/* Transfer complete, invokes the callback.*/
_usb_isr_invoke_out_cb(usbp, ep);
}
else {
/* Transfer not complete, there are more packets to receive.*/
EPR_SET_STAT_RX(ep, EPR_STAT_RX_VALID);
}
}
}
istr = STM32_USB->ISTR;
}
CH_IRQ_EPILOGUE();
}
#endif
/*===========================================================================*/
/* Driver exported functions. */
/*===========================================================================*/
/**
* @brief Low level USB driver initialization.
*
* @notapi
*/
void usb_lld_init(void) {
/* Driver initialization.*/
usbObjectInit(&USBD1);
}
/**
* @brief Configures and activates the USB peripheral.
*
* @param[in] usbp pointer to the @p USBDriver object
*
* @notapi
*/
void usb_lld_start(USBDriver *usbp) {
if (usbp->state == USB_STOP) {
/* Clock activation.*/
#if STM32_USB_USE_USB1
if (&USBD1 == usbp) {
/* USB clock enabled.*/
rccEnableUSB(FALSE);
/* Powers up the transceiver while holding the USB in reset state.*/
STM32_USB->CNTR = CNTR_FRES;
/* Enabling the USB IRQ vectors, this also gives enough time to allow
the transceiver power up (1uS).*/
nvicEnableVector(STM32_USB1_HP_NUMBER,
CORTEX_PRIORITY_MASK(STM32_USB_USB1_HP_IRQ_PRIORITY));
nvicEnableVector(STM32_USB1_LP_NUMBER,
CORTEX_PRIORITY_MASK(STM32_USB_USB1_LP_IRQ_PRIORITY));
/* Releases the USB reset.*/
STM32_USB->CNTR = 0;
}
#endif
/* Reset procedure enforced on driver start.*/
_usb_reset(usbp);
}
/* Configuration.*/
}
/**
* @brief Deactivates the USB peripheral.
*
* @param[in] usbp pointer to the @p USBDriver object
*
* @notapi
*/
void usb_lld_stop(USBDriver *usbp) {
/* If in ready state then disables the USB clock.*/
if (usbp->state == USB_STOP) {
#if STM32_USB_USE_USB1
if (&USBD1 == usbp) {
nvicDisableVector(STM32_USB1_HP_NUMBER);
nvicDisableVector(STM32_USB1_LP_NUMBER);
STM32_USB->CNTR = CNTR_PDWN | CNTR_FRES;
rccDisableUSB(FALSE);
}
#endif
}
}
/**
* @brief USB low level reset routine.
*
* @param[in] usbp pointer to the @p USBDriver object
*
* @notapi
*/
void usb_lld_reset(USBDriver *usbp) {
uint32_t cntr;
/* Post reset initialization.*/
STM32_USB->BTABLE = 0;
STM32_USB->ISTR = 0;
STM32_USB->DADDR = DADDR_EF;
cntr = /*CNTR_ESOFM | */ CNTR_RESETM | CNTR_SUSPM |
CNTR_WKUPM | /*CNTR_ERRM | CNTR_PMAOVRM |*/ CNTR_CTRM;
/* The SOF interrupt is only enabled if a callback is defined for
this service because it is an high rate source.*/
if (usbp->config->sof_cb != NULL)
cntr |= CNTR_SOFM;
STM32_USB->CNTR = cntr;
/* Resets the packet memory allocator.*/
usb_pm_reset(usbp);
/* EP0 initialization.*/
usbp->epc[0] = &ep0config;
usb_lld_init_endpoint(usbp, 0);
}
/**
* @brief Sets the USB address.
*
* @param[in] usbp pointer to the @p USBDriver object
*
* @notapi
*/
void usb_lld_set_address(USBDriver *usbp) {
STM32_USB->DADDR = (uint32_t)(usbp->address) | DADDR_EF;
}
/**
* @brief Enables an endpoint.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_init_endpoint(USBDriver *usbp, usbep_t ep) {
uint16_t nblocks, epr;
stm32_usb_descriptor_t *dp;
const USBEndpointConfig *epcp = usbp->epc[ep];
/* Setting the endpoint type.*/
switch (epcp->ep_mode & USB_EP_MODE_TYPE) {
case USB_EP_MODE_TYPE_ISOC:
epr = EPR_EP_TYPE_ISO;
break;
case USB_EP_MODE_TYPE_BULK:
epr = EPR_EP_TYPE_BULK;
break;
case USB_EP_MODE_TYPE_INTR:
epr = EPR_EP_TYPE_INTERRUPT;
break;
default:
epr = EPR_EP_TYPE_CONTROL;
}
/* IN endpoint initially in NAK mode.*/
if (epcp->in_cb != NULL)
epr |= EPR_STAT_TX_NAK;
/* OUT endpoint initially in NAK mode.*/
if (epcp->out_cb != NULL)
epr |= EPR_STAT_RX_NAK;
/* EPxR register setup.*/
EPR_SET(ep, epr | ep);
EPR_TOGGLE(ep, epr);
/* Endpoint size and address initialization.*/
if (epcp->out_maxsize > 62)
nblocks = (((((epcp->out_maxsize - 1) | 0x1f) + 1) / 32) << 10) |
0x8000;
else
nblocks = ((((epcp->out_maxsize - 1) | 1) + 1) / 2) << 10;
dp = USB_GET_DESCRIPTOR(ep);
dp->TXCOUNT0 = 0;
dp->RXCOUNT0 = nblocks;
dp->TXADDR0 = usb_pm_alloc(usbp, epcp->in_maxsize);
dp->RXADDR0 = usb_pm_alloc(usbp, epcp->out_maxsize);
}
/**
* @brief Disables all the active endpoints except the endpoint zero.
*
* @param[in] usbp pointer to the @p USBDriver object
*
* @notapi
*/
void usb_lld_disable_endpoints(USBDriver *usbp) {
unsigned i;
/* Resets the packet memory allocator.*/
usb_pm_reset(usbp);
/* Disabling all endpoints.*/
for (i = 1; i <= USB_ENDOPOINTS_NUMBER; i++) {
EPR_TOGGLE(i, 0);
EPR_SET(i, 0);
}
}
/**
* @brief Returns the status of an OUT endpoint.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
* @return The endpoint status.
* @retval EP_STATUS_DISABLED The endpoint is not active.
* @retval EP_STATUS_STALLED The endpoint is stalled.
* @retval EP_STATUS_ACTIVE The endpoint is active.
*
* @notapi
*/
usbepstatus_t usb_lld_get_status_out(USBDriver *usbp, usbep_t ep) {
(void)usbp;
switch (STM32_USB->EPR[ep] & EPR_STAT_RX_MASK) {
case EPR_STAT_RX_DIS:
return EP_STATUS_DISABLED;
case EPR_STAT_RX_STALL:
return EP_STATUS_STALLED;
default:
return EP_STATUS_ACTIVE;
}
}
/**
* @brief Returns the status of an IN endpoint.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
* @return The endpoint status.
* @retval EP_STATUS_DISABLED The endpoint is not active.
* @retval EP_STATUS_STALLED The endpoint is stalled.
* @retval EP_STATUS_ACTIVE The endpoint is active.
*
* @notapi
*/
usbepstatus_t usb_lld_get_status_in(USBDriver *usbp, usbep_t ep) {
(void)usbp;
switch (STM32_USB->EPR[ep] & EPR_STAT_TX_MASK) {
case EPR_STAT_TX_DIS:
return EP_STATUS_DISABLED;
case EPR_STAT_TX_STALL:
return EP_STATUS_STALLED;
default:
return EP_STATUS_ACTIVE;
}
}
/**
* @brief Reads a setup packet from the dedicated packet buffer.
* @details This function must be invoked in the context of the @p setup_cb
* callback in order to read the received setup packet.
* @pre In order to use this function the endpoint must have been
* initialized as a control endpoint.
* @post The endpoint is ready to accept another packet.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
* @param[out] buf buffer where to copy the packet data
*
* @notapi
*/
void usb_lld_read_setup(USBDriver *usbp, usbep_t ep, uint8_t *buf) {
uint32_t *pmap;
stm32_usb_descriptor_t *udp;
uint32_t n;
(void)usbp;
udp = USB_GET_DESCRIPTOR(ep);
pmap = USB_ADDR2PTR(udp->RXADDR0);
for (n = 0; n < 4; n++) {
*(uint16_t *)buf = (uint16_t)*pmap++;
buf += 2;
}
}
/**
* @brief Prepares for a receive operation.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_prepare_receive(USBDriver *usbp, usbep_t ep) {
USBOutEndpointState *osp = usbp->epc[ep]->out_state;
/* Transfer initialization.*/
if (osp->rxsize == 0) /* Special case for zero sized packets.*/
osp->rxpkts = 1;
else
osp->rxpkts = (uint16_t)((osp->rxsize + usbp->epc[ep]->out_maxsize - 1) /
usbp->epc[ep]->out_maxsize);
}
/**
* @brief Prepares for a transmit operation.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_prepare_transmit(USBDriver *usbp, usbep_t ep) {
size_t n;
USBInEndpointState *isp = usbp->epc[ep]->in_state;
/* Transfer initialization.*/
n = isp->txsize;
if (n > (size_t)usbp->epc[ep]->in_maxsize)
n = (size_t)usbp->epc[ep]->in_maxsize;
if (isp->txqueued)
usb_packet_write_from_queue(USB_GET_DESCRIPTOR(ep),
isp->mode.queue.txqueue, n);
else
usb_packet_write_from_buffer(USB_GET_DESCRIPTOR(ep),
isp->mode.linear.txbuf, n);
}
/**
* @brief Starts a receive operation on an OUT endpoint.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_start_out(USBDriver *usbp, usbep_t ep) {
(void)usbp;
EPR_SET_STAT_RX(ep, EPR_STAT_RX_VALID);
}
/**
* @brief Starts a transmit operation on an IN endpoint.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_start_in(USBDriver *usbp, usbep_t ep) {
(void)usbp;
EPR_SET_STAT_TX(ep, EPR_STAT_TX_VALID);
}
/**
* @brief Brings an OUT endpoint in the stalled state.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_stall_out(USBDriver *usbp, usbep_t ep) {
(void)usbp;
EPR_SET_STAT_RX(ep, EPR_STAT_RX_STALL);
}
/**
* @brief Brings an IN endpoint in the stalled state.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_stall_in(USBDriver *usbp, usbep_t ep) {
(void)usbp;
EPR_SET_STAT_TX(ep, EPR_STAT_TX_STALL);
}
/**
* @brief Brings an OUT endpoint in the active state.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_clear_out(USBDriver *usbp, usbep_t ep) {
(void)usbp;
/* Makes sure to not put to NAK an endpoint that is already
transferring.*/
if ((STM32_USB->EPR[ep] & EPR_STAT_RX_MASK) != EPR_STAT_RX_VALID)
EPR_SET_STAT_TX(ep, EPR_STAT_RX_NAK);
}
/**
* @brief Brings an IN endpoint in the active state.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
*
* @notapi
*/
void usb_lld_clear_in(USBDriver *usbp, usbep_t ep) {
(void)usbp;
/* Makes sure to not put to NAK an endpoint that is already
transferring.*/
if ((STM32_USB->EPR[ep] & EPR_STAT_TX_MASK) != EPR_STAT_TX_VALID)
EPR_SET_STAT_TX(ep, EPR_STAT_TX_NAK);
}
#endif /* HAL_USE_USB */
/** @} */

View File

@@ -0,0 +1,447 @@
/*
ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/**
* @file STM32/USBv1/usb_lld.h
* @brief STM32 USB subsystem low level driver header.
*
* @addtogroup USB
* @{
*/
#ifndef _USB_LLD_H_
#define _USB_LLD_H_
#if HAL_USE_USB || defined(__DOXYGEN__)
#include "stm32_usb.h"
/*===========================================================================*/
/* Driver constants. */
/*===========================================================================*/
/**
* @brief Maximum endpoint address.
*/
#define USB_MAX_ENDPOINTS USB_ENDOPOINTS_NUMBER
/**
* @brief Status stage handling method.
*/
#define USB_EP0_STATUS_STAGE USB_EP0_STATUS_STAGE_SW
/**
* @brief This device requires the address change after the status packet.
*/
#define USB_SET_ADDRESS_MODE USB_LATE_SET_ADDRESS
/**
* @brief Method for set address acknowledge.
*/
#define USB_SET_ADDRESS_ACK_HANDLING USB_SET_ADDRESS_ACK_SW
/*===========================================================================*/
/* Driver pre-compile time settings. */
/*===========================================================================*/
/**
* @brief USB1 driver enable switch.
* @details If set to @p TRUE the support for USB1 is included.
* @note The default is @p TRUE.
*/
#if !defined(STM32_USB_USE_USB1) || defined(__DOXYGEN__)
#define STM32_USB_USE_USB1 FALSE
#endif
/**
* @brief Enables the USB device low power mode on suspend.
*/
#if !defined(STM32_USB_LOW_POWER_ON_SUSPEND) || defined(__DOXYGEN__)
#define STM32_USB_LOW_POWER_ON_SUSPEND FALSE
#endif
/**
* @brief USB1 interrupt priority level setting.
*/
#if !defined(STM32_USB_USB1_HP_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_USB_USB1_HP_IRQ_PRIORITY 13
#endif
/**
* @brief USB1 interrupt priority level setting.
*/
#if !defined(STM32_USB_USB1_LP_IRQ_PRIORITY) || defined(__DOXYGEN__)
#define STM32_USB_USB1_LP_IRQ_PRIORITY 14
#endif
/*===========================================================================*/
/* Derived constants and error checks. */
/*===========================================================================*/
#if STM32_USB_USE_USB1 && !STM32_HAS_USB
#error "USB not present in the selected device"
#endif
#if !STM32_USB_USE_USB1
#error "USB driver activated but no USB peripheral assigned"
#endif
#if STM32_USB_USE_USB1 && \
!CORTEX_IS_VALID_KERNEL_PRIORITY(STM32_USB_USB1_HP_IRQ_PRIORITY)
#error "Invalid IRQ priority assigned to USB HP"
#endif
#if STM32_USB_USE_USB1 && \
!CORTEX_IS_VALID_KERNEL_PRIORITY(STM32_USB_USB1_LP_IRQ_PRIORITY)
#error "Invalid IRQ priority assigned to USB LP"
#endif
#if STM32_USBCLK != 48000000
#error "the USB driver requires a 48MHz clock"
#endif
/*===========================================================================*/
/* Driver data structures and types. */
/*===========================================================================*/
/**
* @brief Type of an IN endpoint state structure.
*/
typedef struct {
/**
* @brief Buffer mode, queue or linear.
*/
bool_t txqueued;
/**
* @brief Requested transmit transfer size.
*/
size_t txsize;
/**
* @brief Transmitted bytes so far.
*/
size_t txcnt;
union {
struct {
/**
* @brief Pointer to the transmission linear buffer.
*/
const uint8_t *txbuf;
} linear;
struct {
/**
* @brief Pointer to the output queue.
*/
OutputQueue *txqueue;
} queue;
/* End of the mandatory fields.*/
} mode;
} USBInEndpointState;
/**
* @brief Type of an OUT endpoint state structure.
*/
typedef struct {
/**
* @brief Buffer mode, queue or linear.
*/
bool_t rxqueued;
/**
* @brief Requested receive transfer size.
*/
size_t rxsize;
/**
* @brief Received bytes so far.
*/
size_t rxcnt;
union {
struct {
/**
* @brief Pointer to the receive linear buffer.
*/
uint8_t *rxbuf;
} linear;
struct {
/**
* @brief Pointer to the input queue.
*/
InputQueue *rxqueue;
} queue;
} mode;
/* End of the mandatory fields.*/
/**
* @brief Number of packets to receive.
*/
uint16_t rxpkts;
} USBOutEndpointState;
/**
* @brief Type of an USB endpoint configuration structure.
* @note Platform specific restrictions may apply to endpoints.
*/
typedef struct {
/**
* @brief Type and mode of the endpoint.
*/
uint32_t ep_mode;
/**
* @brief Setup packet notification callback.
* @details This callback is invoked when a setup packet has been
* received.
* @post The application must immediately call @p usbReadPacket() in
* order to access the received packet.
* @note This field is only valid for @p USB_EP_MODE_TYPE_CTRL
* endpoints, it should be set to @p NULL for other endpoint
* types.
*/
usbepcallback_t setup_cb;
/**
* @brief IN endpoint notification callback.
* @details This field must be set to @p NULL if the IN endpoint is not
* used.
*/
usbepcallback_t in_cb;
/**
* @brief OUT endpoint notification callback.
* @details This field must be set to @p NULL if the OUT endpoint is not
* used.
*/
usbepcallback_t out_cb;
/**
* @brief IN endpoint maximum packet size.
* @details This field must be set to zero if the IN endpoint is not
* used.
*/
uint16_t in_maxsize;
/**
* @brief OUT endpoint maximum packet size.
* @details This field must be set to zero if the OUT endpoint is not
* used.
*/
uint16_t out_maxsize;
/**
* @brief @p USBEndpointState associated to the IN endpoint.
* @details This structure maintains the state of the IN endpoint.
*/
USBInEndpointState *in_state;
/**
* @brief @p USBEndpointState associated to the OUT endpoint.
* @details This structure maintains the state of the OUT endpoint.
*/
USBOutEndpointState *out_state;
/* End of the mandatory fields.*/
/**
* @brief Reserved field, not currently used.
* @note Initialize this field to 1 in order to be forward compatible.
*/
uint16_t ep_buffers;
/**
* @brief Pointer to a buffer for setup packets.
* @details Setup packets require a dedicated 8-bytes buffer, set this
* field to @p NULL for non-control endpoints.
*/
uint8_t *setup_buf;
} USBEndpointConfig;
/**
* @brief Type of an USB driver configuration structure.
*/
typedef struct {
/**
* @brief USB events callback.
* @details This callback is invoked when an USB driver event is registered.
*/
usbeventcb_t event_cb;
/**
* @brief Device GET_DESCRIPTOR request callback.
* @note This callback is mandatory and cannot be set to @p NULL.
*/
usbgetdescriptor_t get_descriptor_cb;
/**
* @brief Requests hook callback.
* @details This hook allows to be notified of standard requests or to
* handle non standard requests.
*/
usbreqhandler_t requests_hook_cb;
/**
* @brief Start Of Frame callback.
*/
usbcallback_t sof_cb;
/* End of the mandatory fields.*/
} USBConfig;
/**
* @brief Structure representing an USB driver.
*/
struct USBDriver {
/**
* @brief Driver state.
*/
usbstate_t state;
/**
* @brief Current configuration data.
*/
const USBConfig *config;
/**
* @brief Bit map of the transmitting IN endpoints.
*/
uint16_t transmitting;
/**
* @brief Bit map of the receiving OUT endpoints.
*/
uint16_t receiving;
/**
* @brief Active endpoints configurations.
*/
const USBEndpointConfig *epc[USB_MAX_ENDPOINTS + 1];
/**
* @brief Fields available to user, it can be used to associate an
* application-defined handler to an IN endpoint.
* @note The base index is one, the endpoint zero does not have a
* reserved element in this array.
*/
void *in_params[USB_MAX_ENDPOINTS];
/**
* @brief Fields available to user, it can be used to associate an
* application-defined handler to an OUT endpoint.
* @note The base index is one, the endpoint zero does not have a
* reserved element in this array.
*/
void *out_params[USB_MAX_ENDPOINTS];
/**
* @brief Endpoint 0 state.
*/
usbep0state_t ep0state;
/**
* @brief Next position in the buffer to be transferred through endpoint 0.
*/
uint8_t *ep0next;
/**
* @brief Number of bytes yet to be transferred through endpoint 0.
*/
size_t ep0n;
/**
* @brief Endpoint 0 end transaction callback.
*/
usbcallback_t ep0endcb;
/**
* @brief Setup packet buffer.
*/
uint8_t setup[8];
/**
* @brief Current USB device status.
*/
uint16_t status;
/**
* @brief Assigned USB address.
*/
uint8_t address;
/**
* @brief Current USB device configuration.
*/
uint8_t configuration;
#if defined(USB_DRIVER_EXT_FIELDS)
USB_DRIVER_EXT_FIELDS
#endif
/* End of the mandatory fields.*/
/**
* @brief Pointer to the next address in the packet memory.
*/
uint32_t pmnext;
};
/*===========================================================================*/
/* Driver macros. */
/*===========================================================================*/
/**
* @brief Returns the current frame number.
*
* @param[in] usbp pointer to the @p USBDriver object
* @return The current frame number.
*
* @notapi
*/
#define usb_lld_get_frame_number(usbp) (STM32_USB->FNR & FNR_FN_MASK)
/**
* @brief Returns the exact size of a receive transaction.
* @details The received size can be different from the size specified in
* @p usbStartReceiveI() because the last packet could have a size
* different from the expected one.
* @pre The OUT endpoint must have been configured in transaction mode
* in order to use this function.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
* @return Received data size.
*
* @notapi
*/
#define usb_lld_get_transaction_size(usbp, ep) \
((usbp)->epc[ep]->out_state->rxcnt)
/**
* @brief Returns the exact size of a received packet.
* @pre The OUT endpoint must have been configured in packet mode
* in order to use this function.
*
* @param[in] usbp pointer to the @p USBDriver object
* @param[in] ep endpoint number
* @return Received data size.
*
* @notapi
*/
#define usb_lld_get_packet_size(usbp, ep) \
((size_t)USB_GET_DESCRIPTOR(ep)->RXCOUNT & RXCOUNT_COUNT_MASK)
/*===========================================================================*/
/* External declarations. */
/*===========================================================================*/
#if STM32_USB_USE_USB1 && !defined(__DOXYGEN__)
extern USBDriver USBD1;
#endif
#ifdef __cplusplus
extern "C" {
#endif
void usb_lld_init(void);
void usb_lld_start(USBDriver *usbp);
void usb_lld_stop(USBDriver *usbp);
void usb_lld_reset(USBDriver *usbp);
void usb_lld_set_address(USBDriver *usbp);
void usb_lld_init_endpoint(USBDriver *usbp, usbep_t ep);
void usb_lld_disable_endpoints(USBDriver *usbp);
usbepstatus_t usb_lld_get_status_in(USBDriver *usbp, usbep_t ep);
usbepstatus_t usb_lld_get_status_out(USBDriver *usbp, usbep_t ep);
void usb_lld_read_setup(USBDriver *usbp, usbep_t ep, uint8_t *buf);
void usb_lld_prepare_receive(USBDriver *usbp, usbep_t ep);
void usb_lld_prepare_transmit(USBDriver *usbp, usbep_t ep);
void usb_lld_start_out(USBDriver *usbp, usbep_t ep);
void usb_lld_start_in(USBDriver *usbp, usbep_t ep);
void usb_lld_stall_out(USBDriver *usbp, usbep_t ep);
void usb_lld_stall_in(USBDriver *usbp, usbep_t ep);
void usb_lld_clear_out(USBDriver *usbp, usbep_t ep);
void usb_lld_clear_in(USBDriver *usbp, usbep_t ep);
#ifdef __cplusplus
}
#endif
#endif /* HAL_USE_USB */
#endif /* _USB_LLD_H_ */
/** @} */