From 1c476012cdc88228ffc38723a36b652fa5c8831d Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Tue, 19 Apr 2011 22:03:42 -0400 Subject: i2c: Various fixes, extensions, documentation. -Fix clock calculations for fast-mode support -Add I2C_REMAP option to remap i2c1 (untested) -Add I2C_BUS_RESET option to reset bus on initialization -Add optional timeout parameter -Doxygen comments -Various cleanup 10-bit slave addressing is untested until I have a device that speaks such. --- libmaple/gpio.c | 14 ++++ libmaple/gpio.h | 30 +++++++ libmaple/i2c.c | 227 ++++++++++++++++++++++++++++++++++++++------------- libmaple/i2c.h | 84 ++++++++++++++----- libmaple/systick.c | 4 +- libmaple/systick.h | 6 +- wirish/wirish_time.h | 2 +- 7 files changed, 286 insertions(+), 81 deletions(-) diff --git a/libmaple/gpio.c b/libmaple/gpio.c index 5484e21..c250f68 100644 --- a/libmaple/gpio.c +++ b/libmaple/gpio.c @@ -174,3 +174,17 @@ void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port) { cr |= gpio_port << shift; *exti_cr = cr; } + +/** + * @brief Remap an alternate function peripheral to a different pin + * mapping + * @param peripheral to remap + */ +void afio_remap(AFIORemapPeripheral p) { + if (p & AFIO_REMAP_USE_MAPR2) { + p &= ~AFIO_REMAP_USE_MAPR2; + AFIO_BASE->MAPR2 |= p; + } else { + AFIO_BASE->MAPR |= p; + } +} diff --git a/libmaple/gpio.h b/libmaple/gpio.h index 353f965..b15124c 100644 --- a/libmaple/gpio.h +++ b/libmaple/gpio.h @@ -315,6 +315,36 @@ typedef enum { #define AFIO_MAPR2_TIM10_REMAP BIT(6) #define AFIO_MAPR2_TIM9_REMAP BIT(5) +/* HACK: Use upper bit to denote MAPR2, Bit 31 is reserved and + * not used in either MAPR or MAPR2 */ +#define AFIO_REMAP_USE_MAPR2 (1 << 31) +typedef enum AFIORemapPeripheral { + AFIO_REMAP_ADC2_ETRGREG = AFIO_MAPR_ADC2_ETRGREG_REMAP, + AFIO_REMAP_ADC2_ETRGINJ = AFIO_MAPR_ADC2_ETRGINJ_REMAP, + AFIO_REMAP_ADC1_ETRGREG = AFIO_MAPR_ADC1_ETRGREG_REMAP, + AFIO_REMAP_ADC1_ETRGINJ = AFIO_MAPR_ADC1_ETRGINJ_REMAP, + AFIO_REMAP_TIM5CH4_I = AFIO_MAPR_TIM5CH4_IREMAP, + AFIO_REMAP_PD01 = AFIO_MAPR_PD01_REMAP, + AFIO_REMAP_CAN = AFIO_MAPR_CAN_REMAP, + AFIO_REMAP_TIM4 = AFIO_MAPR_TIM4_REMAP, + AFIO_REMAP_TIM3 = AFIO_MAPR_TIM3_REMAP, + AFIO_REMAP_TIM2 = AFIO_MAPR_TIM2_REMAP, + AFIO_REMAP_TIM1 = AFIO_MAPR_TIM1_REMAP, + AFIO_REMAP_USART3 = AFIO_MAPR_USART3_REMAP, + AFIO_REMAP_USART2 = AFIO_MAPR_USART2_REMAP, + AFIO_REMAP_USART1 = AFIO_MAPR_USART1_REMAP, + AFIO_REMAP_I2C1 = AFIO_MAPR_I2C1_REMAP, + AFIO_REMAP_SPI1 = AFIO_MAPR_SPI1_REMAP, + AFIO_REMAP_FSMC_NADV = AFIO_MAPR2_FSMC_NADV | AFIO_REMAP_USE_MAPR2, + AFIO_REMAP_TIM14 = AFIO_MAPR2_TIM14_REMAP | AFIO_REMAP_USE_MAPR2, + AFIO_REMAP_TIM13 = AFIO_MAPR2_TIM13_REMAP | AFIO_REMAP_USE_MAPR2, + AFIO_REMAP_TIM11 = AFIO_MAPR2_TIM11_REMAP | AFIO_REMAP_USE_MAPR2, + AFIO_REMAP_TIM10 = AFIO_MAPR2_TIM10_REMAP | AFIO_REMAP_USE_MAPR2, + AFIO_REMAP_TIM9 = AFIO_MAPR2_TIM9_REMAP | AFIO_REMAP_USE_MAPR2 +} AFIORemapPeripheral; + +void afio_remap(AFIORemapPeripheral p); + /* * AFIO convenience routines */ diff --git a/libmaple/i2c.c b/libmaple/i2c.c index f4cb522..5c8ee02 100644 --- a/libmaple/i2c.c +++ b/libmaple/i2c.c @@ -26,7 +26,8 @@ /** * @file i2c.c - * @brief Inter-Integrated Circuit (I2C) support. + * @brief Inter-Integrated Circuit (I2C) support. Currently supports only master + * mode. */ #include "libmaple.h" @@ -36,8 +37,7 @@ #include "nvic.h" #include "i2c.h" #include "string.h" - -static inline int32 wait_for_state_change(i2c_dev *dev, i2c_state state); +#include "systick.h" static i2c_dev i2c_dev1 = { .regs = I2C1_BASE, @@ -47,9 +47,8 @@ static i2c_dev i2c_dev1 = { .clk_line = RCC_I2C1, .ev_nvic_line = NVIC_I2C1_EV, .er_nvic_line = NVIC_I2C1_ER, - .state = I2C_STATE_IDLE + .state = I2C_STATE_DISABLED }; - i2c_dev* const I2C1 = &i2c_dev1; static i2c_dev i2c_dev2 = { @@ -60,29 +59,52 @@ static i2c_dev i2c_dev2 = { .clk_line = RCC_I2C2, .ev_nvic_line = NVIC_I2C2_EV, .er_nvic_line = NVIC_I2C2_ER, - .state = I2C_STATE_IDLE + .state = I2C_STATE_DISABLED }; - i2c_dev* const I2C2 = &i2c_dev2; -struct crumb { - uint32 event; - uint32 sr1; - uint32 sr2; -}; +static inline int32 wait_for_state_change(i2c_dev *dev, + i2c_state state, + uint32 timeout); + +/** + * @brief Fill data register with slave address + * @param dev i2c device + * @param addr slave address + * @param rw read/write bit + */ +static inline void i2c_send_slave_addr(i2c_dev *dev, uint32 addr, uint32 rw) { + dev->regs->DR = (addr << 1) | rw; +} + +/* + * Simple debugging trail. Define I2C_DEBUG to turn on. + */ +#ifdef I2C_DEBUG -#define NR_CRUMBS 128 +#define NR_CRUMBS 128 static struct crumb crumbs[NR_CRUMBS]; static uint32 cur_crumb = 0; -static inline void leave_big_crumb(uint32 event, uint32 sr1, uint32 sr2) { +static inline void i2c_drop_crumb(uint32 event, uint32 arg0, uint32 arg1) { if (cur_crumb < NR_CRUMBS) { struct crumb *crumb = &crumbs[cur_crumb++]; crumb->event = event; - crumb->sr1 = sr1; - crumb->sr2 = sr2; + crumb->arg0 = arg0; + crumb->arg1 = arg1; } } +#define I2C_CRUMB(event, arg0, arg1) i2c_drop_crumb(event, arg0, arg1) + +#else +#define I2C_CRUMB(event, arg0, arg1) +#endif + +struct crumb { + uint32 event; + uint32 arg0; + uint32 arg1; +}; enum { IRQ_ENTRY = 1, @@ -100,6 +122,7 @@ enum { ERROR_ENTRY = 13, }; + /** * @brief IRQ handler for i2c master. Handles transmission/reception. * @param dev i2c device @@ -111,7 +134,12 @@ static void i2c_irq_handler(i2c_dev *dev) { uint32 sr1 = dev->regs->SR1; uint32 sr2 = dev->regs->SR2; - leave_big_crumb(IRQ_ENTRY, sr1, sr2); + I2C_CRUMB(IRQ_ENTRY, sr1, sr2); + + /* + * Reset timeout counter + */ + dev->timestamp = systick_uptime(); /* * EV5: Start condition sent @@ -145,10 +173,10 @@ static void i2c_irq_handler(i2c_dev *dev) { i2c_disable_ack(dev); if (dev->msgs_left > 1) { i2c_start_condition(dev); - leave_big_crumb(RX_ADDR_START, 0, 0); + I2C_CRUMB(RX_ADDR_START, 0, 0); } else { i2c_stop_condition(dev); - leave_big_crumb(RX_ADDR_STOP, 0, 0); + I2C_CRUMB(RX_ADDR_STOP, 0, 0); } } } else { @@ -157,8 +185,9 @@ static void i2c_irq_handler(i2c_dev *dev) { * register. We should get another TXE interrupt * immediately to fill DR again. */ - if (msg->length != 1) - i2c_write(dev, msg->data[msg->xferred++]); + if (msg->length != 1) { + i2c_write(dev, msg->data[msg->xferred++]); + } } sr1 = sr2 = 0; } @@ -169,7 +198,7 @@ static void i2c_irq_handler(i2c_dev *dev) { * byte written. */ if ((sr1 & I2C_SR1_TXE) && !(sr1 & I2C_SR1_BTF)) { - leave_big_crumb(TXE_ONLY, 0, 0); + I2C_CRUMB(TXE_ONLY, 0, 0); if (dev->msgs_left) { i2c_write(dev, msg->data[msg->xferred++]); if (msg->xferred == msg->length) { @@ -194,9 +223,9 @@ static void i2c_irq_handler(i2c_dev *dev) { * Last byte sent, program repeated start/stop */ if ((sr1 & I2C_SR1_TXE) && (sr1 & I2C_SR1_BTF)) { - leave_big_crumb(TXE_BTF, 0, 0); + I2C_CRUMB(TXE_BTF, 0, 0); if (dev->msgs_left) { - leave_big_crumb(TEST, 0, 0); + I2C_CRUMB(TEST, 0, 0); /* * Repeated start insanity: We can't disable ITEVTEN or else SB * won't interrupt, but if we don't disable ITEVTEN, BTF will @@ -216,7 +245,7 @@ static void i2c_irq_handler(i2c_dev *dev) { * me. */ i2c_disable_irq(dev, I2C_IRQ_EVENT); - leave_big_crumb(STOP_SENT, 0, 0); + I2C_CRUMB(STOP_SENT, 0, 0); dev->state = I2C_STATE_XFER_DONE; } sr1 = sr2 = 0; @@ -226,7 +255,7 @@ static void i2c_irq_handler(i2c_dev *dev) { * EV7: Master Receiver */ if (sr1 & I2C_SR1_RXNE) { - leave_big_crumb(RXNE_ONLY, 0, 0); + I2C_CRUMB(RXNE_ONLY, 0, 0); msg->data[msg->xferred++] = dev->regs->DR; /* @@ -238,10 +267,10 @@ static void i2c_irq_handler(i2c_dev *dev) { i2c_disable_ack(dev); if (dev->msgs_left > 2) { i2c_start_condition(dev); - leave_big_crumb(RXNE_START_SENT, 0, 0); + I2C_CRUMB(RXNE_START_SENT, 0, 0); } else { i2c_stop_condition(dev); - leave_big_crumb(RXNE_STOP_SENT, 0, 0); + I2C_CRUMB(RXNE_STOP_SENT, 0, 0); } } else if (msg->xferred == msg->length) { dev->msgs_left--; @@ -249,7 +278,7 @@ static void i2c_irq_handler(i2c_dev *dev) { /* * We're done. */ - leave_big_crumb(RXNE_DONE, 0, 0); + I2C_CRUMB(RXNE_DONE, 0, 0); dev->state = I2C_STATE_XFER_DONE; } else { dev->msg++; @@ -266,13 +295,25 @@ void __irq_i2c2_ev(void) { i2c_irq_handler(&i2c_dev2); } + +/** + * @brief Interrupt handler for i2c error conditions + * @param dev i2c device + * @sideeffect Aborts any pending i2c transactions + */ static void i2c_irq_error_handler(i2c_dev *dev) { uint32 sr1 = dev->regs->SR1; uint32 sr2 = dev->regs->SR2; - leave_big_crumb(ERROR_ENTRY, sr1, sr2); + I2C_CRUMB(ERROR_ENTRY, sr1, sr2); + + /* Clear flags */ + dev->regs->SR1 = 0; + dev->regs->SR2 = 0; i2c_stop_condition(dev); i2c_disable_irq(dev, I2C_IRQ_BUFFER | I2C_IRQ_EVENT | I2C_IRQ_ERROR); + dev->error_flags = sr2 & (I2C_SR1_BERR | I2C_SR1_ARLO | I2C_SR1_AF | + I2C_SR1_OVR); dev->state = I2C_STATE_ERROR; } @@ -284,7 +325,14 @@ void __irq_i2c2_er(void) { i2c_irq_error_handler(&i2c_dev2); } -static void i2c_bus_reset(const i2c_dev *dev) { + +/** + * @brief Reset an i2c bus by clocking out pulses until any hung + * slaves release SDA and SCL, then generate a START condition, then + * a STOP condition. + * @param dev i2c device + */ +void i2c_bus_reset(const i2c_dev *dev) { /* Release both lines */ gpio_write_bit(dev->gpio_port, dev->scl_pin, 1); gpio_write_bit(dev->gpio_port, dev->sda_pin, 1); @@ -335,16 +383,29 @@ void i2c_init(i2c_dev *dev) { * @param dev Device to enable * @param flags Bitwise or of the following I2C options: * I2C_FAST_MODE: 400 khz operation + * I2C_DUTY_16_9: 16/9 Tlow/Thigh duty cycle (only applicable for fast mode) + * I2C_BUS_RESET: Reset the bus and clock out any hung slaves on initialization * I2C_10BIT_ADDRESSING: Enable 10-bit addressing + * I2C_REMAP: Remap I2C1 to SCL/PB8 SDA/PB9 */ void i2c_master_enable(i2c_dev *dev, uint32 flags) { #define I2C_CLK (PCLK1/1000000) -#define STANDARD_CCR (PCLK1/(100000*2)) -#define STANDARD_TRISE (I2C_CLK+1) -#define FAST_CCR (I2C_CLK/10) -#define FAST_TRISE ((I2C_CLK*3)/10+1) + uint32 ccr = 0; + uint32 trise = 0; + + /* PE must be disabled to configure the device */ + ASSERT(!(dev->regs->CR1 & I2C_CR1_PE)); + + if ((dev == I2C1) && (flags & I2C_REMAP)) { + afio_remap(AFIO_REMAP_I2C1); + I2C1->sda_pin = 9; + I2C1->scl_pin = 8; + } + /* Reset the bus. Clock out any hung slaves. */ - i2c_bus_reset(dev); + if (flags & I2C_BUS_RESET) { + i2c_bus_reset(dev); + } /* Turn on clock and set GPIO modes */ i2c_init(dev); @@ -354,22 +415,33 @@ void i2c_master_enable(i2c_dev *dev, uint32 flags) { /* I2C1 and I2C2 are fed from APB1, clocked at 36MHz */ i2c_set_input_clk(dev, I2C_CLK); - if(flags & I2C_FAST_MODE) { - /* 400 kHz for fast mode, set DUTY and F/S bits */ - i2c_set_clk_control(dev, FAST_CCR|I2C_CCR_DUTY|I2C_CCR_FS); + if (flags & I2C_FAST_MODE) { + ccr |= I2C_CCR_FS; - /* Set scl rise time, max rise time in fast mode: 300ns */ - i2c_set_trise(dev, FAST_TRISE); + if (flags & I2C_DUTY_16_9) { + /* Tlow/Thigh = 16/9 */ + ccr |= I2C_CCR_DUTY; + ccr |= PCLK1/(400000 * 25); + } else { + /* Tlow/Thigh = 2 */ + ccr |= PCLK1/(400000 * 3); + } + trise = (300 * (I2C_CLK)/1000) + 1; } else { + /* Tlow/Thigh = 1 */ + ccr = PCLK1/(100000 * 2); + trise = I2C_CLK + 1; + } - /* 100 kHz for standard mode */ - i2c_set_clk_control(dev, STANDARD_CCR); - - /* Max rise time in standard mode: 1000 ns */ - i2c_set_trise(dev, STANDARD_TRISE); + /* Set minimum required value if CCR < 1*/ + if ((ccr & I2C_CCR_CCR) == 0) { + ccr |= 0x1; } + i2c_set_clk_control(dev, ccr); + i2c_set_trise(dev, trise); + /* Enable event and buffer interrupts */ nvic_irq_enable(dev->ev_nvic_line); nvic_irq_enable(dev->er_nvic_line); @@ -407,40 +479,81 @@ void i2c_master_enable(i2c_dev *dev, uint32 flags) { /* Make it go! */ i2c_peripheral_enable(dev); + + dev->state = I2C_STATE_IDLE; } -int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num) { + +/** + * @brief Process an i2c transaction. Transactions are composed of + * one or more i2c_msg's and may be read or write tranfers. Multiple i2c_msg's + * will generate a repeated start inbetween messages. + * @param dev i2c device + * @param msgs messages to send/receive + * @param num number of messages to send/receive + * @param timeout bus idle timeout in milliseconds before aborting the + * transfer. 0 denotes no timeout. + * @return 0 on success + * I2C_ERROR_PROTOCOL if there was a protocol error. + * I2C_ERROR_TIMEOUT if the transfer timed out. + */ +int32 i2c_master_xfer(i2c_dev *dev, + i2c_msg *msgs, + uint16 num, + uint32 timeout) { int32 rc; + ASSERT(dev->state == I2C_STATE_IDLE); + dev->msg = msgs; dev->msgs_left = num; - - while (dev->regs->SR2 & I2C_SR2_BUSY) - ; - + dev->timestamp = systick_uptime(); dev->state = I2C_STATE_BUSY; - i2c_enable_irq(dev, I2C_IRQ_EVENT); + i2c_enable_irq(dev, I2C_IRQ_EVENT); i2c_start_condition(dev); - rc = wait_for_state_change(dev, I2C_STATE_XFER_DONE); + + rc = wait_for_state_change(dev, I2C_STATE_XFER_DONE, timeout); if (rc < 0) { goto out; } dev->state = I2C_STATE_IDLE; - rc = num; out: return rc; } -static inline int32 wait_for_state_change(i2c_dev *dev, i2c_state state) { + +/** + * @brief Wait for an i2c event, or timeout in case of error + * @param dev i2c device + * @param state i2c_state state to wait for + * @param timeout timeout in milliseconds + * @return 0 if target state is reached, <0 on error + */ +static inline int32 wait_for_state_change(i2c_dev *dev, + i2c_state state, + uint32 timeout) { int32 rc; i2c_state tmp; while (1) { tmp = dev->state; - if ((tmp == state) || (tmp == I2C_STATE_ERROR)) { - return (tmp == I2C_STATE_ERROR) ? -1 : 0; + + if (tmp == I2C_STATE_ERROR) { + return I2C_STATE_ERROR; + } + + if (tmp == state) { + return 0; + } + + if (timeout) { + if (systick_uptime() > (dev->timestamp + timeout)) { + /* TODO: overflow? */ + /* TODO: racy? */ + return I2C_ERROR_TIMEOUT; + } } } } diff --git a/libmaple/i2c.h b/libmaple/i2c.h index 3f351b2..3fd7133 100644 --- a/libmaple/i2c.h +++ b/libmaple/i2c.h @@ -45,9 +45,10 @@ typedef struct i2c_reg_map { } i2c_reg_map; typedef enum i2c_state { - I2C_STATE_IDLE, - I2C_STATE_XFER_DONE, - I2C_STATE_BUSY, + I2C_STATE_DISABLED = 0, + I2C_STATE_IDLE = 1, + I2C_STATE_XFER_DONE = 2, + I2C_STATE_BUSY = 3, I2C_STATE_ERROR = -1 } i2c_state; @@ -72,6 +73,8 @@ typedef struct i2c_dev { volatile uint8 state; uint16 msgs_left; i2c_msg *msg; + volatile uint32 timestamp; + uint32 error_flags; } i2c_dev; extern i2c_dev* const I2C1; @@ -80,10 +83,6 @@ extern i2c_dev* const I2C2; #define I2C1_BASE (i2c_reg_map*)0x40005400 #define I2C2_BASE (i2c_reg_map*)0x40005800 -/* i2c enable options */ -#define I2C_FAST_MODE 0x1 // 400 khz -#define I2C_DUTY_16_9 0x2 // 16/9 duty ratio - /* Control register 1 bits */ #define I2C_CR1_SWRST BIT(15) // Software reset #define I2C_CR1_ALERT BIT(13) // SMBus alert @@ -137,9 +136,23 @@ extern i2c_dev* const I2C2; extern "C" { #endif -void i2c_init(i2c_dev *dev); +/* i2c enable options */ +#define I2C_FAST_MODE BIT(0) // 400 khz +#define I2C_DUTY_16_9 BIT(1) // 16/9 duty ratio +#define I2C_REMAP BIT(2) // Use alternate pin mapping +#define I2C_BUS_RESET BIT(3) // Perform a bus reset void i2c_master_enable(i2c_dev *dev, uint32 flags); -int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num); + +#define I2C_ERROR_PROTOCOL (-1) +#define I2C_ERROR_TIMEOUT (-2) +int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num, uint32 timeout); + +void i2c_bus_reset(const i2c_dev *dev); + +static inline void i2c_disable(i2c_dev *dev) { + dev->regs->CR1 &= ~I2C_CR1_PE; + dev->state = I2C_STATE_DISABLED; +} /* * Low level register twiddling functions @@ -195,22 +208,22 @@ static inline void i2c_set_clk_control(i2c_dev *dev, uint32 val) { dev->regs->CCR = ccr; } -static inline void i2c_set_fast_mode(i2c_dev *dev) { - dev->regs->CCR |= I2C_CCR_FS; -} - -static inline void i2c_set_standard_mode(i2c_dev *dev) { - dev->regs->CCR &= ~I2C_CCR_FS; -} /** * @brief Set SCL rise time - * @param + * @param dev device to configure + * @param trise Maximum rise time in fast/standard mode (See RM008 for + * formula) */ static inline void i2c_set_trise(i2c_dev *dev, uint32 trise) { dev->regs->TRISE = trise; } + +/** + * @brief Generate a start condition on the bus. + * @param device i2c device to use + */ static inline void i2c_start_condition(i2c_dev *dev) { uint32 cr1; while ((cr1 = dev->regs->CR1) & (I2C_CR1_START | @@ -221,6 +234,10 @@ static inline void i2c_start_condition(i2c_dev *dev) { dev->regs->CR1 |= I2C_CR1_START; } +/** + * @brief Generate a stop condition on the bus + * @param device i2c device to use + */ static inline void i2c_stop_condition(i2c_dev *dev) { uint32 cr1; while ((cr1 = dev->regs->CR1) & (I2C_CR1_START | @@ -229,12 +246,22 @@ static inline void i2c_stop_condition(i2c_dev *dev) { ; } dev->regs->CR1 |= I2C_CR1_STOP; -} + while ((cr1 = dev->regs->CR1) & (I2C_CR1_START | + I2C_CR1_STOP | + I2C_CR1_PEC)) { + ; + } -static inline void i2c_send_slave_addr(i2c_dev *dev, uint32 addr, uint32 rw) { - dev->regs->DR = (addr << 1) | rw; } +/** + * @brief Enable one or more i2c interrupts + * @param dev i2c device + * @param irqs bitwise-or of: + * I2C_IRQ_ERROR: Error interrupt + * I2C_IRQ_EVENT: Event interrupt + * I2C_IRQ_BUFFER: Buffer interrupt + */ #define I2C_IRQ_ERROR I2C_CR2_ITERREN #define I2C_IRQ_EVENT I2C_CR2_ITEVTEN #define I2C_IRQ_BUFFER I2C_CR2_ITBUFEN @@ -242,14 +269,31 @@ static inline void i2c_enable_irq(i2c_dev *dev, uint32 irqs) { dev->regs->CR2 |= irqs; } +/** + * @brief Disable one or more i2c interrupts + * @param dev i2c device + * @param irqs bitwise-or of: + * I2C_IRQ_ERROR: Error interrupt + * I2C_IRQ_EVENT: Event interrupt + * I2C_IRQ_BUFFER: Buffer interrupt + */ static inline void i2c_disable_irq(i2c_dev *dev, uint32 irqs) { dev->regs->CR2 &= ~irqs; } + +/** + * @brief Enable i2c acknowledgment + * @param dev i2c device + */ static inline void i2c_enable_ack(i2c_dev *dev) { dev->regs->CR1 |= I2C_CR1_ACK; } +/** + * @brief Disable i2c acknowledgment + * @param dev i2c device + */ static inline void i2c_disable_ack(i2c_dev *dev) { dev->regs->CR1 &= ~I2C_CR1_ACK; } diff --git a/libmaple/systick.c b/libmaple/systick.c index c04f4f3..7582436 100644 --- a/libmaple/systick.c +++ b/libmaple/systick.c @@ -28,7 +28,7 @@ #include "systick.h" -volatile uint32 systick_timer_millis; +volatile uint32 systick_uptime_millis; /** * @brief Initialize and enable SysTick. @@ -67,5 +67,5 @@ void systick_enable() { */ void __exc_systick(void) { - systick_timer_millis++; + systick_uptime_millis++; } diff --git a/libmaple/systick.h b/libmaple/systick.h index 35b4cb9..9d6d3b9 100644 --- a/libmaple/systick.h +++ b/libmaple/systick.h @@ -73,7 +73,11 @@ typedef struct systick_reg_map { #define SYSTICK_CVR_TENMS 0xFFFFFF /** System elapsed time, in milliseconds */ -extern volatile uint32 systick_timer_millis; +extern volatile uint32 systick_uptime_millis; + +static inline uint32 systick_uptime(void) { + return systick_uptime_millis; +} void systick_init(uint32 reload_val); void systick_disable(); diff --git a/wirish/wirish_time.h b/wirish/wirish_time.h index d5349e3..e326ea7 100644 --- a/wirish/wirish_time.h +++ b/wirish/wirish_time.h @@ -43,7 +43,7 @@ * @see micros() */ static inline uint32 millis(void) { - return systick_timer_millis; + return systick_uptime(); } /** -- cgit v1.2.3