Formatting code according to ARM guidelines. Ran pylint and astyle. Rebased latest ARMmbed-os code.

pull/2590/head
Radhika 2016-08-26 16:52:11 +05:30 committed by 0xc0170
parent 5e81f0fd73
commit 8310d415af
67 changed files with 3412 additions and 3633 deletions

View File

@ -2032,6 +2032,7 @@
"progen": {"target": "ncs36510"},
"progen_target": "ncs36510",
"supported_toolchains": ["GCC_ARM", "ARM", "IAR"],
"device_has": ["ANALOGIN", "SERIAL", "I2C", "INTERRUPTIN", "LOWPOWERTIMER", "PORTIN", "PORTINOUT", "PORTOUT", "PWMOUT", "RTC", "SERIAL", "SERIAL_FC", "SLEEP", "SPI"]
"device_has": ["ANALOGIN", "SERIAL", "I2C", "INTERRUPTIN", "PORTIN", "PORTINOUT", "PORTOUT", "PWMOUT", "RTC", "SERIAL", "SERIAL_FC", "SLEEP", "SPI"],
"release_versions": ["2", "5"]
}
}

View File

@ -101,7 +101,7 @@ void fPadInit()
boolean fPadIOCtrl(uint8_t PadNum, uint8_t OutputDriveStrength, uint8_t OutputDriveType, uint8_t PullType)
{
PadReg_t *PadRegOffset;
/** \verbatim
/** \verbatim
Table: O/p drive strength
Drive strength 3.3V (min/typ/max) 1V (min/typ/max)
@ -118,8 +118,7 @@ boolean fPadIOCtrl(uint8_t PadNum, uint8_t OutputDriveStrength, uint8_t OutputDr
if((PadNum <= PAD_NUM_OF_IO) &&
(OutputDriveStrength <= PAD_OP_DRIVE_STRGTH_MAX) &&
(OutputDriveType <= PAD_OP_DRIVE_TYPE_MAX) && (PullType <= PAD_OP_PULL_TYPE_MAX))
{
(OutputDriveType <= PAD_OP_DRIVE_TYPE_MAX) && (PullType <= PAD_OP_PULL_TYPE_MAX)) {
/** - Get PAD IO register address for the PAD number */
PadRegOffset = (PadReg_t*)(PADREG_BASE + (PadNum * PAD_REG_ADRS_BYTE_SIZE));

View File

@ -26,8 +26,8 @@
#include "cmsis.h"
#include "memory_map.h" //I think this is needed because enums are using base adresses
#include "PinNames.h" //this needed?
#include "memory_map.h" /* This is needed because enums use base adresses */
#include "PinNames.h"
#ifdef __cplusplus
extern "C" {
#endif
@ -57,7 +57,7 @@ typedef enum {
typedef enum {
PWM_0 = (int)PWMREG_BASE,
}PWMName;
} PWMName;
#ifdef __cplusplus
}

View File

@ -14,7 +14,7 @@
* limitations under the License.
*/
/*todo: determine how function argument is used */
/*todo: determine how function argument is used */
#include "PeripheralPins.h"
@ -67,28 +67,32 @@ const PinMap PinMap_SPI_SCLK[] = {
{SPI1_SCLK_2, SPI_0, 6},
{SPI1_SCLK_3, SPI_0, 6},
{SPI2_SCLK, SPI_1, 6},
{NC, NC, 0}};
{NC, NC, 0}
};
const PinMap PinMap_SPI_MOSI[] = {
/*todo: other pins are possible, need to add */
{SPI1_SDATAO_2, SPI_0, 6},
{SPI1_SDATAO_3, SPI_0, 6},
{SPI2_SDATAO, SPI_1, 6},
{NC, NC, 0}};
{NC, NC, 0}
};
const PinMap PinMap_SPI_MISO[] = {
/*todo: other pins are possible, need to add */
{SPI1_SDATAI_2, SPI_0, 6},
{SPI1_SDATAI_3, SPI_0, 6},
{SPI2_SDATAI, SPI_1, 6},
{NC, NC, 0}};
{NC, NC, 0}
};
const PinMap PinMap_SPI_SSEL[] = {
/*todo: other pins are possible, need to add */
/* TODO what about SSNO */
{SPI1_SSNI_2, SPI_0, 6},
{SPI2_SSNI, SPI_1, 6},
{NC, NC, 0}};
{NC, NC, 0}
};
const PinMap PinMap_PWM[] = {

View File

@ -1,7 +1,7 @@
/**
******************************************************************************
* @file PinNames.h
* @brief Implements an assertion.
* @brief Implements common PIN names for peripherals.
* @internal
* @author ON Semiconductor
* $Rev: 0.1 $
@ -142,13 +142,13 @@ typedef enum {
D14 = GPIO3,
D15 = GPIO2,
NC = (int)0xFFFFFFFF
} PinName;
} PinName;
typedef enum {
PIN_INPUT,
PIN_OUTPUT,
}PinDirection;
} PinDirection;
typedef enum {
PushPullPullDown = 0,

View File

@ -48,36 +48,31 @@ extern "C" {
#define ADC_DELAY_WARMUP_BIT_POS 16
#define ADC_DELAY_SAMPLE_TIME_BIT_POS 24
typedef enum
{
typedef enum {
ADC_CHANNEL0 = 0,
ADC_CHANNEL1,
ADC_CHANNEL2,
ADC_CHANNEL3,
ADC_TEMPSENSR = 6,
ADC_BATTERY
}Type_RefCh_ConvCh;
} Type_RefCh_ConvCh;
typedef enum
{
typedef enum {
ADC_RELATIVE_MEAS = 0,
ADC_ABSOLUTE_MEAS
}Type_Meastype;
} Type_Meastype;
typedef enum
{
typedef enum {
ADC_SINGLE_SAMPLE = 0,
ADC_CONTINUOUS_SAMPLE
}Type_Mode;
} Type_Mode;
typedef enum
{
typedef enum {
ADC_INT_DISABLE = 0,
ADC_INT_ENABLE
}Type_Intrpt;
} Type_Intrpt;
typedef enum
{
typedef enum {
ADC_IP_SCALE_1_0 = 0,
ADC_IP_SCALE_0_6923,
ADC_IP_SCALE_0_5294,
@ -86,7 +81,7 @@ typedef enum
ADC_IP_SCALE_0_3103,
ADC_IP_SCALE_0_2728,
ADC_IP_SCALE_0_2432
}Ip_Scale_Type;
} Ip_Scale_Type;
void fAdcHandler(void);

View File

@ -34,11 +34,9 @@
#include "architecture.h"
/* ADC Control HW Structure Overlay */
typedef struct{
union
{
struct
{
typedef struct {
union {
struct {
__IO uint32_t MODE :1; /** 1= Continuous Conversion 0= Single Shot */
__IO uint32_t START_CONV :1; /** 1= Start Conversion 0= No effect*/
__IO uint32_t ABORT :1; /** 1= Aborts the Continuous Conversion mode 0=No effect */
@ -48,32 +46,28 @@ typedef struct{
__IO uint32_t CONV_CH :3; /** Selects 1 or 8 channels to do a conversion on. 000 A[0] 000 A[1] 010 A[2] 011 A[3] 100 N/A 101 N/A 110 Temperature sensor 111 Battery */
__I uint32_t NA :1; /** NA */
__IO uint32_t REF_CH :3; /** Selects 1 to 8 channels for reference channel 000 A[0] 000 A[1] 010 A[2] 011 A[3] 100 N/A 101 N/A 110 Temperature sensor 111 Battery */
}BITS;
} BITS;
__IO uint32_t WORD;
}CONTROL;
union
{
struct
{
} CONTROL;
union {
struct {
__IO uint32_t SAMPLE_RATE :16; /** Sets the sample rate in units of PCLKperiod * (Prescale + 1). */
__IO uint32_t WARMUP_TIME :8; /** Sets the warm-up time in units of PCLKperiod * (Prescale + 1) */
__IO uint32_t SAMPLE_TIME :8; /** Sample Time. Sets the measure time in units of PCLKperiod * (Prescale + 1).*/
}BITS;
} BITS;
__IO uint32_t WORD;
}DELAY;
} DELAY;
__I uint32_t DATA;
__IO uint32_t IR;
union
{
struct
{
union {
struct {
__IO uint32_t PRESC_VAL :8; /**Set the pre-scalar value. The SAR ADC nominally runs at 4MHz, so this value should be programmed to 32 Mhz/4mhz -1=7 */
__IO uint32_t PRESC_EN :1; /** 1= enables PreScalar 0= Disable Prescalar */
// __IO uint32_t PHASE_CTRL :1; /** 1 = Phase 2 is delayed two 32MHz clock from phase 1. 0= Phase 2 is delayed one 32MHz clock from phase 1. */
}BITS;
} BITS;
__IO uint32_t WORD;
}PRESCALE;
} PRESCALE;
__I uint32_t STATUS;
}ADCReg_t,*AdcReg_pt;
} ADCReg_t,*AdcReg_pt;
#endif /* ADC_MAP_H_ */

View File

@ -3,7 +3,7 @@
* @file aes_map.h
* @brief AES HW register map
* @internal
* @author Industrial ASSP Application Team.
* @author ON Semiconductor.
* $Rev: 2110 $
* $Date: 2013-07-16 20:13:03 +0530 (Tue, 16 Jul 2013) $
******************************************************************************

View File

@ -59,8 +59,7 @@ void analogin_init(analogin_t *obj, PinName pin)
obj->pin = pin;
obj->pinFlag = 1;
switch (pin)
{
switch (pin) {
case A0:
adc_pin=0;
break;
@ -78,8 +77,7 @@ void analogin_init(analogin_t *obj, PinName pin)
}
/* If no config parameters are passed on; assume default value */
if (obj->adcConf == Null)
{
if (obj->adcConf == Null) {
/* Single sample, absolute conversion, scale = 1 */
obj->adcReg->CONTROL.WORD = ((0 << ADC_CONTROL_MODE_BIT_POS) |
(1 << ADC_CONTROL_MEASTYPE_BIT_POS) |
@ -95,22 +93,17 @@ void analogin_init(analogin_t *obj, PinName pin)
(0x1A << ADC_DELAY_SAMPLE_TIME_BIT_POS)); /** 2.5 uS Sets the warm-up time in units of PCLKperiod * (Prescale + 1). */
obj->adcReg->IR = 0; /** No interrupt generated */
}
else
{
} else {
obj->adcConf->convCh = adc_pin;
/* ADC register settings */
if((obj->adcConf->measurementType) == ADC_RELATIVE_MEAS)
{
if((obj->adcConf->measurementType) == ADC_RELATIVE_MEAS) {
obj->adcReg->CONTROL.WORD = ((obj->adcConf->mode << ADC_CONTROL_MODE_BIT_POS) |
(obj->adcConf->measurementType << ADC_CONTROL_MEASTYPE_BIT_POS) |
(obj->adcConf->inputScale << ADC_CONTROL_INPUTSCALE_BIT_POS) |
(obj->adcConf->convCh << ADC_CONTROL_MEAS_CH_BIT_POS) |
(obj->adcConf->referenceCh << ADC_CONTROL_REF_CH_BIT_POS));
}
else
{
} else {
obj->adcReg->CONTROL.WORD = ((obj->adcConf->mode << ADC_CONTROL_MODE_BIT_POS) |
(obj->adcConf->measurementType << ADC_CONTROL_MEASTYPE_BIT_POS) |
(obj->adcConf->inputScale << ADC_CONTROL_INPUTSCALE_BIT_POS) |
@ -157,10 +150,8 @@ uint16_t analogin_read_u16(analogin_t *obj)
CLOCK_ENABLE(CLOCK_ADC);
if (obj->pinFlag)
{
switch (obj->pin)
{
if (obj->pinFlag) {
switch (obj->pin) {
case A0:
adc_pin=0;
break;
@ -183,23 +174,13 @@ uint16_t analogin_read_u16(analogin_t *obj)
obj->adcReg->CONTROL.BITS.START_CONV=1; /* Start The Conversion */
while((uint32_t)(obj->adcReg->STATUS)!=(uint32_t)1)
{}
while((uint32_t)(obj->adcReg->STATUS)!=(uint32_t)1) {
}
adcData =(uint16_t)(obj->adcReg->DATA);
CLOCK_DISABLE(CLOCK_ADC);
return(adcData);
}
/*ADC handler function */
void fAdcHandler(void)
{
uint16_t adcData = 0;
AdcReg_pt adcReg = (AdcReg_pt)ADC_0;
adcReg->IR = True;
NVIC_ClearPendingIRQ(Adc_IRQn);
adcData =(uint16_t)(adcReg->DATA);
}
#endif // DEVICE_ANALOGIN

View File

@ -42,8 +42,7 @@
/** DMA control HW registers structure overlay */
#ifdef REVB
typedef struct
{
typedef struct {
__IO uint32_t CONTROL; /**< Write 1 to enable DMA, write 0 to disable */
__IO uint32_t SOURCE; /**< Address of source, read to get the number of bytes written */
__IO uint32_t DESTINATION; /**< Address of destination, read to get the number of bytes written */
@ -52,63 +51,52 @@ typedef struct
__IO uint32_t INT_ENABLE; /**< Enable interrupt source by writing 1. Bit 0: DMA done, Bit 1: Source Error, Bit 2: Destination Error */
__IO uint32_t INT_CLEAR_ENABLE; /**< Clear Interrupt source by writing 1. Bit 0: DMA done, Bit 1: Source Error, Bit 2: Destination Error */
__I uint32_t INT_STATUS; /**< Current interrupt status. Bit 0: DMA done, Bit 1: Source Error, Bit 2: Destination Error */
}DmaReg_t, *DmaReg_pt;
} DmaReg_t, *DmaReg_pt;
#endif /* REVB */
#ifdef REVD
typedef struct
{
union
{
struct
{
typedef struct {
union {
struct {
__IO uint32_t ENABLE:1; /**< DMA enable: 1 to enable; 0 to disable */
__IO uint32_t MODE :2; /**< DMA mode: 00 Memory to memory; 01 Memory to peripheral; 10 Peripheral to memory; 11 Peripheral to peripheral */
}BITS;
} BITS;
__IO uint32_t WORD;
}CONTROL; /**< Control register */
} CONTROL; /**< Control register */
__IO uint32_t SOURCE; /**< Address of source, read to get the number of bytes written */
__IO uint32_t DESTINATION; /**< Address of destination, read to get the number of bytes written */
__IO uint32_t SIZE; /**< Lenght of the entire transfer */
union
{
struct
{
union {
struct {
__I uint32_t COMPLETED:1; /**< Done: 0 Not complete, 1 Complete */
__I uint32_t SOURCE_ERROR:1; /**< Source Error: 0 No Error, 1 Error */
__I uint32_t DESTINATION_ERROR:1; /**< Destination Error: 0 No Error, 1 Source Error */
}BITS;
} BITS;
__I uint32_t WORD;
}STATUS; /**< Status register */
union
{
struct
{
} STATUS; /**< Status register */
union {
struct {
__IO uint32_t COMPLETED:1; /**< A write of 1 enables the interrupt generated by a DMA transfer complete */
__IO uint32_t SOURCE_ERROR:1; /**< A write of 1 enables the interrupt generated by an error on the source side of the DMA transfer */
__IO uint32_t DESTINATION_ERROR:1; /**< A write of 1 enables the interrupt generated by an error on the destination side of the DMA transfer */
}BITS;
} BITS;
__IO uint32_t WORD;
}INT_ENABLE; /**< Interrupt enable */
union
{
struct
{
} INT_ENABLE; /**< Interrupt enable */
union {
struct {
__IO uint32_t COMPLETED:1; /**< A write clears the interrupt generated by a DMA transfer complete */
__IO uint32_t SOURCE_ERROR:1; /**< A write clears the interrupt generated by an error on the source side of the DMA transfer */
__IO uint32_t DESTINATION_ERROR:1; /**< A write clears the interrupt generated by an error on the destination side of the DMA transfer */
}BITS;
} BITS;
__IO uint32_t WORD;
}INT_CLEAR; /**< Interrupt clear */
union
{
struct
{
} INT_CLEAR; /**< Interrupt clear */
union {
struct {
__I uint32_t COMPLETED:1; /**< Transfer complete interrupt */
__I uint32_t SOURCE_ERROR:1; /**< Source error interrupt */
__I uint32_t DESTINATION_ERROR:1; /**< Destination error interrupt */
}BITS;
} BITS;
__I uint32_t WORD;
}INT_STATUS; /**< Interrupt status */
}DmaReg_t, *DmaReg_pt;
} INT_STATUS; /**< Interrupt status */
} DmaReg_t, *DmaReg_pt;
#endif /* REVD */
#endif /* DMA_MAP_H_ */

View File

@ -57,13 +57,15 @@ extern void fSysTickHandler(void);
*************************************************************************************************/
/** Not implemented exception, exception handler */
void NotImplemented_Handler(void){
while (1){};
void NotImplemented_Handler(void)
{
while (1) {};
}
/** Hardware fault interrupt handler */
void HardFault_Handler(void) {
while (1){};
void HardFault_Handler(void)
{
while (1) {};
}
/*************************************************************************************************
@ -71,48 +73,47 @@ void HardFault_Handler(void) {
* Functions *
* *
*************************************************************************************************/
/** Call the MacHw IRQ handler */
/* commented out - implemented in network stack
void fIrqMacHwHandler() {
NotImplemented_Handler();
}
*/
/** MacHw IRQ handler implemented in the RF driver stack */
/** Call the Timer0 IRQ handler */
void fIrqTim0Handler() {
void fIrqTim0Handler()
{
us_timer_isr();
}
/** Call the Timer1 IRQ handler */
void fIrqTim1Handler() {
void fIrqTim1Handler()
{
us_ticker_isr();
}
/** Call the Timer2 IRQ handler */
void fIrqTim2Handler() {
void fIrqTim2Handler()
{
NotImplemented_Handler();
}
/** Call the Gpio IRQ handler */
void fIrqGpioHandler() {
#if DEVICE_INTERRUPTIN
void fIrqGpioHandler()
{
fGpioHandler();
#endif
}
/** Call the Spi IRQ handler */
void fIrqSpiHandler() {
void fIrqSpiHandler()
{
NotImplemented_Handler();
}
/** Call the Uart 1 IRQ handler */
void fIrqUart1Handler(void) {
void fIrqUart1Handler(void)
{
Uart1_Irq();
}
/** Call the Uart 2 IRQ handler */
void fIrqUart2Handler(void) {
void fIrqUart2Handler(void)
{
Uart2_Irq();
}

View File

@ -37,7 +37,7 @@
typedef struct {
unsigned int fwbase_address;
mib_systemRevision_t fw_version;
}fibtable_t;
} fibtable_t;
#endif

View File

@ -70,8 +70,7 @@
**/
uint32_t gpio_set(PinName pin)
{
if (pin != NC)
{
if (pin != NC) {
/* Configure to GPIO using pin function API*/
pin_function(pin, CONFIGURE_AS_GPIO);
@ -161,12 +160,9 @@ void gpio_write(gpio_t *obj, int value)
CLOCK_ENABLE(CLOCK_GPIO);
/* Set the GPIO based on value */
if (value)
{
if (value) {
obj->GPIOMEMBASE->R_STATE_W_SET = obj->gpioMask;
}
else
{
} else {
obj->GPIOMEMBASE->R_IRQ_W_CLEAR = obj->gpioMask;
}

View File

@ -91,14 +91,12 @@ void fGpioHandler(void)
/** - Store all active interrupts */
active_interrupts = gpioBase->R_IRQ_W_CLEAR;
for (index=0; index < NUMBER_OF_GPIO; index++)
{
for (index=0; index < NUMBER_OF_GPIO; index++) {
/* Check the pin for which IRQ is raised */
if ((active_interrupts >> index) & 0x01)
{
if ((active_interrupts >> index) & 0x01) {
/* Check if it is edge triggered and clear the interrupt */
if ((gpioBase->IRQ_EDGE >> index) & 0x01){
if ((gpioBase->IRQ_EDGE >> index) & 0x01) {
if ((gpioBase->IRQ_POLARITY_SET >> index) &0x01) {
/* Edge triggered high */
event = IRQ_RISE;
@ -130,8 +128,7 @@ void fGpioHandler(void)
int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id)
{
/* If Pin is not connected; then return -1 */
if (pin == NC)
{
if (pin == NC) {
return(-1);
}
@ -194,19 +191,15 @@ void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable)
/* Enable the GPIO clock */
CLOCK_ENABLE(CLOCK_GPIO);
switch(event)
{
switch(event) {
case IRQ_RISE:
obj->GPIOMEMBASE->IRQ_EDGE = (obj->pinMask);
obj->GPIOMEMBASE->IRQ_LEVEL = (IO_ALL ^ (obj->pinMask));
/* Enable is an integer; hence checking for 1 or 0*/
if (enable == 1)
{
if (enable == 1) {
/* Enable rising edge */
obj->GPIOMEMBASE->IRQ_POLARITY_SET = (obj->pinMask);
}
else if (enable == 0)
{
} else if (enable == 0) {
/* Disable rising edge */
obj->GPIOMEMBASE->IRQ_POLARITY_SET = (IO_ALL ^ (obj->pinMask));
}
@ -216,13 +209,10 @@ void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable)
obj->GPIOMEMBASE->IRQ_EDGE = (obj->pinMask);
obj->GPIOMEMBASE->IRQ_LEVEL = (IO_ALL ^ (obj->pinMask));
/* Enable is an integer; hence checking for 1 or 0*/
if (enable == 1)
{
if (enable == 1) {
/* Enable falling edge */
obj->GPIOMEMBASE->IRQ_POLARITY_CLEAR = (obj->pinMask);
}
else if (enable == 0)
{
} else if (enable == 0) {
/* Disable falling edge */
obj->GPIOMEMBASE->IRQ_POLARITY_CLEAR = (IO_ALL ^ (obj->pinMask));
}

View File

@ -54,35 +54,35 @@ int i2c_stop(i2c_t *obj)
/* See i2c_api.h for details */
int i2c_read(i2c_t *obj, int address, char *data, int length, int stop)
{ /* TODO address parameter not usable */
{
/* TODO address parameter not usable */
int Count, status;
const char WriteData = (address | (~I2C_READ_WRITE_BIT_MASK)) & 0xFF;
/* Send start bit */
status = fI2cStart(obj);
if(status)
{/* Error sending start bit */
if(status) {
/* Error sending start bit */
return status;
}
/* Send address | read */
Count = fI2cWriteB(obj, &WriteData, 1);
if(Count != 1)
{/* Error sending address */
if(Count != 1) {
/* Error sending address */
return Count;
}
/* Send command/s */
Count = fI2cReadB(obj, data, length);
if(Count != length)
{/* Error sending coomand/s */
if(Count != length) {
/* Error sending coomand/s */
return Count;
}
if(stop) /* Send stop bit if requested */
{
if(stop) { /* Send stop bit if requested */
status = fI2cStop(obj);
if(status)
{/* Error sending stop bit */
if(status) {
/* Error sending stop bit */
return status;
}
}
@ -97,30 +97,30 @@ int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop)
/* Send start bit */
status = fI2cStart(obj);
if(status)
{/* Error sending start bit */
if(status) {
/* Error sending start bit */
return status;
}
/* Send address | write */
Count = fI2cWriteB(obj, &WriteData, 1);
if(Count != 1)
{/* Error sending address */
if(Count != 1) {
/* Error sending address */
return Count;
}
/* Sens command, [data] */
Count = fI2cWriteB(obj, data, length);
if(Count != length)
{/* Error sending address */
if(Count != length) {
/* Error sending address */
return Count;
}
if(stop) /* If stop requested */
{/* Send stop bit */
if(stop) { /* If stop requested */
/* Send stop bit */
status = fI2cStop(obj);
if(status)
{/* Error sending stop bit */
if(status) {
/* Error sending stop bit */
return status;
}
}
@ -139,16 +139,15 @@ int i2c_byte_read(i2c_t *obj, int last) /* TODO return size can be uint8_t */
int Count;
char data;
Count = fI2cReadB(obj, &data, 1);
if(Count != 1)
{/* Error */
if(Count != 1) {
/* Error */
return Count;
}
if(last)
{/* ACK */
if(last) {
/* ACK */
obj->membase->CMD_REG = I2C_CMD_WDAT0;
}
else
{/* No ACK */
} else {
/* No ACK */
obj->membase->CMD_REG = I2C_CMD_WDAT1;
}
return data;
@ -159,8 +158,7 @@ int i2c_byte_write(i2c_t *obj, int data)
{
int Count;
Count = fI2cWriteB(obj, (const char *)&data, 1);
if(Count != 1)
{
if(Count != 1) {
return Count;
}
@ -168,12 +166,11 @@ int i2c_byte_write(i2c_t *obj, int data)
while(obj->membase->STATUS.WORD & I2C_STATUS_CMD_FIFO_OFL_BIT); /* Wait till command overflow ends */
if(obj->membase->STATUS.WORD & I2C_STATUS_BUS_ERR_BIT)
{/* Bus error means NAK received */
if(obj->membase->STATUS.WORD & I2C_STATUS_BUS_ERR_BIT) {
/* Bus error means NAK received */
return 0;
}
else
{/* ACK received */
} else {
/* ACK received */
return 1;
}
}

View File

@ -214,57 +214,57 @@ typedef struct {
__IO uint32_t CRD_LONG_ADDR_LO; /**< 0x40014078 */
#endif /* REVB */
#ifdef REVD
} CRD_SHORT_ADDR; /**< 0x4001406C */
__IO uint32_t CRD_LONG_ADDR_HI; /**< 0x40014070 */
__IO uint32_t CRD_LONG_ADDR_LO; /**< 0x40014074 */
__O uint32_t PAD5; /**< 0x40014078 */
} CRD_SHORT_ADDR; /**< 0x4001406C */
__IO uint32_t CRD_LONG_ADDR_HI; /**< 0x40014070 */
__IO uint32_t CRD_LONG_ADDR_LO; /**< 0x40014074 */
__O uint32_t PAD5; /**< 0x40014078 */
#endif /* REVD */
__O uint32_t PAD9; /**< 0x4001407C */
__O uint32_t PAD10; /**< 0x40014080 */
__O uint32_t PAD11; /**< 0x40014084 */
__IO uint32_t RX_LENGTH; /**< 0x40014088 */
union {
__O uint32_t PAD9; /**< 0x4001407C */
__O uint32_t PAD10; /**< 0x40014080 */
__O uint32_t PAD11; /**< 0x40014084 */
__IO uint32_t RX_LENGTH; /**< 0x40014088 */
union {
struct {
__IO uint32_t TXLENGTH:7;
__O uint32_t PAD0:1;
__IO uint32_t TX_PRE_CHIPS:4;
} BITS;
__IO uint32_t WORD;
} TX_LENGTH; /**< 0x4001408C */
__IO uint32_t TX_SEQ_NUMBER; /**< 0x40014090 */
__IO uint32_t TX_ACK_DELAY; /**< 0x40014094 */
union {
} TX_LENGTH; /**< 0x4001408C */
__IO uint32_t TX_SEQ_NUMBER; /**< 0x40014090 */
__IO uint32_t TX_ACK_DELAY; /**< 0x40014094 */
union {
struct {
__IO uint32_t RXACKDELAY:12;
__IO uint32_t PAD0:4;
__IO uint32_t RXAUTODELAY:12;
} BITS;
__IO uint32_t WORD;
} RX_ACK_DELAY; /**< 0x40014098 */
__IO uint32_t TX_FLUSH; /**< 0x4001409C */
union {
} RX_ACK_DELAY; /**< 0x40014098 */
__IO uint32_t TX_FLUSH; /**< 0x4001409C */
union {
struct {
__IO uint32_t CCA_DELAY:12;
__IO uint32_t PAD0:4;
__IO uint32_t CCA_LENGTH:12;
} BITS;
__IO uint32_t WORD;
} CCA; /**< 0x400140A0 */
union {
} CCA; /**< 0x400140A0 */
union {
struct {
__IO uint32_t RXACK_END:12;
__IO uint32_t PAD0:4;
__IO uint32_t RXSLOTTED_END:12;
} BITS;
__IO uint32_t WORD;
} ACK_STOP; /**< 0x400140A4 */
__IO uint32_t TXCCA; /**< 0x400140A8 */
__IO uint32_t ADDR_L_LOC; /**< 0x400140AC */
__IO uint32_t ADDR_S_LOC; /**< 0x400140B0 */
__IO uint32_t FRAME_MATCH_RESULT; /**< 0x400140B4 */
__IO uint32_t FRAME_MATCH_ADDR_L; /**< 0x400140B8 */
__IO uint32_t FRAME_MATCH_ADDR_S; /**< 0x400140BC */
union {
} ACK_STOP; /**< 0x400140A4 */
__IO uint32_t TXCCA; /**< 0x400140A8 */
__IO uint32_t ADDR_L_LOC; /**< 0x400140AC */
__IO uint32_t ADDR_S_LOC; /**< 0x400140B0 */
__IO uint32_t FRAME_MATCH_RESULT; /**< 0x400140B4 */
__IO uint32_t FRAME_MATCH_ADDR_L; /**< 0x400140B8 */
__IO uint32_t FRAME_MATCH_ADDR_S; /**< 0x400140BC */
union {
struct {
__IO uint32_t AA:1;
__IO uint32_t AFA:1;
@ -273,8 +273,8 @@ typedef struct {
__IO uint32_t GAIN_START:4;
} BITS;
__IO uint32_t WORD;
} AGC_CONTROL; /**< 0x400140C0 */
union {
} AGC_CONTROL; /**< 0x400140C0 */
union {
struct {
__IO uint32_t SETTLE_DELAY:8;
__IO uint32_t MEASURE_DELAY:8;
@ -283,8 +283,8 @@ typedef struct {
__IO uint32_t LOW_THRESHOLD:4;
} BITS;
__IO uint32_t WORD;
} AGC_SETTINGS; /**< 0x400140C4 */
union {
} AGC_SETTINGS; /**< 0x400140C4 */
union {
struct {
__IO uint32_t GC1:3;
__IO uint32_t GC2:3;
@ -293,8 +293,8 @@ typedef struct {
__IO uint32_t AGC_STATE:4;
} BITS;
__IO uint32_t WORD;
} AGC_STATUS; /**< 0x400140C8 */
union {
} AGC_STATUS; /**< 0x400140C8 */
union {
struct {
__IO uint32_t GAIN3:7;
__IO uint32_t PAD0:1;
@ -306,8 +306,8 @@ typedef struct {
__IO uint32_t PAD3:1;
} BITS;
__IO uint32_t WORD;
} AGC_GAIN_TABLE0; /**< 0x400140CC */
union {
} AGC_GAIN_TABLE0; /**< 0x400140CC */
union {
struct {
__IO uint32_t GAIN7:7;
__IO uint32_t PAD0:1;
@ -319,8 +319,8 @@ typedef struct {
__IO uint32_t PAD3:1;
} BITS;
__IO uint32_t WORD;
} AGC_GAIN_TABLE1; /**< 0x400140D0 */
union {
} AGC_GAIN_TABLE1; /**< 0x400140D0 */
union {
struct {
__IO uint32_t GAIN11:7;
__IO uint32_t PAD0:1;
@ -332,8 +332,8 @@ typedef struct {
__IO uint32_t PAD3:1;
} BITS;
__IO uint32_t WORD;
} AGC_GAIN_TABLE2; /**< 0x400140D4 */
union {
} AGC_GAIN_TABLE2; /**< 0x400140D4 */
union {
struct {
__IO uint32_t GAIN15:7;
__IO uint32_t PAD0:1;
@ -345,7 +345,7 @@ typedef struct {
__IO uint32_t PAD3:1;
} BITS;
__IO uint32_t WORD;
} AGC_GAIN_TABLE3; /**< 0x400140D8 */
} AGC_GAIN_TABLE3; /**< 0x400140D8 */
} MacHwReg_t, *MacHwReg_pt;
/** macHw register map (demodulator part) */

View File

@ -3,7 +3,7 @@
* @file macros.h
* @brief Implements some handy macros
* @internal
* @author : Industrial ASSP Application Team
* @author : ON Semiconductor.
* $Rev: 2076 $
* $Date: 2013-07-10 18:26:10 +0530 (Wed, 10 Jul 2013) $
*******************************************************************************

View File

@ -3,7 +3,7 @@
* @file ncs36510_init.c
* @brief Initialization of Orion SoC
* @internal
* @author Radhika R, ON Semiconductors
* @author ON Semiconductor
* $Rev:
* $Date: $
******************************************************************************
@ -37,7 +37,8 @@ void fPmuInit(void);
* This function copies trim codes from specific flash location
* where they are stored to proper hw registers.
*/
boolean fTrim() {
boolean fTrim()
{
/**- Check if trim values are present */
/**- If Trim data is present. Only trim if valid trim values are present. */
@ -85,20 +86,21 @@ boolean fTrim() {
}
/* See clock.h for documentation. */
void fClockInit() {
void fClockInit()
{
/** Enable external 32MHz oscillator */
CLOCKREG->CCR.BITS.OSC_SEL = 1;
/** - Wait external 32MHz oscillator to be ready */
while(CLOCKREG->CSR.BITS.XTAL32M != 1){} /* If you get stuck here, something is wrong with board or trim values */
while(CLOCKREG->CSR.BITS.XTAL32M != 1) {} /* If you get stuck here, something is wrong with board or trim values */
/** Internal 32MHz calibration \n *//** - Enable internal 32MHz clock */
PMUREG->CONTROL.BITS.INT32M = 0;
/** - Wait 5 uSec for clock to stabilize */
volatile uint8_t Timer;
for(Timer = 0;Timer < 10;Timer++);
for(Timer = 0; Timer < 10; Timer++);
/** - Enable calibration */
CLOCKREG->CCR.BITS.CAL32M = True;
@ -116,7 +118,7 @@ void fClockInit() {
PMUREG->CONTROL.BITS.INT32K = 0;
/** - Wait 5 uSec for clock to stabilize */
for(Timer = 0;Timer < 10;Timer++);
for(Timer = 0; Timer < 10; Timer++);
/** - Enable calibration */
CLOCKREG->CCR.BITS.CAL32K = True;
@ -177,7 +179,8 @@ uint32_t fClockGetPeriphClockfrequency()
* This function initializes hardware at application start up prior
* to other initializations or OS operations.
*/
static void fHwInit(void) {
static void fHwInit(void)
{
/* Trim register settings */
fTrim();

View File

@ -3,7 +3,7 @@
* @file ncs36510_init.h
* @brief Initialization of Orion SoC
* @internal
* @author Radhika R, ON Semiconductors
* @author ON Semiconductor.
* $Rev:
* $Date: $
******************************************************************************

View File

@ -69,14 +69,11 @@ void fI2cInit(i2c_t *obj,PinName sda,PinName scl)
obj->membase->IER.WORD = False;
/* enable interrupt associated with the device */
if(obj->membase == I2C1REG)
{
if(obj->membase == I2C1REG) {
CLOCK_ENABLE(CLOCK_I2C); /* enable i2c peripheral */
NVIC_ClearPendingIRQ(I2C_IRQn);
NVIC_EnableIRQ(I2C_IRQn);
}
else
{
} else {
CLOCK_ENABLE(CLOCK_I2C2); /* enable i2c peripheral */
NVIC_ClearPendingIRQ(I2C2_IRQn);
NVIC_EnableIRQ(I2C2_IRQn);
@ -143,8 +140,8 @@ int32_t fI2cStop(i2c_t *obj)
obj->membase->CMD_REG = I2C_CMD_STOP;
if (obj->membase->STATUS.WORD & (I2C_STATUS_CMD_FIFO_FULL_BIT |
I2C_STATUS_CMD_FIFO_OFL_BIT |
I2C_STATUS_BUS_ERR_BIT))
{/* I2c error occured */
I2C_STATUS_BUS_ERR_BIT)) {
/* I2c error occured */
return I2C_ERROR_BUS_BUSY;
}
return I2C_API_STATUS_SUCCESS;
@ -155,31 +152,27 @@ int32_t fI2cReadB(i2c_t *d, char *buf, int len)
{
int32_t read = 0;
while (read < len)
{
while (read < len) {
/* Send read command */
d->membase->CMD_REG = I2C_CMD_RDAT8;
while(!RD_DATA_READY)
{
if (I2C_BUS_ERR_CHECK)
{/* Bus error occured */
while(!RD_DATA_READY) {
if (I2C_BUS_ERR_CHECK) {
/* Bus error occured */
return I2C_ERROR_BUS_BUSY;
}
}
buf[read++] = d->membase->RD_FIFO_REG; /**< Reading 'read FIFO register' will clear status register */
if(!(read>=len)) /* No ACK will be generated for the last read, upper level I2C protocol should generate */
{
if(!(read>=len)) { /* No ACK will be generated for the last read, upper level I2C protocol should generate */
d->membase->CMD_REG=I2C_CMD_WDAT0; /* TODO based on requirement generate ACK or NACK Based on the requirement. */
}
/* check for FIFO underflow */
if(I2C_UFL_CHECK)
{
if(I2C_UFL_CHECK) {
return I2C_ERROR_NO_SLAVE; /* TODO No error available for this in i2c_api.h */
}
if(I2C_BUS_ERR_CHECK)
{/* Bus error */
if(I2C_BUS_ERR_CHECK) {
/* Bus error */
return I2C_ERROR_BUS_BUSY;
}
}
@ -192,11 +185,11 @@ int32_t fI2cWriteB(i2c_t *d, const char *buf, int len)
{
int32_t write = 0;
while (write < len)
{ /* Send write command */
while (write < len) {
/* Send write command */
d->membase->CMD_REG = I2C_CMD_WDAT8;
if(buf[write] == I2C_CMD_RDAT8)
{/* SW work around to counter FSM issue. If the only command in the CMD FIFO is the WDAT8 command (data of 0x13)
if(buf[write] == I2C_CMD_RDAT8) {
/* SW work around to counter FSM issue. If the only command in the CMD FIFO is the WDAT8 command (data of 0x13)
then as the command is read out (i.e. the FIFO goes empty), the WDAT8 command will be misinterpreted as a
RDAT8 command by the data FSM; resulting in an I2C bus error (NACK instead of an ACK). */
/* Send 0x13 bit wise */
@ -209,17 +202,16 @@ int32_t fI2cWriteB(i2c_t *d, const char *buf, int len)
d->membase->CMD_REG = I2C_CMD_WDAT0;
d->membase->CMD_REG = I2C_CMD_WDAT1;
d->membase->CMD_REG = I2C_CMD_WDAT1;
}
else
{ /* Send data */
} else {
/* Send data */
d->membase->CMD_REG = buf[write++];
}
d->membase->CMD_REG = I2C_CMD_VRFY_ACK; /* TODO Verify ACK based on requirement, Do we need? */
while(FIFO_OFL_CHECK); /* Wait till command overflow ends */
if (I2C_BUS_ERR_CHECK)
{/* Bus error */
if (I2C_BUS_ERR_CHECK) {
/* Bus error */
return I2C_ERROR_BUS_BUSY;
}
}

View File

@ -92,14 +92,12 @@ void lp_ticker_sleep_until(uint32_t now, uint32_t time)
mbed_exit_sleep(&obj);
}
#ifdef TOOLCHAIN_ARM
/* Dummy functions added for the compilation of ARMCC compiler toolchain */
/** Disable low power ticker interrupt
*
*/
void lp_ticker_disable_interrupt(void)
{
//TODO : dummy function to get compilation running
/* TODO : This is an empty implementation for now */
}
/** Clear the low power ticker interrupt
@ -107,8 +105,7 @@ void lp_ticker_disable_interrupt(void)
*/
void lp_ticker_clear_interrupt(void)
{
//TODO : dummy function to get compilation running
/* TODO : This is an empty implementation for now */
}
#endif /* TOOLCHAIN_ARM */
#endif /* DEVICE_LOWPOWERTIMER */

View File

@ -61,12 +61,11 @@ void fSpiInit(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel
MBED_ASSERT((int)obj->membase != NC);
/* Check device to be activated */
if(obj->membase == SPI1REG)
{/* SPI 1 selected */
if(obj->membase == SPI1REG) {
/* SPI 1 selected */
CLOCK_ENABLE(CLOCK_SPI); /* Enable clock */
}
else
{/* SPI 2 selected */
} else {
/* SPI 2 selected */
CLOCK_ENABLE(CLOCK_SPI2); /* Enable clock */
}

View File

@ -104,8 +104,7 @@ uint32_t us_ticker_read()
{
uint32_t retval, tim0cval;
if (!us_ticker_inited)
{
if (!us_ticker_inited) {
us_timer_init();
}
@ -114,8 +113,7 @@ uint32_t us_ticker_read()
retval = (0xFFFF - tim0cval); /* subtract down count */
NVIC_DisableIRQ(Tim0_IRQn);
if (TIM0REG->CONTROL.BITS.INT)
{
if (TIM0REG->CONTROL.BITS.INT) {
TIM0REG->CLEAR = 0;
msb_counter++;
tim0cval = TIM0REG->VALUE; /* read current time again after interrupt */
@ -165,13 +163,10 @@ extern void us_ticker_isr(void)
TIM1REG->CLEAR = 0;
/* If this is a longer timer it will take multiple full hw counter cycles */
if (us_ticker_int_counter > 0)
{
if (us_ticker_int_counter > 0) {
ticker_set(0xFFFF);
us_ticker_int_counter--;
}
else
{
} else {
TIM1REG->CONTROL.BITS.ENABLE = False;
us_ticker_irq_handler();
}
@ -182,8 +177,7 @@ void us_ticker_set_interrupt(timestamp_t timestamp)
{
int32_t delta = (uint32_t)timestamp - us_ticker_read();
if (delta <= 0)
{
if (delta <= 0) {
/* This event was in the past */
//us_ticker_irq_handler();
// This event was in the past.

View File

@ -50,13 +50,12 @@ struct serial_s {
int index;
};
typedef struct _gpio_t
{
typedef struct _gpio_t {
GpioReg_pt GPIOMEMBASE;
PinName gpioPin;
uint32_t gpioMask;
}gpio_t;
} gpio_t;
/* TODO: This is currently a dummy structure; implementation will be done along
@ -65,7 +64,7 @@ typedef struct _gpio_t
typedef struct sleep_s {
uint32_t timeToSleep; /* 0: Use sleep type variable; Noz-zero: Selects sleep type based on duration using table 1. sleep below */
uint8_t SleepType; /* 0: Sleep; 1: DeepSleep; 2: Coma */
}sleep_t;
} sleep_t;
/* Table 1. Sleep
___________________________________________________________________________________
@ -136,8 +135,7 @@ typedef enum {
fallingEdge
} spi_clockPhase_t, *spi_clockPhase_pt;
struct spi_s
{
struct spi_s {
SpiIpc7207Reg_pt membase; /* Register address */
IRQn_Type irq; /* IRQ number of the IRQ associated to the device. */
uint8_t irqEnable; /* IRQ enables for 8 IRQ sources:
@ -179,8 +177,7 @@ struct spi_s
uint32_t event;
};
struct i2c_s
{
struct i2c_s {
uint32_t baudrate; /**< The expected baud rate. */
uint32_t I2cStatusFromInt;
uint8_t ClockSource; /**< I2C clock source, 0 clkI2C pin, 1 PCLK */

View File

@ -42,8 +42,7 @@ void pin_mode(PinName pin, PinMode mode)
/** - Enable the clock for PAD peripheral device */
CLOCK_ENABLE(CLOCK_PAD);
switch (mode)
{
switch (mode) {
case PushPullPullDown:
padRegOffset->PADIO0.BITS.TYPE = PAD_OUTCFG_PUSHPULL;
padRegOffset->PADIO0.BITS.PULL = PAD_PULL_DOWN;

View File

@ -1,17 +1,21 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2015 ARM Limited
/**
******************************************************************************
* @file port_api.c
* @brief Implementation of a port API
* @internal
* @author ON Semiconductor
* $Rev:
* $Date:
******************************************************************************
* @copyright (c) 2012 ON Semiconductor. All rights reserved.
* ON Semiconductor is supplying this software for use with ON Semiconductor
* processor based microcontrollers only.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ON SEMICONDUCTOR SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL,
* INCIDENTAL, OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*/
#include "gpio.h"
#include "port_api.h"
@ -50,8 +54,7 @@ void port_init(port_t *obj, PortName port, int mask, PinDirection dir)
/* Store GPIO base address */
obj->GPIOMEMBASE = GPIOREG;
for (i=0; i<NUMBER_OF_GPIO; i++)
{
for (i=0; i<NUMBER_OF_GPIO; i++) {
/* check for valid pin */
if (obj->mask & (1<<i)) {
@ -78,8 +81,7 @@ void port_mode(port_t *obj, PinMode mode)
PinName pin;
/* For each pin in the mask, set the mode to that defined in "mode" parameter */
for (i=0; i < NUMBER_OF_GPIO; i++)
{
for (i=0; i < NUMBER_OF_GPIO; i++) {
/* check for valid pin */
if (obj->mask & (1<<i)) {
@ -144,7 +146,7 @@ int port_read(port_t *obj)
gpio_level = obj->GPIOMEMBASE->R_STATE_W_SET;
/* Disable the GPIO clock */
CLOCK_ENABLE(CLOCK_GPIO);
CLOCK_DISABLE(CLOCK_GPIO);
return(gpio_level);
}

View File

@ -69,31 +69,26 @@ typedef struct {
#endif /* REVB */
#ifdef REVD
typedef struct
{
typedef struct {
__IO uint32_t DUTYCYCLE;
union
{
struct
{
union {
struct {
__O uint32_t ENABLE :8; /**< Write any value to enable PWM output */
__I uint32_t PAD :1; /** < Pad */
__I uint32_t ENABLE_STATE :1; /**< Current state of pwmEnable configuration bit. 1 PWM output is enabled. 0 PWN output is disabled. */
__I uint32_t OUTPUT_STATE :1; /**< Current state of PWM output */
}BITS;
} BITS;
__IO uint32_t WORD;
}PWM_ENABLE;
} PWM_ENABLE;
__O uint32_t PWM_DISABLE;
union
{
struct
{
union {
struct {
__O uint32_t ENABLE :8; /**< Write any value to select enable the 4-bit prescaler */
__I uint32_t STATE:1; /**< Current state of the prescaler. 1 the prescaler is enabled. 0 the prescaler is disabled. */
}BITS;
} BITS;
__IO uint32_t WORD;
}PRESCALE_ENABLE;
} PRESCALE_ENABLE;
__O uint32_t PRESCALE_DISABLE;
}PwmReg_t, *PwmReg_pt;
} PwmReg_t, *PwmReg_pt;
#endif /* REVD */
#endif /* PWM_MAP_H_ */

View File

@ -1,19 +1,23 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2015 ARM Limited
/**
******************************************************************************
* @file pwmout_api.c
* @brief Implementation of a PWM driver
* @internal
* @author ON Semiconductor
* $Rev:
* $Date:
******************************************************************************
* @copyright (c) 2012 ON Semiconductor. All rights reserved.
* ON Semiconductor is supplying this software for use with ON Semiconductor
* processor based microcontrollers only.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ON SEMICONDUCTOR SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL,
* INCIDENTAL, OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
* @endinternal
*/
#include "pwmout_api.h"
#include "PeripheralPins.h"
#include "mbed_assert.h"
@ -75,16 +79,11 @@ void pwmout_free(pwmout_t *obj)
*/
void pwmout_write(pwmout_t *obj, float percent)
{
if (percent == 0.0)
{
if (percent == 0.0) {
obj->pwmReg->DUTYCYCLE = 0x00;
}
else if (percent == 1.0)
{
} else if (percent == 1.0) {
obj->pwmReg->DUTYCYCLE = 0xFF;
}
else
{
} else {
/* Write the duty cycle config register 0x4000B000, with the value passed on */
/* ((percent * 255) + 1) is the duty cycle. Plus 1 is for accounting for round off errors; like a ceil function */
obj->pwmReg->DUTYCYCLE = (uint8_t)((percent * 255) + 1);
@ -180,8 +179,7 @@ void pwmout_pulsewidth_us(pwmout_t *obj, int us)
int pulseWidth = 0;
/* Check if the uSec value is greater than 128uSec, if so reject */
if (us > 128)
{
if (us > 128) {
return;
}
/* If pulsewidth is less than 128uSec, set the prescaler to 4096
@ -191,16 +189,11 @@ void pwmout_pulsewidth_us(pwmout_t *obj, int us)
/* Calculate the duty cycle based on the width of the pulse */
/* ((255 * us) / 128) + 1 = duty cycle */
pulseWidth = (int)((float)(255 * us)/(float)128) + 1;
if (us == 0)
{
if (us == 0) {
obj->pwmReg->DUTYCYCLE = 0x0;
}
else if (us == 128)
{
} else if (us == 128) {
obj->pwmReg->DUTYCYCLE = 0xFF;
}
else
{
} else {
obj->pwmReg->DUTYCYCLE = (uint8_t)pulseWidth;
}
}

View File

@ -46,10 +46,8 @@ typedef struct {
#ifdef REVB
__IO uint32_t MODE;
#endif /* REVB */
union
{
struct
{
union {
struct {
__IO uint32_t MODE :1; /**<Mode Register, 0 LSFR is updated on every rising edge of PCLK, 1 LSFR is only updated on a read event of the LSFR register */
__IO uint32_t BYTE_SWAP :1; /**<Byte Swap Control, 0 32-bit byte swap, 1 64-bit byte swap */
__IO uint32_t MEATSTABLE_SPEED :1; /**<Meta-stable Latch TRNG Speed Control, 0 Slow mode, 1 Fast mode */
@ -59,10 +57,8 @@ typedef struct {
} BITS;
__IO uint32_t WORD;
} CONTROL; /* Control register - 0x40011004 */
union
{
struct
{
union {
struct {
__IO uint32_t BYTE_0 :8; /**<Byte #0*/
__IO uint32_t BYTE_1 :8; /**<Byte #1*/
__IO uint32_t BYTE_2 :8; /**<Byte #2*/
@ -70,10 +66,8 @@ typedef struct {
} BITS;
__IO uint32_t WORD;
} WRITE_BUF_LSW; /* Byte swap write buffer Least significant word - 0x40011008 */
union
{
struct
{
union {
struct {
__IO uint32_t BYTE_4 :8; /**<Byte #4*/
__IO uint32_t BYTE_5 :8; /**<Byte #5*/
__IO uint32_t BYTE_6 :8; /**<Byte #6*/
@ -81,10 +75,8 @@ typedef struct {
} BITS;
__IO uint32_t WORD;
} WRITE_BUF_MSW; /* Byte swap write buffer Most significant word - 0x4001100C */
union
{
struct
{
union {
struct {
__IO uint32_t BYTE_7_3 :8; /**<Byte Swap Control == 1? Byte #7 : Byte #3*/
__IO uint32_t BYTE_6_2 :8; /**<Byte Swap Control == 1? Byte #6 : Byte #2*/
__IO uint32_t BYTE_5_1 :8; /**<Byte Swap Control == 1? Byte #5 : Byte #1*/
@ -92,10 +84,8 @@ typedef struct {
} BITS;
__IO uint32_t WORD;
} READ_BUF_LSW; /* Byte swap read buffer Least significant word - 0x40011010 */
union
{
struct
{
union {
struct {
__IO uint32_t BYTE_3 :8; /**<Byte #3*/
__IO uint32_t BYTE_2 :8; /**<Byte #2*/
__IO uint32_t BYTE_1 :8; /**<Byte #1*/

View File

@ -91,13 +91,15 @@ const uint32_t rfLut[16][4] = {{0x50,0x00D4A7,0x4B,0x00A000},
{0x52,0x00D4A7,0x4D,0x002000},
{0x52,0x017F52,0x4D,0x00C001},
{0x53,0xFE29FB,0x4D,0x016001},
{0x53,0xFED4A6,0x4E,0xFDFFFE}};
{0x53,0xFED4A6,0x4E,0xFDFFFE}
};
const uint8_t txPowerLut[43] = {0,0,0, // -32dBm to -30dBm
0,0,0,0,0,0,0,0,0,0, // -29dBm to -20dBm
0,0,0,0,0,0,0,0,1,2, // -19dBm to -10dBm
3,4,5,6,7,8,9,10,11,12, // -9dBm to 0dBm
13,14,15,16,17,18,19,20,20,20}; // +1dBm to +10 dBm
13,14,15,16,17,18,19,20,20,20
}; // +1dBm to +10 dBm
#endif /* REVD */
@ -120,13 +122,14 @@ const uint32_t rfLut[16][4] = {{0x47,0xFF15FC,0x4B,0x00A000},
{0x49,0xFEBBA1,0x4D,0x00C001},
{0x49,0xFF5238,0x4D,0x016001},
{0x49,0xFFE8CF,0x4E,0xFDFFFE}
};
};
const uint8_t txPowerLut[43] = {0,0,0, // -32dBm to -30dBm
0,0,0,0,0,0,0,0,0,0, // -29dBm to -20dBm
0,0,0,0,0,0,1,1,2,2, // -19dBm to -10dBm (clamp low at -14dB)
3,3,4,6,7,9,10,12,13,15, // -9dBm to 0dBm
17,19,20,20,20,20,20,20,20,20}; // +1dBm to +10 dBm (clamp high at +3dB)
17,19,20,20,20,20,20,20,20,20
}; // +1dBm to +10 dBm (clamp high at +3dB)
#endif /* REVC */
#ifdef REVB
@ -147,13 +150,15 @@ const uint32_t rfLut[16][4] = {{0x47,0xFF15FC,0x4B,0x00A000},
{0x49,0xFE250A,0x4D,0x002000},
{0x49,0xFEBBA1,0x4D,0x00C001},
{0x49,0xFF5238,0x4D,0x016001},
{0x49,0xFFE8CF,0x4E,0xFDFFFE}};
{0x49,0xFFE8CF,0x4E,0xFDFFFE}
};
const uint8_t txPowerLut[43] = {0,0,0, // -32dBm to -30dBm
0,0,0,0,0,0,0,0,0,0, // -29dBm to -20dBm
0,0,0,0,0,0,1,1,2,2, // -19dBm to -10dBm (clamp low at -14dB)
3,3,4,6,7,9,10,12,13,15, // -9dBm to 0dBm
17,19,20,20,20,20,20,20,20,20}; // +1dBm to +10 dBm (clamp high at +3dB)
17,19,20,20,20,20,20,20,20,20
}; // +1dBm to +10 dBm (clamp high at +3dB)
#endif
#ifdef REVA
@ -172,13 +177,15 @@ const uint32_t rfLut[16][4] = {{0x57,0xFF5D2F,0x51,0x018001},
{0x59,0xFF5D2F,0x53,0x010001},
{0x59,0x0007DA,0x53,0x01A001},
{0x59,0x00B285,0x53,0xFE3FFF},
{0x59,0x015D30,0x53,0xFEDFFF}};
{0x59,0x015D30,0x53,0xFEDFFF}
};
const uint8_t txPowerLut[43] = {1,2,3, // -32dBm to -30dBm
4,5,5,5,5,5,5,5,5,5, // -29dBm to -20dBm (clamp at -28dB)
5,5,5,5,5,5,5,5,5,5, // -19dBm to -10dBm
5,5,5,5,5,5,5,5,5,5, // -9dBm to 0dBm
5,5,5,5,5,5,5,5,5,5}; // +1dBm to +10 dBm
5,5,5,5,5,5,5,5,5,5
}; // +1dBm to +10 dBm
#endif
/*************************************************************************************************
@ -187,7 +194,8 @@ const uint8_t txPowerLut[43] = {1,2,3, // -32dBm to -30dBm
* *
*************************************************************************************************/
void fRfAnaInit() {
void fRfAnaInit()
{
// Enable rfana clock
CLOCK_ENABLE(CLOCK_RFANA);
@ -207,7 +215,8 @@ void fRfAnaInit() {
RFANAREG->RX_CONTROL.BITS.ADC_DITHER_MODE = 0x0; // Dither mode disabled
}
boolean fRfAnaIoctl (uint32_t request, void *argument) {
boolean fRfAnaIoctl (uint32_t request, void *argument)
{
uint8_t channel, txPower;
// Enable rfana clock (in case fRfAnaIoctl is used before call of fRfAnaInit)

View File

@ -97,10 +97,9 @@ void fRtcSetInterrupt(uint32_t timestamp)
uint32_t Second = False;
uint8_t DividerAdjust = 1;
if(timestamp)
{
if(timestamp >= RTC_SEC_TO_US)
{/* TimeStamp is big enough to set second alarm */
if(timestamp) {
if(timestamp >= RTC_SEC_TO_US) {
/* TimeStamp is big enough to set second alarm */
Second = ((timestamp / RTC_SEC_TO_US) & RTC_SEC_MASK); /* Convert micro second to second */
RTCREG->SECOND_ALARM = Second; /* Write to alarm register */
@ -108,12 +107,11 @@ void fRtcSetInterrupt(uint32_t timestamp)
RTCREG->CONTROL.WORD |= (True << RTC_CONTROL_SEC_CNT_INT_BIT_POS);
}
timestamp = timestamp - Second * RTC_SEC_TO_US; /* Take out micro second for sub second alarm */
if(timestamp > False)
{/* We have some thing for sub second */
if(timestamp > False) {
/* We have some thing for sub second */
/* Convert micro second to sub_seconds(each count = 30.5 us) */
if(timestamp > 131000)
{
if(timestamp > 131000) {
DividerAdjust = 100;
}
@ -121,14 +119,13 @@ void fRtcSetInterrupt(uint32_t timestamp)
timestamp = (uint64_t)(Temp / RTC_SEC_TO_US * DividerAdjust);
SubSecond = Temp & RTC_SUB_SEC_MASK;
if(SubSecond <= 5)
{
if(SubSecond <= 5) {
SubSecond = 0;
}
if(SubSecond > False)
{ /* Second interrupt not enabled */
if(SubSecond > False) {
/* Second interrupt not enabled */
/* Set SUB SEC_ALARM */
RTCREG->SUB_SECOND_ALARM = SubSecond; /* Write to sub second alarm */
@ -186,11 +183,10 @@ uint64_t fRtcRead(void)
* If it changed, then the Second rolled over while reading Sub-seconds, so go back and read them both again.
*/
do
{
do {
Second = RTCREG->SECOND_COUNTER; /* Get SEC_COUNTER reg value */
SubSecond = (RTCREG->SUB_SECOND_COUNTER - 1) & 0x7FFF; /* Get SUB_SEC_COUNTER reg value */
}while (Second != RTCREG->SECOND_COUNTER); /* Repeat if the second has changed */
} while (Second != RTCREG->SECOND_COUNTER); /* Repeat if the second has changed */
//note: casting to float removed to avoid reduction in resolution
uint64_t RtcTimeus = ((uint64_t)SubSecond * RTC_SEC_TO_US / RTC_CLOCK_HZ) + ((uint64_t)Second * RTC_SEC_TO_US);
@ -211,14 +207,13 @@ void fRtcWrite(uint64_t RtcTimeus)
RTCREG->CONTROL.WORD &= ~((True << RTC_CONTROL_SUBSEC_CNT_START_BIT_POS) |
(True << RTC_CONTROL_SEC_CNT_START_BIT_POS));
if(RtcTimeus > RTC_SEC_TO_US)
{/* TimeStamp is big enough to set second counter */
if(RtcTimeus > RTC_SEC_TO_US) {
/* TimeStamp is big enough to set second counter */
Second = ((RtcTimeus / RTC_SEC_TO_US) & RTC_SEC_MASK);
}
RTCREG->SECOND_COUNTER = Second;
RtcTimeus = RtcTimeus - (Second * RTC_SEC_TO_US);
if(RtcTimeus > False)
{
if(RtcTimeus > False) {
/* Convert TimeStamp to sub_seconds */
SubSecond = (uint16_t)((float)(RtcTimeus * RTC_CLOCK_HZ / RTC_SEC_TO_US)) & RTC_SUB_SEC_MASK;
}
@ -235,7 +230,8 @@ void fRtcWrite(uint64_t RtcTimeus)
/* See rtc.h for details */
void fRtcHandler(void)
{/* SUB_SECOND/SECOND interrupt occured */
{
/* SUB_SECOND/SECOND interrupt occured */
volatile uint32_t TempStatus = RTCREG->STATUS.WORD;
/* disable all interrupts */
@ -246,24 +242,22 @@ void fRtcHandler(void)
(True << RTC_INT_CLR_SEC_BIT_POS));
/* TODO ANDing SUB_SEC & SEC interrupt - work around for RTC issue - will be solved in REV G */
if(TempStatus & RTC_SEC_INT_STATUS_MASK)
{/* Second interrupt occured */
if(SubSecond > False)
{/* Set SUB SEC_ALARM */
if(TempStatus & RTC_SEC_INT_STATUS_MASK) {
/* Second interrupt occured */
if(SubSecond > False) {
/* Set SUB SEC_ALARM */
RTCREG->SUB_SECOND_ALARM = SubSecond + RTCREG->SUB_SECOND_COUNTER;
/* Enable sub second interrupt */
while(RTCREG->STATUS.BITS.BSY_CTRL_REG_WRT == True);
RTCREG->CONTROL.WORD |= (True << RTC_CONTROL_SUBSEC_CNT_INT_BIT_POS);
}
else
{/* We reach here after second interrupt is occured */
} else {
/* We reach here after second interrupt is occured */
while(RTCREG->STATUS.BITS.BSY_CTRL_REG_WRT == True);
RTCREG->CONTROL.WORD &= ~(True << RTC_CONTROL_SUBSEC_CNT_INT_BIT_POS) |
(True << RTC_CONTROL_SEC_CNT_INT_BIT_POS);
}
}
else
{/* We reach here after sub_second or (Sub second + second) interrupt occured */
} else {
/* We reach here after sub_second or (Sub second + second) interrupt occured */
while(RTCREG->STATUS.BITS.BSY_CTRL_REG_WRT == True);
RTCREG->CONTROL.WORD &= ~(True << RTC_CONTROL_SUBSEC_CNT_INT_BIT_POS) |
(True << RTC_CONTROL_SEC_CNT_INT_BIT_POS);
@ -274,12 +268,9 @@ void fRtcHandler(void)
boolean fIsRtcEnabled(void)
{
if(RTCREG->CONTROL.BITS.SUB_SEC_COUNTER_EN | RTCREG->CONTROL.BITS.SEC_COUNTER_EN)
{
if(RTCREG->CONTROL.BITS.SUB_SEC_COUNTER_EN | RTCREG->CONTROL.BITS.SEC_COUNTER_EN) {
return True;
}
else
{
} else {
return False;
}
}

View File

@ -3,7 +3,7 @@
* @file rtc_map.h
* @brief Real Time Clock HW register map
* @internal
* @author Mehul shah
* @author ON Semiconductor.
* $Rev: 3008 $
* $Date: 2014-10-16 18:42:48 +0530 (Thu, 16 Oct 2014) $
******************************************************************************
@ -109,21 +109,17 @@ typedef struct {
__IO uint32_t SECOND_COUNTER; /**<SECOND Counter */ /* 0x4000F004 */
__IO uint32_t SUB_SECOND_ALARM; /**< SUB SECOND alarm */ /* 0x4000F008 */
__IO uint32_t SECOND_ALARM; /**< SECOND alarm */ /* 0x4000F00c */
union
{
struct
{
union {
struct {
__IO uint32_t SUB_SEC_COUNTER_EN :1; /**<Sub-second counter enable. (1=count is enabled, 0=retain count value) */
__IO uint32_t SEC_COUNTER_EN :1; /**<Second counter enable. (1=count is enabled, 0=retain count value) */
__IO uint32_t SUB_SECOND_INT_EN :1; /**<Sub-second interrupt enable (1=interrupt enabled, 0=interrupt disabled) */
__IO uint32_t SECOND_INT_EN :1; /**<Second interrupt enable (1=interrupt enabled, 0=interrupt disabled) */
}BITS;
} BITS;
__IO uint32_t WORD;
}CONTROL; /* 0x4000F010 */
union
{
struct
{
} CONTROL; /* 0x4000F010 */
union {
struct {
/**<Any write to the status register will clear the error bit. */
__IO uint32_t SUB_SECOND_INT:1; /**<Sub-second interrupt status. (1=interrupt active, 0=no interrupt)*/
__IO uint32_t SECOND_INT :1; /**<Second interrupt status. (1=interrupt active, 0=no interrupt)*/
@ -136,18 +132,16 @@ typedef struct {
__IO uint32_t BSY_CTRL_REG_WRT :1; /**<Busy with a control register write.*/
__IO uint32_t BSY_SUB_SEC_INT_CLR_WRT :1; /**<Busy with a sub-second interrupt clear write.*/
__IO uint32_t BSY_SEC_INT_CLR_WRT :1; /**<Busy with a second interrupt clear write.*/
}BITS;
} BITS;
__IO uint32_t WORD;
}STATUS; /* 0x4000F014 */
union
{
struct
{
} STATUS; /* 0x4000F014 */
union {
struct {
__O uint32_t SUB_SECOND :1; /**<Write 1 to this register to clear the sub-second interrupt.*/
__O uint32_t SECOND :1; /**<Write 1 to this register to clear the second interrupt.*/
}BITS;
} BITS;
__O uint32_t WORD;
}INT_CLEAR; /* 0x4000F018 */
} INT_CLEAR; /* 0x4000F018 */
#endif /* REVD */
} RtcReg_t, *RtcReg_pt;

View File

@ -83,28 +83,25 @@ void serial_init(serial_t *obj, PinName tx, PinName rx)
memcpy(&stdio_uart, obj, sizeof(serial_t));
}
/*TODO: determine if pullups are needed/recommended */
/* if (tx != NC) {
/* if (tx != NC) {
pin_mode(tx, PullUp);
}
if (rx != NC) {
pin_mode(rx, PullUp);
}
*/
*/
/* Configure IOs to UART using cross bar, pad and GPIO settings */
if(obj->UARTREG == UART2REG)
{/* UART 2 */
if(obj->UARTREG == UART2REG) {
/* UART 2 */
CLOCK_ENABLE(CLOCK_UART2);
Irq = Uart2_IRQn;
}
else if(obj->UARTREG == UART1REG)
{ /* UART 1 */
} else if(obj->UARTREG == UART1REG) {
/* UART 1 */
CLOCK_ENABLE(CLOCK_UART1);
Irq = Uart1_IRQn;
}
else
{
} else {
MBED_ASSERT(False);
}
@ -156,8 +153,7 @@ void serial_init(serial_t *obj, PinName tx, PinName rx)
* flow control state. */
obj->UARTREG->SCR = obj->UARTREG->MSR.WORD;
if((int)obj->UARTREG == STDIO_UART)
{
if((int)obj->UARTREG == STDIO_UART) {
stdio_uart_inited = 1;
memcpy(&stdio_uart, obj, sizeof(serial_t));
}
@ -197,23 +193,17 @@ DataLen 00 5 bits; 01 6 bits; 10 7 bits; 11 8 bits
*/
void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits)
{
if(data_bits >= 5 && data_bits <= 8 && parity <= 7 && stop_bits >= 1 && stop_bits <= 2)
{
if(parity == (SerialParity)0)
{
if(data_bits >= 5 && data_bits <= 8 && parity <= 7 && stop_bits >= 1 && stop_bits <= 2) {
if(parity == (SerialParity)0) {
parity = (SerialParity)0;
}
else
{
} else {
parity = (SerialParity)(parity + parity - 1) ;
}
obj->UARTREG->LCR.WORD |= ((((data_bits - 5) << UART_LCR_DATALEN_BIT_POS) |
(parity << UART_LCR_PARITY_BIT_POS) |
((stop_bits - 1) << UART_LCR_STPBIT_BIT_POS)) & 0x3F);
}
else
{
} else {
MBED_ASSERT(False);
}
}
@ -232,11 +222,11 @@ void Uart1_Irq()
uint8_t active_irq = (uint8_t)(UART1REG->LSR.WORD) & 0xFF;
uint8_t irq_mask = 0;
if(UART1REG->IER.WORD & UART_IER_TX_EMPTY_MASK){ /*check if TX interrupt is enabled*/
if(UART1REG->IER.WORD & UART_IER_TX_EMPTY_MASK) { /*check if TX interrupt is enabled*/
irq_mask |= active_irq & UART_LSR_TX_EMPTY_MASK;
}
if(UART1REG->IER.WORD & UART_IER_RX_DATA_READY_MASK){ /*check if RX interrupt is enabled*/
if(UART1REG->IER.WORD & UART_IER_RX_DATA_READY_MASK) { /*check if RX interrupt is enabled*/
irq_mask |= active_irq & UART_LSR_RX_DATA_READY_MASK;
}
@ -249,11 +239,11 @@ void Uart2_Irq()
uint8_t active_irq = (uint8_t)(UART2REG->LSR.WORD) & 0xFF;
uint8_t irq_mask = 0;
if(UART2REG->IER.WORD & UART_IER_TX_EMPTY_MASK){ /*check if TX interrupt is enabled*/
if(UART2REG->IER.WORD & UART_IER_TX_EMPTY_MASK) { /*check if TX interrupt is enabled*/
irq_mask |= active_irq & UART_LSR_TX_EMPTY_MASK;
}
if(UART2REG->IER.WORD & UART_IER_RX_DATA_READY_MASK){ /*check if RX interrupt is enabled*/
if(UART2REG->IER.WORD & UART_IER_RX_DATA_READY_MASK) { /*check if RX interrupt is enabled*/
irq_mask |= active_irq & UART_LSR_RX_DATA_READY_MASK;
}
@ -264,14 +254,11 @@ void Uart2_Irq()
static inline void uart_irq(uint8_t status, uint32_t index)
{
if (serial_irq_ids[index] != 0)
{
if (status & UART_LSR_TX_EMPTY_MASK)
{
if (serial_irq_ids[index] != 0) {
if (status & UART_LSR_TX_EMPTY_MASK) {
irq_handler(serial_irq_ids[index], TxIrq);
}
if (status & UART_LSR_RX_DATA_READY_MASK)
{
if (status & UART_LSR_RX_DATA_READY_MASK) {
irq_handler(serial_irq_ids[index], RxIrq);
}
}
@ -284,54 +271,44 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable)
uint32_t Vector = 0;
/* Check UART number & assign irq handler */
if(obj->UARTREG == UART1REG)
{/* UART 2 */
if(obj->UARTREG == UART1REG) {
/* UART 2 */
Vector = (uint32_t)&Uart1_Irq;
irq_n = Uart1_IRQn;
}
else if(obj->UARTREG == UART2REG)
{/* UART 1 */
} else if(obj->UARTREG == UART2REG) {
/* UART 1 */
Vector = (uint32_t)&Uart2_Irq;
irq_n = Uart2_IRQn;
}
else
{
} else {
MBED_ASSERT(False);
}
/* Check IRQ type & enable/disable accordingly */
if(enable)
{/* Enable */
if(irq == RxIrq)
{/* Rx IRQ */
if(enable) {
/* Enable */
if(irq == RxIrq) {
/* Rx IRQ */
obj->UARTREG->FCR.BITS.RX_FIFO_TRIG = 0x0;
obj->UARTREG->IER.BITS.RX_DATA_INT = True;
}
else if(irq == TxIrq)
{/* Tx IRQ */
} else if(irq == TxIrq) {
/* Tx IRQ */
obj->UARTREG->IER.BITS.TX_HOLD_INT = True;
}
else
{
} else {
MBED_ASSERT(False);
}
NVIC_SetVector(irq_n, Vector);
NVIC_EnableIRQ(irq_n);
}
else
{/* Disable */
} else {
/* Disable */
NVIC_DisableIRQ(irq_n);
if(irq == RxIrq)
{/* Rx IRQ */
if(irq == RxIrq) {
/* Rx IRQ */
obj->UARTREG->IER.BITS.RX_DATA_INT = False;
}
else if(irq == TxIrq)
{/* Tx IRQ */
} else if(irq == TxIrq) {
/* Tx IRQ */
obj->UARTREG->IER.BITS.TX_HOLD_INT = False;
}
else
{
} else {
MBED_ASSERT(False);
}
}
@ -387,8 +364,6 @@ void serial_pinout_tx(PinName tx)
fPadIOCtrl(tx, 1, 0, 1);
}
#ifdef TOOLCHAIN_ARM
/* Dummy function in order to get ARMCC compilation */
/** Configure the serial for the flow control. It sets flow control in the hardware
* if a serial peripheral supports it, otherwise software emulation is used.
*
@ -399,8 +374,7 @@ void serial_pinout_tx(PinName tx)
*/
void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow)
{
//TODO: Dummy serial function
/* TODO: This is an empty implementation for now.*/
}
#endif /* TOOLCHAIN_ARM */
#endif /* DEVICE_SERIAL */

View File

@ -32,57 +32,7 @@
void mbed_enter_sleep(sleep_t *obj)
{
#if 0
#if 1 /* TODO Temporary code will be removed once mbed OS paases this details */
obj->timeToSleep = False;
obj->SleepType = SLEEP_TYPE_DEEPSLEEP;
#endif
CLOCK_ENABLE(CLOCK_PMU);
/* Select sleep mode */
if(obj->timeToSleep == False)
{/* Use SleepType to select sleep mode*/
if(obj->SleepType == SLEEP_TYPE_SLEEP)
{
sleep();
}
else if(obj->SleepType == SLEEP_TYPE_DEEPSLEEP)
{
deepsleep();
}
else if(obj->SleepType == SLEEP_TYPE_COMA)
{
coma();
}
else
{
/* Do nothing */
}
}
else
{/* Select sleep mode using TimetoSleep */
if((obj->timeToSleep >= SLEEP_DURATION_SLEEP_MIN) && (obj->timeToSleep <= SLEEP_DURATION_SLEEP_MAX))
{
sleep();
}
else if((obj->timeToSleep > SLEEP_DURATION_SLEEP_MAX) && (obj->timeToSleep <= SLEEP_DURATION_DEEPSLEEP_MAX))
{
deepsleep();
}
else if((obj->timeToSleep > SLEEP_DURATION_DEEPSLEEP_MAX) && (obj->timeToSleep <= SLEEP_DURATION_COMA_MAX))
{
coma();
}
else
{
/* Do nothing */
}
}
CLOCK_DISABLE(CLOCK_PMU);
#endif
/* Empty implementation, this will be implemented for mbed5.0 */
}
void mbed_exit_sleep(sleep_t *obj)

View File

@ -35,7 +35,7 @@
extern "C" {
#endif
/* Miscellaneous I/O and control operations codes */
/* Miscellaneous I/O and control operations codes */
#define SPI_IPC7207_IOCTL_GET_SLAVE_SELECT (0x1) /**< <b>Ioctl request code</b>: Reading slaveSelect register */
#define SPI_IPC7207_IOCTL_SET_SLAVE_SELECT (0x2) /**< <b>Ioctl request code</b>: Setting slaveSelect register */
#define SPI_IPC7207_IOCTL_FLUSH (0x3) /**< <b>Ioctl request code</b>: Flushin FIFOs and serial shift registers */

View File

@ -53,26 +53,24 @@ void spi_free(spi_t *obj)
void spi_format(spi_t *obj, int bits, int mode, int slave)
{
if(slave)
{/* Slave mode */
if(slave) {
/* Slave mode */
obj->membase->CONTROL.BITS.MODE = SPI_SLAVE_MODE;
}
else
{/* Master mode */
} else {
/* Master mode */
obj->membase->CONTROL.BITS.MODE = SPI_MASTER_MODE;
}
obj->membase->CONTROL.BITS.WORD_WIDTH = bits >> 0x4; /* word width */
obj->membase->CONTROL.BITS.CPOL = mode >> 0x1; /* CPOL */
obj->membase->CONTROL.BITS.CPHA = mode & 0x1; /* CPHA */
obj->membase->CONTROL.BITS.ENDIAN = SPI_ENDIAN_LSB_FIRST; /* Endian TODO ARM needs to confirm? */
obj->membase->CONTROL.BITS.ENDIAN = SPI_ENDIAN_LSB_FIRST; /* Endian */
}
void spi_frequency(spi_t *obj, int hz)
{
/* TODO if the frequency is outside the allowable range, set it to the max */
if(hz > SPI_FREQ_MAX)
{
/* If the frequency is outside the allowable range, set it to the max */
if(hz > SPI_FREQ_MAX) {
hz = SPI_FREQ_MAX;
}
obj->membase->FDIV = ((fClockGetPeriphClockfrequency() / hz) >> 1) - 1;
@ -90,16 +88,11 @@ int spi_busy(spi_t *obj)
uint8_t spi_get_module(spi_t *obj)
{
if(obj->membase == SPI1REG)
{
if(obj->membase == SPI1REG) {
return 0; /* UART #1 */
}
else if(obj->membase == SPI2REG)
{
} else if(obj->membase == SPI2REG) {
return 1; /* UART #2 */
}
else
{
} else {
return 2; /* Invalid address */
}
}
@ -109,25 +102,23 @@ uint8_t spi_get_module(spi_t *obj)
void spi_master_transfer(spi_t *obj, void *tx, size_t tx_length, void *rx, size_t rx_length, uint32_t handler, uint32_t event, DMAUsage hint)
{
uint32_t i; int ndata = 0;
uint32_t i;
int ndata = 0;
uint16_t *tx_ptr = (uint16_t *) tx;
if(obj->spi->CONTROL.BITS.WORD_WIDTH == 0)
{/* Word size 8 bits */
if(obj->spi->CONTROL.BITS.WORD_WIDTH == 0) {
/* Word size 8 bits */
WORD_WIDTH_MASK = 0xFF;
}
else if(obj->spi->CONTROL.BITS.WORD_WIDTH == 1)
{/* Word size 16 bits */
} else if(obj->spi->CONTROL.BITS.WORD_WIDTH == 1) {
/* Word size 16 bits */
WORD_WIDTH_MASK = 0xFFFF;
}
else
{/* Word size 32 bits */
} else {
/* Word size 32 bits */
WORD_WIDTH_MASK = 0xFFFFFFFF;
}
//frame size
if(tx_length == 0)
{
if(tx_length == 0) {
tx_length = rx_length;
tx = (void*) 0;
}
@ -160,22 +151,17 @@ void spi_master_transfer(spi_t *obj, void *tx, size_t tx_length, void *rx, size_
//write async
if ( && )
{
if ( && ) {
}
while ((obj->tx_buff.pos < obj->tx_buff.length) &&
(obj->spi->STATUS.BITS.TX_FULL == False) &&
(obj->spi->STATUS.BITS.RX_FULL == False))
{
(obj->spi->STATUS.BITS.RX_FULL == False)) {
// spi_buffer_tx_write(obj);
if (obj->tx_buff.buffer == (void *)0)
{
if (obj->tx_buff.buffer == (void *)0) {
data = SPI_FILL_WORD;
}
else
{
} else {
uint16_t *tx = (uint16_t *)(obj->tx_buff.buffer);
data = tx[obj->tx_buff.pos] & 0xFF;
}
@ -183,8 +169,8 @@ void spi_master_transfer(spi_t *obj, void *tx, size_t tx_length, void *rx, size_
}
ndata++;
}
return ndata;
}
return ndata;
}

View File

@ -3,7 +3,7 @@
* @file ticker.h
* @brief Microcontroller uSec ticker
* @internal
* @author Radhika
* @author ON Semiconductor.
* $Rev:
* $Date:
******************************************************************************

View File

@ -39,7 +39,7 @@
#ifndef TIMER_H_
#define TIMER_H_
#ifdef __cplusplus
#ifdef __cplusplus
extern "C" {
#endif
@ -72,7 +72,7 @@ typedef enum {
CLK_DIVIDER_128 = 6,
CLK_DIVIDER_256 = 2,
CLK_DIVIDER_1024 = 7
}ClockDivider;
} ClockDivider;
#define TIME_MODE_FREE_RUNNING 0x0
#define TIME_MODE_PERIODIC 0x1

View File

@ -3,7 +3,7 @@
* @file uart_16c550_map.h
* @brief UART module hardware register map.
* @internal
* @author Industrial ASSP Applications Team
* @author ON Semiconductor.
* $Rev: 2615 $
* $Date: 2013-12-13 13:17:21 +0530 (Fri, 13 Dec 2013) $
******************************************************************************

View File

@ -130,24 +130,19 @@ typedef struct {
#endif /* REVB */
#ifdef REVD
typedef struct
{
typedef struct {
__IO uint32_t LOAD; /**< 0x4000A000 Contains the value from which the counter is decremented. When this register is written to the count is immediately restarted from the new value. The minimum valid value is 1. */
__I uint32_t CURRENT_VALUE; /**< 0x4000A004 Gives the current value of the decrementing counter */
union
{
struct
{
union {
struct {
__IO uint32_t WDT_EN :1; /**< Watchdog enable, 0 Watchdog disabled, 1 Watchdog enabled */
} BITS;
__IO uint32_t WORD;
} CONTROL; /* 0x4000A008 */
__O uint32_t KICK; /**< 0x4000A00C A write of any value to this register reloads the value register from the load register */
__O uint32_t LOCK; /**< 0x4000A010 Use of this register causes write-access to all other registers to be disabled. This is to prevent rogue software from disabling the watchdog functionality. Writing a value of 0x1ACCE551 enables write access to all other registers. Writing any other value disables write access. A read from this register only returns the bottom bit…, 0 Write access is enabled, 1 Write access is disabled */
union
{
struct
{
union {
struct {
__I uint32_t WRITE_BUSY_ANY :1; /**< Busy writing any register */
__I uint32_t WRITE_BUSY_LOAD :1; /**< Busy writing the load register */
__I uint32_t WRITE_BUSY_CONTROL :1; /**< Busy writing the control enable register */

View File

@ -1,33 +1,24 @@
#!/usr/bin/env python
"""
@copyright (c) 2012 ON Semiconductor. All rights reserved.
ON Semiconductor is supplying this software for use with ON Semiconductor
processor based microcontrollers only.
THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
ON SEMICONDUCTOR SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL,
INCIDENTAL, OR CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
"""
# CMSIS-DAP Interface Firmware
# Copyright (c) 2009-2013 ARM Limited
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
from __future__ import absolute_import
from __future__ import print_function
import argparse
import itertools
import binascii
import intelhex
import os
FIB_BASE = 0x2000
FLASH_BASE = 0x3000
FW_REV = 0x01000100 #todo: determine if revision can be passed from yotta
FW_REV = 0x01000100
def ranges(i):
for _, b in itertools.groupby(enumerate(i), lambda x_y: x_y[1] - x_y[0]):
b = list(b)
@ -35,31 +26,9 @@ def ranges(i):
def add_fib_at_start(arginput):
#parser = argparse.ArgumentParser(description='Firmware Information Block generation script')
#parser.add_argument("input", type=str, help="bin file to read from.")
#args = parser.parse_args()
#input_file = args.input + "_orig.bin"
#output_file = args.input #use same name, does not include extension
#file_name_hex = args.input + ".hex"
#file_name_bin = args.input + ".bin"
print("inputfile", arginput)
input_file = arginput + ".bin"
output_file = arginput #use same name, does not include extension
file_name_hex = arginput + "_fib.hex"
file_name_bin = arginput + ".bin"
print("inputfile", input_file)
print("output_file", output_file)
print("file_name_hex", file_name_hex)
print("file_name_bin", file_name_bin)
# Import intelhex if avaialable, otherwise fail
try:
from intelhex import IntelHex
except:
return fail('error: You do not have \'intelhex\' installed. Please run \'pip install intelhex\' then retry.')
# Read in hex file
input_hex_file = intelhex.IntelHex()
@ -81,7 +50,8 @@ def add_fib_at_start(arginput):
start = min(min(start_end_pairs))
end = max(max(start_end_pairs))
assert start >= FLASH_BASE, ("Error - start 0x%x less than begining of user flash area" %start)
assert start >= FLASH_BASE, ("Error - start 0x%x less than begining of user\
flash area" %start)
# Compute checksum over the range (don't include data at location of crc)
size = end - start + 1
data = input_hex_file.tobinarray(start=start, size=size)
@ -91,11 +61,12 @@ def add_fib_at_start(arginput):
checksum = (start + size + crc32 + fw_rev) & 0xFFFFFFFF
print("Writing FIB: base 0x%08X, size 0x%08X, crc32 0x%08X, fw rev 0x%08X, checksum 0x%08X" % (start, size, crc32, fw_rev, checksum))
print("Writing FIB: base 0x%08X, size 0x%08X, crc32 0x%08X, fw rev 0x%08X,\
checksum 0x%08X" % (start, size, crc32, fw_rev, checksum))
#expected initial values used by daplink to validate that it is a valid bin file
#added as dummy values in this file because the fib area preceeds the application area
#the bootloader will ignore these dummy values
#expected initial values used by daplink to validate that it is a valid bin
#file added as dummy values in this file because the fib area preceeds the
#application area the bootloader will ignore these dummy values
# 00 is stack pointer (RAM address)
# 04 is Reset vector (FLASH address)
# 08 NMI_Handler (FLASH address)
@ -109,7 +80,8 @@ def add_fib_at_start(arginput):
#expected fib structure
#typedef struct fib{
#uint32_t base; /**< Base offset of firmware, indicating what flash the firmware is in. (will never be 0x11111111) */
#uint32_t base; /**< Base offset of firmware, indicating what flash the
# firmware is in. (will never be 0x11111111) */
#uint32_t size; /**< Size of the firmware */
#uint32_t crc; /**< CRC32 for firmware correctness check */
#uint32_t rev; /**< Revision number */
@ -183,3 +155,4 @@ def add_fib_at_start(arginput):
# Write out file(s)
output_hex_file.tofile(file_name_hex, 'hex')
output_hex_file.tofile(file_name_bin, 'bin')

View File

@ -37,7 +37,7 @@ GCC_ARM_PATH = ""
GCC_CR_PATH = "C:/code_red/RedSuite_4.2.0_349/redsuite/Tools/bin"
# IAR
IAR_PATH = "C:\\tools_w32\IAR7.7\\arm"
IAR_PATH = "C:/Program Files (x86)/IAR Systems/Embedded Workbench 7.3/arm"
# Goanna static analyser. Please overload it in mbed_settings.py
GOANNA_PATH = "c:/Program Files (x86)/RedLizards/Goanna Central 3.2.3/bin"