Code made compliant with KR Coding style.

pull/1214/head
vimalrajr 2015-06-23 14:15:37 +05:30 committed by Karthik Purushothaman
parent a7b2cee60d
commit 4380fe8d35
164 changed files with 14840 additions and 14860 deletions

View File

@ -33,7 +33,8 @@
#define NVIC_RAM_VECTOR_ADDRESS (0x20000000) // Vectors positioned at start of RAM
#define NVIC_FLASH_VECTOR_ADDRESS (0x0) // Initial vector position in flash
void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) {
void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector)
{
uint32_t *vectors = (uint32_t*)SCB->VTOR;
uint32_t i;
@ -49,7 +50,8 @@ void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) {
vectors[IRQn + 16] = vector;
}
uint32_t NVIC_GetVector(IRQn_Type IRQn) {
uint32_t NVIC_GetVector(IRQn_Type IRQn)
{
uint32_t *vectors = (uint32_t*)SCB->VTOR;
return vectors[IRQn + 16];
}

View File

@ -33,7 +33,8 @@
#define NVIC_RAM_VECTOR_ADDRESS (0x20000000) // Vectors positioned at start of RAM
#define NVIC_FLASH_VECTOR_ADDRESS (0x0) // Initial vector position in flash
void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) {
void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector)
{
uint32_t *vectors = (uint32_t*)SCB->VTOR;
uint32_t i;
@ -49,7 +50,8 @@ void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) {
vectors[IRQn + 16] = vector;
}
uint32_t NVIC_GetVector(IRQn_Type IRQn) {
uint32_t NVIC_GetVector(IRQn_Type IRQn)
{
uint32_t *vectors = (uint32_t*)SCB->VTOR;
return vectors[IRQn + 16];
}

View File

@ -94,8 +94,7 @@ typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volati
/*@{*/
/** Interrupt Number Definition */
typedef enum IRQn
{
typedef enum IRQn {
/****** Cortex-M0+ Processor Exceptions Numbers ******************************/
NonMaskableInt_IRQn = -14,/**< 2 Non Maskable Interrupt */
HardFault_IRQn = -13,/**< 3 Cortex-M0+ Hard Fault Interrupt */
@ -135,8 +134,7 @@ typedef enum IRQn
PERIPH_COUNT_IRQn = 28 /**< Number of peripheral IDs */
} IRQn_Type;
typedef struct _DeviceVectors
{
typedef struct _DeviceVectors {
/* Stack pointer */
void* pvStack;

View File

@ -93,8 +93,7 @@ typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volati
/*@{*/
/** Interrupt Number Definition */
typedef enum IRQn
{
typedef enum IRQn {
/****** Cortex-M0+ Processor Exceptions Numbers ******************************/
NonMaskableInt_IRQn = -14,/**< 2 Non Maskable Interrupt */
HardFault_IRQn = -13,/**< 3 Cortex-M0+ Hard Fault Interrupt */
@ -134,8 +133,7 @@ typedef enum IRQn
PERIPH_COUNT_IRQn = 28 /**< Number of peripheral IDs */
} IRQn_Type;
typedef struct _DeviceVectors
{
typedef struct _DeviceVectors {
/* Stack pointer */
void* pvStack;

View File

@ -220,8 +220,7 @@ typedef uint32_t iram_size_t;
* @{ */
/** 16-bit union. */
typedef union
{
typedef union {
int16_t s16;
uint16_t u16;
int8_t s8[2];
@ -229,8 +228,7 @@ typedef union
} Union16;
/** 32-bit union. */
typedef union
{
typedef union {
int32_t s32;
uint32_t u32;
int16_t s16[2];
@ -240,8 +238,7 @@ typedef union
} Union32;
/** 64-bit union. */
typedef union
{
typedef union {
int64_t s64;
uint64_t u64;
int32_t s32[2];
@ -253,8 +250,7 @@ typedef union
} Union64;
/** Union of pointers to 64-, 32-, 16- and 8-bit unsigned integers. */
typedef union
{
typedef union {
int64_t *s64ptr;
uint64_t *u64ptr;
int32_t *s32ptr;
@ -266,8 +262,7 @@ typedef union
} UnionPtr;
/** Union of pointers to volatile 64-, 32-, 16- and 8-bit unsigned integers. */
typedef union
{
typedef union {
volatile int64_t *s64ptr;
volatile uint64_t *u64ptr;
volatile int32_t *s32ptr;
@ -279,8 +274,7 @@ typedef union
} UnionVPtr;
/** Union of pointers to constant 64-, 32-, 16- and 8-bit unsigned integers. */
typedef union
{
typedef union {
const int64_t *s64ptr;
const uint64_t *u64ptr;
const int32_t *s32ptr;
@ -292,8 +286,7 @@ typedef union
} UnionCPtr;
/** Union of pointers to constant volatile 64-, 32-, 16- and 8-bit unsigned integers. */
typedef union
{
typedef union {
const volatile int64_t *s64ptr;
const volatile uint64_t *u64ptr;
const volatile int32_t *s32ptr;
@ -305,8 +298,7 @@ typedef union
} UnionCVPtr;
/** Structure of pointers to 64-, 32-, 16- and 8-bit unsigned integers. */
typedef struct
{
typedef struct {
int64_t *s64ptr;
uint64_t *u64ptr;
int32_t *s32ptr;
@ -318,8 +310,7 @@ typedef struct
} StructPtr;
/** Structure of pointers to volatile 64-, 32-, 16- and 8-bit unsigned integers. */
typedef struct
{
typedef struct {
volatile int64_t *s64ptr;
volatile uint64_t *u64ptr;
volatile int32_t *s32ptr;
@ -331,8 +322,7 @@ typedef struct
} StructVPtr;
/** Structure of pointers to constant 64-, 32-, 16- and 8-bit unsigned integers. */
typedef struct
{
typedef struct {
const int64_t *s64ptr;
const uint64_t *u64ptr;
const int32_t *s32ptr;
@ -344,8 +334,7 @@ typedef struct
} StructCPtr;
/** Structure of pointers to constant volatile 64-, 32-, 16- and 8-bit unsigned integers. */
typedef struct
{
typedef struct {
const volatile int64_t *s64ptr;
const volatile uint64_t *u64ptr;
const volatile int32_t *s32ptr;
@ -1078,8 +1067,7 @@ static inline void convert_64_bit_to_byte_array(uint64_t value, uint8_t *data)
{
uint8_t index = 0;
while (index < 8)
{
while (index < 8) {
data[index++] = value & 0xFF;
value = value >> 8;
}
@ -1128,14 +1116,12 @@ static inline uint16_t convert_byte_array_to_16_bit(uint8_t *data)
/* Converts a 4 Byte array into a 32-Bit value */
static inline uint32_t convert_byte_array_to_32_bit(uint8_t *data)
{
union
{
union {
uint32_t u32;
uint8_t u8[4];
} long_addr;
uint8_t index;
for (index = 0; index < 4; index++)
{
for (index = 0; index < 4; index++) {
long_addr.u8[index] = *data++;
}
return long_addr.u32;
@ -1151,16 +1137,14 @@ static inline uint32_t convert_byte_array_to_32_bit(uint8_t *data)
*/
static inline uint64_t convert_byte_array_to_64_bit(uint8_t *data)
{
union
{
union {
uint64_t u64;
uint8_t u8[8];
} long_addr;
uint8_t index;
for (index = 0; index < 8; index++)
{
for (index = 0; index < 8; index++) {
long_addr.u8[index] = *data++;
}

View File

@ -459,8 +459,7 @@ uint32_t find_mux_setting (PinName output, PinName input, PinName clock)
if (((output_values.pad == 0) && (clock_values.pad == 1)) || (output_values.pad == 0)) {
mux_setting |= SERCOM_USART_CTRLA_TXPO(0);
}
else if((output_values.pad == 2) && (clock_values.pad == 3)) {
} else if((output_values.pad == 2) && (clock_values.pad == 3)) {
mux_setting |= SERCOM_USART_CTRLA_TXPO(1);
}
/*else if((output_values.pad == 0)) { // condition for hardware enabled

View File

@ -24,8 +24,7 @@ uint8_t g_sys_init = 0;
//TODO: To be implemented by adding system init and board init
void mbed_sdk_init()
{
if(g_sys_init == 0)
{
if(g_sys_init == 0) {
g_sys_init = 1;
system_init();
}

View File

@ -642,7 +642,8 @@ static inline void dma_unregister_callback(struct dma_resource *resource,
*
* \param[in] resource Pointer to the DMA resource
*/
static inline void dma_trigger_transfer(struct dma_resource *resource) {
static inline void dma_trigger_transfer(struct dma_resource *resource)
{
Assert(resource);
DMAC->SWTRIGCTRL.reg |= (1 << resource->channel_id);

View File

@ -350,8 +350,7 @@ typedef void (*extint_callback_t)(void);
/** \internal
* Internal EXTINT module device instance structure definition.
*/
struct _extint_module
{
struct _extint_module {
// TEMP: Commented by V
//# if EXTINT_CALLBACK_MODE == true
/** Asynchronous channel callback table, for user-registered handlers. */

View File

@ -162,8 +162,7 @@ enum status_code extint_chan_enable_callback(
Eic *const eic = _extint_get_eic_from_channel(channel);
eic->INTENSET.reg = (1UL << channel);
}
else {
} else {
Assert(false);
return STATUS_ERR_INVALID_ARG;
}
@ -192,8 +191,7 @@ enum status_code extint_chan_disable_callback(
Eic *const eic = _extint_get_eic_from_channel(channel);
eic->INTENCLR.reg = (1UL << channel);
}
else {
} else {
Assert(false);
return STATUS_ERR_INVALID_ARG;
}

View File

@ -63,8 +63,7 @@ extern "C" {
*/
/** Enum for the possible callback types for the EXTINT module. */
enum extint_callback_type
{
enum extint_callback_type {
/** Callback type for when an external interrupt detects the configured
* channel criteria (i.e. edge or level detection)
*/

View File

@ -125,8 +125,7 @@ void _sercom_set_handler(
enum system_interrupt_vector _sercom_get_interrupt_vector(
Sercom *const sercom_instance)
{
const uint8_t sercom_int_vectors[SERCOM_INST_NUM] =
{
const uint8_t sercom_int_vectors[SERCOM_INST_NUM] = {
MREPEAT(SERCOM_INST_NUM, _SERCOM_INTERRUPT_VECT_NUM, ~)
};

View File

@ -116,8 +116,7 @@ static enum status_code _usart_set_config(
enum status_code status_code = STATUS_OK;
/* Get baud value from mode and clock */
switch (config->transfer_mode)
{
switch (config->transfer_mode) {
case USART_TRANSFER_SYNCHRONOUSLY:
if (!config->use_external_clock) {
status_code = _sercom_get_sync_baud_val(config->baudrate,
@ -163,8 +162,7 @@ static enum status_code _usart_set_config(
if (config->use_external_clock == false) {
ctrla |= SERCOM_USART_CTRLA_MODE(0x1);
}
else {
} else {
ctrla |= SERCOM_USART_CTRLA_MODE(0x0);
}

View File

@ -242,8 +242,7 @@ void system_pinmux_group_set_output_slew_rate(
if (mask & (1UL << i)) {
if (mode == SYSTEM_PINMUX_PIN_SLEW_RATE_LIMITED) {
port->PINCFG[i].reg |= PORT_PINCFG_SLEWLIM;
}
else {
} else {
port->PINCFG[i].reg &= ~PORT_PINCFG_SLEWLIM;
}
}
@ -273,8 +272,7 @@ void system_pinmux_group_set_output_strength(
if (mask & (1UL << i)) {
if (mode == SYSTEM_PINMUX_PIN_STRENGTH_HIGH) {
port->PINCFG[i].reg |= PORT_PINCFG_DRVSTR;
}
else {
} else {
port->PINCFG[i].reg &= ~PORT_PINCFG_DRVSTR;
}
}

View File

@ -390,8 +390,7 @@ static inline uint8_t system_pinmux_pin_get_mux_position(
if (pin_index & 1) {
return (pmux_reg & PORT_PMUX_PMUXO_Msk) >> PORT_PMUX_PMUXO_Pos;
}
else {
} else {
return (pmux_reg & PORT_PMUX_PMUXE_Msk) >> PORT_PMUX_PMUXE_Pos;
}
}
@ -455,8 +454,7 @@ static inline void system_pinmux_pin_set_output_strength(
if (mode == SYSTEM_PINMUX_PIN_STRENGTH_HIGH) {
port->PINCFG[pin_index].reg |= PORT_PINCFG_DRVSTR;
}
else {
} else {
port->PINCFG[pin_index].reg &= ~PORT_PINCFG_DRVSTR;
}
}
@ -501,8 +499,7 @@ static inline void system_pinmux_pin_set_output_slew_rate(
if (mode == SYSTEM_PINMUX_PIN_SLEW_RATE_LIMITED) {
port->PINCFG[pin_index].reg |= PORT_PINCFG_SLEWLIM;
}
else {
} else {
port->PINCFG[pin_index].reg &= ~PORT_PINCFG_SLEWLIM;
}
}
@ -545,8 +542,7 @@ static inline void system_pinmux_pin_set_output_drive(
if (mode == SYSTEM_PINMUX_PIN_DRIVE_OPEN_DRAIN) {
port->PINCFG[pin_index].reg |= PORT_PINCFG_ODRAIN;
}
else {
} else {
port->PINCFG[pin_index].reg &= ~PORT_PINCFG_ODRAIN;
}
}

View File

@ -78,11 +78,9 @@ enum status_code tc_register_callback(
/* Set the bit corresponding to the callback_type */
if (callback_type == TC_CALLBACK_CC_CHANNEL0) {
module->register_callback_mask |= TC_INTFLAG_MC(1);
}
else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
} else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
module->register_callback_mask |= TC_INTFLAG_MC(2);
}
else {
} else {
module->register_callback_mask |= (1 << callback_type);
}
return STATUS_OK;
@ -110,11 +108,9 @@ enum status_code tc_unregister_callback(
/* Clear the bit corresponding to the callback_type */
if (callback_type == TC_CALLBACK_CC_CHANNEL0) {
module->register_callback_mask &= ~TC_INTFLAG_MC(1);
}
else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
} else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
module->register_callback_mask &= ~TC_INTFLAG_MC(2);
}
else {
} else {
module->register_callback_mask &= ~(1 << callback_type);
}
return STATUS_OK;

View File

@ -69,8 +69,7 @@ extern void *_tc_instances[TC_INST_NUM];
static enum system_interrupt_vector _tc_interrupt_get_interrupt_vector(
uint32_t inst_num)
{
static uint8_t tc_interrupt_vectors[TC_INST_NUM] =
{
static uint8_t tc_interrupt_vectors[TC_INST_NUM] = {
#if (SAML21E) || (SAML21G)
SYSTEM_INTERRUPT_MODULE_TC0,
SYSTEM_INTERRUPT_MODULE_TC1,
@ -124,12 +123,10 @@ static inline void tc_enable_callback(
if (callback_type == TC_CALLBACK_CC_CHANNEL0) {
module->enable_callback_mask |= TC_INTFLAG_MC(1);
module->hw->COUNT8.INTENSET.reg = TC_INTFLAG_MC(1);
}
else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
} else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
module->enable_callback_mask |= TC_INTFLAG_MC(2);
module->hw->COUNT8.INTENSET.reg = TC_INTFLAG_MC(2);
}
else {
} else {
module->enable_callback_mask |= (1 << callback_type);
module->hw->COUNT8.INTENSET.reg = (1 << callback_type);
}
@ -148,7 +145,8 @@ static inline void tc_enable_callback(
*/
static inline void tc_disable_callback(
struct tc_module *const module,
const enum tc_callback callback_type){
const enum tc_callback callback_type)
{
/* Sanity check arguments */
Assert(module);
@ -156,12 +154,10 @@ static inline void tc_disable_callback(
if (callback_type == TC_CALLBACK_CC_CHANNEL0) {
module->hw->COUNT8.INTENCLR.reg = TC_INTFLAG_MC(1);
module->enable_callback_mask &= ~TC_INTFLAG_MC(1);
}
else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
} else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
module->hw->COUNT8.INTENCLR.reg = TC_INTFLAG_MC(2);
module->enable_callback_mask &= ~TC_INTFLAG_MC(2);
}
else {
} else {
module->hw->COUNT8.INTENCLR.reg = (1 << callback_type);
module->enable_callback_mask &= ~(1 << callback_type);
}

View File

@ -223,8 +223,7 @@ enum status_code tc_init(
inst_pm_apbmask[instance]);
/* Enable the slave counter if counter_size is 32-bit */
if ((config->counter_size == TC_COUNTER_SIZE_32BIT))
{
if ((config->counter_size == TC_COUNTER_SIZE_32BIT)) {
/* Enable the user interface clock in the PM */
system_apb_clock_set_mask(SYSTEM_CLOCK_APB_APBC,
inst_pm_apbmask[instance + 1]);

View File

@ -20,12 +20,14 @@
#include "compiler.h"
#include "port.h"
uint32_t gpio_set(PinName pin) {
uint32_t gpio_set(PinName pin)
{
MBED_ASSERT(pin != (PinName)NC);
return (1UL << (pin % 32));
}
void gpio_init(gpio_t *obj, PinName pin) {
void gpio_init(gpio_t *obj, PinName pin)
{
MBED_ASSERT(pin != (PinName)NC);
struct port_config pin_conf;
PortGroup *const port_base = (PortGroup*)port_get_group_from_gpio_pin(pin);
@ -46,7 +48,8 @@ void gpio_init(gpio_t *obj, PinName pin) {
obj->IN = &port_base->IN.reg;
}
void gpio_mode(gpio_t *obj, PinMode mode) {
void gpio_mode(gpio_t *obj, PinMode mode)
{
MBED_ASSERT(obj->pin != (PinName)NC);
struct port_config pin_conf;
@ -67,7 +70,8 @@ void gpio_mode(gpio_t *obj, PinMode mode) {
port_pin_set_config(obj->pin, &pin_conf);
}
void gpio_dir(gpio_t *obj, PinDirection direction) {
void gpio_dir(gpio_t *obj, PinDirection direction)
{
MBED_ASSERT(obj->pin != (PinName)NC);
struct port_config pin_conf;

View File

@ -34,7 +34,8 @@ typedef struct {
__I uint32_t *IN;
} gpio_t;
static inline void gpio_write(gpio_t *obj, int value) {
static inline void gpio_write(gpio_t *obj, int value)
{
MBED_ASSERT(obj->pin != (PinName)NC);
if (value)
*obj->OUTSET = obj->mask;
@ -42,12 +43,14 @@ static inline void gpio_write(gpio_t *obj, int value) {
*obj->OUTCLR = obj->mask;
}
static inline int gpio_read(gpio_t *obj) {
static inline int gpio_read(gpio_t *obj)
{
MBED_ASSERT(obj->pin != (PinName)NC);
return ((*obj->IN & obj->mask) ? 1 : 0);
}
static inline int gpio_is_connected(const gpio_t *obj) {
static inline int gpio_is_connected(const gpio_t *obj)
{
return obj->pin != (PinName)NC;
}

View File

@ -123,8 +123,7 @@ static enum status_code usart_set_config_asf( serial_t *obj)
(pSERIAL_S(obj)->clock_polarity_inverted << SERCOM_USART_CTRLA_CPOL_Pos);
/* Get baud value from mode and clock */
switch (pSERIAL_S(obj)->transfer_mode)
{
switch (pSERIAL_S(obj)->transfer_mode) {
case USART_TRANSFER_SYNCHRONOUSLY:
if (!pSERIAL_S(obj)->use_external_clock) {
_sercom_get_sync_baud_val(pSERIAL_S(obj)->baudrate,
@ -156,8 +155,7 @@ static enum status_code usart_set_config_asf( serial_t *obj)
if (pSERIAL_S(obj)->use_external_clock == false) {
ctrla |= SERCOM_USART_CTRLA_MODE(0x1);
}
else {
} else {
ctrla |= SERCOM_USART_CTRLA_MODE(0x0);
}
@ -197,7 +195,8 @@ static enum status_code usart_set_config_asf( serial_t *obj)
return STATUS_OK;
}
void get_default_serial_values(serial_t *obj){
void get_default_serial_values(serial_t *obj)
{
/* Set default config to object */
pSERIAL_S(obj)->data_order = USART_DATAORDER_LSB;
pSERIAL_S(obj)->transfer_mode = USART_TRANSFER_ASYNCHRONOUSLY;
@ -221,7 +220,8 @@ void get_default_serial_values(serial_t *obj){
};
void serial_init(serial_t *obj, PinName tx, PinName rx) {
void serial_init(serial_t *obj, PinName tx, PinName rx)
{
if (g_sys_init == 0) {
system_init();
g_sys_init = 1;
@ -333,11 +333,13 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) {
}
void serial_free(serial_t *obj) {
void serial_free(serial_t *obj)
{
serial_irq_ids[serial_get_index(obj)] = 0;
}
void serial_baud(serial_t *obj, int baudrate) {
void serial_baud(serial_t *obj, int baudrate)
{
MBED_ASSERT((baudrate == 110) || (baudrate == 150) || (baudrate == 300) || (baudrate == 1200) ||
(baudrate == 2400) || (baudrate == 4800) || (baudrate == 9600) || (baudrate == 19200) || (baudrate == 38400) ||
(baudrate == 57600) || (baudrate == 115200) || (baudrate == 230400) || (baudrate == 460800) || (baudrate == 921600) );
@ -362,8 +364,7 @@ void serial_baud(serial_t *obj, int baudrate) {
sercom_set_gclk_generator(pSERIAL_S(obj)->generator_source, false);
/* Get baud value from mode and clock */
switch (pSERIAL_S(obj)->transfer_mode)
{
switch (pSERIAL_S(obj)->transfer_mode) {
case USART_TRANSFER_SYNCHRONOUSLY:
if (!pSERIAL_S(obj)->use_external_clock) {
_sercom_get_sync_baud_val(pSERIAL_S(obj)->baudrate,
@ -392,7 +393,8 @@ void serial_baud(serial_t *obj, int baudrate) {
enable_usart(obj);
}
void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits) {
void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits)
{
MBED_ASSERT((stop_bits == 1) || (stop_bits == 2));
MBED_ASSERT((parity == ParityNone) || (parity == ParityOdd) || (parity == ParityEven));
MBED_ASSERT((data_bits == 5) || (data_bits == 6) || (data_bits == 7) || (data_bits == 8) /*|| (data_bits == 9)*/);
@ -507,13 +509,13 @@ inline uint8_t serial_get_index(serial_t *obj)
}
return 0;
}
static inline void uart_irq(SercomUsart *const usart, uint32_t index) {
static inline void uart_irq(SercomUsart *const usart, uint32_t index)
{
uint16_t interrupt_status;
interrupt_status = usart->INTFLAG.reg;
interrupt_status &= usart->INTENSET.reg;
if (serial_irq_ids[index] != 0) {
if (interrupt_status & SERCOM_USART_INTFLAG_TXC) // for transmit complete
{
if (interrupt_status & SERCOM_USART_INTFLAG_TXC) { // for transmit complete
usart->INTENCLR.reg = SERCOM_USART_INTFLAG_TXC;
irq_handler(serial_irq_ids[index], TxIrq);
}
@ -530,44 +532,51 @@ static inline void uart_irq(SercomUsart *const usart, uint32_t index) {
usart->INTENCLR.reg = SERCOM_USART_INTFLAG_DRE;
}
}*/
if (interrupt_status & SERCOM_USART_INTFLAG_RXC) // for receive complete
{
if (interrupt_status & SERCOM_USART_INTFLAG_RXC) { // for receive complete
usart->INTENCLR.reg = SERCOM_USART_INTFLAG_RXC;
irq_handler(serial_irq_ids[index], RxIrq);
}
}
}
void uart0_irq() {
void uart0_irq()
{
uart_irq((SercomUsart *)UART_0, 0);
}
void uart1_irq() {
void uart1_irq()
{
uart_irq((SercomUsart *)UART_1, 0);
}
void uart2_irq() {
void uart2_irq()
{
uart_irq((SercomUsart *)UART_2, 0);
}
void uart3_irq() {
void uart3_irq()
{
uart_irq((SercomUsart *)UART_3, 0);
}
void uart4_irq() {
void uart4_irq()
{
uart_irq((SercomUsart *)UART_4, 0);
}
void uart5_irq() {
void uart5_irq()
{
uart_irq((SercomUsart *)UART_5, 0);
}
void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) {
void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id)
{
irq_handler = handler;
serial_irq_ids[serial_get_index(obj)] = id;
}
void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable)
{
IRQn_Type irq_n = (IRQn_Type)0;
uint32_t vector = 0;
uint32_t ctrlb = 0;
@ -633,36 +642,38 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
/******************************************************************************
* READ/WRITE
******************************************************************************/
int serial_getc(serial_t *obj) {
int serial_getc(serial_t *obj)
{
_USART(obj).INTENSET.reg = SERCOM_USART_INTFLAG_RXC; // test
while (!serial_readable(obj));
return _USART(obj).DATA.reg ;
}
void serial_putc(serial_t *obj, int c) {
void serial_putc(serial_t *obj, int c)
{
uint16_t q = (c & SERCOM_USART_DATA_MASK);
while (!serial_writable(obj));
_USART(obj).DATA.reg = q;
while (!(_USART(obj).INTFLAG.reg & SERCOM_USART_INTFLAG_TXC)); // wait till data is sent
}
int serial_readable(serial_t *obj) {
int serial_readable(serial_t *obj)
{
uint32_t status = 1;
if (!(_USART(obj).INTFLAG.reg & SERCOM_USART_INTFLAG_RXC)) {
status = 0;
}
else {
} else {
status = 1;
}
return status;
}
int serial_writable(serial_t *obj) {
int serial_writable(serial_t *obj)
{
uint32_t status = 1;
if (!(_USART(obj).INTFLAG.reg & SERCOM_USART_INTFLAG_DRE)) {
status = 0;
}
else {
} else {
status = 1;
}
return status;

View File

@ -19,6 +19,7 @@
#include "mbed_assert.h"
#include "ins_gclk.h"
#include "compiler.h"
#include "system.h"
#include "tc.h"
#include "tc_interrupt.h"
@ -34,18 +35,17 @@ struct tc_module us_ticker_module;
static inline void tc_clear_interrupt(
struct tc_module *const module,
const enum tc_callback callback_type){
const enum tc_callback callback_type)
{
/* Sanity check arguments */
MBED_ASSERT(module);
/* Clear interrupt flags */
if (callback_type == TC_CALLBACK_CC_CHANNEL0) {
module->hw->COUNT8.INTENCLR.reg = TC_INTFLAG_MC(1);
}
else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
} else if (callback_type == TC_CALLBACK_CC_CHANNEL1) {
module->hw->COUNT8.INTENCLR.reg = TC_INTFLAG_MC(2);
}
else {
} else {
module->hw->COUNT8.INTENCLR.reg = (1 << callback_type);
}
}
@ -128,8 +128,7 @@ void us_ticker_set_interrupt(timestamp_t timestamp)
cur_time = us_ticker_read();
delta = (int32_t)((uint32_t)timestamp - cur_time);
if (delta < 0)
{
if (delta < 0) {
/* Event already occurred in past */
us_ticker_irq_handler();
return;
@ -145,13 +144,15 @@ void us_ticker_set_interrupt(timestamp_t timestamp)
NVIC_EnableIRQ(TICKER_COUNTER_IRQn);
}
void us_ticker_disable_interrupt(void) {
void us_ticker_disable_interrupt(void)
{
/* Disable the callback */
tc_disable_callback(&us_ticker_module, TC_CALLBACK_CC_CHANNEL0);
NVIC_DisableIRQ(TICKER_COUNTER_IRQn);
}
void us_ticker_clear_interrupt(void) {
void us_ticker_clear_interrupt(void)
{
uint32_t status_flags;
/* Clear TC channel 0 match */