ADC, code indentation

- ADC resolution - 12bit, all pins definition
  - code indentation
pull/11/head
0xc0170 2013-07-02 19:34:11 +02:00
parent ed200183d0
commit 90bb8521aa
16 changed files with 76 additions and 92 deletions

View File

@ -1,4 +1,3 @@
LR_IROM1 0x00000000 0x8000 { ; load region size_region (32k)
ER_IROM1 0x00000000 0x8000 { ; load address = execution address
*.o (RESET, +First)
@ -11,4 +10,3 @@ LR_IROM1 0x00000000 0x8000 { ; load region size_region (32k)
.ANY (+RW +ZI)
}
}

View File

@ -1,7 +1,7 @@
/* mbed Microcontroller Library - CMSIS
* Copyright (C) 2009-2011 ARM Limited. All rights reserved.
*
* A generic CMSIS include header, pulling in KL05 specifics
* A generic CMSIS include header, pulling in KL05Z specifics
*/
#ifndef MBED_CMSIS_H

View File

@ -1,4 +1,4 @@
/* mbed Microcontroller Library - cmsis_nvic for LPC11U24
/* mbed Microcontroller Library - cmsis_nvic for KL05Z
* Copyright (c) 2011 ARM Limited. All rights reserved.
*
* CMSIS-style functionality to support dynamic vectors

View File

@ -1,36 +1,21 @@
#include <stdint.h>
#include "MKL05Z4.h"
#define DISABLE_WDOG 1
#define DISABLE_WDOG 1
#define CLOCK_SETUP 0
/* Predefined clock setups
0 ... Multipurpose Clock Generator (MCG) in FLL Engaged Internal (FEI) mode
Multipurpose Clock Generator (MCG) in FLL Engaged Internal (FEI) mode
Reference clock source for MCG module is the slow internal clock source 32.768kHz
Core clock = 47.97MHz, BusClock = 23.48MHz
*/
/*----------------------------------------------------------------------------
Define clock source values
*----------------------------------------------------------------------------*/
#if (CLOCK_SETUP == 0)
#define CPU_XTAL_CLK_HZ 32768u /* Value of the external crystal or oscillator clock frequency in Hz */
#define CPU_INT_SLOW_CLK_HZ 32768u /* Value of the slow internal oscillator clock frequency in Hz */
#define CPU_INT_FAST_CLK_HZ 4000000u /* Value of the fast internal oscillator clock frequency in Hz */
#define DEFAULT_SYSTEM_CLOCK 47972352u /* Default System clock value */
#endif /* (CLOCK_SETUP == 0) */
/* ----------------------------------------------------------------------------
-- Core clock
---------------------------------------------------------------------------- */
#define CPU_XTAL_CLK_HZ 32768u /* Value of the external crystal or oscillator clock frequency in Hz */
#define CPU_INT_SLOW_CLK_HZ 32768u /* Value of the slow internal oscillator clock frequency in Hz */
#define CPU_INT_FAST_CLK_HZ 4000000u /* Value of the fast internal oscillator clock frequency in Hz */
#define DEFAULT_SYSTEM_CLOCK 47972352u /* Default System clock value */
uint32_t SystemCoreClock = DEFAULT_SYSTEM_CLOCK;
/* ----------------------------------------------------------------------------
-- SystemInit()
---------------------------------------------------------------------------- */
void SystemInit(void) {
#if (DISABLE_WDOG)
/* Disable the WDOG module */
@ -46,34 +31,22 @@ void SystemInit(void) {
/* SIM_SOPT1: OSC32KSEL=0 */
SIM->SOPT1 &= (uint32_t)~(uint32_t)(SIM_SOPT1_OSC32KSEL(0x03)); /* System oscillator drives 32 kHz clock for various peripherals */
/* SIM_SOPT2: TPMSRC=2 */
SIM->SOPT2 = (uint32_t)((SIM->SOPT2 & (uint32_t)~(uint32_t)(
SIM_SOPT2_TPMSRC(0x01)
)) | (uint32_t)(
SIM_SOPT2_TPMSRC(0x02)
)); /* Set the TPM clock */
SIM->SOPT2 = (uint32_t)((SIM->SOPT2 & (uint32_t)~(uint32_t)(SIM_SOPT2_TPMSRC(0x01))) |
(uint32_t)(SIM_SOPT2_TPMSRC(0x02))); /* Set the TPM clock */
/* PORTA_PCR3: ISF=0,MUX=0 */
PORTA->PCR[3] &= (uint32_t)~(uint32_t)((PORT_PCR_ISF_MASK | PORT_PCR_MUX(0x07)));
/* MCG_SC: FCRDIV=1 */
MCG->SC = (uint8_t)((MCG->SC & (uint8_t)~(uint8_t)(
MCG_SC_FCRDIV(0x06)
)) | (uint8_t)(
MCG_SC_FCRDIV(0x01)
));
MCG->SC = (uint8_t)((MCG->SC & (uint8_t)~(uint8_t)(MCG_SC_FCRDIV(0x06))) |
(uint8_t)(MCG_SC_FCRDIV(0x01)));
/* Switch to FEI Mode */
/* MCG_C1: CLKS=0,FRDIV=0,IREFS=1,IRCLKEN=1,IREFSTEN=0 */
MCG->C1 = MCG_C1_CLKS(0x00) |
MCG_C1_FRDIV(0x00) |
MCG_C1_IREFS_MASK |
MCG_C1_IRCLKEN_MASK;
MCG->C1 = MCG_C1_CLKS(0x00) | MCG_C1_FRDIV(0x00) |
MCG_C1_IREFS_MASK | MCG_C1_IRCLKEN_MASK;
/* MCG_C2: LOCRE0=0,??=0,RANGE0=0,HGO0=0,EREFS0=0,LP=0,IRCS=1 */
MCG->C2 = (MCG_C2_RANGE0(0x00) | MCG_C2_IRCS_MASK);
/* MCG_C4: DMX32=1,DRST_DRS=1 */
MCG->C4 = (uint8_t)((MCG->C4 & (uint8_t)~(uint8_t)(
MCG_C4_DRST_DRS(0x02)
)) | (uint8_t)(
MCG_C4_DMX32_MASK |
MCG_C4_DRST_DRS(0x01)
));
MCG->C4 = (uint8_t)((MCG->C4 & (uint8_t)~(uint8_t)(MCG_C4_DRST_DRS(0x02))) |
(uint8_t)(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS(0x01)));
/* OSC0_CR: ERCLKEN=1,??=0,EREFSTEN=0,??=0,SC2P=0,SC4P=0,SC8P=0,SC16P=0 */
OSC0->CR = OSC_CR_ERCLKEN_MASK;
while((MCG->S & MCG_S_IREFST_MASK) == 0x00U) { /* Check that the source of the FLL reference clock is the internal reference clock. */
@ -82,13 +55,6 @@ void SystemInit(void) {
}
}
// Make sure we are pulling in the retargeting module at link time
extern int stdio_retargeting_module;
/* ----------------------------------------------------------------------------
-- SystemCoreClockUpdate()
---------------------------------------------------------------------------- */
void SystemCoreClockUpdate(void) {
uint32_t MCGOUTClock;
uint8_t Divider;

View File

@ -35,8 +35,16 @@ typedef enum {
} I2CName;
typedef enum {
ADC0_SE0 = 0,
ADC0_SE1 = 1,
ADC0_SE2 = 2,
ADC0_SE3 = 3,
ADC0_SE4 = 4,
ADC0_SE5 = 5,
ADC0_SE6 = 6,
ADC0_SE7 = 7,
ADC0_SE8 = 8,
ADC0_SE9 = 9,
ADC0_SE10 = 10,
ADC0_SE11 = 11,
ADC0_SE12 = 12,

View File

@ -73,9 +73,9 @@ typedef enum {
PTB19 = 0x104c,
PTB20 = 0x1050,
LED_RED = PTB8,
LED_RED = PTB8,
LED_GREEN = PTB9,
LED_BLUE = PTB10,
LED_BLUE = PTB10,
// mbed original LED naming
LED1 = LED_BLUE,

View File

@ -20,13 +20,23 @@
#include "error.h"
static const PinMap PinMap_ADC[] = {
/* A0-A5 pins */
{PTA0, ADC0_SE12, 0},
{PTA8, ADC0_SE3, 0},
{PTA9, ADC0_SE2, 0},
{PTB8, ADC0_SE11, 0},
{PTB9, ADC0_SE10, 0},
{PTB13, ADC0_SE13, 0},
{NC, NC, 0}
/* Rest of pins ADC Mux */
{PTB2, ADC0_SE4, 0},
{PTB1, ADC0_SE5, 0},
{PTB5, ADC0_SE1, 0},
{PTA12, ADC0_SE0, 0},
{PTB10, ADC0_SE9, 0},
{PTB11, ADC0_SE8, 0},
{PTB7, ADC0_SE7, 0},
{PTB0, ADC0_SE6, 0},
{NC, NC, 0}
};
void analogin_init(analogin_t *obj, PinName pin) {
@ -45,7 +55,7 @@ void analogin_init(analogin_t *obj, PinName pin) {
ADC0->CFG1 = ADC_CFG1_ADLPC_MASK // Low-Power Configuration
| ADC_CFG1_ADIV(3) // Clock Divide Select: (Input Clock)/8
| ADC_CFG1_ADLSMP_MASK // Long Sample Time
| ADC_CFG1_MODE(3) // (16)bits Resolution
| ADC_CFG1_MODE(1) // (12)bits Resolution
| ADC_CFG1_ADICLK(1); // Input Clock: (Bus Clock)/2
ADC0->CFG2 = ADC_CFG2_MUXSEL_MASK // ADxxb channels are selected
@ -68,7 +78,7 @@ uint16_t analogin_read_u16(analogin_t *obj) {
// Wait Conversion Complete
while ((ADC0->SC1[0] & ADC_SC1_COCO_MASK) != ADC_SC1_COCO_MASK);
// Return value
// Return value (12bit !!)
return (uint16_t)ADC0->R[0];
}

View File

@ -55,8 +55,9 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) {
event = (gpio->PDIR & pmask) ? (IRQ_RISE) : (IRQ_FALL);
break;
}
if (event != IRQ_NONE)
if (event != IRQ_NONE) {
irq_handler(id, event);
}
}
}
port->ISFR = mask;
@ -95,7 +96,7 @@ int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32
break;
default:
error("gpio_irq only supported on Port A and D\n");
error("gpio_irq only supported on Port A and B\n");
break;
}
NVIC_SetVector(irq_n, vector);

View File

@ -31,10 +31,11 @@ typedef struct {
} gpio_t;
static inline void gpio_write(gpio_t *obj, int value) {
if (value)
if (value) {
*obj->reg_set = obj->mask;
else
} else {
*obj->reg_clr = obj->mask;
}
}
static inline int gpio_read(gpio_t *obj) {

View File

@ -59,9 +59,9 @@ void i2c_init(i2c_t *obj, PinName sda, PinName scl) {
// enable power
switch ((int)obj->i2c) {
case I2C_0:
SIM->SCGC5 |= SIM_SCGC5_PORTB_MASK;
SIM->SCGC4 |= SIM_SCGC4_I2C0_MASK;
break;
SIM->SCGC5 |= SIM_SCGC5_PORTB_MASK;
SIM->SCGC4 |= SIM_SCGC4_I2C0_MASK;
break;
}
@ -107,8 +107,9 @@ static int timeout_status_poll(i2c_t *obj, uint32_t mask) {
uint32_t i, timeout = 1000;
for (i = 0; i < timeout; i++) {
if (obj->i2c->S & mask)
if (obj->i2c->S & mask) {
return 0;
}
}
return 1;
@ -310,7 +311,6 @@ int i2c_byte_write(i2c_t *obj, int data) {
}
#if DEVICE_I2CSLAVE
void i2c_slave_mode(i2c_t *obj, int enable_slave) {
if (enable_slave) {
// set slave mode
@ -397,5 +397,3 @@ int i2c_slave_write(i2c_t *obj, const char *data, int length) {
void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask) {
obj->i2c->A1 = address & 0xfe;
}
#endif

View File

@ -30,7 +30,9 @@ void pin_function(PinName pin, int function) {
}
void pin_mode(PinName pin, PinMode mode) {
if (pin == (uint32_t)NC) { return; }
if (pin == (uint32_t)NC) {
return;
}
__IO uint32_t* pin_pcr = (__IO uint32_t*)(PORTA_BASE + pin);

View File

@ -54,7 +54,7 @@ void port_mode(port_t *obj, PinMode mode) {
void port_dir(port_t *obj, PinDirection dir) {
switch (dir) {
case PIN_INPUT :
case PIN_INPUT:
*obj->reg_dir &= ~obj->mask;
break;
case PIN_OUTPUT:

View File

@ -63,7 +63,7 @@ void pwmout_init(pwmout_t* obj, PinName pin) {
// default to 20ms: standard for servos, and fine for e.g. brightness control
pwmout_period_ms(obj, 20);
pwmout_write (obj, 0);
pwmout_write(obj, 0);
// Wire pinout
pinmap_pinout(pin, PinMap_PWM);

View File

@ -34,7 +34,7 @@ void rtc_init(void) {
RTC->CR |= RTC_CR_OSCE_MASK;
//delay for OSCE stabilization
for(i=0; i<0x100000; i++);
for(i=0; i<0x1000; i++) __NOP();
// enable counter
RTC->SR |= RTC_SR_TCE_MASK;

View File

@ -210,8 +210,12 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
if (enable) {
switch (irq) {
case RxIrq: obj->uart->C2 |= (UART0_C2_RIE_MASK); break;
case TxIrq: obj->uart->C2 |= (UART0_C2_TIE_MASK); break;
case RxIrq:
obj->uart->C2 |= (UART0_C2_RIE_MASK);
break;
case TxIrq:
obj->uart->C2 |= (UART0_C2_TIE_MASK);
break;
}
NVIC_SetVector(irq_n, vector);
NVIC_EnableIRQ(irq_n);
@ -220,12 +224,20 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
int all_disabled = 0;
SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq);
switch (irq) {
case RxIrq: obj->uart->C2 &= ~(UART0_C2_RIE_MASK); break;
case TxIrq: obj->uart->C2 &= ~(UART0_C2_TIE_MASK); break;
case RxIrq:
obj->uart->C2 &= ~(UART0_C2_RIE_MASK);
break;
case TxIrq:
obj->uart->C2 &= ~(UART0_C2_TIE_MASK);
break;
}
switch (other_irq) {
case RxIrq: all_disabled = (obj->uart->C2 & (UART0_C2_RIE_MASK)) == 0; break;
case TxIrq: all_disabled = (obj->uart->C2 & (UART0_C2_TIE_MASK)) == 0; break;
case RxIrq:
all_disabled = (obj->uart->C2 & (UART0_C2_RIE_MASK)) == 0;
break;
case TxIrq:
all_disabled = (obj->uart->C2 & (UART0_C2_TIE_MASK)) == 0;
break;
}
if (all_disabled)
NVIC_DisableIRQ(irq_n);

View File

@ -20,6 +20,7 @@
/* Prototypes */
static void pit_init(void);
static void lptmr_init(void);
static void lptmr_isr(void);
/* Global variables */
static uint32_t us_ticker_inited = 0;
@ -35,9 +36,6 @@ void us_ticker_init(void) {
lptmr_init();
}
/******************************************************************************
* Timer for us timing.
******************************************************************************/
static void pit_init(void) {
SIM->SCGC6 |= SIM_SCGC6_PIT_MASK; // Clock PIT
PIT->MCR = 0; // Enable PIT
@ -60,15 +58,6 @@ uint32_t us_ticker_read() {
return ~(PIT->CHANNEL[1].CVAL);
}
/******************************************************************************
* Timer Event
*
* It schedules interrupts at given (32bit)us interval of time.
* It is implemented used the 16bit Low Power Timer that remains powered in all
* power modes.
******************************************************************************/
static void lptmr_isr(void);
static void lptmr_init(void) {
/* Clock the timer */
SIM->SCGC5 |= SIM_SCGC5_LPTMR_MASK;
@ -89,7 +78,7 @@ void us_ticker_disable_interrupt(void) {
}
void us_ticker_clear_interrupt(void) {
// we already clear interrupt in lptmr_isr
// we've already cleared interrupt in lptmr_isr
}
static void lptmr_set(unsigned short count) {
@ -113,7 +102,6 @@ static void lptmr_isr(void) {
if (us_ticker_int_counter > 0) {
lptmr_set(0xFFFF);
us_ticker_int_counter--;
} else {
if (us_ticker_int_remainder > 0) {
lptmr_set(us_ticker_int_remainder);