init hw, draft

This commit is contained in:
pkolesnikov 2015-09-29 15:53:20 +02:00
parent cd6b51847b
commit e6ab9cc339
15 changed files with 1274 additions and 234 deletions

View File

@ -61,6 +61,9 @@ config ARCH_CHIP_LPC4357FBD208
config ARCH_CHIP_LPC4357FET256
bool "LPC4357FET256"
config ARCH_CHIP_LPC4370FET100
bool "LPC4370FET100"
endchoice
config ARCH_FAMILY_LPC4310
@ -93,6 +96,11 @@ config ARCH_FAMILY_LPC4357
default y if ARCH_CHIP_LPC4357FET180 || ARCH_CHIP_LPC4357FBD208 || ARCH_CHIP_LPC4357FET256
select ARCH_HAVE_TICKLESS
config ARCH_FAMILY_LPC4370
bool
default y if ARCH_CHIP_LPC4370FET100
select ARCH_HAVE_TICKLESS
choice
prompt "LPC43XX Boot Configuration"
default LPC43_BOOT_SRAM

View File

@ -133,6 +133,10 @@
# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4357fet256_pinconfig.h"
#elif defined(CONFIG_ARCH_CHIP_LPC4370FET100)
# define ARMV7M_PERIPHERAL_INTERRUPTS 53
# include "chip/lpc435357_memorymap.h"
# include "chip/lpc4357fet256_pinconfig.h"
#else
# error "Unsupported LPC43xx chip"
#endif

View File

@ -0,0 +1,573 @@
/*******************************************************************************
* arch/arm/src/lpc43xx/lpc43_i2c.c
*
* Copyright (C) 2012, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from from the LPC17 version:
*
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
* History: 0.1 2011-08-20 initial version
*
* Derived from arch/arm/src/lpc31xx/lpc31_i2c.c
*
* Author: David Hewson
*
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*******************************************************************************/
/*******************************************************************************
* Included Files
*******************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/wdog.h>
#include <nuttx/i2c.h>
#include <arch/irq.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "lpc43_i2c.h"
#include "lpc43_scu.h"
#include "lpc43_ccu.h"
#if defined(CONFIG_LPC43_I2C0) || defined(CONFIG_LPC43_I2C1)
#ifndef PINCONF_I2C1_SCL
# define PINCONF_I2C1_SCL PINCONF_I2C1_SCL_1
# define PINCONF_I2C1_SDA PINCONF_I2C1_SDA_1
#endif
#ifndef CONFIG_I2C0_FREQ
# define CONFIG_I2C0_FREQ 100000
#endif
#ifndef CONFIG_I2C1_FREQ
# define CONFIG_I2C1_FREQ 100000
#endif
#ifndef CONFIG_I2C2_FREQ
# define CONFIG_I2C2_FREQ 100000
#endif
/*******************************************************************************
* Pre-processor Definitions
*******************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define I2C_TIMEOUT ((20 * CLK_TCK) / 1000) /* 20 mS */
/****************************************************************************
* Private Data
****************************************************************************/
struct lpc43_i2cdev_s
{
struct i2c_dev_s dev; /* Generic I2C device */
struct i2c_msg_s msg; /* a single message for legacy read/write */
unsigned int base; /* Base address of registers */
uint16_t irqid; /* IRQ for this device */
sem_t mutex; /* Only one thread can access at a time */
sem_t wait; /* Place to wait for state machine completion */
volatile uint8_t state; /* State of state machine */
WDOG_ID timeout; /* watchdog to timeout when bus hung */
uint16_t wrcnt; /* number of bytes sent to tx fifo */
uint16_t rdcnt; /* number of bytes read from rx fifo */
};
#ifdef CONFIG_LPC43_I2C0
static struct lpc43_i2cdev_s g_i2c0dev;
#endif
#ifdef CONFIG_LPC43_I2C1
static struct lpc43_i2cdev_s g_i2c1dev;
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
static int i2c_start(struct lpc43_i2cdev_s *priv);
static void i2c_stop(struct lpc43_i2cdev_s *priv);
static int i2c_interrupt(int irq, FAR void *context);
static void i2c_timeout(int argc, uint32_t arg, ...);
/****************************************************************************
* I2C device operations
****************************************************************************/
static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev,
uint32_t frequency);
static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr,
int nbits);
static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer,
int buflen);
static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer,
int buflen);
static int i2c_transfer(FAR struct i2c_dev_s *dev,
FAR struct i2c_msg_s *msgs, int count);
struct i2c_ops_s lpc43_i2c_ops =
{
.setfrequency = i2c_setfrequency,
.setaddress = i2c_setaddress,
.write = i2c_write,
.read = i2c_read,
#ifdef CONFIG_I2C_TRANSFER
.transfer = i2c_transfer
#endif
};
/*******************************************************************************
* Name: lpc43_i2c_setfrequency
*
* Description:
* Set the frequence for the next transfer
*
*******************************************************************************/
static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *) dev;
if (frequency > 100000)
{
/* asymetric per 400Khz I2C spec */
putreg32(LPC43_CCLK / (83 + 47) * 47 / frequency, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK / (83 + 47) * 83 / frequency, priv->base + LPC43_I2C_SCLL_OFFSET);
}
else
{
/* 50/50 mark space ratio */
putreg32(LPC43_CCLK / 100 * 50 / frequency, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK / 100 * 50 / frequency, priv->base + LPC43_I2C_SCLL_OFFSET);
}
/* FIXME: This function should return the actual selected frequency */
return (frequency);
}
/*******************************************************************************
* Name: lpc43_i2c_setaddress
*
* Description:
* Set the I2C slave address for a subsequent read/write
*
*******************************************************************************/
static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *)dev;
DEBUGASSERT(dev != NULL);
DEBUGASSERT(nbits == 7);
priv->msg.addr = addr << 1;
priv->msg.flags = 0 ;
return (0);
}
/*******************************************************************************
* Name: lpc43_i2c_write
*
* Description:
* Send a block of data on I2C using the previously selected I2C
* frequency and slave address.
*
*******************************************************************************/
static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer,
int buflen)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *)dev;
int ret;
DEBUGASSERT(dev != NULL);
priv->wrcnt = 0;
priv->rdcnt = 0;
priv->msg.addr &= ~0x01;
priv->msg.buffer = (uint8_t*)buffer;
priv->msg.length = buflen;
ret = i2c_start(priv);
return (ret > 0 ? 0 : -ETIMEDOUT);
}
/*******************************************************************************
* Name: lpc43_i2c_read
*
* Description:
* Receive a block of data on I2C using the previously selected I2C
* frequency and slave address.
*
*******************************************************************************/
static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *)dev;
int ret;
DEBUGASSERT(dev != NULL);
priv->wrcnt=0;
priv->rdcnt=0;
priv->msg.addr |= 0x01;
priv->msg.buffer = buffer;
priv->msg.length = buflen;
ret = i2c_start(priv);
return (ret >0 ? 0 : -ETIMEDOUT);
}
/*******************************************************************************
* Name: i2c_start
*
* Description:
* Perform a I2C transfer start
*
*******************************************************************************/
static int i2c_start(struct lpc43_i2cdev_s *priv)
{
int ret = -1;
sem_wait(&priv->mutex);
putreg32(I2C_CONCLR_STAC|I2C_CONCLR_SIC,priv->base+LPC43_I2C_CONCLR_OFFSET);
putreg32(I2C_CONSET_STA,priv->base+LPC43_I2C_CONSET_OFFSET);
wd_start(priv->timeout, I2C_TIMEOUT, i2c_timeout, 1, (uint32_t)priv);
sem_wait(&priv->wait);
wd_cancel(priv->timeout);
sem_post(&priv->mutex);
if (priv-> state == 0x18 || priv->state == 0x28)
{
ret = priv->wrcnt;
}
else if (priv-> state == 0x50 || priv->state == 0x58)
{
ret = priv->rdcnt;
}
return (ret);
}
/*******************************************************************************
* Name: i2c_stop
*
* Description:
* Perform a I2C transfer stop
*
*******************************************************************************/
static void i2c_stop(struct lpc43_i2cdev_s *priv)
{
if (priv->state != 0x38)
{
putreg32(I2C_CONSET_STO|I2C_CONSET_AA,priv->base+LPC43_I2C_CONSET_OFFSET);
}
sem_post(&priv->wait);
}
/*******************************************************************************
* Name: i2c_timeout
*
* Description:
* Watchdog timer for timeout of I2C operation
*
*******************************************************************************/
static void i2c_timeout(int argc, uint32_t arg, ...)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *)arg;
irqstate_t flags = irqsave();
priv->state = 0xff;
sem_post(&priv->wait);
irqrestore(flags);
}
/*******************************************************************************
* Name: i2c_interrupt
*
* Description:
* The I2C Interrupt Handler
*
*******************************************************************************/
static int i2c_interrupt(int irq, FAR void *context)
{
struct lpc43_i2cdev_s *priv;
uint32_t state;
#ifdef CONFIG_LPC43_I2C0
if (irq == LPC43M0_IRQ_I2C0)
{
priv = &g_i2c0dev;
}
else
#endif
#ifdef CONFIG_LPC43_I2C1
if (irq == LPC43_IRQ_I2C1)
{
priv = &g_i2c1dev;
}
else
#endif
{
PANIC();
}
/* Reference UM10360 19.10.5 */
state = getreg32(priv->base+LPC43_I2C_STAT_OFFSET);
putreg32(I2C_CONCLR_SIC, priv->base + LPC43_I2C_CONCLR_OFFSET);
priv->state = state;
state &= 0xf8;
switch (state)
{
case 0x00: /* Bus Error */
case 0x20:
case 0x30:
case 0x38:
case 0x48:
i2c_stop(priv);
break;
case 0x08: /* START */
case 0x10: /* Repeated START */
putreg32(priv->msg.addr, priv->base + LPC43_I2C_DAT_OFFSET);
putreg32(I2C_CONCLR_STAC, priv->base + LPC43_I2C_CONCLR_OFFSET);
break;
case 0x18:
priv->wrcnt=0;
putreg32(priv->msg.buffer[0], priv->base + LPC43_I2C_DAT_OFFSET);
break;
case 0x28:
priv->wrcnt++;
if (priv->wrcnt < priv->msg.length)
{
putreg32(priv->msg.buffer[priv->wrcnt],priv->base+LPC43_I2C_DAT_OFFSET);
}
else
{
i2c_stop(priv);
}
break;
case 0x40:
priv->rdcnt = -1;
putreg32(I2C_CONSET_AA, priv->base + LPC43_I2C_CONSET_OFFSET);
break;
case 0x50:
priv->rdcnt++;
if (priv->rdcnt < priv->msg.length)
{
priv->msg.buffer[priv->rdcnt]=getreg32(priv->base+LPC43_I2C_BUFR_OFFSET);
}
if (priv->rdcnt >= priv->msg.length - 1)
{
putreg32(I2C_CONCLR_AAC|I2C_CONCLR_SIC,priv->base+LPC43_I2C_CONCLR_OFFSET);
}
break;
case 0x58:
i2c_stop(priv);
break;
default:
i2c_stop(priv);
break;
}
return (0);
}
/****************************************************************************
* Public Functions
****************************************************************************/
/*******************************************************************************
* Name: up_i2cinitialize
*
* Description:
* Initialise an I2C device
*
*******************************************************************************/
struct i2c_dev_s *up_i2cinitialize(int port)
{
struct lpc43_i2cdev_s *priv;
if (port>2)
{
dbg("lpc I2C Only support 0,1,2\n");
return NULL;
}
irqstate_t flags;
uint32_t regval;
flags = irqsave();
#ifdef CONFIG_LPC43_I2C0
if (port == 0)
{
priv = &g_i2c0dev;
priv->base = LPC43_I2C0_BASE;
priv->irqid = LPC43M0_IRQ_I2C0;
//enable
regval = getreg32(LPC43_SCU_SFSI2C0 );
regval |= SCU_SFSI2C0_SCL_EZI | SCU_SFSI2C0_SDA_EZI;
if ( CONFIG_I2C0_FREQ == 1000000 ) { //super fast mode
regval |= SCU_SFSI2C0_SCL_EHD | SCU_SFSI2C0_SDA_EHD;
}
putreg32(regval, LPC43_SCU_SFSI2C0);
//enable clock
regval = getreg32(LPC43_CCU1_APB1_I2C0_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_APB1_I2C0_CFG);
//
putreg32(LPC43_CCLK/CONFIG_I2C0_FREQ/2, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK/CONFIG_I2C0_FREQ/2, priv->base + LPC43_I2C_SCLL_OFFSET);
//no pins configuration needed
}
else
#endif
#ifdef CONFIG_LPC43_I2C1
if (port == 1)
{
priv = &g_i2c1dev;
priv->base = LPC43_I2C1_BASE;
priv->irqid = LPC43_IRQ_I2C1;
regval = getreg32(LPC43_SCU_SFSI2C0);
regval |= SYSCON_PCONP_PCI2C1;
putreg32(regval, LPC43_SCU_SFSI2C0);
regval = getreg32(LPC43_SYSCON_PCLKSEL1);
regval &= ~SYSCON_PCLKSEL1_I2C1_MASK;
regval |= (SYSCON_PCLKSEL_CCLK << SYSCON_PCLKSEL1_I2C1_SHIFT);
putreg32(regval, LPC43_SYSCON_PCLKSEL1);
lpc43_pin_config(PINCONF_I2C1_SCL);
lpc43_pin_config(PINCONF_I2C1_SDA);
putreg32(LPC43_CCLK/CONFIG_I2C1_FREQ/2, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK/CONFIG_I2C1_FREQ/2, priv->base + LPC43_I2C_SCLL_OFFSET);
}
else
#endif
{
return NULL;
}
putreg32(I2C_CONSET_I2EN,priv->base+LPC43_I2C_CONSET_OFFSET);
sem_init(&priv->mutex, 0, 1);
sem_init(&priv->wait, 0, 0);
/* Allocate a watchdog timer */
priv->timeout = wd_create();
DEBUGASSERT(priv->timeout != 0);
/* Attach Interrupt Handler */
irq_attach(priv->irqid, i2c_interrupt);
/* Enable Interrupt Handler */
up_enable_irq(priv->irqid);
/* Install our operations */
priv->dev.ops = &lpc43_i2c_ops;
return (&priv->dev);
}
/*******************************************************************************
* Name: up_i2cuninitalize
*
* Description:
* Uninitialise an I2C device
*
*******************************************************************************/
int up_i2cuninitialize(FAR struct i2c_dev_s * dev)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *) dev;
putreg32(I2C_CONCLRT_I2ENC,priv->base+LPC43_I2C_CONCLR_OFFSET);
up_disable_irq(priv->irqid);
irq_detach(priv->irqid);
return (0);
}
#endif

View File

@ -565,9 +565,9 @@
#define USBHOST_USBMODE_CM_SHIFT (0) /* Bits 0-1: Controller mode */
#define USBHOST_USBMODE_CM_MASK (3 << USBHOST_USBMODE_CM_SHIFT)
# define USBHOST_USBMODE_CMIDLE (0 << USBHOST_USBMODE_CM_SHIFT) /* Idle */
# define USBHOST_USBMODE_CMDEVICE (2 << USBHOST_USBMODE_CM_SHIFT) /* Device controller */
# define USBHOST_USBMODE_CMHOST (3 << USBHOST_USBMODE_CM_SHIFT) /* Host controller */
#define USBHOST_USBMODE_CM_IDLE (0 << USBHOST_USBMODE_CM_SHIFT) /* Idle */
#define USBHOST_USBMODE_CM_DEVICE (2 << USBHOST_USBMODE_CM_SHIFT) /* Device controller */
#define USBHOST_USBMODE_CM_HOST (3 << USBHOST_USBMODE_CM_SHIFT) /* Host controller */
#define USBHOST_USBMODE_ES (1 << 2) /* Bit 2: Endian select */
/* Bit 3: Not used in host mode */
#define USBHOST_USBMODE_SDIS (1 << 4) /* Bit 4: Stream disable mode */

View File

@ -0,0 +1,66 @@
/****************************************************************************
* arch/arm/src/lpc43xx/lpc43_ccu.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC43XX_LPC43_CCU_H
#define __ARCH_ARM_SRC_LPC43XX_LPC43_CCU_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc43_ccu.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_CCU_H */

View File

@ -428,7 +428,8 @@ static inline void lpc43_m4clkselect(uint32_t clksel)
void lpc43_pll0usbconfig(void)
{
putreg32(BOARD_USB0_CTL, LPC43_PLL0USB_CTRL);
//power down, no bypass, direct i-o,
putreg32( (PLL0USB_CTRL_PD | PLL0USB_CTRL_DIRECTI | PLL0USB_CTRL_DIRECTO | PLL0USB_CTRL_CLKEN | PLL0USB_CTRL_AUTOBLOCK | BOARD_USB0_CLKSRC), LPC43_PLL0USB_CTRL);
putreg32(BOARD_USB0_MDIV, LPC43_PLL0USB_MDIV);
putreg32(BOARD_USB0_NP_DIV, LPC43_PLL0USB_NP_DIV);
@ -448,7 +449,7 @@ void lpc43_pll0usbenable(void)
{
uint32_t regval;
/* Take PLL1 out of power down mode. The reset state of the PD bit
/* Take PLL0 out of power down mode. The reset state of the PD bit
* is one, i.e., powered down.
*/
@ -456,7 +457,7 @@ void lpc43_pll0usbenable(void)
regval &= ~PLL0USB_CTRL_PD;
putreg32(regval, LPC43_PLL0USB_CTRL);
/* When the power-down mode is terminated, PPL1 will resume its normal
/* When the power-down mode is terminated, PPL0 will resume its normal
* operation and will make the lock signal high once it has regained
* lock on the input clock
*
@ -488,6 +489,106 @@ void lpc43_pll0usbdisable(void)
putreg32(regval, LPC43_PLL0USB_CTRL);
}
#if defined(BOARD_IDIVA_DIVIDER) && defined(BOARD_IDIVA_CLKSRC )
void lpc43_idiva(void)
{
uint32_t regval;
//set clock source, divider
regval = getreg32(LPC43_IDIVA_CTRL);
regval &= ~( IDIVA_CTRL_CLKSEL_MASK | IDIVA_CTRL_IDIV_MASK );
regval |= BOARD_IDIVA_CLKSRC | IDIVA_CTRL_AUTOBLOCK | IDIVA_CTRL_IDIV(BOARD_IDIVA_DIVIDER);
putreg32(regval, LPC43_IDIVA_CTRL);
}
#endif
#if defined(BOARD_IDIVB_DIVIDER) && defined(BOARD_IDIVB_CLKSRC)
void lpc43_idivb(void)
{
uint32_t regval;
//set clock source, divider
regval = getreg32(LPC43_IDIVB_CTRL);
regval &= ~( IDIVBCD_CTRL_CLKSEL_MASK | IDIVBCD_CTRL_IDIV_MASK );
regval |= BOARD_IDIVB_CLKSRC | IDIVBCD_CTRL_AUTOBLOCK | IDIVBCD_CTRL_IDIV(BOARD_IDIVB_DIVIDER);
putreg32(regval, LPC43_IDIVB_CTRL);
}
#endif
#if defined(BOARD_IDIVC_DIVIDER) && defined(BOARD_IDIVC_CLKSRC)
void lpc43_idivc(void)
{
uint32_t regval;
//set clock source, divider
regval = getreg32(LPC43_IDIVC_CTRL);
regval &= ~( IDIVBCD_CTRL_CLKSEL_MASK | IDIVBCD_CTRL_IDIV_MASK );
regval |= BOARD_IDIVC_CLKSRC | IDIVBCD_CTRL_AUTOBLOCK | IDIVBCD_CTRL_IDIV(BOARD_IDIVC_DIVIDER);
putreg32(regval, LPC43_IDIVC_CTRL);
}
#endif
#if defined(BOARD_IDIVD_DIVIDER) && defined(BOARD_IDIVD_CLKSRC)
void lpc43_idivd(void)
{
uint32_t regval;
//set clock source, divider
regval = getreg32(LPC43_IDIVD_CTRL);
regval &= ~( IDIVBCD_CTRL_CLKSEL_MASK | IDIVBCD_CTRL_IDIV_MASK );
regval |= BOARD_IDIVD_CLKSRC | IDIVBCD_CTRL_AUTOBLOCK | IDIVBCD_CTRL_IDIV(BOARD_IDIVD_DIVIDER);
putreg32(regval, LPC43_IDIVD_CTRL);
}
#endif
#if defined(BOARD_IDIVE_DIVIDER) && defined(BOARD_IDIVE_CLKSRC)
void lpc43_idive(void)
{
uint32_t regval;
//set clock source, divider
regval = getreg32(LPC43_IDIVE_CTRL);
regval &= ~( IDIVE_CTRL_CLKSEL_MASK | IDIVE_CTRL_IDIV_MASK );
regval |= BOARD_IDIVE_CLKSRC | IDIVE_CTRL_AUTOBLOCK | IDIVE_CTRL_IDIV(BOARD_IDIVE_DIVIDER);
putreg32(regval, LPC43_IDIVE_CTRL);
}
#endif
#if defined(BOARD_ABP1_CLKSRC)
void lpc43_abp1(void)
{
uint32_t regval;
//set clock source
regval = getreg32(LPC43_BASE_APB1_CLK);
regval &= ~BASE_APB1_CLK_CLKSEL_MASK;
regval |= BOARD_ABP1_CLKSRC | BASE_APB1_CLK_AUTOBLOCK;
putreg32(regval, LPC43_BASE_APB1_CLK);
}
#endif
#if defined(BOARD_ABP3_CLKSRC)
void lpc43_abp3(void)
{
uint32_t regval;
//set clock source
regval = getreg32(LPC43_BASE_APB3_CLK);
regval &= ~BASE_APB3_CLK_CLKSEL_MASK;
regval |= BOARD_ABP3_CLKSRC | BASE_APB3_CLK_AUTOBLOCK;
putreg32(regval, LPC43_BASE_APB3_CLK);
}
#endif
/****************************************************************************
* Name: lpc43_clockconfig
*
@ -550,4 +651,38 @@ void lpc43_clockconfig(void)
lpc43_pll1config(PLL_CONTROLS);
#endif
//configure idivs
#if defined(BOARD_IDIVA_DIVIDER) && defined(BOARD_IDIVA_CLKSRC)
lpc43_idiva();
#endif
#if defined(BOARD_IDIVB_DIVIDER) && defined(BOARD_IDIVB_CLKSRC)
lpc43_idivb();
#endif
#if defined(BOARD_IDIVC_DIVIDER) && defined(BOARD_IDIVC_CLKSRC)
lpc43_idivc();
#endif
#if defined(BOARD_IDIVD_DIVIDER) && defined(BOARD_IDIVD_CLKSRC)
lpc43_idivd();
#endif
#if defined(BOARD_IDIVE_DIVIDER) && defined(BOARD_IDIVE_CLKSRC)
lpc43_idive();
#endif
//configure abpXs
#if defined(BOARD_ABP1_CLKSRC)
lpc43_abp1();
#endif
#if defined(BOARD_ABP3_CLKSRC)
lpc43_abp3();
#endif
}

View File

@ -0,0 +1,66 @@
/****************************************************************************
* arch/arm/src/lpc43xx/lpc43_creg.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC43XX_LPC43_CREG_H
#define __ARCH_ARM_SRC_LPC43XX_LPC43_CREG_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc43_creg.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_CREG_H */

View File

@ -71,38 +71,18 @@
#include "up_arch.h"
#include "up_internal.h"
#include "lpc43_syscon.h"
#include "lpc43_pinconn.h"
#include "lpc43_i2c.h"
#include "lpc43_scu.h"
#include "lpc43_ccu.h"
#include "lpc43_pinconfig.h"
#if defined(CONFIG_LPC43_I2C0) || defined(CONFIG_LPC43_I2C1)
#ifndef GPIO_I2C1_SCL
# define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
# define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
#endif
#ifndef CONFIG_I2C0_FREQ
# define CONFIG_I2C0_FREQ 100000
#endif
#ifndef CONFIG_I2C1_FREQ
# define CONFIG_I2C1_FREQ 100000
#endif
#ifndef CONFIG_I2C2_FREQ
# define CONFIG_I2C2_FREQ 100000
#endif
/*******************************************************************************
* Pre-processor Definitions
*******************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define I2C_TIMEOUT ((20 * CLK_TCK) / 1000) /* 20 mS */
#define I2C_TIMEOUT (20*1000/CONFIG_USEC_PER_TICK) /* 20 mS */
/****************************************************************************
* Private Data
@ -114,12 +94,16 @@ struct lpc43_i2cdev_s
struct i2c_msg_s msg; /* a single message for legacy read/write */
unsigned int base; /* Base address of registers */
uint16_t irqid; /* IRQ for this device */
uint32_t baseFreq; /* branch frequency */
sem_t mutex; /* Only one thread can access at a time */
sem_t wait; /* Place to wait for state machine completion */
volatile uint8_t state; /* State of state machine */
WDOG_ID timeout; /* watchdog to timeout when bus hung */
struct i2c_msg_s *msgs; /* remaining transfers - first one is in progress */
unsigned int nmsg; /* number of transfer remaining */
uint16_t wrcnt; /* number of bytes sent to tx fifo */
uint16_t rdcnt; /* number of bytes read from rx fifo */
};
@ -152,8 +136,10 @@ static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer,
int buflen);
static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer,
int buflen);
#ifdef CONFIG_I2C_TRANSFER
static int i2c_transfer(FAR struct i2c_dev_s *dev,
FAR struct i2c_msg_s *msgs, int count);
#endif
struct i2c_ops_s lpc43_i2c_ops =
{
@ -166,6 +152,8 @@ struct i2c_ops_s lpc43_i2c_ops =
#endif
};
/*******************************************************************************
* Name: lpc43_i2c_setfrequency
*
@ -173,7 +161,6 @@ struct i2c_ops_s lpc43_i2c_ops =
* Set the frequence for the next transfer
*
*******************************************************************************/
static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *) dev;
@ -182,20 +169,20 @@ static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency)
{
/* asymetric per 400Khz I2C spec */
putreg32(LPC43_CCLK / (83 + 47) * 47 / frequency, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK / (83 + 47) * 83 / frequency, priv->base + LPC43_I2C_SCLL_OFFSET);
putreg32(priv->baseFreq / (83 + 47) * 47 / frequency, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(priv->baseFreq / (83 + 47) * 83 / frequency, priv->base + LPC43_I2C_SCLL_OFFSET);
}
else
{
/* 50/50 mark space ratio */
putreg32(LPC43_CCLK / 100 * 50 / frequency, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK / 100 * 50 / frequency, priv->base + LPC43_I2C_SCLL_OFFSET);
putreg32(priv->baseFreq / 100 * 50 / frequency, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(priv->baseFreq / 100 * 50 / frequency, priv->base + LPC43_I2C_SCLL_OFFSET);
}
/* FIXME: This function should return the actual selected frequency */
return frequency;
return (frequency);
}
/*******************************************************************************
@ -232,7 +219,7 @@ static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer,
int buflen)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *)dev;
int ret;
int ret = 0;
DEBUGASSERT(dev != NULL);
@ -242,9 +229,14 @@ static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer,
priv->msg.buffer = (uint8_t*)buffer;
priv->msg.length = buflen;
ret = i2c_start(priv);
priv->nmsg = 1;
priv->msgs = &(priv->msg);
return ret > 0 ? OK : -ETIMEDOUT;
if ( buflen>0 ) {
ret = i2c_start(priv);
}
return (ret == 0 ? 0 : -ETIMEDOUT);
}
/*******************************************************************************
@ -259,7 +251,7 @@ static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer,
static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *)dev;
int ret;
int ret = 0;
DEBUGASSERT(dev != NULL);
@ -269,9 +261,14 @@ static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen)
priv->msg.buffer = buffer;
priv->msg.length = buflen;
ret = i2c_start(priv);
priv->nmsg = 1;
priv->msgs = &(priv->msg);
return ret >0 ? OK : -ETIMEDOUT;
if ( buflen>0 ) {
ret = i2c_start(priv);
}
return (ret == 0 ? 0 : -ETIMEDOUT);
}
/*******************************************************************************
@ -293,19 +290,14 @@ static int i2c_start(struct lpc43_i2cdev_s *priv)
wd_start(priv->timeout, I2C_TIMEOUT, i2c_timeout, 1, (uint32_t)priv);
sem_wait(&priv->wait);
wd_cancel(priv->timeout);
ret = priv->nmsg;
sem_post(&priv->mutex);
if (priv-> state == 0x18 || priv->state == 0x28)
{
ret = priv->wrcnt;
}
else if (priv-> state == 0x50 || priv->state == 0x58)
{
ret = priv->rdcnt;
}
return ret;
return (ret);
}
/*******************************************************************************
@ -344,6 +336,43 @@ static void i2c_timeout(int argc, uint32_t arg, ...)
irqrestore(flags);
}
/*******************************************************************************
* Name: i2c_transfer
*
* Description:
* Perform a sequence of I2C transfers
*
*******************************************************************************/
static int i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int count)
{
struct lpc43_i2cdev_s *priv = (struct lpc43_i2cdev_s *)dev;
int ret;
DEBUGASSERT(dev != NULL);
priv->wrcnt=0;
priv->rdcnt=0;
priv->msgs = msgs;
priv->nmsg = count;
ret = count - i2c_start(priv);
return (ret);
}
void startStopNextMessage(struct lpc43_i2cdev_s *priv) {
priv->nmsg--;
if( priv->nmsg > 0 ) {
priv->msgs++;
putreg32(I2C_CONSET_STA,priv->base+LPC43_I2C_CONSET_OFFSET);
} else {
i2c_stop(priv);
}
}
/*******************************************************************************
* Name: i2c_interrupt
*
@ -355,10 +384,11 @@ static void i2c_timeout(int argc, uint32_t arg, ...)
static int i2c_interrupt(int irq, FAR void *context)
{
struct lpc43_i2cdev_s *priv;
struct i2c_msg_s *msg;
uint32_t state;
#ifdef CONFIG_LPC43_I2C0
if (irq == LPC43_IRQ_I2C0)
if (irq == LPC43M0_IRQ_I2C0)
{
priv = &g_i2c0dev;
}
@ -376,65 +406,59 @@ static int i2c_interrupt(int irq, FAR void *context)
}
/* Reference UM10360 19.10.5 */
state = getreg32(priv->base+LPC43_I2C_STAT_OFFSET);
putreg32(I2C_CONCLR_SIC, priv->base + LPC43_I2C_CONCLR_OFFSET);
msg = priv->msgs;
priv->state = state;
state &= 0xf8;
state &= 0xf8; //state mask, only 0xX8 is possible
switch (state)
{
case 0x00: /* Bus Error */
case 0x20:
case 0x30:
case 0x38:
case 0x48:
i2c_stop(priv);
case 0x08: /* A START condition has been transmitted. */
case 0x10: /* A Repeated START condition has been transmitted. */
putreg32(msg->addr, priv->base + LPC43_I2C_DAT_OFFSET); //set address
putreg32(I2C_CONCLR_STAC, priv->base + LPC43_I2C_CONCLR_OFFSET); //clear start bit
break;
case 0x08: /* START */
case 0x10: /* Repeated START */
putreg32(priv->msg.addr, priv->base + LPC43_I2C_DAT_OFFSET);
putreg32(I2C_CONCLR_STAC, priv->base + LPC43_I2C_CONCLR_OFFSET);
break;
case 0x18:
//write cases
case 0x18: //SLA+W has been transmitted; ACK has been received
priv->wrcnt=0;
putreg32(priv->msg.buffer[0], priv->base + LPC43_I2C_DAT_OFFSET);
putreg32(msg->buffer[0], priv->base + LPC43_I2C_DAT_OFFSET); //put first byte
break;
case 0x28:
case 0x28: //Data byte in DAT has been transmitted; ACK has been received.
priv->wrcnt++;
if (priv->wrcnt < priv->msg.length)
{
putreg32(priv->msg.buffer[priv->wrcnt],priv->base+LPC43_I2C_DAT_OFFSET);
}
else
{
i2c_stop(priv);
if (priv->wrcnt < msg->length) {
putreg32(msg->buffer[priv->wrcnt],priv->base+LPC43_I2C_DAT_OFFSET); //put next byte
} else {
startStopNextMessage(priv);
}
break;
case 0x40:
priv->rdcnt = -1;
putreg32(I2C_CONSET_AA, priv->base + LPC43_I2C_CONSET_OFFSET);
//read cases
case 0x40: //SLA+R has been transmitted; ACK has been received
priv->rdcnt = 0;
if ( msg->length > 1 ) {
putreg32(I2C_CONSET_AA, priv->base + LPC43_I2C_CONSET_OFFSET); // set ACK next read
} else {
putreg32(I2C_CONCLR_AAC,priv->base + LPC43_I2C_CONCLR_OFFSET); // do not ACK because only one byte
}
break;
case 0x50:
case 0x50: //Data byte has been received; ACK has been returned.
priv->rdcnt++;
if (priv->rdcnt < priv->msg.length)
{
priv->msg.buffer[priv->rdcnt]=getreg32(priv->base+LPC43_I2C_BUFR_OFFSET);
}
msg->buffer[priv->rdcnt-1 ] = getreg32(priv->base+LPC43_I2C_BUFR_OFFSET);
if ( priv->rdcnt >= (msg->length - 1) ) {
putreg32(I2C_CONCLR_AAC,priv->base+LPC43_I2C_CONCLR_OFFSET); // do not ACK any more
if (priv->rdcnt >= priv->msg.length - 1)
{
putreg32(I2C_CONCLR_AAC|I2C_CONCLR_SIC,priv->base+LPC43_I2C_CONCLR_OFFSET);
}
break;
case 0x58:
i2c_stop(priv);
case 0x58: //Data byte has been received; NACK has been returned.
msg->buffer[priv->rdcnt ] = getreg32(priv->base+LPC43_I2C_BUFR_OFFSET);
startStopNextMessage(priv);
break;
default:
@ -442,9 +466,13 @@ static int i2c_interrupt(int irq, FAR void *context)
break;
}
putreg32(I2C_CONCLR_SIC, priv->base + LPC43_I2C_CONCLR_OFFSET); //clear interrupt
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
@ -461,9 +489,9 @@ struct i2c_dev_s *up_i2cinitialize(int port)
{
struct lpc43_i2cdev_s *priv;
if (port>2)
if (port>1)
{
dbg("lpc I2C Only support 0,1,2\n");
dbg("lpc I2C Only support 0,1\n");
return NULL;
}
@ -477,22 +505,25 @@ struct i2c_dev_s *up_i2cinitialize(int port)
{
priv = &g_i2c0dev;
priv->base = LPC43_I2C0_BASE;
priv->irqid = LPC43_IRQ_I2C0;
priv->irqid = LPC43M0_IRQ_I2C0;
priv->baseFreq = BOARD_ABP1_FREQUENCY;
regval = getreg32(LPC43_SYSCON_PCONP);
regval |= SYSCON_PCONP_PCI2C0;
putreg32(regval, LPC43_SYSCON_PCONP);
//enable, set mode
regval = getreg32(LPC43_SCU_SFSI2C0 );
regval |= SCU_SFSI2C0_SCL_EZI | SCU_SFSI2C0_SDA_EZI;
if ( CONFIG_I2C0_FREQ == 1000000 ) { //super fast mode
regval |= SCU_SFSI2C0_SCL_EHD | SCU_SFSI2C0_SDA_EHD;
}
putreg32(regval, LPC43_SCU_SFSI2C0);
regval = getreg32(LPC43_SYSCON_PCLKSEL0);
regval &= ~SYSCON_PCLKSEL0_I2C0_MASK;
regval |= (SYSCON_PCLKSEL_CCLK << SYSCON_PCLKSEL0_I2C0_SHIFT);
putreg32(regval, LPC43_SYSCON_PCLKSEL0);
//enable clock
regval = getreg32(LPC43_CCU1_APB1_I2C0_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_APB1_I2C0_CFG);
lpc43_configgpio(GPIO_I2C0_SCL);
lpc43_configgpio(GPIO_I2C0_SDA);
i2c_setfrequency( (struct i2c_dev_s *)priv,CONFIG_I2C0_FREQ);
putreg32(LPC43_CCLK/CONFIG_I2C0_FREQ/2, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK/CONFIG_I2C0_FREQ/2, priv->base + LPC43_I2C_SCLL_OFFSET);
//no pins configuration needed
}
else
#endif
@ -501,22 +532,22 @@ struct i2c_dev_s *up_i2cinitialize(int port)
{
priv = &g_i2c1dev;
priv->base = LPC43_I2C1_BASE;
priv->irqid = LPC43_IRQ_I2C1;
priv->irqid = LPC43M0_IRQ_I2C1;
priv->baseFreq = BOARD_ABP3_FREQUENCY;
regval = getreg32(LPC43_SYSCON_PCONP);
regval |= SYSCON_PCONP_PCI2C1;
putreg32(regval, LPC43_SYSCON_PCONP);
//no need to enable
regval = getreg32(LPC43_SYSCON_PCLKSEL1);
regval &= ~SYSCON_PCLKSEL1_I2C1_MASK;
regval |= (SYSCON_PCLKSEL_CCLK << SYSCON_PCLKSEL1_I2C1_SHIFT);
putreg32(regval, LPC43_SYSCON_PCLKSEL1);
//enable clock
regval = getreg32(LPC43_CCU1_APB3_I2C1_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_APB3_I2C1_CFG);
lpc43_configgpio(GPIO_I2C1_SCL);
lpc43_configgpio(GPIO_I2C1_SDA);
//pins configuration
lpc43_pin_config(PINCONF_I2C1_SCL);
lpc43_pin_config(PINCONF_I2C1_SDA);
i2c_setfrequency(priv,CONFIG_I2C1_FREQ);
putreg32(LPC43_CCLK/CONFIG_I2C1_FREQ/2, priv->base + LPC43_I2C_SCLH_OFFSET);
putreg32(LPC43_CCLK/CONFIG_I2C1_FREQ/2, priv->base + LPC43_I2C_SCLL_OFFSET);
}
else
#endif
@ -524,6 +555,8 @@ struct i2c_dev_s *up_i2cinitialize(int port)
return NULL;
}
irqrestore(flags);
putreg32(I2C_CONSET_I2EN,priv->base+LPC43_I2C_CONSET_OFFSET);
sem_init(&priv->mutex, 0, 1);
@ -545,7 +578,7 @@ struct i2c_dev_s *up_i2cinitialize(int port)
/* Install our operations */
priv->dev.ops = &lpc43_i2c_ops;
return &priv->dev;
return (&priv->dev);
}
/*******************************************************************************
@ -566,4 +599,5 @@ int up_i2cuninitialize(FAR struct i2c_dev_s * dev)
return OK;
}
#endif

View File

@ -0,0 +1,66 @@
/****************************************************************************
* arch/arm/src/lpc43xx/lpc43_i2c.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC43XX_LPC43_I2C_H
#define __ARCH_ARM_SRC_LPC43XX_LPC43_I2C_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc43_i2c.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_I2C_H */

View File

@ -0,0 +1,66 @@
/****************************************************************************
* arch/arm/src/lpc43xx/lpc43_scu.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC43XX_LPC43_SCU_H
#define __ARCH_ARM_SRC_LPC43XX_LPC43_SCU_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc43_scu.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_SCU_H */

View File

@ -365,7 +365,7 @@ static uart_dev_t g_uart3port =
# elif defined(CONFIG_USART2_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart2port /* USART2=console */
# define TTYS0_DEV g_uart2port /* USART2=ttyS0 */
# ifdef CONFIG_LPC43_USART2
# ifdef CONFIG_LPC43_USART0
# define TTYS1_DEV g_uart0port /* USART2=ttyS0;USART0=ttyS1 */
# ifdef CONFIG_LPC43_UART1
# define TTYS2_DEV g_uart1port /* USART2=ttyS0;USART0=ttyS1;UART1=ttyS2 */
@ -882,7 +882,7 @@ static int up_interrupt(int irq, void *context)
* RS-485/EIA-485 Auto Address Detection (AAD) mode -- NOT supported
*
* In this mode, the receiver will compare any address byte received
* (parity = 1) to the 8-bit value programmed into the RS485ADRMATCH
* (parity = <EFBFBD>1<EFBFBD>) to the 8-bit value programmed into the RS485ADRMATCH
* register. When a matching address character is detected it will be
* pushed onto the RXFIFO along with the parity bit, and the receiver
* will be automatically enabled.

View File

@ -55,9 +55,12 @@
#include "chip.h"
#include "lpc43_syscon.h"
#include "lpc43_pinconn.h"
#include "lpc43_ssp.h"
#include "lpc43_cgu.h"
#include "lpc43_scu.h"
#include "lpc43_ccu.h"
#include "lpc43_pinconfig.h"
#if defined(CONFIG_LPC43_SSP0) || defined(CONFIG_LPC43_SSP1)
@ -84,25 +87,7 @@
# define spivdbg(x...)
#endif
/* SSP Clocking.
*
* The CPU clock by 1, 2, 4, or 8 to get the SSP peripheral clock (SSP_CLOCK).
* SSP_CLOCK may be further divided by 2-254 to get the SSP clock. If we
* want a usable range of 4KHz to 25MHz for the SSP, then:
*
* 1. SSPCLK must be greater than (2*25MHz) = 50MHz, and
* 2. SSPCLK must be less than (254*40Khz) = 101.6MHz.
*
* If we assume that CCLK less than or equal to 100MHz, we can just
* use the CCLK undivided to get the SSP_CLOCK.
*/
#if LPC43_CCLK > 100000000
# error "CCLK <= 100,000,000 assumed"
#endif
#define SSP_PCLKSET_DIV SYSCON_PCLKSEL_CCLK
#define SSP_CLOCK LPC43_CCLK
/****************************************************************************
* Private Types
@ -114,6 +99,7 @@ struct lpc43_sspdev_s
{
struct spi_dev_s spidev; /* Externally visible part of the SPI interface */
uint32_t sspbase; /* SPIn base address */
uint32_t sspbasefreq;
#ifdef CONFIG_LPC43_SSP_INTERRUPTS
uint8_t sspirq; /* SPI IRQ number */
#endif
@ -189,6 +175,7 @@ static struct lpc43_sspdev_s g_ssp0dev =
{
.spidev = { &g_spi0ops },
.sspbase = LPC43_SSP0_BASE,
.sspbasefreq = BOARD_SSP0_BASEFREQ
#ifdef CONFIG_LPC43_SSP_INTERRUPTS
.sspirq = LPC43_IRQ_SSP0,
#endif
@ -223,6 +210,7 @@ static struct lpc43_sspdev_s g_ssp1dev =
{
.spidev = { &g_spi1ops },
.sspbase = LPC43_SSP1_BASE,
.sspbasefreq = BOARD_SSP1_BASEFREQ
#ifdef CONFIG_LPC43_SSP_INTERRUPTS
.sspirq = LPC43_IRQ_SSP1,
#endif
@ -346,9 +334,6 @@ static uint32_t ssp_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
uint32_t divisor;
uint32_t actual;
/* Check if the requested frequence is the same as the frequency selection */
DEBUGASSERT(priv && frequency <= SSP_CLOCK / 2);
#ifndef CONFIG_SPI_OWNBUS
if (priv->frequency == frequency)
{
@ -360,7 +345,7 @@ static uint32_t ssp_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
/* frequency = SSP_CLOCK / divisor, or divisor = SSP_CLOCK / frequency */
divisor = SSP_CLOCK / frequency;
divisor = priv->sspbasefreq / frequency;
/* "In master mode, CPSDVSRmin = 2 or larger (even numbers only)" */
@ -381,7 +366,7 @@ static uint32_t ssp_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
/* Calculate the new actual */
actual = SSP_CLOCK / divisor;
actual = priv->sspbasefreq / divisor;
/* Save the frequency setting */
@ -720,32 +705,30 @@ static inline FAR struct lpc43_sspdev_s *lpc43_ssp0initialize(void)
irqstate_t flags;
uint32_t regval;
/* Configure multiplexed pins as connected on the board. Chip select
* pins must be configured by board-specific logic. All SSP0 pins and
* one SSP1 pin (SCK) have multiple, alternative pin selection.
* Definitions in the board.h file must be provided to resolve the
* board-specific pin configuration like:
*
* #define GPIO_SSP0_SCK GPIO_SSP0_SCK_1
*/
flags = irqsave();
lpc43_configgpio(GPIO_SSP0_SCK);
lpc43_configgpio(GPIO_SSP0_MISO);
lpc43_configgpio(GPIO_SSP0_MOSI);
/* Configure clocking */
regval = getreg32(LPC43_BASE_SSP0_CLK);
regval &= ~BASE_SSP0_CLK_CLKSEL_MASK;
regval |= (BOARD_SSP0_CLKSRC | BASE_SSP0_CLK_AUTOBLOCK);
putreg32(regval, LPC43_BASE_SSP0_CLK);
regval = getreg32(LPC43_SYSCON_PCLKSEL1);
regval &= ~SYSCON_PCLKSEL1_SSP0_MASK;
regval |= (SSP_PCLKSET_DIV << SYSCON_PCLKSEL1_SSP0_SHIFT);
putreg32(regval, LPC43_SYSCON_PCLKSEL1);
//clock register
regval = getreg32(LPC43_CCU1_M4_SSP0_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_M4_SSP0_CFG);
/* Enable peripheral clocking to SSP0 */
//clock peripheral
regval = getreg32(LPC43_CCU2_APB0_SSP0_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU2_APB0_SSP0_CFG);
//pins configuration
lpc43_pin_config(PINCONF_SSP0_SCK);
lpc43_pin_config(PINCONF_SSP0_SSEL);
lpc43_pin_config(PINCONF_SSP0_MISO);
lpc43_pin_config(PINCONF_SSP0_MOSI);
regval = getreg32(LPC43_SYSCON_PCONP);
regval |= SYSCON_PCONP_PCSSP0;
putreg32(regval, LPC43_SYSCON_PCONP);
irqrestore(flags);
return &g_ssp0dev;
@ -772,32 +755,30 @@ static inline FAR struct lpc43_sspdev_s *lpc43_ssp1initialize(void)
irqstate_t flags;
uint32_t regval;
/* Configure multiplexed pins as connected on the board. Chip select
* pins must be configured by board-specific logic. All SSP0 pins and
* one SSP1 pin (SCK) have multiple, alternative pin selection.
* Definitions in the board.h file must be provided to resolve the
* board-specific pin configuration like:
*
* #define GPIO_SSP0_SCK GPIO_SSP0_SCK_1
*/
flags = irqsave();
lpc43_configgpio(GPIO_SSP1_SCK);
lpc43_configgpio(GPIO_SSP1_MISO);
lpc43_configgpio(GPIO_SSP1_MOSI);
/* Configure clocking */
regval = getreg32(LPC43_BASE_SSP1_CLK);
regval &= ~BASE_SSP1_CLK_CLKSEL_MASK;
regval |= (BOARD_SSP1_CLKSRC | BASE_SSP1_CLK_AUTOBLOCK);
putreg32(regval, LPC43_BASE_SSP1_CLK);
regval = getreg32(LPC43_SYSCON_PCLKSEL0);
regval &= ~SYSCON_PCLKSEL0_SSP1_MASK;
regval |= (SSP_PCLKSET_DIV << SYSCON_PCLKSEL0_SSP1_SHIFT);
putreg32(regval, LPC43_SYSCON_PCLKSEL0);
//clock register
regval = getreg32(LPC43_CCU1_M4_SSP1_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_M4_SSP1_CFG);
/* Enable peripheral clocking to SSP0 and SSP1 */
//clock peripheral
regval = getreg32(LPC43_CCU2_APB2_SSP1_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU2_APB2_SSP1_CFG);
//pins configuration
lpc43_pin_config(PINCONF_SSP1_SCK);
lpc43_pin_config(PINCONF_SSP1_SSEL);
lpc43_pin_config(PINCONF_SSP1_MISO);
lpc43_pin_config(PINCONF_SSP1_MOSI);
regval = getreg32(LPC43_SYSCON_PCONP);
regval |= SYSCON_PCONP_PCSSP1;
putreg32(regval, LPC43_SYSCON_PCONP);
irqrestore(flags);
return &g_ssp1dev;

View File

@ -103,7 +103,7 @@ extern "C"
*
****************************************************************************/
FAR struct spi_dev_s *lpc43_sspinitialize(int port)
FAR struct spi_dev_s *lpc43_sspinitialize(int port);
/************************************************************************************
* Name: lpc43_ssp0/1select, lpc43_ssp0/1status, and lpc43_ssp0/1cmddata

View File

@ -52,6 +52,7 @@
#include "lpc43_pinconfig.h"
#include "lpc43_rgu.h"
#include "lpc43_cgu.h"
#include "lpc43_ccu.h"
#include "lpc43_uart.h"
@ -333,6 +334,16 @@ void lpc43_usart0_setup(void)
regval |= (BOARD_USART0_CLKSRC | BASE_USART0_CLK_AUTOBLOCK);
putreg32(regval, LPC43_BASE_USART0_CLK);
//clock register
regval = getreg32(LPC43_CCU1_M4_USART0_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_M4_USART0_CFG);
//clock peripheral
regval = getreg32(LPC43_CCU2_APB0_USART0_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU2_APB0_USART0_CFG);
/* Configure I/O pins. NOTE that multiple pin configuration options must
* be disambiguated by defining the pin configuration in the board.h
* header file.
@ -370,6 +381,16 @@ void lpc43_uart1_setup(void)
regval |= (BOARD_UART1_CLKSRC | BASE_UART1_CLK_AUTOBLOCK);
putreg32(regval, LPC43_BASE_UART1_CLK);
//clock register
regval = getreg32(LPC43_CCU1_M4_UART1_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_M4_UART1_CFG);
//clock peripheral
regval = getreg32(LPC43_CCU2_APB0_UART1_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU2_APB0_UART1_CFG);
/* Configure I/O pins. NOTE that multiple pin configuration options must
* be disambiguated by defining the pin configuration in the board.h
* header file.
@ -407,6 +428,17 @@ void lpc43_usart2_setup(void)
regval |= (BOARD_USART2_CLKSRC | BASE_USART2_CLK_AUTOBLOCK);
putreg32(regval, LPC43_BASE_USART2_CLK);
//clock register
regval = getreg32(LPC43_CCU1_M4_USART2_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_M4_USART2_CFG);
//clock peripheral
regval = getreg32(LPC43_CCU2_APB2_USART2_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU2_APB2_USART2_CFG);
/* Configure I/O pins. NOTE that multiple pin configuration options must
* be disambiguated by defining the pin configuration in the board.h
* header file.
@ -444,6 +476,16 @@ void lpc43_usart3_setup(void)
regval |= (BOARD_USART3_CLKSRC | BASE_USART3_CLK_AUTOBLOCK);
putreg32(regval, LPC43_BASE_USART3_CLK);
//clock register
regval = getreg32(LPC43_CCU1_M4_USART3_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_M4_USART3_CFG);
//clock peripheral
regval = getreg32(LPC43_CCU2_APB2_USART3_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU2_APB2_USART3_CFG);
/* Configure I/O pins. NOTE that multiple pin configuration options must
* be disambiguated by defining the pin configuration in the board.h
* header file.

View File

@ -71,6 +71,10 @@
#include "up_internal.h"
#include "lpc43_usb0dev.h"
#include "lpc43_creg.h"
#include "lpc43_ccu.h"
#include "lpc43_cgu.h"
#include "lpc43_rgu.h"
/*******************************************************************************
* Pre-processor Definitions
@ -245,9 +249,6 @@ struct lpc43_dqh_s
#define LPC43_INTRMAXPACKET (1024) /* Interrupt endpoint max packet (1 to 1024) */
#define LPC43_ISOCMAXPACKET (512) /* Acutally 1..1023 */
/* The address of the endpoint control register */
#define LPC43_USBDEV_ENDPTCTRL(epphy) (LPC43_USBDEV_ENDPTCTRL0 + ((epphy)>>1)*4)
/* Endpoint bit position in SETUPSTAT, PRIME, FLUSH, STAT, COMPLETE registers */
#define LPC43_ENDPTSHIFT(epphy) (LPC43_EPPHYIN(epphy) ? (16 + ((epphy) >> 1)) : ((epphy) >> 1))
#define LPC43_ENDPTMASK(epphy) (1 << LPC43_ENDPTSHIFT(epphy))
@ -2106,7 +2107,6 @@ static int lpc43_epsubmit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *r
static int lpc43_epcancel(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req)
{
FAR struct lpc43_ep_s *privep = (FAR struct lpc43_ep_s *)ep;
FAR struct lpc43_usbdev_s *priv;
irqstate_t flags;
#ifdef CONFIG_DEBUG
@ -2118,7 +2118,6 @@ static int lpc43_epcancel(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *r
#endif
usbtrace(TRACE_EPCANCEL, privep->epphy);
priv = privep->dev;
flags = irqsave();
@ -2434,10 +2433,8 @@ static int lpc43_pullup(struct usbdev_s *dev, bool enable)
*
* Assumptions:
* - This function is called very early in the initialization sequence
* - PLL and GIO pin initialization is not performed here but should been in
* the low-level boot logic: PLL1 must be configured for operation at 48MHz
* and P0.23 and PO.31 in PINSEL1 must be configured for Vbus and USB connect
* LED.
* - PLL initialization is not performed here but should been in
* the low-level boot logic: PLL0 must be configured for operation at 480MHz
*
*******************************************************************************/
@ -2445,6 +2442,7 @@ void up_usbinitialize(void)
{
struct lpc43_usbdev_s *priv = &g_usbdev;
int i;
uint32_t regval;
usbtrace(TRACE_DEVINIT, 0);
@ -2507,48 +2505,51 @@ void up_usbinitialize(void)
}
}
/* Enable USB to AHB clock and to Event router*/
lpc43_enableclock (CLKID_USBOTGAHBCLK);
lpc43_enableclock (CLKID_EVENTROUTERPCLK);
//clock
regval = getreg32(LPC43_BASE_USB0_CLK);
regval &= ~BASE_USB0_CLK_CLKSEL_MASK;
regval |= (BASE_USB0_CLKSEL_PLL0USB | BASE_USB0_CLK_AUTOBLOCK);
putreg32(regval, LPC43_BASE_USB0_CLK);
//clock run
regval = getreg32(LPC43_CCU1_M4_USB0_CFG);
regval |= CCU_CLK_CFG_RUN;
putreg32(regval, LPC43_CCU1_M4_USB0_CFG);
/* Enable PLL0 clock*/
lpc43_pll0usbconfig();
lpc43_pll0usbenable();
/* Reset USB block */
lpc43_softreset (RESETID_USBOTGAHBRST);
/* Enable USB OTG PLL and wait for lock */
lpc43_putreg (0, LPC43_SYSCREG_USB_ATXPLLPDREG);
uint32_t bank = EVNTRTR_BANK(EVENTRTR_USBATXPLLLOCK);
uint32_t bit = EVNTRTR_BIT(EVENTRTR_USBATXPLLLOCK);
while (! (lpc43_getreg(LPC43_EVNTRTR_RSR(bank)) & (1 << bit)))
;
/* Enable USB AHB clock */
lpc43_enableclock (CLKID_USBOTGAHBCLK);
regval = lpc43_getreg(LPC43_RGU_CTRL0);
regval |= RGU_CTRL0_USB0_RST;
lpc43_putreg(regval, LPC43_RGU_CTRL0);
/* Reset the controller */
lpc43_putreg (USBDEV_USBCMD_RST, LPC43_USBDEV_USBCMD);
while (lpc43_getreg (LPC43_USBDEV_USBCMD) & USBDEV_USBCMD_RST)
;
//power PHY
regval = getreg32(LPC43_CREG0);
regval &= ~CREG0_USB0PHY;
putreg32(regval, LPC43_CREG0);
/* Attach USB controller interrupt handler */
if (irq_attach(LPC43_IRQ_USBOTG, lpc43_usbinterrupt) != 0)
if (irq_attach(LPC43M4_IRQ_USB0, lpc43_usbinterrupt) != 0)
{
usbtrace(TRACE_DEVERROR(LPC43_TRACEERR_IRQREGISTRATION),
(uint16_t)LPC43_IRQ_USBOTG);
(uint16_t)LPC43M4_IRQ_USB0);
goto errout;
}
/* Program the controller to be the USB device controller */
lpc43_putreg (USBDEV_USBMODE_SDIS | USBDEV_USBMODE_SLOM | USBDEV_USBMODE_CMDEVICE,
lpc43_putreg (USBDEV_USBMODE_SDIS | USBDEV_USBMODE_SLOM | USBDEV_USBMODE_CM_DEVICE,
LPC43_USBDEV_USBMODE);
/* Disconnect device */
@ -2590,8 +2591,8 @@ void up_usbuninitialize(void)
/* Disable and detach IRQs */
up_disable_irq(LPC43_IRQ_USBOTG);
irq_detach(LPC43_IRQ_USBOTG);
up_disable_irq(LPC43M4_IRQ_USB0);
irq_detach(LPC43M4_IRQ_USB0);
/* Reset the controller */
@ -2601,9 +2602,7 @@ void up_usbuninitialize(void)
/* Turn off USB power and clocking */
lpc43_disableclock (CLKID_USBOTGAHBCLK);
lpc43_disableclock (CLKID_EVENTROUTERPCLK);
lpc43_pll0usbdisable();
irqrestore(flags);
}
@ -2654,7 +2653,7 @@ int usbdev_register(struct usbdevclass_driver_s *driver)
{
/* Enable USB controller interrupts */
up_enable_irq(LPC43_IRQ_USBOTG);
up_enable_irq(LPC43M4_IRQ_USB0);
/* FIXME: nothing seems to call DEV_CONNECT(), but we need to set
* the RS bit to enable the controller. It kind of makes sense
@ -2697,7 +2696,7 @@ int usbdev_unregister(struct usbdevclass_driver_s *driver)
/* Disable USB controller interrupts */
up_disable_irq(LPC43_IRQ_USBOTG);
up_disable_irq(LPC43M4_IRQ_USB0);
/* Unhook the driver */