Merge pull request #1547 from Parthasarathy/master

Fixed GCC Compiler warnings
pull/1551/head
Martin Kojtal 2016-02-15 09:50:40 +00:00
commit e641fd47cf
23 changed files with 96 additions and 101 deletions

View File

@ -139,13 +139,14 @@
#endif
/* Define WEAK attribute */
#if defined ( __CC_ARM )
# define WEAK __attribute__ ((weak))
#elif defined ( __ICCARM__ )
# define WEAK __weak
#elif defined ( __GNUC__ )
# define WEAK __attribute__ ((weak))
#endif
//defined in toochain.h
//#if defined ( __CC_ARM )
//# define WEAK __attribute__ ((weak))
//#elif defined ( __ICCARM__ )
//# define WEAK __weak
//#elif defined ( __GNUC__ )
//# define WEAK __attribute__ ((weak))
//#endif
/* Define NO_INIT attribute */
#if defined ( __CC_ARM )

View File

@ -218,7 +218,7 @@ const struct pwm_pin_channel pwn_pins[] = {
{PB31, PWM_0, 1},
/* Not connected */
{NC , NC , NC}
{(PinName) NC ,(PWMName) NC ,(uint8_t) NC}
};

View File

@ -17,6 +17,7 @@
#include "compiler.h"
#include "system.h"
uint8_t g_sys_init = 0;
//called before main - implement here if board needs it ortherwise, let

View File

@ -192,10 +192,10 @@ void analogin_init(analogin_t *obj, PinName pin)
static uint8_t init_flag = 0;
pos_input = pinmap_find_peripheral(pin, PinMap_ADC);
MBED_ASSERT(pos_input != NC);
MBED_ASSERT(pos_input != (uint32_t)NC);
adc_get_config_defaults(&(obj->config_adc));
obj->config_adc.positive_input = pos_input;
obj->config_adc.positive_input = (enum adc_positive_input)pos_input;
if (init_flag == 0) { // ADC init and enable to be done only once.
adc_init(&adc_instance, ADC, &(obj->config_adc));
adc_enable(&adc_instance);

View File

@ -83,7 +83,7 @@ static void dma_handler(const struct dma_resource* const resource)
return;
}
callback_func = dma_channels[channel_index].handler;
callback_func = (void(*)(void))(dma_channels[channel_index].handler);
if (callback_func) {
callback_func();
}
@ -268,7 +268,6 @@ bool dma_start_transfer(int channelid)
*/
bool dma_busy(int channelid)
{
int res = 0;
/* Sanity check arguments */
MBED_ASSERT(channelid < CONF_MAX_USED_CHANNEL_NUM);
@ -278,7 +277,8 @@ bool dma_busy(int channelid)
if (channel_index >= CONF_MAX_USED_CHANNEL_NUM) {
/* This channel is not active! return zero for now */
res = 0;
//res = 0;
return 0;
}
return dma_is_busy(&dma_channels[channel_index].resource);
@ -292,7 +292,6 @@ bool dma_busy(int channelid)
*/
bool dma_is_transfer_complete(int channelid)
{
int res = 0;
/* Sanity check arguments */
MBED_ASSERT(channelid < CONF_MAX_USED_CHANNEL_NUM);
@ -302,7 +301,8 @@ bool dma_is_transfer_complete(int channelid)
if (channel_index >= CONF_MAX_USED_CHANNEL_NUM) {
/* This channel is not active! return zero for now */
res = 0;
// res = 0;
return 0;
}
return (STATUS_OK == dma_get_job_status(&dma_channels[channel_index].resource));
@ -332,10 +332,10 @@ void dma_set_handler(int channelid, uint32_t handler, uint32_t event)
dma_channels[channel_index].handler = handler;
if (event & DMA_TRANSFER_ERROR) {
dma_register_callback(&dma_channels[channel_index].resource, dma_handler, DMA_CALLBACK_TRANSFER_ERROR);
dma_register_callback(&dma_channels[channel_index].resource, (dma_callback_t)dma_handler, DMA_CALLBACK_TRANSFER_ERROR);
}
if (event & DMA_TRANSFER_COMPLETE) {
dma_register_callback(&dma_channels[channel_index].resource, dma_handler, DMA_CALLBACK_TRANSFER_DONE);
dma_register_callback(&dma_channels[channel_index].resource, (dma_callback_t)dma_handler, DMA_CALLBACK_TRANSFER_DONE);
}
/* Set interrupt vector if someone have removed it */

View File

@ -103,4 +103,4 @@ void dma_set_handler(int channelid, uint32_t handler, uint32_t event);
}
#endif
#endif /* _DMA_API_HAL_H */
#endif /* _DMA_API_HAL_H */

View File

@ -487,40 +487,29 @@ enum status_code system_clock_source_write_calibration(
{
switch (clock_source) {
case SYSTEM_CLOCK_SOURCE_OSC8M:
if (calibration_value > 0xfff || freq_range > 4) {
return STATUS_ERR_INVALID_ARG;
}
SYSCTRL->OSC8M.bit.CALIB = calibration_value;
SYSCTRL->OSC8M.bit.FRANGE = freq_range;
break;
case SYSTEM_CLOCK_SOURCE_OSC32K:
if (calibration_value > 128) {
return STATUS_ERR_INVALID_ARG;
}
_system_osc32k_wait_for_sync();
SYSCTRL->OSC32K.bit.CALIB = calibration_value;
break;
case SYSTEM_CLOCK_SOURCE_ULP32K:
if (calibration_value > 32) {
return STATUS_ERR_INVALID_ARG;
}
SYSCTRL->OSCULP32K.bit.CALIB = calibration_value;
break;
default:
Assert(false);
return STATUS_ERR_INVALID_ARG;
break;
}
return STATUS_OK;
}

View File

@ -518,7 +518,7 @@ enum status_code system_clock_source_write_calibration(
default:
Assert(false);
return STATUS_ERR_INVALID_ARG;
break;
}
return STATUS_OK;

View File

@ -45,6 +45,7 @@
*/
#include <system.h>
#include <toolchain.h>
/**
* \internal

View File

@ -55,7 +55,7 @@ void gpio_mode(gpio_t *obj, PinMode mode)
struct port_config pin_conf;
obj->mode = mode;
pin_conf.direction = obj->direction;
pin_conf.direction = (enum port_pin_dir)obj->direction;
pin_conf.powersave = obj->powersave;
switch (mode) {
case PullNone :
@ -75,9 +75,8 @@ void gpio_dir(gpio_t *obj, PinDirection direction)
{
MBED_ASSERT(obj->pin != (PinName)NC);
struct port_config pin_conf;
obj->direction = direction;
pin_conf.input_pull = obj->mode;
pin_conf.input_pull = (enum port_pin_pull)obj->mode;
pin_conf.powersave = obj->powersave;
switch (direction) {
case PIN_INPUT :

View File

@ -43,7 +43,7 @@ void gpio_irq(void)
if (extint_chan_is_detected(current_channel)) {
extint_chan_clear_detected(current_channel);
port_base = (PortGroup*)port_get_group_from_gpio_pin(ext_int_pins[current_channel]);
mask = gpio_set(ext_int_pins[current_channel]);
mask = gpio_set((PinName)ext_int_pins[current_channel]);
if ((port_base->IN.reg & mask) != 0) {
event = IRQ_RISE;
} else {

View File

@ -64,6 +64,7 @@ static uint32_t i2c_instances[SERCOM_INST_NUM] = {0};
const uint32_t sercom_irq_handlers[SERCOM_INST_NUM] = {
MREPEAT(SERCOM_INST_NUM, _SERCOM_INTERRUPT_HANDLERS, ~)
};
#endif
/* Forward declaration */
@ -330,7 +331,7 @@ int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop)
struct i2c_master_packet packet;
packet.address = (address & 0xFF) >> 1;
packet.data_length = length;
packet.data = data;
packet.data = (uint8_t *)data;
packet.ten_bit_address = false;
packet.high_speed = false;
@ -596,7 +597,7 @@ void i2c_slave_mode(i2c_t *obj, int enable_slave)
uint32_t sercom_index = _sercom_get_sercom_inst_index(pI2C_S(obj)->master.hw);
for (i=0; i<2; i++) {
mux_func[i] = pinmap_function_sercom(pI2C_S(obj)->pins[0], sercom_index);
if (mux_func[i] == NC) return;
if (mux_func[i] == (uint32_t)NC) return;
}
if (enable_slave) {
@ -721,7 +722,7 @@ int i2c_slave_write(i2c_t *obj, const char *data, int length)
struct i2c_slave_packet packet;
packet.data_length = length;
packet.data = data;
packet.data = (uint8_t *)data;
tmp_status = i2c_slave_write_packet_wait(&pI2C_S(obj)->slave, &packet);
@ -731,6 +732,7 @@ int i2c_slave_write(i2c_t *obj, const char *data, int length)
/* Currently, no way to track no of bytes transmitted, so return 0 */
return 0;
}
}
/** Configure I2C slave address.
@ -863,7 +865,7 @@ void i2c_transfer_asynch(i2c_t *obj, const void *tx, size_t tx_length, void *rx,
/* Init i2c packet. */
pI2C_S(obj)->wr_packet.address = address >> 1;
pI2C_S(obj)->wr_packet.data_length = tx_length;
pI2C_S(obj)->wr_packet.data = tx;
pI2C_S(obj)->wr_packet.data = (uint8_t *)tx;
pI2C_S(obj)->rd_packet.address = address >> 1;
pI2C_S(obj)->rd_packet.data_length = rx_length;
@ -877,8 +879,8 @@ void i2c_transfer_asynch(i2c_t *obj, const void *tx, size_t tx_length, void *rx,
/* Set interrupt handler to default handler of ASF */
/* Enable interrupt */
NVIC_SetVector((SERCOM0_IRQn + sercom_index), sercom_irq_handlers[sercom_index]);
NVIC_EnableIRQ(SERCOM0_IRQn + sercom_index);
NVIC_SetVector((IRQn_Type)((uint32_t)SERCOM0_IRQn + sercom_index), sercom_irq_handlers[sercom_index]);
NVIC_EnableIRQ((IRQn_Type)((uint32_t)SERCOM0_IRQn + sercom_index));
/* Register callbacks */
i2c_master_register_callback(&pI2C_S(obj)->master, i2c_transfer_complete_callback, I2C_MASTER_CALLBACK_ERROR);
@ -927,20 +929,20 @@ uint32_t i2c_irq_handler_asynch(i2c_t *obj)
case STATUS_OK:
/* Transfer is complete */
return (I2C_EVENT_TRANSFER_COMPLETE & event_mask);
break;
case STATUS_ERR_BAD_ADDRESS:
/* Received a NACK */
return (I2C_EVENT_ERROR_NO_SLAVE & event_mask);
break;
case STATUS_ERR_PACKET_COLLISION:
/* An error occurred in between transfer */
return (I2C_EVENT_ERROR & event_mask);
break;
default:
return 0;
}
return 0;
//return 0;
}
/** Attempts to determine if I2C peripheral is already in use.

View File

@ -103,4 +103,4 @@ void pin_mode(PinName pin, PinMode mode)
}
system_pinmux_pin_set_config(pin, &pin_conf);
}
}

View File

@ -47,9 +47,9 @@ static uint32_t pinmap_merge_pins(uint32_t a, uint32_t b)
*/
uint32_t pinmap_find_peripheral_from_pad(PinName pin, enum sercom_pad_selection pad_select)
{
uint32_t pin_sercom = NC;
uint32_t pin_sercom =(uint32_t)NC;
if (pin == NC) return NC;
if (pin == NC) return (uint32_t)NC;
if (pad_select == SERCOM_USE_EXTENDED_PAD) {
pin_sercom = pinmap_find_peripheral(pin, PinMap_SERCOM_PADEx);
@ -99,7 +99,7 @@ uint32_t pinmap_find_sercom(PinName pin1, PinName pin2, PinName pin3, PinName pi
{
int i;
uint32_t sercom_index[4];
uint32_t pin_com = NC;
uint32_t pin_com = (uint32_t)NC;
sercom_index[0] = pinmap_find_peripheral_from_pad(pin1, SERCOM_USE_DEFAULT_PAD);
sercom_index[1] = pinmap_find_peripheral_from_pad(pin2, SERCOM_USE_DEFAULT_PAD);
@ -112,7 +112,7 @@ uint32_t pinmap_find_sercom(PinName pin1, PinName pin2, PinName pin3, PinName pi
if (pin_com == (uint32_t)NC) {
pin_com = sercom_index[i] & 0x0F;
} else if (pin_com != (sercom_index[i] & 0x0F)) {
return NC;
return (uint32_t)NC;
}
}
}
@ -128,12 +128,12 @@ uint32_t pinmap_find_sercom(PinName pin1, PinName pin2, PinName pin3, PinName pi
*/
uint32_t pinmap_function_sercom(PinName pin, uint32_t sercom_index)
{
uint32_t func = NC;
uint32_t func = (uint32_t)NC;
uint32_t index;
sercom_index &= 0x0F;
if ((pin == NC) || (sercom_index >= SERCOM_INST_NUM)) {
return NC;
return (uint32_t)NC;
}
index = pinmap_peripheral(pin, PinMap_SERCOM_PAD);
if ((index & 0x0F) == sercom_index) {
@ -145,7 +145,7 @@ uint32_t pinmap_function_sercom(PinName pin, uint32_t sercom_index)
func = pinmap_function(pin, PinMap_SERCOM_PADEx);
return func;
}
return NC;
return (uint32_t)NC;
}
/** Find the MUX pad of input pin specific to given SERCOM index
@ -160,7 +160,7 @@ uint32_t pinmap_pad_sercom(PinName pin, uint32_t sercom_index)
sercom_index &= 0x0F;
if ((pin == NC) || (sercom_index >= SERCOM_INST_NUM)) {
return NC;
return (uint32_t)NC;
}
index = pinmap_peripheral(pin, PinMap_SERCOM_PAD);
if ((index & 0x0F) == sercom_index) {
@ -170,7 +170,7 @@ uint32_t pinmap_pad_sercom(PinName pin, uint32_t sercom_index)
if ((index & 0x0F) == sercom_index) {
return ((index >> 4) & 0x0F);
}
return NC;
return (uint32_t)NC;
}
/** Find the MUX function of input pin specific to given SERCOM index
@ -201,7 +201,7 @@ uint32_t pinmap_peripheral_sercom(PinName pin, uint32_t sercom_index)
uint32_t index = sercom_index & 0x0F;
if (index >= SERCOM_INST_NUM) {
return NC;
return (uint32_t)NC;
}
return sercom_address[(sercom_index&0x0F)];
}
@ -222,5 +222,5 @@ uint32_t pinmap_channel_pwm(PinName pin, PWMName pwm)
}
pwm_ch++;
}
return NC;
return (uint32_t)NC;
}

View File

@ -18,6 +18,7 @@
#include "gpio_api.h"
#include "port.h"
#if defined(TARGET_SAMR21G18A)
#define PORTA_MASK 0xDBDFFFF3 // mask for available pins in Port A
#define PORTB_MASK 0xC0C3C30D // mask for available pins in Port B
@ -39,7 +40,7 @@ uint32_t start_pin(PortName port)
if(port < PortMax) { /* PortC value is 2*/
return port * 32;
} else {
return NC;
return (uint32_t)NC;
}
}
void port_init(port_t *obj, PortName port, int mask, PinDirection dir)
@ -139,7 +140,7 @@ void port_dir(port_t *obj, PinDirection dir)
if(start == NC)
return;
obj->direction = dir;
pin_conf.input_pull = obj->mode;
pin_conf.input_pull = (enum port_pin_pull)obj->mode;
pin_conf.powersave = obj->powersave;
for (i = start, j = 0; j < 32; i++, j++) {

View File

@ -66,7 +66,7 @@ static void pwmout_set_period(pwmout_t* obj, int period_us)
us_per_cycle = 1000000.00 / div_freq;
max_period = us_per_cycle * count_max;
if (max_period >= us_period) {
obj->clock_prescaler = tcc_prescaler[i];
obj->clock_prescaler = (enum tc_clock_prescaler)tcc_prescaler[i];
obj->period = us_period / us_per_cycle;
obj->us_per_cycle = us_per_cycle;
break;
@ -81,12 +81,12 @@ static void pwmout_set_period(pwmout_t* obj, int period_us)
*/
bool pwmout_init_hw(pwmout_t* obj)
{
uint32_t mux_func = NC;
uint32_t pwm = NC;
uint32_t mux_func = (uint32_t)NC;
uint32_t pwm = (uint32_t)NC;
PinName pin;
uint32_t ch_index = NC;
uint32_t ch_index = (uint32_t)NC;
struct tcc_config config_tcc;
uint32_t tcc_channel = NC;
uint32_t tcc_channel = (uint32_t)NC;
/* Sanity check arguments */
MBED_ASSERT(obj);
@ -96,7 +96,7 @@ bool pwmout_init_hw(pwmout_t* obj)
if (pwm == (uint32_t)NC) return 0; /* Pin not supported */
mux_func = pinmap_function(pin, PinMap_PWM);
ch_index = pinmap_channel_pwm(pin, pwm);
ch_index = pinmap_channel_pwm(pin, (PWMName) pwm);
if ((mux_func == (uint32_t)NC) || (ch_index == (uint32_t)NC)) {
/* Pin not supported */
return 0;
@ -114,7 +114,7 @@ bool pwmout_init_hw(pwmout_t* obj)
tcc_get_config_defaults(&config_tcc, (Tcc*)pwm);
config_tcc.counter.clock_source = obj->clock_source;
config_tcc.counter.clock_prescaler = obj->clock_prescaler;
config_tcc.counter.clock_prescaler = (enum tcc_clock_prescaler)obj->clock_prescaler;
config_tcc.counter.period = obj->period;
config_tcc.compare.wave_generation = TCC_WAVE_GENERATION_SINGLE_SLOPE_PWM;
@ -147,7 +147,7 @@ void pwmout_init(pwmout_t* obj, PinName pin)
obj->period = 0xFFFF;
obj->duty_cycle = 1;
obj->clock_source = GCLK_GENERATOR_0; /* 8Mhz input clock */
obj->clock_prescaler = TCC_CLOCK_PRESCALER_DIV8; /* Default to 1MHz for 8Mhz input clock */
obj->clock_prescaler = (enum tc_clock_prescaler)TCC_CLOCK_PRESCALER_DIV8; /* Default to 1MHz for 8Mhz input clock */
/* Update the changes */
if (pwmout_init_hw(obj)) {

View File

@ -122,4 +122,4 @@ void rtc_write(time_t t)
uint32_t count_value = (uint32_t)t;
rtc_count_set_count(&rtc_instance, count_value);
}
}

View File

@ -41,7 +41,7 @@ uint8_t sercom_setup_tx_channel(uint8_t sercom_index, uint8_t *tx_id)
sercom_channels[sercom_index].tx_status = DMA_ALLOCATED;
} else {
/* Couldn't find a channel */
return DMA_ERROR_OUT_OF_CHANNELS;
return (uint8_t)DMA_ERROR_OUT_OF_CHANNELS;
}
}
return *tx_id;
@ -65,7 +65,7 @@ uint8_t sercom_setup_rx_channel(uint8_t sercom_index, uint8_t *rx_id)
sercom_channels[sercom_index].rx_status = DMA_ALLOCATED;
} else {
/* Couldn't find a channel */
return DMA_ERROR_OUT_OF_CHANNELS;
return (uint8_t)DMA_ERROR_OUT_OF_CHANNELS;
}
}
return *rx_id;

View File

@ -59,4 +59,4 @@ void sercom_release_channel(uint8_t sercom_index);
}
#endif
#endif /* _SERCOM_DMA_H */
#endif /* _SERCOM_DMA_H */

View File

@ -27,6 +27,7 @@
#define USART_RXFLOW_INDEX 2
#define USART_TXFLOW_INDEX 3
#if DEVICE_SERIAL_ASYNCH
#define pUSART_S(obj) obj->serial.usart
#define pSERIAL_S(obj) ((struct serial_s*)&(obj->serial))
@ -36,17 +37,17 @@
#endif
#define _USART(obj) pUSART_S(obj)->USART
#define USART_NUM 6
#define SUPPRESS_WARNING(a) (void)a
uint8_t serial_get_index(serial_t *obj);
IRQn_Type get_serial_irq_num (serial_t *obj);
uint32_t get_serial_vector (serial_t *obj);
void uart0_irq();
void uart1_irq();
void uart2_irq();
void uart3_irq();
void uart4_irq();
void uart5_irq();
void uart0_irq(void);
void uart1_irq(void);
void uart2_irq(void);
void uart3_irq(void);
void uart4_irq(void);
void uart5_irq(void);
static uint32_t serial_irq_ids[USART_NUM] = {0};
static uart_irq_handler irq_handler;
@ -103,6 +104,7 @@ static inline void reset_usart(serial_t *obj)
/* Reset module */
_USART(obj).CTRLA.reg = SERCOM_USART_CTRLA_SWRST;
SUPPRESS_WARNING(reset_usart);
}
uint32_t serial_find_mux_settings (serial_t *obj)
@ -258,7 +260,7 @@ void serial_init(serial_t *obj, PinName tx, PinName rx)
return;
}
sercom_index &= 0x0F;
uart = pinmap_peripheral_sercom(NC, sercom_index);
uart = (UARTName)pinmap_peripheral_sercom(NC, sercom_index);
pUSART_S(obj) = (Sercom *)uart;
/* Disable USART module */
@ -320,7 +322,7 @@ void serial_init(serial_t *obj, PinName tx, PinName rx)
for (uint8_t pad = 0; pad < 4; pad++) {
uint32_t current_pin = pSERIAL_S(obj)->pins[pad];
if (current_pin != (uint32_t)NC) {
pin_conf.mux_position = pinmap_function_sercom(current_pin, sercom_index);
pin_conf.mux_position = pinmap_function_sercom((PinName)current_pin, sercom_index);
if ((uint8_t)NC != pin_conf.mux_position) {
system_pinmux_pin_set_config(current_pin, &pin_conf);
}
@ -533,7 +535,7 @@ void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, Pi
for (uint8_t pad = 0; pad < 2; pad++) { // setting for rx and tx
uint32_t current_pin = pSERIAL_S(obj)->pins[pad];
if (current_pin != (uint32_t)NC) {
pin_conf.mux_position = pinmap_function_sercom(current_pin, sercom_index);
pin_conf.mux_position = pinmap_function_sercom((PinName)current_pin, sercom_index);
if ((uint8_t)NC != pin_conf.mux_position) {
system_pinmux_pin_set_config(current_pin, &pin_conf);
}
@ -1085,4 +1087,4 @@ void serial_rx_abort_asynch(serial_t *obj)
obj->rx_buff.pos = 0;
}
#endif
#endif

View File

@ -47,4 +47,4 @@ void deepsleep(void)
{
system_set_sleepmode(SYSTEM_SLEEPMODE_STANDBY);
system_sleep();
}
}

View File

@ -197,7 +197,7 @@ static uint32_t spi_find_mux_settings(spi_t *obj)
if (pSPI_S(obj)->pins[i_dipo] != NC) {
/* Set Data input MUX padding for master */
mux_pad = pinmap_pad_sercom(pSPI_S(obj)->pins[i_dipo], sercom_index);
if (mux_pad != NC) {
if (mux_pad != (uint32_t)NC) {
/* MUX pad value is same as DIPO value */
dipo = mux_pad;
mux_settings |= ((dipo << SERCOM_SPI_CTRLA_DIPO_Pos) & SERCOM_SPI_CTRLA_DIPO_Msk);
@ -207,7 +207,7 @@ static uint32_t spi_find_mux_settings(spi_t *obj)
if (pSPI_S(obj)->pins[i_dopo] != NC) {
/* Set Data output MUX padding for master */
mux_pad = pinmap_pad_sercom(pSPI_S(obj)->pins[i_dopo], sercom_index);
if (mux_pad != NC) {
if (mux_pad != (uint32_t)NC) {
if (mux_pad != 0) {
dopo = mux_pad - 1;
} else {
@ -338,8 +338,8 @@ void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel
/* Configure the SERCOM pins according to the user configuration */
for (uint8_t pad = 0; pad < 4; pad++) {
uint32_t current_pin = pSPI_S(obj)->pins[pad];
if (current_pin != NC) {
pin_conf.mux_position = pinmap_function_sercom(current_pin, sercom_index);
if (current_pin != (uint32_t)NC) {
pin_conf.mux_position = pinmap_function_sercom((PinName)current_pin, sercom_index);
if ((uint8_t)NC != pin_conf.mux_position) {
system_pinmux_pin_set_config(current_pin, &pin_conf);
}
@ -775,8 +775,8 @@ static void _spi_clear_interrupts(spi_t *obj)
SERCOM_SPI_INTFLAG_TXC |
SERCOM_SPI_INTFLAG_RXC |
SERCOM_SPI_INTFLAG_ERROR;
NVIC_DisableIRQ(SERCOM0_IRQn + sercom_index);
NVIC_SetVector((SERCOM0_IRQn + sercom_index), (uint32_t)NULL);
NVIC_DisableIRQ((IRQn_Type)((uint8_t)SERCOM0_IRQn + sercom_index));
NVIC_SetVector((IRQn_Type)((uint8_t)SERCOM0_IRQn + sercom_index), (uint32_t)NULL);
}
/**
@ -833,7 +833,7 @@ static enum status_code _spi_transceive_buffer(spi_t *obj)
} else {
obj->spi.status = STATUS_ERR_BAD_DATA;
}
return obj->spi.status;
return (enum status_code)obj->spi.status;
}
if ((obj->tx_buff.pos >= obj->tx_buff.length) && (obj->rx_buff.pos >= obj->rx_buff.length) && (interrupt_status & SERCOM_SPI_INTFLAG_TXC)) {
@ -845,7 +845,7 @@ static enum status_code _spi_transceive_buffer(spi_t *obj)
obj->spi.status = STATUS_OK;
}
return obj->spi.status;
return (enum status_code)(obj->spi.status);
}
/** Begin the SPI transfer. Buffer pointers and lengths are specified in tx_buff and rx_buff
@ -863,13 +863,14 @@ static enum status_code _spi_transceive_buffer(spi_t *obj)
void spi_master_transfer(spi_t *obj, const void *tx, size_t tx_length, void *rx, size_t rx_length, uint8_t bit_width, uint32_t handler, uint32_t event, DMAUsage hint)
{
uint16_t dummy_read;
(void) dummy_read;
/* Sanity check arguments */
MBED_ASSERT(obj);
uint8_t sercom_index = _sercom_get_sercom_inst_index(obj->spi.spi);
obj->spi.tx_buffer = tx;
obj->tx_buff.buffer = tx;
obj->spi.tx_buffer = (void *)tx;
obj->tx_buff.buffer =(void *)tx;
obj->tx_buff.pos = 0;
if (tx) {
/* Only two bit rates supported now */
@ -912,8 +913,8 @@ void spi_master_transfer(spi_t *obj, const void *tx, size_t tx_length, void *rx,
obj->spi.status = STATUS_BUSY;
/* Enable interrupt */
NVIC_SetVector((SERCOM0_IRQn + sercom_index), handler);
NVIC_EnableIRQ(SERCOM0_IRQn + sercom_index);
NVIC_SetVector((IRQn_Type)((uint8_t)SERCOM0_IRQn + sercom_index), handler);
NVIC_EnableIRQ((IRQn_Type)((uint8_t)SERCOM0_IRQn + sercom_index));
/* Clear all interrupts */
_SPI(obj).INTENCLR.reg = SERCOM_SPI_INTFLAG_TXC | SERCOM_SPI_INTFLAG_RXC | SERCOM_SPI_INTFLAG_ERROR;
@ -991,8 +992,8 @@ void spi_abort_asynch(spi_t *obj)
SERCOM_SPI_INTFLAG_ERROR;
// TODO: Disable and remove irq handler
NVIC_DisableIRQ(SERCOM0_IRQn + sercom_index);
NVIC_SetVector((SERCOM0_IRQn + sercom_index), (uint32_t)NULL);
NVIC_DisableIRQ((IRQn_Type)((uint8_t)SERCOM0_IRQn + sercom_index));
NVIC_SetVector((IRQn_Type)((uint8_t)SERCOM0_IRQn + sercom_index), (uint32_t)NULL);
obj->spi.status = STATUS_ABORTED;
}

View File

@ -72,7 +72,6 @@ void us_ticker_init(void)
uint32_t cycles_per_us;
uint32_t prescaler = 0;
struct tc_config config_tc;
enum status_code ret_status;
if (us_ticker_inited) return;
us_ticker_inited = 1;
@ -102,15 +101,14 @@ void us_ticker_init(void)
prescaler = 5;
}
config_tc.clock_prescaler = TC_CTRLA_PRESCALER(prescaler);
config_tc.clock_prescaler = (enum tc_clock_prescaler)TC_CTRLA_PRESCALER(prescaler);
config_tc.counter_size = TC_COUNTER_SIZE_32BIT;
config_tc.run_in_standby = true;
config_tc.counter_32_bit.value = 0;
config_tc.counter_32_bit.compare_capture_channel[TC_COMPARE_CAPTURE_CHANNEL_0] = 0xFFFFFFFF;
/* Initialize the timer */
ret_status = tc_init(&us_ticker_module, TICKER_COUNTER_uS, &config_tc);
MBED_ASSERT(ret_status == STATUS_OK);
tc_init(&us_ticker_module, TICKER_COUNTER_uS, &config_tc);
/* Register callback function */
tc_register_callback(&us_ticker_module, (tc_callback_t)us_ticker_irq_handler_internal, TC_CALLBACK_CC_CHANNEL0);
@ -168,4 +166,4 @@ void us_ticker_clear_interrupt(void)
/* Clear the interrupt */
tc_clear_interrupt(&us_ticker_module, TC_CALLBACK_CC_CHANNEL0);
NVIC_ClearPendingIRQ(TICKER_COUNTER_IRQn);
}
}