add Lib_OemBaseBoard to bsp/board but current exclude from all builds (added when needed later)

This commit is contained in:
hathach
2013-04-09 02:30:33 +07:00
parent c036efff1d
commit 11dff6f978
18 changed files with 2383 additions and 2 deletions

View File

@@ -0,0 +1,49 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __ACC_H
#define __ACC_H
typedef enum
{
ACC_MODE_STANDBY,
ACC_MODE_MEASURE,
ACC_MODE_LEVEL, /* level detection */
ACC_MODE_PULSE, /* pulse detection */
} acc_mode_t;
typedef enum
{
ACC_RANGE_8G,
ACC_RANGE_2G,
ACC_RANGE_4G,
} acc_range_t;
void acc_init (void);
void acc_read (int8_t *x, int8_t *y, int8_t *z);
void acc_setRange(acc_range_t range);
void acc_setMode(acc_mode_t mode);
#endif /* end __LIGHT_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View File

@@ -0,0 +1,31 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __BASE_EEPROM_H
#define __BASE_EEPROM_H
#define BASE_EEPROM_TOTAL_SIZE 8192
void base_eeprom_init (void);
int16_t base_eeprom_read(uint8_t* buf, uint16_t offset, uint16_t len);
int16_t base_eeprom_write(uint8_t* buf, uint16_t offset, uint16_t len);
#endif /* end __BASE_EEPROM_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View File

@@ -0,0 +1,37 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __JOYSTICK_H
#define __JOYSTICK_H
#define JOYSTICK_CENTER 0x01
#define JOYSTICK_UP 0x02
#define JOYSTICK_DOWN 0x04
#define JOYSTICK_LEFT 0x08
#define JOYSTICK_RIGHT 0x10
void joystick_init (void);
uint8_t joystick_read(void);
#endif /* end __JOYSTICK_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View File

@@ -0,0 +1,29 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __LM75A_H
#define __LM75A_H
void lm75a_init (void);
int32_t lm75a_readTemp(void);
#endif /* end __LM75A_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View File

@@ -0,0 +1,30 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __MEMREG_H
#define __MEMREG_H
#define MEMREG_BASE 0x1e000000
extern uint32_t memreg_init (void);
#endif /* end __MEMREG_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View File

@@ -0,0 +1,56 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __NORFLASH_H
#define __NORFLASH_H
#define NORFLASH_SIZE 0x400000 /*Bytes or 0x200000 16bit words*/
#define NORFLASH_BLOCK_SIZE 0x10000 /*Bytes, or 32K 16bit words*/
#define NORFLASH_BASE 0x1C000000
//16 bit data
#define GET_ADDR(addr) (volatile uint16_t *)(NORFLASH_BASE | ((addr) << 1))
typedef struct
{
uint32_t device_size; /* Device size in bytes */
uint32_t num_sectors; /* Number of sectors */
uint32_t sector_size; /* Sector size in bytes */
uint32_t num_blocks; /* Number of blocks */
uint32_t block_size; /* Block size in bytes */
} geometry_t;
extern uint32_t norflash_init(void);
extern void norflash_getGeometry(geometry_t* geometry);
extern uint32_t norflash_eraseBlock(uint32_t addr);
extern uint32_t norflash_eraseSector(uint32_t addr);
extern uint32_t norflash_eraseEntireChip(void);
extern uint32_t norflash_writeWord(uint32_t addr, uint16_t data);
extern uint32_t norflash_writeBuff(uint32_t addr, uint16_t* data, uint16_t len);
extern void norflash_secid_read(uint16_t SST_SecID[8], uint16_t user_SecID[8]);
extern uint32_t norflash_secid_getLockStatus(void);
extern uint32_t norflash_secid_lockOut(void);
extern uint32_t norflash_secid_writeWord(uint16_t target, uint16_t* data, uint16_t len);
#endif /* end __NORFLASH_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View File

@@ -0,0 +1,94 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
#ifndef __PCA9532C_H
#define __PCA9532C_H
#define PCA9532_I2C_ADDR (0x60)
#define PCA9532_INPUT0 0x00
#define PCA9532_INPUT1 0x01
#define PCA9532_PSC0 0x02
#define PCA9532_PWM0 0x03
#define PCA9532_PSC1 0x04
#define PCA9532_PWM1 0x05
#define PCA9532_LS0 0x06
#define PCA9532_LS1 0x07
#define PCA9532_LS2 0x08
#define PCA9532_LS3 0x09
#define PCA9532_AUTO_INC 0x10
/*
* The Keys on the base board are mapped to LED0 -> LED3 on
* the PCA9532.
*/
#define KEY1 0x0001
#define KEY2 0x0002
#define KEY3 0x0004
#define KEY4 0x0008
#define KEY_MASK 0x000F
/*
* MMC Card Detect and MMC Write Protect are mapped to LED4
* and LED5 on the PCA9532. Please note that WP is active low.
*/
#define MMC_CD 0x0010
#define MMC_WP 0x0020
#define MMC_MASK 0x30
/* NOTE: LED6 and LED7 on PCA9532 are not connected to anything */
#define PCA9532_NOT_USED 0xC0
/*
* Below are the LED constants to use when enabling/disabling a LED.
* The LED names are the names printed on the base board and not
* the names from the PCA9532 device. base_LED1 -> LED8 on PCA9532,
* base_LED2 -> LED9, and so on.
*/
#define LED1 0x0100
#define LED2 0x0200
#define LED3 0x0400
#define LED4 0x0800
#define LED5 0x1000
#define LED6 0x2000
#define LED7 0x4000
#define LED8 0x8000
#define LED_MASK 0xFF00
void pca9532_init (void);
uint16_t pca9532_getLedState (uint32_t shadow);
void pca9532_setLeds (uint16_t ledOnMask, uint16_t ledOffMask);
void pca9532_setBlink0Period(uint8_t period);
void pca9532_setBlink0Duty(uint8_t duty);
void pca9532_setBlink0Leds(uint16_t ledMask);
void pca9532_setBlink1Period(uint8_t period);
void pca9532_setBlink1Duty(uint8_t duty);
void pca9532_setBlink1Leds(uint16_t ledMask);
#endif /* end __PCA9532C_H */
/****************************************************************************
** End Of File
*****************************************************************************/

View File

@@ -0,0 +1,93 @@
#ifndef _UDA1380_H_
#define _UDA1380_H_
#include "lpc_types.h"
#define UDA1380_SYSCLK_USED 0
#define UDA1380_SLAVE_ADDR 0x1A
#define UDA1380_CMD_BUFF_SIZE 3
/** UDA1380 Registers */
#define UDA1380_REG_EVALCLK 0x00
#define UDA1380_REG_I2S 0x01
#define UDA1380_REG_PWRCTRL 0x02
#define UDA1380_REG_ANAMIX 0x03
#define UDA1380_REG_HEADAMP 0x04
#define UDA1380_REG_MSTRVOL 0x10
#define UDA1380_REG_MIXVOL 0x11
#define UDA1380_REG_MODEBBT 0x12
#define UDA1380_REG_MSTRMUTE 0x13
#define UDA1380_REG_MIXSDO 0x14
#define UDA1380_REG_DECVOL 0x20
#define UDA1380_REG_PGA 0x21
#define UDA1380_REG_ADC 0x22
#define UDA1380_REG_AGC 0x23
#define UDA1380_REG_L3 0x7f
#define UDA1380_REG_HEADPHONE 0x18
#define UDA1380_REG_DEC 0x28
// UDA1380_REG_EVALCLK bit defines
#define EVALCLK_ADC_EN 0x0800 // Enable ADC clock
#define EVALCLK_DEC_EN 0x0400 // Enable decimator clock
#define EVALCLK_DAC_EN 0x0200 // Enable DAC clock
#define EVALCLK_INT_EN 0x0100 // Enable interpolator clock
#define EVALCLK_ADC_SEL_WSPLL 0x0020 // Select SYSCLK input for ADC clock
#define EVALCLK_ADC_SEL_SYSCLK 0x0000 // Select WSPLL clock for ADC clock
#define EVALCLK_DAC_SEL_WSPLL 0x0010 // Select SYSCLK input for DAC clock
#define EVALCLK_DAC_SEL_SYSCLK 0x0000 // Select WSPLL clock for DAC clock
#define EVALCLK_SYSDIV_SEL(n) ((n) << 2) // System clock input divider select
#define EVALCLK_WSPLL_SEL6_12K 0x0000 // WSPLL input freq selection = 6.25 to 12.5K
#define EVALCLK_WSPLL_SEL12_25K 0x0001 // WSPLL input freq selection = 12.5K to 25K
#define EVALCLK_WSPLL_SEL25_50K 0x0002 // WSPLL input freq selection = 25K to 50K
#define EVALCLK_WSPLL_SEL50_100K 0x0003 // WSPLL input freq selection = 50K to 100K
// UDA1380_REG_I2S
#define I2S_SFORI_I2S 0x0000
#define I2S_SFORI_LSB16 0x0100
#define I2S_SFORI_LSB18 0x0200
#define I2S_SFORI_LSB20 0x0300
#define I2S_SFORI_MSB 0x0500
#define I2S_SFORI_MASK 0x0700
#define I2S_SFORO_I2S 0x0000
#define I2S_SFORO_LSB16 0x0001
#define I2S_SFORO_LSB18 0x0002
#define I2S_SFORO_LSB20 0x0003
#define I2S_SFORO_LSB24 0x0004
#define I2S_SFORO_MSB 0x0005
#define I2S_SFORO_MASK 0x0007
#define I2S_SEL_SOURCE 0x0040
#define I2S_SIM 0x0010
// UDA1380_REG_PWRCTRL bit defines
#define PWR_PON_PLL_EN 0x8000 // WSPLL enable
#define PWR_PON_HP_EN 0x2000 // Headphone driver enable
#define PWR_PON_DAC_EN 0x0400 // DAC power enable
#define PWR_PON_BIAS_EN 0x0100 // Power on bias enable (for ADC, AVC, and FSDAC)
#define PWR_EN_AVC_EN 0x0080 // Analog mixer enable
#define PWR_PON_AVC_EN 0x0040 // Analog mixer power enable
#define PWR_EN_LNA_EN 0x0010 // LNA and SDC power enable
#define PWR_EN_PGAL_EN 0x0008 // PGA left power enable
#define PWR_EN_ADCL_EN 0x0004 // ADC left power enable
#define PWR_EN_PGAR_EN 0x0002 // PGA right power enable
#define PWR_EN_ADCR_EN 0x0001 // ADC right power enable
// UDA1380_REG_MSTRMUTE bit defines
#define MSTRMUTE_MTM_MUTE_EN 0x4000 // Master mute enable
#define MSRTMUTE_CHANNEL2_MUTE_EN 0x0800
#define MSRTMUTE_CHANNEL1_MUTE_EN 0x0008
// UDA1380_REG_MODEBBT bit defines
#define MODEBBT_BOOST_FLAT 0x0000 // Bits for selecting flat boost
#define MODEBBT_BOOST_FULL 0xC000 // Bits for selecting maximum boost
#define MODEBBT_BOOST_MASK 0xC000 // Bits for selecting boost mask
#define UDA1380_FUNC_OK 0
#define UDA1380_FUNC_ERR -1
int32_t Uda1380_Init(uint32_t i2cClockFreq, uint32_t i2sClockFreq);
int32_t Uda1380_WriteData(uint8_t reg, uint16_t data);
int32_t Uda1380_ReadData(uint8_t reg, uint16_t *data);
#endif /* _UDA1380_H_ */

View File

@@ -0,0 +1,251 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/******************************************************************************
* Includes
*****************************************************************************/
#include "lpc_types.h"
#include "lpc43xx_i2c.h"
#include "../inc/acc.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
#define I2C_PORT (LPC_I2C0)
#define ACC_I2C_ADDR (0x1D)
#define ACC_ADDR_XOUTL 0x00
#define ACC_ADDR_XOUTH 0x01
#define ACC_ADDR_YOUTL 0x02
#define ACC_ADDR_YOUTX 0x03
#define ACC_ADDR_ZOUTL 0x04
#define ACC_ADDR_ZOUTH 0x05
#define ACC_ADDR_XOUT8 0x06
#define ACC_ADDR_YOUT8 0x07
#define ACC_ADDR_ZOUT8 0x08
#define ACC_ADDR_STATUS 0x09
#define ACC_ADDR_DETSRC 0x0A
#define ACC_ADDR_TOUT 0x0B
#define ACC_ADDR_I2CAD 0x0D
#define ACC_ADDR_USRINF 0x0E
#define ACC_ADDR_WHOAMI 0x0F
#define ACC_ADDR_XOFFL 0x10
#define ACC_ADDR_XOFFH 0x11
#define ACC_ADDR_YOFFL 0x12
#define ACC_ADDR_YOFFH 0x13
#define ACC_ADDR_ZOFFL 0x14
#define ACC_ADDR_ZOFFH 0x15
#define ACC_ADDR_MCTL 0x16
#define ACC_ADDR_INTRST 0x17
#define ACC_ADDR_CTL1 0x18
#define ACC_ADDR_CTL2 0x19
#define ACC_ADDR_LDTH 0x1A
#define ACC_ADDR_PDTH 0x1B
#define ACC_ADDR_PW 0x1C
#define ACC_ADDR_LT 0x1D
#define ACC_ADDR_TW 0x1E
#define ACC_MCTL_MODE(m) ((m) << 0)
#define ACC_MCTL_GLVL(g) ((g) << 2)
#define ACC_STATUS_DRDY 0x01
#define ACC_STATUS_DOVR 0x02
#define ACC_STATUS_PERR 0x04
/******************************************************************************
* External global variables
*****************************************************************************/
/******************************************************************************
* Local variables
*****************************************************************************/
static Status I2CWrite(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = buf;
i2cData.tx_length = len;
i2cData.rx_data = NULL;
i2cData.rx_length = 0;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
static Status I2CRead(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = NULL;
i2cData.tx_length = 0;
i2cData.rx_data = buf;
i2cData.rx_length = len;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
static uint8_t getStatus(void)
{
uint8_t buf[1];
buf[0] = ACC_ADDR_STATUS;
I2CWrite(ACC_I2C_ADDR, buf, 1);
I2CRead(ACC_I2C_ADDR, buf, 1);
return buf[0];
}
static uint8_t getModeControl(void)
{
uint8_t buf[1];
buf[0] = ACC_ADDR_MCTL;
I2CWrite(ACC_I2C_ADDR, buf, 1);
I2CRead(ACC_I2C_ADDR, buf, 1);
return buf[0];
}
static void setModeControl(uint8_t mctl)
{
uint8_t buf[2];
buf[0] = ACC_ADDR_MCTL;
buf[1] = mctl;
I2CWrite(ACC_I2C_ADDR, buf, 2);
}
/******************************************************************************
* Local Functions
*****************************************************************************/
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the ISL29003 Device
*
*****************************************************************************/
void acc_init (void)
{
/* set to measurement mode by default */
setModeControl( (ACC_MCTL_MODE(ACC_MODE_MEASURE)
| ACC_MCTL_GLVL(ACC_RANGE_2G) ));
}
/******************************************************************************
*
* Description:
* Read accelerometer data
*
* Params:
* [out] x - read x value
* [out] y - read y value
* [out] z - read z value
*
*****************************************************************************/
void acc_read (int8_t *x, int8_t *y, int8_t *z)
{
uint8_t buf[1];
/* wait for ready flag */
while ((getStatus() & ACC_STATUS_DRDY) == 0);
/*
* Have experienced problems reading all registers
* at once. Change to reading them one-by-one.
*/
buf[0] = ACC_ADDR_XOUT8;
I2CWrite(ACC_I2C_ADDR, buf, 1);
I2CRead(ACC_I2C_ADDR, buf, 1);
*x = (int8_t)buf[0];
buf[0] = ACC_ADDR_YOUT8;
I2CWrite(ACC_I2C_ADDR, buf, 1);
I2CRead(ACC_I2C_ADDR, buf, 1);
*y = (int8_t)buf[0];
buf[0] = ACC_ADDR_ZOUT8;
I2CWrite(ACC_I2C_ADDR, buf, 1);
I2CRead(ACC_I2C_ADDR, buf, 1);
*z = (int8_t)buf[0];
}
/******************************************************************************
*
* Description:
* Set the g-Range
*
* Params:
* [in] range - the g-Range
*
*****************************************************************************/
void acc_setRange(acc_range_t range)
{
uint8_t mctl = 0;
mctl = getModeControl();
mctl &= ~(0x03 << 2);
mctl |= ACC_MCTL_GLVL(range);
setModeControl(mctl);
}
/******************************************************************************
*
* Description:
* Set sensor mode
*
* Params:
* [in] mode - the mode to set
*
*****************************************************************************/
void acc_setMode(acc_mode_t mode)
{
uint8_t mctl = 0;
mctl = getModeControl();
mctl &= ~(0x03 << 0);
mctl |= ACC_MCTL_MODE(mode);
setModeControl(mctl);
}

View File

@@ -0,0 +1,195 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/*
* NOTE: I2C must have been initialized before calling any functions in this
* file.
*/
/******************************************************************************
* Includes
*****************************************************************************/
#include <string.h>
#include <stdio.h>
#include "lpc_types.h"
#include "lpc43xx_i2c.h"
#include "../inc/base_eeprom.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
#define I2C_PORT (LPC_I2C0)
#ifndef MIN
#define MIN(x, y) ((x) < (y) ? (x) : (y))
#endif
#define EEPROM_I2C_ADDR (0x57)
#define EEPROM_PAGE_SIZE 32
/******************************************************************************
* External global variables
*****************************************************************************/
/******************************************************************************
* Local variables
*****************************************************************************/
/******************************************************************************
* Local Functions
*****************************************************************************/
static void eepromDelay(void)
{
volatile int i = 0;
for (i = 0; i <0x20000; i++);
}
static Status I2CWrite(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = buf;
i2cData.tx_length = len;
i2cData.rx_data = NULL;
i2cData.rx_length = 0;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
static Status I2CRead(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = NULL;
i2cData.tx_length = 0;
i2cData.rx_data = buf;
i2cData.rx_length = len;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the EEPROM Driver
*
*****************************************************************************/
void base_eeprom_init (void)
{
I2C_Cmd(I2C_PORT, ENABLE);
}
/******************************************************************************
*
* Description:
* Read from the EEPROM
*
* Params:
* [in] buf - read buffer
* [in] offset - offset to start to read from
* [in] len - number of bytes to read
*
* Returns:
* number of read bytes or -1 in case of an error
*
*****************************************************************************/
int16_t base_eeprom_read(uint8_t* buf, uint16_t offset, uint16_t len)
{
uint8_t addr = 0;
int i = 0;
uint8_t off[2];
if (len > BASE_EEPROM_TOTAL_SIZE || offset+len > BASE_EEPROM_TOTAL_SIZE) {
return -1;
}
addr = EEPROM_I2C_ADDR;
off[0] = ((offset >> 8) & 0xff);
off[1] = (offset & 0xff);
I2CWrite((addr << 1), off, 2);
for ( i = 0; i < 0x2000; i++);
I2CRead((addr << 1), buf, len);
return len;
}
/******************************************************************************
*
* Description:
* Write to the EEPROM
*
* Params:
* [in] buf - data to write
* [in] offset - offset to start to write to
* [in] len - number of bytes to write
*
* Returns:
* number of written bytes or -1 in case of an error
*
*****************************************************************************/
int16_t base_eeprom_write(uint8_t* buf, uint16_t offset, uint16_t len)
{
uint8_t addr = 0;
int16_t written = 0;
uint16_t wLen = 0;
uint16_t off = offset;
uint8_t tmp[EEPROM_PAGE_SIZE+2];
if (len > BASE_EEPROM_TOTAL_SIZE || offset+len > BASE_EEPROM_TOTAL_SIZE) {
return -1;
}
addr = EEPROM_I2C_ADDR;
wLen = EEPROM_PAGE_SIZE - (off % EEPROM_PAGE_SIZE);
wLen = MIN(wLen, len);
while (len) {
tmp[0] = ((off >> 8) & 0xff);
tmp[1] = (off & 0xff);
memcpy(&tmp[2], (void*)&buf[written], wLen);
I2CWrite((addr << 1), tmp, wLen+2);
/* delay to wait for a write cycle */
eepromDelay();
len -= wLen;
written += wLen;
off += wLen;
wLen = MIN(EEPROM_PAGE_SIZE, len);
}
return written;
}

View File

@@ -0,0 +1,155 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/******************************************************************************
* Includes
*****************************************************************************/
#include "lpc_types.h"
#include "lpc43xx_gpio.h"
#include "lpc43xx_scu.h"
#include "../inc/joystick.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
#define GPIO_PIN_LEFT (1<<9)
#define GPIO_PIN_RIGHT (1<<12)
#define GPIO_PIN_UP (1<<10)
#define GPIO_PIN_DOWN (1<<13)
#define GPIO_PIN_CENTER (1<<8)
#define GPIO_PORT 4
/******************************************************************************
* External global variables
*****************************************************************************/
// TODO move later
/* Pin mode defines, more in line with the definitions in the LPC1800/4300 user manual */
/* Defines for SFSPx_y pin configuration registers */
#define PDN_ENABLE (1 << 3) // Pull-down enable
#define PDN_DISABLE (0 << 3) // Pull-down disable
#define PUP_ENABLE (0 << 4) // Pull-up enable
#define PUP_DISABLE (1 << 4) // Pull-up disable
#define SLEWRATE_SLOW (0 << 5) // Slew rate for low noise with medium speed
#define SLEWRATE_FAST (1 << 5) // Slew rate for medium noise with fast speed
#define INBUF_ENABLE (1 << 6) // Input buffer
#define INBUF_DISABLE (0 << 6) // Input buffer
#define FILTER_ENABLE (0 << 7) // Glitch filter (for signals below 30MHz)
#define FILTER_DISABLE (1 << 7) // No glitch filter (for signals above 30MHz)
#define DRIVE_8MA (1 << 8) // Drive strength of 8mA
#define DRIVE_14MA (1 << 9) // Drive strength of 14mA
#define DRIVE_20MA (3 << 8) // Drive strength of 20mA
/* Configuration examples for various I/O pins */
#define EMC_IO (PUP_ENABLE | PDN_ENABLE | SLEWRATE_FAST | INBUF_ENABLE | FILTER_DISABLE)
#define LCD_PINCONFIG (PUP_DISABLE | PDN_DISABLE | SLEWRATE_FAST | INBUF_ENABLE | FILTER_DISABLE)
#define CLK_IN (PUP_ENABLE | PDN_ENABLE | SLEWRATE_FAST | INBUF_ENABLE | FILTER_DISABLE)
#define CLK_OUT (PUP_ENABLE | PDN_ENABLE | SLEWRATE_FAST | INBUF_ENABLE | FILTER_DISABLE)
#define GPIO_PUP (PUP_ENABLE | PDN_DISABLE | SLEWRATE_SLOW | INBUF_ENABLE | FILTER_ENABLE )
#define GPIO_PDN (PUP_DISABLE | PDN_ENABLE | SLEWRATE_SLOW | INBUF_ENABLE | FILTER_ENABLE )
#define GPIO_NOPULL (PUP_DISABLE | PDN_DISABLE | SLEWRATE_SLOW | INBUF_ENABLE | FILTER_ENABLE )
#define UART_RX_TX (PUP_DISABLE | PDN_ENABLE | SLEWRATE_SLOW | INBUF_ENABLE | FILTER_ENABLE )
#define SSP_IO (PUP_ENABLE | PDN_ENABLE | SLEWRATE_FAST | INBUF_ENABLE | FILTER_DISABLE)
/******************************************************************************
* Local variables
*****************************************************************************/
/******************************************************************************
* Local Functions
*****************************************************************************/
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the Joystick Driver
*
*****************************************************************************/
void joystick_init (void)
{
/* set to GPIO function for the 5 pins used with the joystick */
scu_pinmux( 0xa , 1 , GPIO_NOPULL , FUNC0 );//GPIO4[8]
scu_pinmux( 0xa , 2 , GPIO_NOPULL , FUNC0 );//GPIO4[9]
scu_pinmux( 0xa , 3 , GPIO_NOPULL , FUNC0 );//GPIO4[10]
scu_pinmux( 0x9 , 0 , GPIO_NOPULL , FUNC0 );//GPIO4[12]
scu_pinmux( 0x9 , 1 , GPIO_NOPULL , FUNC0 );//GPIO4[13]
/* set the pins as inputs */
GPIO_SetDir(GPIO_PORT, GPIO_PIN_LEFT, 0);
GPIO_SetDir(GPIO_PORT, GPIO_PIN_RIGHT, 0);
GPIO_SetDir(GPIO_PORT, GPIO_PIN_UP, 0);
GPIO_SetDir(GPIO_PORT, GPIO_PIN_DOWN, 0);
GPIO_SetDir(GPIO_PORT, GPIO_PIN_CENTER, 0);
}
/******************************************************************************
*
* Description:
* Read the joystick status
*
* Returns:
* The joystick status. The returned value is a bit mask. More than one
* direction may be active at any given time (e.g. UP and RIGHT)
*
*****************************************************************************/
uint8_t joystick_read(void)
{
uint8_t status = 0;
uint32_t pinVal = 0;
pinVal = GPIO_ReadValue(GPIO_PORT);
pinVal = pinVal;
if ((pinVal & GPIO_PIN_DOWN) == 0) {
status |= JOYSTICK_DOWN;
}
if ((pinVal & GPIO_PIN_RIGHT) == 0) {
status |= JOYSTICK_RIGHT;
}
if ((pinVal & GPIO_PIN_UP) == 0) {
status |= JOYSTICK_UP;
}
if ((pinVal & GPIO_PIN_LEFT) == 0) {
status |= JOYSTICK_LEFT;
}
if ((pinVal & GPIO_PIN_CENTER) == 0) {
status |= JOYSTICK_CENTER;
}
return status;
}

View File

@@ -0,0 +1,128 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/*
* NOTE: I2C must have been initialized before calling any functions in this
* file.
*/
/******************************************************************************
* Includes
*****************************************************************************/
#include <string.h>
#include <stdio.h>
#include "lpc_types.h"
#include "lpc43xx_i2c.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
#define I2C_PORT (LPC_I2C0)
#define LM75A_I2C_ADDR (0x48)
#define LM75A_CMD_TEMP 0x00
#define I2CDEV LPC_I2C2
/******************************************************************************
* External global variables
*****************************************************************************/
/******************************************************************************
* Local variables
*****************************************************************************/
/******************************************************************************
* Local Functions
*****************************************************************************/
static Status I2CWrite(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = buf;
i2cData.tx_length = len;
i2cData.rx_data = NULL;
i2cData.rx_length = 0;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
static Status I2CRead(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = NULL;
i2cData.tx_length = 0;
i2cData.rx_data = buf;
i2cData.rx_length = len;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the EEPROM Driver
*
*****************************************************************************/
void lm75a_init (void)
{
}
/******************************************************************************
*
* Description:
* Read the temperature
*
* Params: None
*
* Returns:
* The measured temperature x 100, i.e. 26.50 degrees returned as 2650
*
*****************************************************************************/
int32_t lm75a_readTemp(void)
{
uint8_t temp[2];
int16_t t = 0;
I2CWrite(LM75A_I2C_ADDR, LM75A_CMD_TEMP, 1);
I2CRead(LM75A_I2C_ADDR, temp, 2);
/* 11 MSB bits used. Celcius is calculated as Temp data * 1/8 */
t = ((temp[0] << 8) | (temp[1]));
return ((t * 100) >> 8);
}

View File

@@ -0,0 +1,170 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/******************************************************************************
* Includes
*****************************************************************************/
#include "lpc43xx.h"
#include "lpc_types.h"
#include "lpc43xx_scu.h"
#include "../inc/memreg.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
/******************************************************************************
* External global variables
*****************************************************************************/
/******************************************************************************
* Local variables
*****************************************************************************/
static void pinConfig(void)
{
/* Set up EMC pin */
scu_pinmux( 2 , 9 , MD_PLN_FAST , 3 );//A0
scu_pinmux( 2 , 10 , MD_PLN_FAST , 3 );//A1
scu_pinmux( 2 , 11 , MD_PLN_FAST , 3 );//A2
scu_pinmux( 2 , 12 , MD_PLN_FAST , 3 );//A3
scu_pinmux( 2 , 13 , MD_PLN_FAST , 3 );//A4
scu_pinmux( 1 , 0 , MD_PLN_FAST , 2 );//A5
scu_pinmux( 1 , 1 , MD_PLN_FAST , 2 );//A6
scu_pinmux( 1 , 2 , MD_PLN_FAST , 2 );//A7
scu_pinmux( 2 , 8 , MD_PLN_FAST , 3 );//A8
scu_pinmux( 2 , 7 , MD_PLN_FAST , 3 );//A9
scu_pinmux( 2 , 6 , MD_PLN_FAST , 2 );//A10
scu_pinmux( 2 , 2 , MD_PLN_FAST , 2 );//A11
scu_pinmux( 2 , 1 , MD_PLN_FAST , 2 );//A12
scu_pinmux( 2 , 0 , MD_PLN_FAST , 2 );//A13
scu_pinmux( 6 , 8 , MD_PLN_FAST , 1 );//A14
scu_pinmux( 6 , 7 , MD_PLN_FAST , 1 );//A15
scu_pinmux( 13 , 16 , MD_PLN_FAST , 2 );//A16
scu_pinmux( 13 , 15 , MD_PLN_FAST , 2 );//A17
scu_pinmux( 14 , 0 , MD_PLN_FAST , 3 );//A18
scu_pinmux( 14 , 1 , MD_PLN_FAST , 3 );//A19
scu_pinmux( 14 , 2 , MD_PLN_FAST , 3 );//A20
scu_pinmux( 14 , 3 , MD_PLN_FAST , 3 );//A21
scu_pinmux( 14 , 4 , MD_PLN_FAST , 3 );//A22
scu_pinmux( 10 , 4 , MD_PLN_FAST , 3 );//A23
scu_pinmux( 1 , 7 , MD_PLN_FAST , 3 );//D0
scu_pinmux( 1 , 8 , MD_PLN_FAST , 3 );//D1
scu_pinmux( 1 , 9 , MD_PLN_FAST , 3 );//D2
scu_pinmux( 1 , 10 , MD_PLN_FAST , 3 );//D3
scu_pinmux( 1 , 11 , MD_PLN_FAST , 3 );//D4
scu_pinmux( 1 , 12 , MD_PLN_FAST , 3 );//D5
scu_pinmux( 1 , 13 , MD_PLN_FAST , 3 );//D6
scu_pinmux( 1 , 14 , MD_PLN_FAST , 3 );//D7
scu_pinmux( 5 , 4 , MD_PLN_FAST , 2 );//D8
scu_pinmux( 5 , 5 , MD_PLN_FAST , 2 );//D9
scu_pinmux( 5 , 6 , MD_PLN_FAST , 2 );//D10
scu_pinmux( 5 , 7 , MD_PLN_FAST , 2 );//D11
scu_pinmux( 5 , 0 , MD_PLN_FAST , 2 );//D12
scu_pinmux( 5 , 1 , MD_PLN_FAST , 2 );//D13
scu_pinmux( 5 , 2 , MD_PLN_FAST , 2 );//D14
scu_pinmux( 5 , 3 , MD_PLN_FAST , 2 );//D15
scu_pinmux( 13 , 2 , MD_PLN_FAST , 2 );//D16
scu_pinmux( 13 , 3 , MD_PLN_FAST , 2 );//D17
scu_pinmux( 13 , 4 , MD_PLN_FAST , 2 );//D18
scu_pinmux( 13 , 5 , MD_PLN_FAST , 2 );//D19
scu_pinmux( 13 , 6 , MD_PLN_FAST , 2 );//D20
scu_pinmux( 13 , 7 , MD_PLN_FAST , 2 );//D21
scu_pinmux( 13 , 8 , MD_PLN_FAST , 2 );//D22
scu_pinmux( 13 , 9 , MD_PLN_FAST , 2 );//D23
scu_pinmux( 14 , 5 , MD_PLN_FAST , 3 );//D24
scu_pinmux( 14 , 6 , MD_PLN_FAST , 3 );//D25
scu_pinmux( 14 , 7 , MD_PLN_FAST , 3 );//D26
scu_pinmux( 14 , 8 , MD_PLN_FAST , 3 );//D27
scu_pinmux( 14 , 9 , MD_PLN_FAST , 3 );//D28
scu_pinmux( 14 , 10 , MD_PLN_FAST , 3 );//D29
scu_pinmux( 14 , 11 , MD_PLN_FAST , 3 );//D30
scu_pinmux( 14 , 12 , MD_PLN_FAST , 3 );//D31
scu_pinmux( 1 , 3 , MD_PLN_FAST , 3 );//OE
scu_pinmux( 1 , 6 , MD_PLN_FAST , 3 );//WE
scu_pinmux( 1 , 4 , MD_PLN_FAST , 3 );//BLS0
scu_pinmux( 6 , 6 , MD_PLN_FAST , 1 );//BLS1
scu_pinmux( 13 , 13 , MD_PLN_FAST , 2 );//BLS2
scu_pinmux( 13 , 10 , MD_PLN_FAST , 2 );//BLS3
scu_pinmux( 1 , 5 , MD_PLN_FAST , 3 );//CS0
scu_pinmux( 6 , 3 , MD_PLN_FAST , 3 );//CS1
scu_pinmux( 13 , 12 , MD_PLN_FAST , 2 );//CS2
scu_pinmux( 13 , 11 , MD_PLN_FAST , 2 );//CS3
scu_pinmux( 6 , 4 , MD_PLN_FAST , 3 );//CAS
scu_pinmux( 6 , 5 , MD_PLN_FAST , 3 );//RAS
scu_pinmux( 6 , 9 , MD_PLN_FAST , 3 );//DYCS0
scu_pinmux( 6 , 1 , MD_PLN_FAST , 1 );//DYCS1
scu_pinmux( 13 , 14 , MD_PLN_FAST , 2 );//DYCS2
scu_pinmux( 15 , 14 , MD_PLN_FAST , 3 );//DYCS3
scu_pinmux( 6 , 11 , MD_PLN_FAST , 3 );//CKEOUT0
scu_pinmux( 6 , 2 , MD_PLN_FAST , 1 );//CKEOUT1
scu_pinmux( 13 , 1 , MD_PLN_FAST , 2 );//CKEOUT2
scu_pinmux( 14 , 15 , MD_PLN_FAST , 3 );//CKEOUT3
scu_pinmux( 6 , 12 , MD_PLN_FAST , 3 );//DQMOUT0
scu_pinmux( 6 , 10 , MD_PLN_FAST , 3 );//DQMOUT1
scu_pinmux( 13 , 0 , MD_PLN_FAST , 2 );//DQMOUT2
scu_pinmux( 14 , 13 , MD_PLN_FAST , 3 );//DQMOUT3
}
/******************************************************************************
* Local Functions
*****************************************************************************/
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the NOR Flash
*
*****************************************************************************/
uint32_t memreg_init (void)
{
LPC_EMC->CONTROL = 0x00000001;
LPC_EMC->CONFIG = 0x00000000;
pinConfig();
// Setup for 16-bit access
LPC_EMC->STATICCONFIG2 = 0x00000001;
return FALSE;
}

View File

@@ -0,0 +1,543 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/******************************************************************************
* Includes
*****************************************************************************/
#include "lpc_types.h"
#include "lpc43xx_scu.h"
#include "lpc43xx_timer.h"
#include "../inc/norflash.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
#define CMD_SWID 0x90
#define CMD_CFI_QRY 0x98
#define CMD_ID_EXIT 0xF0
#define CMD_ERASE_BLOCK 0x0050
#define CMD_ERASE_SECTOR 0x0030
#define CMD_ERASE_CHIP 0x0010
#define MAN_ID_SST 0x00BF
#define DEV_ID_SST39VF3201 0x235B
/******************************************************************************
* External global variables
*****************************************************************************/
/******************************************************************************
* Local variables
*****************************************************************************/
static geometry_t chip_info;
/******************************************************************************
* Local Functions
*****************************************************************************/
static void pinConfig(void)
{
/* Set up EMC pin */
scu_pinmux( 2 , 9 , MD_PLN_FAST , 3 );//A0
scu_pinmux( 2 , 10 , MD_PLN_FAST , 3 );//A1
scu_pinmux( 2 , 11 , MD_PLN_FAST , 3 );//A2
scu_pinmux( 2 , 12 , MD_PLN_FAST , 3 );//A3
scu_pinmux( 2 , 13 , MD_PLN_FAST , 3 );//A4
scu_pinmux( 1 , 0 , MD_PLN_FAST , 2 );//A5
scu_pinmux( 1 , 1 , MD_PLN_FAST , 2 );//A6
scu_pinmux( 1 , 2 , MD_PLN_FAST , 2 );//A7
scu_pinmux( 2 , 8 , MD_PLN_FAST , 3 );//A8
scu_pinmux( 2 , 7 , MD_PLN_FAST , 3 );//A9
scu_pinmux( 2 , 6 , MD_PLN_FAST , 2 );//A10
scu_pinmux( 2 , 2 , MD_PLN_FAST , 2 );//A11
scu_pinmux( 2 , 1 , MD_PLN_FAST , 2 );//A12
scu_pinmux( 2 , 0 , MD_PLN_FAST , 2 );//A13
scu_pinmux( 6 , 8 , MD_PLN_FAST , 1 );//A14
scu_pinmux( 6 , 7 , MD_PLN_FAST , 1 );//A15
scu_pinmux( 13 , 16 , MD_PLN_FAST , 2 );//A16
scu_pinmux( 13 , 15 , MD_PLN_FAST , 2 );//A17
scu_pinmux( 14 , 0 , MD_PLN_FAST , 3 );//A18
scu_pinmux( 14 , 1 , MD_PLN_FAST , 3 );//A19
scu_pinmux( 14 , 2 , MD_PLN_FAST , 3 );//A20
scu_pinmux( 14 , 3 , MD_PLN_FAST , 3 );//A21
scu_pinmux( 14 , 4 , MD_PLN_FAST , 3 );//A22
scu_pinmux( 10 , 4 , MD_PLN_FAST , 3 );//A23
scu_pinmux( 1 , 7 , MD_PLN_FAST , 3 );//D0
scu_pinmux( 1 , 8 , MD_PLN_FAST , 3 );//D1
scu_pinmux( 1 , 9 , MD_PLN_FAST , 3 );//D2
scu_pinmux( 1 , 10 , MD_PLN_FAST , 3 );//D3
scu_pinmux( 1 , 11 , MD_PLN_FAST , 3 );//D4
scu_pinmux( 1 , 12 , MD_PLN_FAST , 3 );//D5
scu_pinmux( 1 , 13 , MD_PLN_FAST , 3 );//D6
scu_pinmux( 1 , 14 , MD_PLN_FAST , 3 );//D7
scu_pinmux( 5 , 4 , MD_PLN_FAST , 2 );//D8
scu_pinmux( 5 , 5 , MD_PLN_FAST , 2 );//D9
scu_pinmux( 5 , 6 , MD_PLN_FAST , 2 );//D10
scu_pinmux( 5 , 7 , MD_PLN_FAST , 2 );//D11
scu_pinmux( 5 , 0 , MD_PLN_FAST , 2 );//D12
scu_pinmux( 5 , 1 , MD_PLN_FAST , 2 );//D13
scu_pinmux( 5 , 2 , MD_PLN_FAST , 2 );//D14
scu_pinmux( 5 , 3 , MD_PLN_FAST , 2 );//D15
scu_pinmux( 13 , 2 , MD_PLN_FAST , 2 );//D16
scu_pinmux( 13 , 3 , MD_PLN_FAST , 2 );//D17
scu_pinmux( 13 , 4 , MD_PLN_FAST , 2 );//D18
scu_pinmux( 13 , 5 , MD_PLN_FAST , 2 );//D19
scu_pinmux( 13 , 6 , MD_PLN_FAST , 2 );//D20
scu_pinmux( 13 , 7 , MD_PLN_FAST , 2 );//D21
scu_pinmux( 13 , 8 , MD_PLN_FAST , 2 );//D22
scu_pinmux( 13 , 9 , MD_PLN_FAST , 2 );//D23
scu_pinmux( 14 , 5 , MD_PLN_FAST , 3 );//D24
scu_pinmux( 14 , 6 , MD_PLN_FAST , 3 );//D25
scu_pinmux( 14 , 7 , MD_PLN_FAST , 3 );//D26
scu_pinmux( 14 , 8 , MD_PLN_FAST , 3 );//D27
scu_pinmux( 14 , 9 , MD_PLN_FAST , 3 );//D28
scu_pinmux( 14 , 10 , MD_PLN_FAST , 3 );//D29
scu_pinmux( 14 , 11 , MD_PLN_FAST , 3 );//D30
scu_pinmux( 14 , 12 , MD_PLN_FAST , 3 );//D31
scu_pinmux( 1 , 3 , MD_PLN_FAST , 3 );//OE
scu_pinmux( 1 , 6 , MD_PLN_FAST , 3 );//WE
scu_pinmux( 1 , 4 , MD_PLN_FAST , 3 );//BLS0
scu_pinmux( 6 , 6 , MD_PLN_FAST , 1 );//BLS1
scu_pinmux( 13 , 13 , MD_PLN_FAST , 2 );//BLS2
scu_pinmux( 13 , 10 , MD_PLN_FAST , 2 );//BLS3
scu_pinmux( 1 , 5 , MD_PLN_FAST , 3 );//CS0
scu_pinmux( 6 , 3 , MD_PLN_FAST , 3 );//CS1
scu_pinmux( 13 , 12 , MD_PLN_FAST , 2 );//CS2
scu_pinmux( 13 , 11 , MD_PLN_FAST , 2 );//CS3
}
#if 0
static void getIdString(uint16_t idString[11])
{
int i = 0;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2aaa)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_CFI_QRY;
for (i = 0; i < 11; i++) {
idString[i] = *(GET_ADDR(0x10 + i));
}
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2aaa)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_ID_EXIT;
}
#endif
static void getGeoInfo(uint16_t info[14])
{
int i = 0;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2aaa)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_CFI_QRY;
for (i = 0; i < 14; i++) {
info[i] = *(GET_ADDR(0x27 + i));
}
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2aaa)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_ID_EXIT;
}
static uint32_t getProductId(void)
{
uint16_t manuid = 0;
uint16_t devid = 0;
uint32_t result = 0;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2aaa)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_SWID;
manuid = *(GET_ADDR(0x00));
devid = *(GET_ADDR(0x01));
result = ((manuid << 16) | devid);
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2aaa)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_ID_EXIT;
return result;
}
/******************************************************************************
*
* Description:
* When the SST39VF160x/320x are in the internal Program operation, any
* attempt to read DQ7 will produce the complement of the true data. Once
* the Program operation is completed, DQ7 will produce true data. Note
* that even though DQ7 may have valid data immediately following the
* completion of an internal Write operation, the remaining data outputs
* may still be invalid: valid data on the entire data bus will appear in
* subsequent successive Read cycles after an interval of 1 <20>s. During
* internal Erase operation, any attempt to read DQ7 will produce a '0'.
* Once the internal Erase operation is completed, DQ7 will produce a '1'.
*
* Parameters:
* addr The device address
* data The original (true) data
* timeout Maximum number of loops to delay
*
* Returns:
* TRUE if success
*
*****************************************************************************/
static uint16_t check_data_polling(uint32_t addr, uint16_t data, uint32_t timeout)
{
volatile uint16_t *p = (uint16_t*) addr;
uint16_t true_data = data & 0x80;
int i;
for (i = 0; i < timeout; i++)
{
if ( true_data == (*p &0x80) )
{
TIM_Waitus(1);
return (TRUE);
}
}
return (FALSE);
}
/******************************************************************************
*
* Description:
* During the internal Program or Erase operation, any consecutive attempts
* to read DQ6 will produce alternating <20>1<EFBFBD>s and <20>0<EFBFBD>s, i.e., toggling
* between 1 and 0. When the internal Program or Erase operation is
* completed, the DQ6 bit will stop toggling. The device is then ready
* for the next operation.
*
* Parameters:
* addr The device address
* timeout Maximum number of loops to delay
*
* Returns:
* TRUE if success
*
*****************************************************************************/
static uint16_t check_toggle_ready(uint32_t addr, uint32_t timeout)
{
volatile uint16_t *p = (uint16_t*) addr;
uint16_t predata, currdata;
int i;
predata = *p & 0x40;
for (i = 0; i < timeout; i++)
{
currdata = *p & 0x40;
if (predata == currdata)
{
TIM_Waitus(1);
return (TRUE);
}
predata = currdata;
}
return (FALSE);
}
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the NOR Flash
*
*****************************************************************************/
uint32_t norflash_init()
{
uint32_t prodId = 0;
// LPC_SC->PCONP |= 0x00000800;
LPC_EMC->CONTROL = 0x00000001;
LPC_EMC->CONFIG = 0x00000000;
//Disable Auto-Byte Addressing (on boards designed for LPC24xx)
//LPC_SC->SCS |= 0x00000001;
pinConfig();
LPC_EMC->STATICCONFIG0 = 0x00000081;
LPC_EMC->STATICWAITWEN0 = 0x00000003; /* ( n + 1 ) -> 4 clock cycles */
LPC_EMC->STATICWAITOEN0 = 0x00000003; /* ( n ) -> 0 clock cycles */
LPC_EMC->STATICWAITRD0 = 0x00000006; /* ( n + 1 ) -> 7 clock cycles */
LPC_EMC->STATICWAITPAG0 = 0x00000003; /* ( n + 1 ) -> 4 clock cycles */
LPC_EMC->STATICWAITWR0 = 0x00000005; /* ( n + 2 ) -> 7 clock cycles */
LPC_EMC->STATICWAITTURN0 = 0x00000003; /* ( n + 1 ) -> 4 clock cycles */
#if 0
M32(0x40086400) = 3;//SFSP8_0, pin config P8_0, FUNC3, (PUP_DISABLE | PDN_DISABLE | INBUF_DISABLE | FILTER_ENABLE)
M32(0x40086404) = 3;//SFSP8_1, pin config P8_1, FUNC3, (PUP_DISABLE | PDN_DISABLE | INBUF_DISABLE | FILTER_ENABLE)
M32(0x40086408) = 3;//SFSP8_2, pin config P8_2, FUNC3, (PUP_DISABLE | PDN_DISABLE | INBUF_DISABLE | FILTER_ENABLE)
M32(0x4008640C) = 3;//SFSP8_3, pin config P8_3, FUNC3, (PUP_DISABLE | PDN_DISABLE | SLEWRATE_SLOW | INBUF_DISABLE | FILTER_ENABLE)
M32(0x40086410) = 3;//SFSP8_4, pin config P8_4, FUNC3, (PUP_DISABLE | PDN_DISABLE | SLEWRATE_SLOW | INBUF_DISABLE | FILTER_ENABLE)
M32(0x40086414) = 3;//SFSP8_5, pin config P8_5, FUNC3, (PUP_DISABLE | PDN_DISABLE | SLEWRATE_SLOW | INBUF_DISABLE | FILTER_ENABLE)
M32(0x40086418) = 3;//SFSP8_6, pin config P8_6, FUNC3, (PUP_DISABLE | PDN_DISABLE | SLEWRATE_SLOW | INBUF_DISABLE | FILTER_ENABLE)
M32(0x4008641C) = 3;//SFSP8_7, pin config P8_7, FUNC3, (PUP_DISABLE | PDN_DISABLE | SLEWRATE_SLOW | INBUF_DISABLE | FILTER_ENABLE)
#endif
prodId = getProductId();
if (prodId == ((MAN_ID_SST << 16) | DEV_ID_SST39VF3201)) {
uint16_t info[14];
getGeoInfo(info);
chip_info.device_size = 1 << info[0];
chip_info.num_sectors = ((info[7] << 8) | info[6]) + 1;
chip_info.sector_size = ((info[9] << 8) | info[8]) * 256;
chip_info.num_blocks = ((info[11] << 8) | info[10]) + 1;
chip_info.block_size = ((info[13] << 8) | info[12]) * 256;
return TRUE;
}
return FALSE;
}
void norflash_getGeometry(geometry_t* geometry)
{
*geometry = chip_info;
}
uint32_t norflash_eraseSector(uint32_t addr)
{
volatile uint16_t* p;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x0080;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
p = (uint16_t*) addr;
*p = CMD_ERASE_SECTOR;
return check_data_polling(addr, 0xffff, 500000);
}
uint32_t norflash_eraseBlock(uint32_t addr)
{
volatile uint16_t* p;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x0080;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
p = (uint16_t*) addr;
*p = CMD_ERASE_BLOCK;
return check_toggle_ready(addr, 500000);
}
uint32_t norflash_eraseEntireChip(void)
{
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x0080;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_ERASE_CHIP;
return check_toggle_ready(NORFLASH_BASE, 500000);
}
uint32_t norflash_writeWord(uint32_t addr, uint16_t data)
{
volatile uint16_t *p;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x00A0;
p = (uint16_t*) addr;
*p = data;
return check_toggle_ready(addr, 500000);
}
uint32_t norflash_writeBuff(uint32_t addr, uint16_t* data, uint16_t len)
{
uint16_t i;
for (i = 0; i < len; i++)
{
if (!norflash_writeWord(addr, data[i]))
{
return (FALSE);
}
}
return (TRUE);
}
/******************************************************************************
*
* Description:
* Reads the security information from the chip. For an explanation
* see the user manual.
*
* Parameters:
* SST_SecID The factory programmed security segment
* User_SecID The user defined security segment
*
*****************************************************************************/
void norflash_secid_read(uint16_t SST_SecID[8], uint16_t User_SecID[8])
{
uint16_t i;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x0088;
for (i = 0; i < 7; i++)
{
SST_SecID[i] = *(GET_ADDR(i)); // SST security is 0x00 - 0x07
User_SecID[i] = *(GET_ADDR(i + 0x10)); // User security is 0x10 - 0x17
}
// exit command
*(GET_ADDR(0x5555)) = CMD_ID_EXIT;
}
/******************************************************************************
*
* Description:
* Checks if the user defined security segment has been locked or not.
* See the user manual for more information.
*
* Returns:
* TRUE if the segment is locked
*
*****************************************************************************/
uint32_t norflash_secid_getLockStatus(void)
{
uint16_t status;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x0088;
// read status
status = *(GET_ADDR(0xff));
status &= 0x0008;
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = CMD_ID_EXIT;
if (!status)
return TRUE; // locked
return FALSE; // not locked
}
/******************************************************************************
*
* Description:
* Lock the user security segment. CANNOT BE UNDONE.
* See the user manual for more information.
*
* Returns:
* TRUE if the segment is locked after programming
*
*****************************************************************************/
uint32_t norflash_secid_lockOut()
{
// Code not verified. Use at own risk
#if 0
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x0085;
*(GET_ADDR(0x0 )) = 0x0000; // Write 0x0000 to any address
if (check_toggle_ready(GET_ADDR(0x0), 500000))
{
return norflash_secid_getLockStatus();
}
#endif
return FALSE;
}
/******************************************************************************
*
* Description:
* Writes data to the user security segment (0x0010 - 0x0017).
* See the user manual for more information.
*
* Parameters:
* target Must be in the range 0x10 to 0x17
* data The data to write
* len The number of words to write
*
* Returns:
* TRUE if the programming was successful
*
*****************************************************************************/
uint32_t norflash_secid_writeWord(uint16_t target, uint16_t* data, uint16_t len)
{
// Code not verified. Use at own risk
#if 0
uint16_t i;
if ((target < 0x10) || (target > 0x17))
return FALSE;
if ((len > 8) || ((target + len) > 0x17))
return FALSE;
for (i = 0; i < len; i++)
{
*(GET_ADDR(0x5555)) = 0x00AA;
*(GET_ADDR(0x2AAA)) = 0x0055;
*(GET_ADDR(0x5555)) = 0x00A5;
*(GET_ADDR(target + i)) = data;
data++;
/* Read the toggle bit to detect end-of-programming for User Sec ID.
Do Not use Data# Polling for User_SecID_Word_Program!! */
if (!check_toggle_ready(GET_ADDR(target + i), 500000))
return FALSE;
}
#endif
return TRUE;
}

View File

@@ -0,0 +1,344 @@
/*****************************************************************************
*
* Copyright(C) 2011, Embedded Artists AB
* All rights reserved.
*
******************************************************************************
* Software that is described herein is for illustrative purposes only
* which provides customers with programming information regarding the
* products. This software is supplied "AS IS" without any warranties.
* Embedded Artists AB assumes no responsibility or liability for the
* use of the software, conveys no license or title under any patent,
* copyright, or mask work right to the product. Embedded Artists AB
* reserves the right to make changes in the software without
* notification. Embedded Artists AB also make no representation or
* warranty that such application will be suitable for the specified
* use without further testing or modification.
*****************************************************************************/
/*
* NOTE: I2C must have been initialized before calling any functions in this
* file.
*/
/******************************************************************************
* Includes
*****************************************************************************/
#include "lpc43xx_i2c.h"
#include "lpc43xx_cgu.h"
#include "lpc_types.h"
#include "../inc/pca9532.h"
/******************************************************************************
* Defines and typedefs
*****************************************************************************/
#define I2C_PORT (LPC_I2C0)
#define LS_MODE_ON 0x01
#define LS_MODE_BLINK0 0x02
#define LS_MODE_BLINK1 0x03
/******************************************************************************
* External global variables
*****************************************************************************/
/******************************************************************************
* Local variables
*****************************************************************************/
static uint16_t blink0Shadow = 0;
static uint16_t blink1Shadow = 0;
static uint16_t ledStateShadow = 0;
/******************************************************************************
* Local Functions
*****************************************************************************/
static Status I2CWrite(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = buf;
i2cData.tx_length = len;
i2cData.rx_data = NULL;
i2cData.rx_length = 0;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
static Status I2CRead(uint32_t addr, uint8_t* buf, uint32_t len)
{
I2C_M_SETUP_Type i2cData;
i2cData.sl_addr7bit = addr;
i2cData.tx_data = NULL;
i2cData.tx_length = 0;
i2cData.rx_data = buf;
i2cData.rx_length = len;
i2cData.retransmissions_max = 3;
return I2C_MasterTransferData(I2C_PORT, &i2cData, I2C_TRANSFER_POLLING);
}
static void setLsStates(uint16_t states, uint8_t* ls, uint8_t mode)
{
#define IS_LED_SET(bit, x) ( ( ((x) & (bit)) != 0 ) ? 1 : 0 )
int i = 0;
for (i = 0; i < 4; i++) {
ls[i] |= ( (IS_LED_SET(0x0001, states)*mode << 0)
| (IS_LED_SET(0x0002, states)*mode << 2)
| (IS_LED_SET(0x0004, states)*mode << 4)
| (IS_LED_SET(0x0008, states)*mode << 6) );
states >>= 4;
}
}
static void setLeds(void)
{
uint8_t buf[5];
uint8_t ls[4] = {0,0,0,0};
uint16_t states = ledStateShadow;
/* LEDs in On/Off state */
setLsStates(states, ls, LS_MODE_ON);
/* set the LEDs that should blink */
setLsStates(blink0Shadow, ls, LS_MODE_BLINK0);
setLsStates(blink1Shadow, ls, LS_MODE_BLINK1);
buf[0] = PCA9532_LS0 | PCA9532_AUTO_INC;
buf[1] = ls[0];
buf[2] = ls[1];
buf[3] = ls[2];
buf[4] = ls[3];
I2CWrite(PCA9532_I2C_ADDR, buf, 5);
}
/******************************************************************************
* Public Functions
*****************************************************************************/
/******************************************************************************
*
* Description:
* Initialize the PCA9532 Device
*
*****************************************************************************/
void pca9532_init (void)
{
/* nothing to initialize */
}
/******************************************************************************
*
* Description:
* Get the LED states
*
* Params:
* [in] shadow - TRUE if the states should be retrieved from the shadow
* variables. The shadow variable are updated when any
* of setLeds, setBlink0Leds and/or setBlink1Leds are
* called.
*
* FALSE if the state should be retrieved from the PCA9532
* device. A blinkin LED may be reported as on or off
* depending on the state when calling the function.
*
* Returns:
* A mask where a 1 indicates that a LED is on (or blinking).
*
*****************************************************************************/
uint16_t pca9532_getLedState (uint32_t shadow)
{
uint8_t buf[2];
uint16_t ret = 0;
if (shadow) {
/* a blink LED is reported as on*/
ret = (ledStateShadow | blink0Shadow | blink1Shadow);
}
else {
/*
* A blinking LED may be reported as on or off depending on
* its state when reading the Input register.
*/
buf[0] = PCA9532_INPUT0;
I2CWrite(PCA9532_I2C_ADDR, buf, 1);
I2CRead(PCA9532_I2C_ADDR, buf, 1);
ret = buf[0];
buf[0] = PCA9532_INPUT1;
I2CWrite(PCA9532_I2C_ADDR, buf, 1);
I2CRead(PCA9532_I2C_ADDR, buf, 1);
ret |= (buf[0] << 8);
/* invert since LEDs are active low */
ret = ((~ret) & 0xFFFF);
}
return (ret & ~PCA9532_NOT_USED);
}
/******************************************************************************
*
* Description:
* Set LED states (on or off).
*
* Params:
* [in] ledOnMask - The LEDs that should be turned on. This mask has
* priority over ledOffMask
* [in] ledOffMask - The LEDs that should be turned off.
*
*****************************************************************************/
void pca9532_setLeds (uint16_t ledOnMask, uint16_t ledOffMask)
{
/* turn off leds */
ledStateShadow &= (~(ledOffMask) & 0xffff);
/* ledOnMask has priority over ledOffMask */
ledStateShadow |= ledOnMask;
/* turn off blinking */
blink0Shadow &= (~(ledOffMask) & 0xffff);
blink1Shadow &= (~(ledOffMask) & 0xffff);
setLeds();
}
/******************************************************************************
*
* Description:
* Set the blink period for PWM0. Valid values are 0 - 255 where 0
* means 152 Hz and 255 means 0.59 Hz. A value of 151 means 1 Hz.
*
* Params:
* [in] period - the period for pwm0
*
*****************************************************************************/
void pca9532_setBlink0Period(uint8_t period)
{
uint8_t buf[2];
buf[0] = PCA9532_PSC0;
buf[1] = period;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the duty cycle for PWM0. Valid values are 0 - 100. 25 means the LED
* is on 25% of the period.
*
* Params:
* [in] duty - duty cycle
*
*****************************************************************************/
void pca9532_setBlink0Duty(uint8_t duty)
{
uint8_t buf[2];
uint32_t tmp = duty;
if (tmp > 100) {
tmp = 100;
}
tmp = (256 * tmp)/100;
buf[0] = PCA9532_PWM0;
buf[1] = tmp;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the LEDs that should blink with rate and duty cycle from PWM0.
* Blinking is turned off with pca9532_setLeds.
*
* Params:
* [in] ledMask - LEDs that should blink.
*
*****************************************************************************/
void pca9532_setBlink0Leds(uint16_t ledMask)
{
blink0Shadow |= ledMask;
setLeds();
}
/******************************************************************************
*
* Description:
* Set the blink period for PWM1. Valid values are 0 - 255 where 0
* means 152 Hz and 255 means 0.59 Hz. A value of 151 means 1 Hz.
*
* Params:
* [in] period - The period for PWM1
*
*****************************************************************************/
void pca9532_setBlink1Period(uint8_t period)
{
uint8_t buf[2];
buf[0] = PCA9532_PSC1;
buf[1] = period;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the duty cycle for PWM1. Valid values are 0 - 100. 25 means the LED
* is on 25% of the period.
*
* Params:
* [in] duty - duty cycle.
*
*****************************************************************************/
void pca9532_setBlink1Duty(uint8_t duty)
{
uint8_t buf[2];
uint32_t tmp = duty;
if (tmp > 100) {
tmp = 100;
}
tmp = (256 * tmp)/100;
buf[0] = PCA9532_PWM1;
buf[1] = tmp;
I2CWrite(PCA9532_I2C_ADDR, buf, 2);
}
/******************************************************************************
*
* Description:
* Set the LEDs that should blink with rate and duty cycle from PWM1.
* Blinking is turned off with pca9532_setLeds.
*
* Params:
* [in] ledMask - LEDs that should blink.
*
*****************************************************************************/
void pca9532_setBlink1Leds(uint16_t ledMask)
{
blink1Shadow |= ledMask;
setLeds();
}

View File

@@ -0,0 +1,156 @@
#include "lpc43xx_i2c.h"
#include "lpc43xx_scu.h"
#include "../inc/uda1380.h"
//Uda1380 link to I2C0 only
#define UDA1380_I2C LPC_I2C0
/*********************************************************************//**
* @brief Initialize Uda1380
* @param[in] i2cClockFreq I2C clock frequency that Uda1380 operate
* @param[in] i2sClockFreq I2S bit clock frequency
* @return None
**********************************************************************/
int32_t Uda1380_Init(uint32_t i2cClockFreq, uint32_t i2sClockFreq)
{
int32_t ret;
uint8_t clk;
// // Config Pin for I2C_SDA and I2C_SCL of I2C0
// scu_pinmux( 2 , 3 , MD_PLN_FAST, FUNC1 );
// scu_pinmux( 2 , 4 , MD_PLN_FAST, FUNC1 );
I2C_Init(UDA1380_I2C, i2cClockFreq);
/* Enable I2C1 operation */
I2C_Cmd(UDA1380_I2C, ENABLE);
/* Reset */
ret = Uda1380_WriteData(UDA1380_REG_L3, 0 );
if(ret != UDA1380_FUNC_OK)
return ret;
/* Write clock settings */
ret = Uda1380_WriteData(UDA1380_REG_I2S,0 );
if(ret != UDA1380_FUNC_OK)
return ret;
ret = Uda1380_WriteData(UDA1380_REG_MSTRMUTE,0);
if(ret != UDA1380_FUNC_OK)
return ret;
ret = Uda1380_WriteData(UDA1380_REG_MIXSDO,0);
if(ret != UDA1380_FUNC_OK)
return ret;
#if UDA1380_SYSCLK_USED //Use SYSCLK
ret = Uda1380_WriteData(UDA1380_REG_EVALCLK,
EVALCLK_DEC_EN | EVALCLK_DAC_EN | EVALCLK_INT_EN | EVALCLK_DAC_SEL_SYSCLK );
if(ret != UDA1380_FUNC_OK)
return ret;
ret = Uda1380_WriteData(UDA1380_REG_PWRCTRL,
PWR_PON_HP_EN | PWR_PON_DAC_EN | PWR_PON_BIAS_EN);
if(ret != UDA1380_FUNC_OK)
return ret;
#else //Use WSPLL
if(i2sClockFreq >= 6250 && i2sClockFreq < 12500)
clk = EVALCLK_WSPLL_SEL6_12K;
else if(i2sClockFreq >= 12501 && i2sClockFreq < 25000)
clk = EVALCLK_WSPLL_SEL12_25K;
else if(i2sClockFreq >= 25001 && i2sClockFreq < 50000)
clk = EVALCLK_WSPLL_SEL25_50K;
else if(i2sClockFreq >= 50001 && i2sClockFreq < 100000)
clk = EVALCLK_WSPLL_SEL50_100K;
else
clk= 0;
ret = Uda1380_WriteData(UDA1380_REG_EVALCLK,
EVALCLK_DEC_EN | EVALCLK_DAC_EN | EVALCLK_INT_EN | EVALCLK_DAC_SEL_WSPLL | clk);
if(ret != UDA1380_FUNC_OK)
return ret;
ret = Uda1380_WriteData(UDA1380_REG_PWRCTRL,
PWR_PON_PLL_EN | PWR_PON_HP_EN | PWR_PON_DAC_EN | PWR_PON_BIAS_EN);
if(ret != UDA1380_FUNC_OK)
return ret;
#endif
return UDA1380_FUNC_OK;
}
/*********************************************************************//**
* @brief Write data to a register of Uda1380
* @param[in] reg Register address
* @param[out] data data value.
* @return None
**********************************************************************/
int32_t Uda1380_WriteData(uint8_t reg, uint16_t data)
{
I2C_M_SETUP_Type i2cData;
uint8_t i2cBuf[UDA1380_CMD_BUFF_SIZE];
i2cBuf[0] = reg;
i2cBuf[1] = (data >> 8) & 0xFF;
i2cBuf[2] = data & 0xFF;
i2cData.sl_addr7bit = UDA1380_SLAVE_ADDR;
i2cData.tx_length = UDA1380_CMD_BUFF_SIZE;
i2cData.tx_data = i2cBuf;
i2cData.rx_data = NULL;
i2cData.rx_length = 0;
i2cData.retransmissions_max = 3;
if (I2C_MasterTransferData(UDA1380_I2C, &i2cData, I2C_TRANSFER_POLLING) == SUCCESS)
{
uint16_t dataTmp;
if(Uda1380_ReadData(reg, &dataTmp) != UDA1380_FUNC_OK) {
return UDA1380_FUNC_ERR;
}
if(dataTmp != data)
return UDA1380_FUNC_ERR;
return UDA1380_FUNC_OK;
}
return UDA1380_FUNC_ERR;
}
/*********************************************************************//**
* @brief Read data stored in register of Uda1380
* @param[in] reg Register address
* @param[out] data point to the buffer which is used for storing data.
* @return None
**********************************************************************/
int32_t Uda1380_ReadData(uint8_t reg, uint16_t *data)
{
I2C_M_SETUP_Type i2cData;
uint8_t i2cBuf[UDA1380_CMD_BUFF_SIZE];
if(data == NULL)
return UDA1380_FUNC_ERR;
i2cBuf[0] = reg;
i2cData.sl_addr7bit = UDA1380_SLAVE_ADDR;
i2cData.tx_length = 1;
i2cData.tx_data = i2cBuf;
i2cData.rx_data = &i2cBuf[1];
i2cData.rx_length = UDA1380_CMD_BUFF_SIZE - 1;
i2cData.retransmissions_max = 3;
if (I2C_MasterTransferData(UDA1380_I2C, &i2cData, I2C_TRANSFER_POLLING) == SUCCESS)
{
*data = i2cBuf[1] << 8 | i2cBuf[2];
return UDA1380_FUNC_OK;
}
return UDA1380_FUNC_ERR;
}

View File

@@ -183,4 +183,24 @@ uint32_t board_uart_recv(uint8_t *buffer, uint32_t length)
} }
#endif #endif
/******************************************************************************
*
* Description:
* Initialize the trim potentiometer, i.e. ADC connected to TrimPot on
* Base Board.
*
*****************************************************************************/
//void trimpot_init(void)
//{
// // pinsel for AD0.3 on p7.5
// scu_pinmux( 7 , 5 , PDN_DISABLE | PUP_DISABLE | INBUF_DISABLE, 0 );
// LPC_SCU->ENAIO0 |= (1<<3);
//
// ADC_Init(LPC_ADC0, 400000, 10);
//
// ADC_IntConfig(LPC_ADC0, ADC_ADINTEN2, DISABLE);
// ADC_ChannelCmd(LPC_ADC0, ADC_CH_TRIMPOT, ENABLE);
//}
#endif #endif

View File

@@ -84,7 +84,7 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="NGX|bsp/lpc13uxx|bsp/lpc11uxx" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="bsp/boards/EA4357|NGX|bsp/lpc13uxx|bsp/lpc11uxx" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@@ -175,7 +175,7 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="NGX|bsp/lpc13uxx|bsp/lpc11uxx" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="bsp/boards/EA4357|NGX|bsp/lpc13uxx|bsp/lpc11uxx" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>