Costmetic fixes to C coding style

This commit is contained in:
Gregory Nutt 2015-10-05 17:13:53 -06:00
parent 7a63e976ad
commit 3fdd914203
160 changed files with 930 additions and 875 deletions

View File

@ -67,7 +67,7 @@
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: a1x_pio_pin

View File

@ -2257,4 +2257,3 @@ void up_netinitialize(void)
}
#endif /* CONFIG_NET */

View File

@ -125,4 +125,3 @@ void up_timer_initialize(void)
irq_attach(C5471_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
up_enable_irq(C5471_IRQ_SYSTIMER);
}

View File

@ -80,7 +80,7 @@ void up_addregion(void)
/* Disable watchdog in first non-common function */
wdog_enable(0);
#endif
// XXX: change to initialization of extern memory with save defaults
/* XXX: change to initialization of extern memory with save defaults */
/* Configure memory interface */
calypso_mem_cfg(CALYPSO_nCS0, 3, CALYPSO_MEM_16bit, 1);
calypso_mem_cfg(CALYPSO_nCS1, 3, CALYPSO_MEM_16bit, 1);

View File

@ -143,7 +143,7 @@ static int pwr_btn_dec(uint32_t * state, uint8_t reg, char *buf, size_t * len)
*state |= 0x80000000;
}
return 1; // break loop in caller
return 1; /* break loop in caller */
}
else
{
@ -164,7 +164,7 @@ static int pwr_btn_dec(uint32_t * state, uint8_t reg, char *buf, size_t * len)
}
}
return 0; // continue with other columns
return 0; /* Continue with other columns */
}
/****************************************************************************

View File

@ -73,7 +73,9 @@
#if UART_FCR_OFFS == UART_EFR_OFFS
# define UART_MULTIPLEX_REGS
// HW flow control not supported yet
/* HW flow control not supported yet */
# undef CONFIG_UART_HWFLOWCONTROL
#endif

View File

@ -161,11 +161,11 @@ void wdog_enable(int on)
void wdog_reset(void)
{
// enable watchdog
/* Enable watchdog */
putreg16(WD_MODE_ENABLE, WDOG_REG(WD_MODE));
// force expiration
/* Force expiration */
putreg16(0x0000, WDOG_REG(WD_LOAD_TIMER));
putreg16(0x0000, WDOG_REG(WD_LOAD_TIMER));

View File

@ -445,6 +445,7 @@ static uint8_t dm320_getreg8(uint32_t addr)
{
lldbg("...\n");
}
return val;
}
}
@ -2133,6 +2134,7 @@ static int dm320_epcancel(struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req)
return -EINVAL;
}
#endif
usbtrace(TRACE_EPCANCEL, privep->epphy);
priv = privep->dev;

View File

@ -240,7 +240,9 @@ int __ramfunc__ msc_load_verify_address(uint32_t* address)
/* Check for invalid address */
if (status & MSC_STATUS_INVADDR)
{
return -EINVAL;
}
/* Check for write protected page */

View File

@ -1284,7 +1284,6 @@ static int efm32_i2c_isr(struct efm32_i2c_priv_s *priv)
}
done:
if (priv->i2c_state == I2CSTATE_DONE)
{
#ifndef CONFIG_I2C_POLLED
@ -1975,7 +1974,6 @@ int up_i2creset(FAR struct i2c_dev_s *dev)
ret = OK;
out:
/* Release the port for re-use by other clients */
efm32_i2c_sem_post(dev);

View File

@ -194,8 +194,10 @@ void efm32_timer_reset(uintptr_t base)
putreg32(_TIMER_TOPB_RESETVALUE, base + EFM32_TIMER_CTRL_OFFSET );
putreg32(_TIMER_CNT_RESETVALUE, base + EFM32_TIMER_CMD_OFFSET );
/* Do not reset route register, setting should be done independently */
/* (Note: ROUTE register may be locked by DTLOCK register.) */
/* Do not reset route register, setting should be done independently
* (Note: ROUTE register may be locked by DTLOCK register.)
*/
//putreg32(_TIMER_ROUTE_RESETVALUE, base + EFM32_TIMER_ROUTE_OFFSET );
for(i = 0; i < EFM32_TIMER_NCC; i++)

View File

@ -817,6 +817,7 @@ static uint32_t efm32_getreg(uint32_t addr)
{
lldbg("...\n");
}
return val;
}
}

View File

@ -73,8 +73,7 @@
* Pre-processor Definitions
****************************************************************************/
/* Configuration ***************************************************************/
/*
* EFM32 USB OTG FS Host Driver Support
/* EFM32 USB OTG FS Host Driver Support
*
* Pre-requisites
*

View File

@ -394,7 +394,7 @@ static int kinetis_transmit(FAR struct kinetis_driver_s *priv)
txdesc->length = kinesis_swap16(priv->dev.d_len);
#ifdef CONFIG_ENET_ENHANCEDBD
txdesc->bdu = 0x00000000;
txdesc->status2 = TXDESC_INT | TXDESC_TS; // | TXDESC_IINS | TXDESC_PINS;
txdesc->status2 = TXDESC_INT | TXDESC_TS; /* | TXDESC_IINS | TXDESC_PINS; */
#endif
txdesc->status1 = (TXDESC_R | TXDESC_L | TXDESC_TC | TXDESC_W);

View File

@ -243,4 +243,3 @@ void kl_clockconfig(void)
//kl_traceconfig();
//kl_fbconfig();
}

View File

@ -378,7 +378,7 @@ static int i2c_interrupt(int irq, FAR void *context)
switch (state)
{
case 0x00: // Bus Error
case 0x00: /* Bus Error */
case 0x20:
case 0x30:
case 0x38:
@ -386,8 +386,8 @@ static int i2c_interrupt(int irq, FAR void *context)
i2c_stop(priv);
break;
case 0x08: // START
case 0x10: // Repeat START
case 0x08: /* START */
case 0x10: /* Repeat START */
putreg32(priv->msg.addr, priv->base + LPC11_I2C_DAT_OFFSET);
putreg32(I2C_CONCLR_STAC, priv->base + LPC11_I2C_CONCLR_OFFSET);
break;

View File

@ -378,8 +378,8 @@ static inline void lpc11_uart0config(void)
#ifdef LPC111x
static inline uint32_t lpc11_uartdl(uint32_t baud, uint8_t divcode)
{
/* TODO: Calculate DL automatically */
uint32_t num = 312;
return num;

View File

@ -326,6 +326,7 @@ static void can_printreg(uint32_t addr, uint32_t value)
{
lldbg("...\n");
}
return;
}
}

View File

@ -375,7 +375,7 @@ static int i2c_interrupt(int irq, FAR void *context)
switch (state)
{
case 0x00: // Bus Error
case 0x00: /* Bus Error */
case 0x20:
case 0x30:
case 0x38:
@ -383,8 +383,8 @@ static int i2c_interrupt(int irq, FAR void *context)
i2c_stop(priv);
break;
case 0x08: // START
case 0x10: // Repeat START
case 0x08: /* START */
case 0x10: /* Repeat START */
putreg32(priv->msg.addr, priv->base + LPC17_I2C_DAT_OFFSET);
putreg32(I2C_CONCLR_STAC, priv->base + LPC17_I2C_CONCLR_OFFSET);
break;

View File

@ -395,7 +395,7 @@ static void mcpwm_set_apb_clock(FAR struct lpc17_mcpwmtimer_s *priv, bool on)
modifyreg32(regaddr, en_bit, 0);
}
}
#endif /*XXXXX*/
#endif
/****************************************************************************
* Name: mcpwm_setup

View File

@ -413,7 +413,7 @@ static void pwm_set_apb_clock(FAR struct lpc17_pwmtimer_s *priv, bool on)
modifyreg32(regaddr, en_bit, 0);
}
}
#endif /*XXXXX*/
#endif
/****************************************************************************
* Name: pwm_setup

View File

@ -864,6 +864,7 @@ static uint8_t lpc17_log2(uint16_t value)
value >>= 1;
log2++;
}
return log2;
}

View File

@ -1256,7 +1256,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* and reset the divider in the CLKSEL0/1 register.
*/
#if 0 // ifdef LPC176x
#if 0 /* ifdef LPC176x */
priv->cclkdiv = lpc17_uartcclkdiv(priv->baud);
#endif
/* DLAB open latch */

View File

@ -541,6 +541,7 @@ static uint32_t lpc214x_getreg(uint32_t addr)
{
lldbg("...\n");
}
return val;
}
}

View File

@ -174,4 +174,3 @@ uint32_t lpc31_clkfreq(enum lpc31_clockid_e clkid,
return freq;
}

View File

@ -122,6 +122,6 @@ int lpc31_fdcndx(enum lpc31_clockid_e clkid, enum lpc31_domainid_e dmnid)
fdcndx = CGU_ESRSEL(regval) + (int)g_fdcbase[dmnid];
}
}
return fdcndx;
}

View File

@ -130,6 +130,7 @@ void lpc31_resetclks(void)
{
regval &= ~CGU_PCR_ENOUTEN;
}
putreg32(regval, regaddr);
/* Set/clear the RUN bit in the PCR regiser of all clocks, depending

View File

@ -504,8 +504,7 @@ static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sel
return;
}
/*
* Since we don't use sequential multi-slave mode, but rather
/* Since we don't use sequential multi-slave mode, but rather
* perform the transfer piecemeal by consecutive calls to
* SPI_SEND, then we must manually assert the chip select
* across the whole transfer
@ -580,7 +579,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
priv->slv1 = (priv->slv1 & ~(SPI_SLV_1_CLKDIV2_MASK | SPI_SLV_1_CLKDIV1_MASK)) | (div2 << SPI_SLV_1_CLKDIV2_SHIFT) | (div1 << SPI_SLV_1_CLKDIV1_SHIFT);
priv->frequency = frequency;
priv->actual = frequency; // FIXME
priv->actual = frequency; /* FIXME */
}
return priv->actual;

View File

@ -167,7 +167,10 @@
/* Hardware interface **********************************************************/
/* This represents a Endpoint Transfer Descriptor - note these must be 32 byte aligned */
/* This represents a Endpoint Transfer Descriptor - note these must be 32 byte
* aligned
*/
struct lpc31_dtd_s
{
volatile uint32_t nextdesc; /* Address of the next DMA descripto in RAM */
@ -181,6 +184,7 @@ struct lpc31_dtd_s
};
/* DTD nextdesc field */
#define DTD_NEXTDESC_INVALID (1 << 0) /* Bit 0 : Next Descriptor Invalid */
/* DTD config field */
@ -499,6 +503,7 @@ static uint32_t lpc31_getreg(uint32_t addr)
{
lldbg("...\n");
}
return val;
}
}
@ -718,25 +723,33 @@ static inline void lpc31_ep0xfer(uint8_t epphy, uint8_t *buf, uint32_t nbytes)
* Read a Setup packet from the DTD.
*
****************************************************************************/
static void lpc31_readsetup(uint8_t epphy, struct usb_ctrlreq_s *ctrl)
{
struct lpc31_dqh_s *dqh = &g_qh[epphy];
int i;
do {
do
{
/* Set the trip wire */
lpc31_setbits(USBDEV_USBCMD_SUTW, LPC31_USBDEV_USBCMD);
/* copy the request... */
for (i = 0; i < 8; i++)
((uint8_t *) ctrl)[i] = ((uint8_t *) dqh->setup)[i];
} while (!(lpc31_getreg(LPC31_USBDEV_USBCMD) & USBDEV_USBCMD_SUTW));
for (i = 0; i < 8; i++)
{
((uint8_t *) ctrl)[i] = ((uint8_t *) dqh->setup)[i];
}
}
while (!(lpc31_getreg(LPC31_USBDEV_USBCMD) & USBDEV_USBCMD_SUTW));
/* Clear the trip wire */
lpc31_clrbits(USBDEV_USBCMD_SUTW, LPC31_USBDEV_USBCMD);
/* Clear the Setup Interrupt */
lpc31_putreg (LPC31_ENDPTMASK(LPC31_EP0_OUT), LPC31_USBDEV_ENDPTSETUPSTAT);
}
@ -909,12 +922,16 @@ static void lpc31_reqcomplete(struct lpc31_ep_s *privep,
static void lpc31_cancelrequests(struct lpc31_ep_s *privep, int16_t status)
{
if (!lpc31_rqempty(privep))
{
lpc31_flushep(privep);
}
while (!lpc31_rqempty(privep))
{
// FIXME: the entry at the head should be sync'd with the DTD
// FIXME: only report the error status if the transfer hasn't completed
/* FIXME: the entry at the head should be sync'd with the DTD
* FIXME: only report the error status if the transfer hasn't completed
*/
usbtrace(TRACE_COMPLETE(privep->epphy),
(lpc31_rqpeek(privep))->req.xfrd);
lpc31_reqcomplete(privep, lpc31_rqdequeue(privep), status);

View File

@ -704,6 +704,7 @@ static uint32_t lpc43_getreg(uint32_t addr)
{
lldbg("...\n");
}
return val;
}
}

View File

@ -442,9 +442,12 @@ static int i2c_interrupt(int irq, FAR void *context)
case 0x28: /* Data byte in DAT has been transmitted; ACK has been received. */
priv->wrcnt++;
if (priv->wrcnt < msg->length) {
if (priv->wrcnt < msg->length)
{
putreg32(msg->buffer[priv->wrcnt],priv->base+LPC43_I2C_DAT_OFFSET); /* Put next byte */
} else {
}
else
{
startStopNextMessage(priv);
}
break;
@ -453,9 +456,12 @@ static int i2c_interrupt(int irq, FAR void *context)
case 0x40: /* SLA+R has been transmitted; ACK has been received */
priv->rdcnt = 0;
if (msg->length > 1) {
if (msg->length > 1)
{
putreg32(I2C_CONSET_AA, priv->base + LPC43_I2C_CONSET_OFFSET); /* Set ACK next read */
} else {
}
else
{
putreg32(I2C_CONCLR_AAC,priv->base + LPC43_I2C_CONCLR_OFFSET); /* Do not ACK because only one byte */
}
break;
@ -567,7 +573,6 @@ struct i2c_dev_s *up_i2cinitialize(int port)
lpc43_pin_config(PINCONF_I2C1_SDA);
i2c_setfrequency(priv, I2C1_DEFAULT_FREQUENCY);
}
else
#endif

View File

@ -33,8 +33,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* Power-Up Reset Overview
/* Power-Up Reset Overview
* -----------------------
*
* The ARM core starts executing code on reset with the program counter set

View File

@ -518,6 +518,7 @@ static uint32_t lpc43_getreg(uint32_t addr)
{
lldbg("...\n");
}
return val;
}
}
@ -956,8 +957,10 @@ static void lpc43_cancelrequests(struct lpc43_ep_s *privep, int16_t status)
while (!lpc43_rqempty(privep))
{
// FIXME: the entry at the head should be sync'd with the DTD
// FIXME: only report the error status if the transfer hasn't completed
/* FIXME: the entry at the head should be sync'd with the DTD
* FIXME: only report the error status if the transfer hasn't completed
*/
usbtrace(TRACE_COMPLETE(privep->epphy),
(lpc43_rqpeek(privep))->req.xfrd);
lpc43_reqcomplete(privep, lpc43_rqdequeue(privep), status);
@ -2646,7 +2649,6 @@ void up_usbinitialize(void)
}
}
/* Clock */
regval = getreg32(LPC43_BASE_USB0_CLK);

View File

@ -83,9 +83,11 @@ void uart_decodeirq(int irq, FAR void *context)
i = 0;
do
{
if (!(status & 0x1)) {
if (!(status & 0x1))
{
irq_dispatch(VIRQ_START + i, context);
}
status >>= 1;
}
while (++i <= 4);
@ -102,8 +104,7 @@ int uart_ioctl(struct file *filep, int cmd, unsigned long arg)
unsigned int opmode;
int bitm_off;
/*
* TODO: calculate bit offset from UART_BASE address.
/* TODO: calculate bit offset from UART_BASE address.
* E.g.:
* 0x9820_0000 -> 0
* 0x9820_0020 -> 1

View File

@ -101,7 +101,8 @@ void up_irqinitialize(void)
(*(volatile uint32_t *)0x98100008) &= ~0x9;
while (!((*(volatile uint32_t *)0x98100008) & 0x2)) { ; }
while (!((*(volatile uint32_t *)0x98100008) & 0x2))
;
(*(volatile uint32_t *)0x98100008) |= 0x4;

View File

@ -69,7 +69,7 @@ void up_systemreset(void)
{
putreg32(0, FTWDT010_CR);
putreg32(0, FTWDT010_LOAD);
putreg32(0x5ab9, FTWDT010_RESTART); // Magic
putreg32(0x5ab9, FTWDT010_RESTART); /* Magic */
putreg32(0x11, FTWDT010_CR);
putreg32(0x13, FTWDT010_CR);

View File

@ -112,7 +112,7 @@ static void aes_encryptblock(void *out, const void *in)
putreg32(AES_CR_START, SAM_AES_CR);
while(!(getreg32(SAM_AES_ISR) & AES_ISR_DATRDY)) {}
while (!(getreg32(SAM_AES_ISR) & AES_ISR_DATRDY));
if (out)
{
@ -125,9 +125,13 @@ static int aes_setup_mr(uint32_t keysize, int mode, int encrypt)
uint32_t regval = AES_MR_SMOD_MANUAL_START | AES_MR_CKEY;
if (encrypt)
{
regval |= AES_MR_CIPHER_ENCRYPT;
}
else
{
regval |= AES_MR_CIPHER_DECRYPT;
}
switch (keysize)
{
@ -176,7 +180,9 @@ int aes_cypher(void *out, const void *in, uint32_t size, const void *iv,
int res = OK;
if (size % 16)
{
return -EINVAL;
}
aes_lock();

View File

@ -769,7 +769,6 @@ int sam_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback)
************************************************************************************/
#if defined(CONFIG_RTC_HIRES) && defined (CONFIG_SAM34_RTT)
int up_rtc_gettime(FAR struct timespec *tp)
{
/* This is a hack to emulate a high resolution rtc using the rtt */
@ -781,8 +780,10 @@ int up_rtc_gettime(FAR struct timespec *tp)
rtc_cal = getreg32(SAM_RTC_CALR);
rtc_tim = getreg32(SAM_RTC_TIMR);
rtt_val = getreg32(SAM_RTT_VR);
} while((rtc_cal != getreg32(SAM_RTC_CALR)) ||
(rtc_tim != getreg32(SAM_RTC_TIMR)) ||
}
while (rtc_cal != getreg32(SAM_RTC_CALR) ||
rtc_tim != getreg32(SAM_RTC_TIMR));
(rtt_val != getreg32(SAM_RTT_VR)));
t.tm_sec = rtc_bcd2bin((rtc_tim & RTC_TIMR_SEC_MASK) >> RTC_TIMR_SEC_SHIFT);

View File

@ -526,7 +526,10 @@ static int sam34_settimeout(FAR struct timer_lowerhalf_s *lower,
DEBUGASSERT(priv);
rttvdbg("Entry: timeout=%d\n", timeout);
if(priv->started) return -EPERM;
if (priv->started)
{
return -EPERM;
}
/* Can this timeout be represented? */

View File

@ -1126,8 +1126,10 @@ static uint32_t twi_hw_setfrequency(struct twi_dev_s *priv, uint32_t frequency)
static void twi_hw_initialize(struct twi_dev_s *priv, unsigned int pid,
uint32_t frequency)
{
//uint32_t regval;
//uint32_t mck;
#if 0
uint32_t regval;
uint32_t mck;
#endif
i2cvdbg("TWI%d Initializing\n", priv->twi);

View File

@ -198,6 +198,7 @@ static uint32_t sam34_getreg(uint32_t addr)
{
lldbg("...\n");
}
return val;
}
}
@ -534,7 +535,7 @@ static int sam34_settimeout(FAR struct watchdog_lowerhalf_s *lower,
static xcpt_t sam34_capture(FAR struct watchdog_lowerhalf_s *lower,
xcpt_t handler)
{
#if 0 // TODO
#if 0 /* TODO */
FAR struct sam34_lowerhalf_s *priv = (FAR struct sam34_lowerhalf_s *)lower;
irqstate_t flags;
xcpt_t oldhandler;

View File

@ -256,7 +256,8 @@ static void dbgu_shutdown(struct uart_dev_s *dev)
/* Reset and disable receiver and transmitter */
putreg32((DBGU_CR_RSTRX|DBGU_CR_RSTTX|DBGU_CR_RXDIS|DBGU_CR_TXDIS), SAM_DBGU_CR);
putreg32((DBGU_CR_RSTRX | DBGU_CR_RSTTX | DBGU_CR_RXDIS | DBGU_CR_TXDIS),
SAM_DBGU_CR);
/* Disable all interrupts */

View File

@ -773,7 +773,8 @@ static void flexus_shutdown(struct uart_dev_s *dev)
/* Reset and disable receiver and transmitter */
flexus_serialout(priv, SAM_FLEXUS_CR_OFFSET,
(FLEXUS_CR_RSTRX|FLEXUS_CR_RSTTX|FLEXUS_CR_RXDIS|FLEXUS_CR_TXDIS));
(FLEXUS_CR_RSTRX | FLEXUS_CR_RSTTX | FLEXUS_CR_RXDIS |
FLEXUS_CR_TXDIS));
/* Disable all interrupts */

View File

@ -1616,13 +1616,15 @@ static int sam_hsmci_interrupt(struct sam_dev_s *priv)
{
/* Yes.. signal a timeout error */
wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_TIMEOUT;
wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_TIMEOUT;
}
else
{
/* No.. signal some generic I/O error */
wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_ERROR;
wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_ERROR;
}
}
else
@ -2393,14 +2395,16 @@ static int sam_waitresponse(FAR struct sdio_dev_s *dev, uint32_t cmd)
{
/* Yes.. return a timeout error */
priv->wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_TIMEOUT;
priv->wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_TIMEOUT;
return -ETIMEDOUT;
}
else
{
/* No.. return some generic I/O error */
priv->wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_ERROR;
priv->wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_ERROR;
return -EIO;
}
}

View File

@ -2717,8 +2717,8 @@ static void sam_show_layer(struct sam_layer_s *layer,
/* Mirror Y then Rotate 90: Top,Left -> Down,Right */
else if ((!rightleft && bottomup && layer->rotation == 90)
||(rightleft && !bottomup && layer->rotation == LCDC_ROT_270))
else if ((!rightleft && bottomup && layer->rotation == 90) ||
( rightleft && !bottomup && layer->rotation == LCDC_ROT_270))
{
/* No rotation optimization */

View File

@ -934,7 +934,9 @@ static int pmecc_pagelayout(uint16_t datasize, uint16_t eccsize)
DEBUGASSERT(bcherr512 >= 0);
break;
}
} /* Otherwise, fall through for the 1KB sectors */
}
/* Otherwise, fall through for the 1KB sectors */
case 2: /* 512B sectors not possible; 1KB sectors possible */
{

View File

@ -109,7 +109,7 @@ void sam_sckc_enable(bool enable)
regval &= ~SCKC_CR_OSC32BYP;
putreg32(regval, SAM_SCKC_CR);
/* Switch slow clock source to external OSC 32 kHz (*/
/* Switch slow clock source to external OSC 32 kHz */
regval |= SCKC_CR_OSCSEL;
putreg32(regval, SAM_SCKC_CR);

View File

@ -1264,7 +1264,8 @@ static void up_shutdown(struct uart_dev_s *dev)
/* Reset and disable receiver and transmitter */
up_serialout(priv, SAM_UART_CR_OFFSET,
(UART_CR_RSTRX|UART_CR_RSTTX|UART_CR_RXDIS|UART_CR_TXDIS));
(UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS |
UART_CR_TXDIS));
/* Disable all interrupts */

View File

@ -102,7 +102,7 @@ int up_timerisr(int irq, uint32_t *regs)
* Interval Value Register (PIT_PIVR), the overflow counter (PICNT) is
* reset and the PITS is cleared, thus acknowledging the interrupt. The
* value of PICNT gives the number of periodic intervals elapsed since the
* last read of PIT_PIVR.
* last read of PIT_PIVR."
*/
uint32_t picnt = getreg32(SAM_PIT_PIVR) >> PIT_PICNT_SHIFT;

View File

@ -200,6 +200,7 @@ static uint32_t sam_getreg(uintptr_t regaddr)
{
lldbg("...\n");
}
return regval;
}
}

View File

@ -649,8 +649,7 @@ int sam_dumppio(uint32_t pinset, const char *msg)
{
lldbg(" SCDR: %08x WPMR: %08x WPSR: %08x IOSSR: %08x\n",
getreg32(SAM_SPIO_SCDR), getreg32(SAM_SPIO_WPMR),
getreg32(SAM_SPIO_WPSR), getreg32(base + SAM_SPIO_IOSSR_OFFSET),
);
getreg32(SAM_SPIO_WPSR), getreg32(base + SAM_SPIO_IOSSR_OFFSET));
}
else
{

View File

@ -63,7 +63,6 @@
#include "sam_gpio.h"
#include "sam_xdmac.h"
#include "sam_periphclks.h"
//#include "sam_memories.h"
#include "sam_hsmci.h"
#include "chip/sam_xdmac.h"
#include "chip/sam_pmc.h"
@ -1549,13 +1548,15 @@ static int sam_hsmci_interrupt(struct sam_dev_s *priv)
{
/* Yes.. signal a timeout error */
wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_TIMEOUT;
wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_TIMEOUT;
}
else
{
/* No.. signal some generic I/O error */
wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_ERROR;
wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_ERROR;
}
}
else
@ -2311,14 +2312,16 @@ static int sam_waitresponse(FAR struct sdio_dev_s *dev, uint32_t cmd)
{
/* Yes.. return a timeout error */
priv->wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_TIMEOUT;
priv->wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_TIMEOUT;
return -ETIMEDOUT;
}
else
{
/* No.. return some generic I/O error */
priv->wkupevent = SDIOWAIT_CMDDONE|SDIOWAIT_RESPONSEDONE|SDIOWAIT_ERROR;
priv->wkupevent = SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE |
SDIOWAIT_ERROR;
return -EIO;
}
}
@ -2450,7 +2453,8 @@ static int sam_recvshort(FAR struct sdio_dev_s *dev,
return ret;
}
static int sam_recvlong(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t rlong[4])
static int sam_recvlong(FAR struct sdio_dev_s *dev, uint32_t cmd,
uint32_t rlong[4])
{
struct sam_dev_s *priv = (struct sam_dev_s *)dev;
int ret = OK;

View File

@ -65,7 +65,6 @@
#include "sam_gpio.h"
#include "sam_xdmac.h"
//#include "sam_memories.h"
#include "sam_periphclks.h"
#include "sam_ssc.h"
#include "chip/sam_pmc.h"

View File

@ -62,8 +62,7 @@
* Pre-processor Definitions
****************************************************************************/
/* Memory Map ***************************************************************/
/*
* 0x0400:0000 - Beginning of the internal FLASH. Address of vectors.
/* 0x0400:0000 - Beginning of the internal FLASH. Address of vectors.
* Mapped as boot memory address 0x0000:0000 at reset.
* 0x041f:ffff - End of flash region (assuming the max of 2MiB of FLASH).
* 0x2000:0000 - Start of internal SRAM and start of .data (_sdata)