Remove the unneeded void cast

Signed-off-by: Xiang Xiao <xiaoxiang@xiaomi.com>
This commit is contained in:
Xiang Xiao 2022-04-17 23:14:13 +08:00 committed by Petro Karashchenko
parent 32ee2ae407
commit ef1a98dd00
108 changed files with 216 additions and 226 deletions

View File

@ -396,8 +396,8 @@ Standard String Operations
#include <strings.h> #include <strings.h>
#define bcmp(b1,b2,len) memcmp(b1,b2,(size_t)len) #define bcmp(b1,b2,len) memcmp(b1,b2,(size_t)len)
#define bcopy(b1,b2,len) (void)memmove(b2,b1,len) #define bcopy(b1,b2,len) memmove(b2,b1,len)
#define bzero(s,n) (void)memset(s,0,n) #define bzero(s,n) memset(s,0,n)
#define index(s,c) strchr(s,c) #define index(s,c) strchr(s,c)
#define rindex(s,c) strrchr(s,c) #define rindex(s,c) strrchr(s,c)

View File

@ -261,7 +261,7 @@ int arm_svcall(int irq, FAR void *context, FAR void *arg)
*/ */
rtcb->flags &= ~TCB_FLAG_SYSCALL; rtcb->flags &= ~TCB_FLAG_SYSCALL;
(void)nxsig_unmask_pendingsignal(); nxsig_unmask_pendingsignal();
} }
break; break;
#endif #endif

View File

@ -239,7 +239,7 @@ uint32_t *arm_syscall(uint32_t *regs)
*/ */
rtcb->flags &= ~TCB_FLAG_SYSCALL; rtcb->flags &= ~TCB_FLAG_SYSCALL;
(void)nxsig_unmask_pendingsignal(); nxsig_unmask_pendingsignal();
} }
break; break;
#endif #endif

View File

@ -275,7 +275,7 @@ int arm_svcall(int irq, FAR void *context, FAR void *arg)
*/ */
rtcb->flags &= ~TCB_FLAG_SYSCALL; rtcb->flags &= ~TCB_FLAG_SYSCALL;
(void)nxsig_unmask_pendingsignal(); nxsig_unmask_pendingsignal();
} }
break; break;
#endif #endif

View File

@ -236,7 +236,7 @@ uint32_t *arm_syscall(uint32_t *regs)
*/ */
rtcb->flags &= ~TCB_FLAG_SYSCALL; rtcb->flags &= ~TCB_FLAG_SYSCALL;
(void)nxsig_unmask_pendingsignal(); nxsig_unmask_pendingsignal();
} }
break; break;
#endif #endif

View File

@ -274,7 +274,7 @@ int arm_svcall(int irq, FAR void *context, FAR void *arg)
*/ */
rtcb->flags &= ~TCB_FLAG_SYSCALL; rtcb->flags &= ~TCB_FLAG_SYSCALL;
(void)nxsig_unmask_pendingsignal(); nxsig_unmask_pendingsignal();
} }
break; break;
#endif #endif

View File

@ -496,8 +496,6 @@ FAR struct pwm_lowerhalf_s *cxd56_pwminitialize(uint32_t channel)
{ {
FAR struct cxd56_pwm_chan_s *pwmch; FAR struct cxd56_pwm_chan_s *pwmch;
(void)g_pwmops;
switch (channel) switch (channel)
{ {
#ifdef CONFIG_CXD56_PWM0 #ifdef CONFIG_CXD56_PWM0

View File

@ -84,7 +84,7 @@ const uintptr_t g_idle_topstack = HEAP_BASE;
#ifdef CONFIG_DEBUG_FEATURES #ifdef CONFIG_DEBUG_FEATURES
# if defined(CONFIG_ARMV7M_ITMSYSLOG) # if defined(CONFIG_ARMV7M_ITMSYSLOG)
# define showprogress(c) (void)syslog_putc(c) # define showprogress(c) syslog_putc(c)
# elif defined(HAVE_UART_CONSOLE) || defined(HAVE_LEUART_CONSOLE) # elif defined(HAVE_UART_CONSOLE) || defined(HAVE_LEUART_CONSOLE)
# define showprogress(c) efm32_lowputc(c) # define showprogress(c) efm32_lowputc(c)
# else # else

View File

@ -581,7 +581,7 @@ void imxrt_flexspi_get_default_config(struct flexspi_config_s *config)
{ {
/* Initializes the configure structure to zero */ /* Initializes the configure structure to zero */
(void)memset(config, 0, sizeof(*config)); memset(config, 0, sizeof(*config));
config->rx_sample_clock = FLEXSPI_READ_SAMPLE_CLK_LOOPBACK_FROM_DQS_PAD; config->rx_sample_clock = FLEXSPI_READ_SAMPLE_CLK_LOOPBACK_FROM_DQS_PAD;
config->enable_sck_free_running = false; config->enable_sck_free_running = false;
@ -606,8 +606,8 @@ void imxrt_flexspi_get_default_config(struct flexspi_config_s *config)
config->ahb_config.ahb_grant_timeout_cycle = 0xff; config->ahb_config.ahb_grant_timeout_cycle = 0xff;
config->ahb_config.ahb_bus_timeout_cycle = 0xffff; config->ahb_config.ahb_bus_timeout_cycle = 0xffff;
config->ahb_config.resume_wait_cycle = 0x20; config->ahb_config.resume_wait_cycle = 0x20;
(void)memset(config->ahb_config.buffer, 0, memset(config->ahb_config.buffer, 0,
sizeof(config->ahb_config.buffer)); sizeof(config->ahb_config.buffer));
/* Use invalid master ID 0xF and buffer size 0 for the first several /* Use invalid master ID 0xF and buffer size 0 for the first several
* buffers. * buffers.

View File

@ -1330,8 +1330,8 @@ static int imxrt_interrupt(int irq, void *context, FAR void *arg)
mcinfo("Queuing callback to %p(%p)\n", mcinfo("Queuing callback to %p(%p)\n",
priv->callback, priv->cbarg); priv->callback, priv->cbarg);
(void)work_queue(HPWORK, &priv->cbwork, priv->callback, work_queue(HPWORK, &priv->cbwork, priv->callback,
priv->cbarg, 0); priv->cbarg, 0);
} }
else else
{ {

View File

@ -756,7 +756,7 @@ static int pplus_uart_interrupt(int irq, void *context, FAR void *arg)
break; break;
case BUSY_IRQ: case BUSY_IRQ:
(void)priv->reg->USR; priv->reg->USR;
break; break;
default: default:
@ -1202,7 +1202,7 @@ static int h4uart_interrupt(int irq, void *context, FAR void *arg)
break; break;
case RLS_IRQ: case RLS_IRQ:
case BUSY_IRQ: case BUSY_IRQ:
(void)preg->USR; preg->USR;
break; break;
default: default:
break; break;

View File

@ -1051,19 +1051,19 @@ void arm_earlyserialinit(void)
void arm_serialinit(void) void arm_serialinit(void)
{ {
#ifdef CONSOLE_DEV #ifdef CONSOLE_DEV
(void)uart_register("/dev/console", &CONSOLE_DEV); uart_register("/dev/console", &CONSOLE_DEV);
#endif #endif
#ifdef TTYS0_DEV #ifdef TTYS0_DEV
(void)uart_register("/dev/ttyS0", &TTYS0_DEV); uart_register("/dev/ttyS0", &TTYS0_DEV);
#endif #endif
#ifdef TTYS1_DEV #ifdef TTYS1_DEV
(void)uart_register("/dev/ttyS1", &TTYS1_DEV); uart_register("/dev/ttyS1", &TTYS1_DEV);
#endif #endif
#ifdef TTYS2_DEV #ifdef TTYS2_DEV
(void)uart_register("/dev/ttyS2", &TTYS2_DEV); uart_register("/dev/ttyS2", &TTYS2_DEV);
#endif #endif
#ifdef TTYS3_DEV #ifdef TTYS3_DEV
(void)uart_register("/dev/ttyS3", &TTYS3_DEV); uart_register("/dev/ttyS3", &TTYS3_DEV);
#endif #endif
} }

View File

@ -286,8 +286,8 @@ void ameba_wdt_initialize(void)
/* Initialize the driver state structure. */ /* Initialize the driver state structure. */
priv->ops = &g_wdgops; priv->ops = &g_wdgops;
(void)watchdog_register(CONFIG_WATCHDOG_DEVPATH, watchdog_register(CONFIG_WATCHDOG_DEVPATH,
(FAR struct watchdog_lowerhalf_s *)priv); (FAR struct watchdog_lowerhalf_s *)priv);
} }
#endif /* CONFIG_WATCHDOG */ #endif /* CONFIG_WATCHDOG */

View File

@ -86,12 +86,10 @@ static void rtk_notify_info_to_wifi(uint8_t length, uint8_t *report_info)
} }
void bt_coex_handle_cmd_complete_evt(uint16_t opcode, uint16_t cause, void bt_coex_handle_cmd_complete_evt(uint16_t opcode, uint16_t cause,
uint8_t total_len, uint8_t *p) uint8_t total_len, uint8_t *p)
{ {
(void)cause;
if (opcode == HCI_VENDOR_MAILBOX_CMD) if (opcode == HCI_VENDOR_MAILBOX_CMD)
{ {
uint8_t status;
status = *p++; /* jump the double subcmd */ status = *p++; /* jump the double subcmd */
total_len--; total_len--;
@ -101,7 +99,6 @@ void bt_coex_handle_cmd_complete_evt(uint16_t opcode, uint16_t cause,
return ; return ;
} }
(void)status;
rltk_coex_mailbox_to_wifi(p, total_len); rltk_coex_mailbox_to_wifi(p, total_len);
/* rtk_parse_vendor_mailbox_cmd_evt(p, total_len, status); */ /* rtk_parse_vendor_mailbox_cmd_evt(p, total_len, status); */
@ -149,10 +146,10 @@ static void bt_coex_dump_buf(net_buf_simple *tmp_buf)
static int bt_coex_unpack_xiaomi_vendor_cmd(net_buf_simple *tmp_buf) static int bt_coex_unpack_xiaomi_vendor_cmd(net_buf_simple *tmp_buf)
{ {
if (tmp_buf-> data[0] == 0x25 && tmp_buf-> data[1] == 0x00) if (tmp_buf->data[0] == 0x25 && tmp_buf->data[1] == 0x00)
{ {
tmp_buf -> data += 2; tmp_buf->data += 2;
tmp_buf -> len -= 2; tmp_buf->len -= 2;
return 1; return 1;
} }

View File

@ -433,7 +433,7 @@ void sam_gpioirqenable(int irq)
{ {
/* Clear (all) pending interrupts and enable this pin interrupt */ /* Clear (all) pending interrupts and enable this pin interrupt */
/* (void)getreg32(base + SAM_PIO_ISR_OFFSET); */ /* getreg32(base + SAM_PIO_ISR_OFFSET); */
putreg32((1 << pin), base + SAM_PIO_IER_OFFSET); putreg32((1 << pin), base + SAM_PIO_IER_OFFSET);
} }

View File

@ -479,7 +479,7 @@ void sam_pioirqenable(int irq)
{ {
/* Clear (all) pending interrupts and enable this pin interrupt */ /* Clear (all) pending interrupts and enable this pin interrupt */
(void)getreg32(base + SAM_PIO_ISR_OFFSET); getreg32(base + SAM_PIO_ISR_OFFSET);
putreg32((1 << pin), base + SAM_PIO_IER_OFFSET); putreg32((1 << pin), base + SAM_PIO_IER_OFFSET);
} }
} }

View File

@ -1427,8 +1427,8 @@ static int sam_interrupt(int irq, void *context, FAR void *arg)
mcinfo("Queuing callback to %p(%p)\n", priv->callback, mcinfo("Queuing callback to %p(%p)\n", priv->callback,
priv->cbarg); priv->cbarg);
(void)work_queue(HPWORK, &priv->cbwork, priv->callback, work_queue(HPWORK, &priv->cbwork, priv->callback,
priv->cbarg, 0); priv->cbarg, 0);
} }
else else
{ {

View File

@ -221,7 +221,7 @@ int sam_oneshot_start(struct sam_oneshot_s *oneshot,
/* Yes.. then cancel it */ /* Yes.. then cancel it */
tmrinfo("Already running... cancelling\n"); tmrinfo("Already running... cancelling\n");
(void)sam_oneshot_cancel(oneshot, freerun, NULL); sam_oneshot_cancel(oneshot, freerun, NULL);
} }
/* Save the new handler and its argument */ /* Save the new handler and its argument */

View File

@ -541,7 +541,7 @@ ssize_t up_progmem_eraseblock(size_t cluster)
/* Erase all pages in the cluster */ /* Erase all pages in the cluster */
#ifdef USE_UNLOCK #ifdef USE_UNLOCK
(void)nvm_unlock(page, SAMD5E5_PAGE_PER_CLUSTER); nvm_unlock(page, SAMD5E5_PAGE_PER_CLUSTER);
#endif #endif
finfo("INFO: erase block=%d address=0x%x\n", finfo("INFO: erase block=%d address=0x%x\n",
@ -549,7 +549,7 @@ ssize_t up_progmem_eraseblock(size_t cluster)
ret = nvm_command(NVMCTRL_CTRLB_CMD_EB, SAMD5E5_PAGE2BYTE(page)); ret = nvm_command(NVMCTRL_CTRLB_CMD_EB, SAMD5E5_PAGE2BYTE(page));
#ifdef USE_LOCK #ifdef USE_LOCK
(void)nvm_lock(page, SAMD5E5_PAGE_PER_CLUSTER); nvm_lock(page, SAMD5E5_PAGE_PER_CLUSTER);
#endif #endif
if (ret < 0) if (ret < 0)
@ -698,7 +698,7 @@ ssize_t up_progmem_write(size_t address, const void *buffer, size_t buflen)
#ifdef USE_UNLOCK /* Make sure that the FLASH is unlocked */ #ifdef USE_UNLOCK /* Make sure that the FLASH is unlocked */
lock = page; lock = page;
locksize = SAMD5E5_BYTE2PAGE(buflen); locksize = SAMD5E5_BYTE2PAGE(buflen);
(void)nvm_unlock(lock, locksize); nvm_unlock(lock, locksize);
#endif #endif
flags = enter_critical_section(); flags = enter_critical_section();
@ -860,7 +860,7 @@ ssize_t up_progmem_write(size_t address, const void *buffer, size_t buflen)
} }
#ifdef USE_LOCK #ifdef USE_LOCK
(void)nvm_lock(lock, locksize); nvm_lock(lock, locksize);
#endif #endif
leave_critical_section(flags); leave_critical_section(flags);

View File

@ -657,7 +657,7 @@ TC_HANDLE sam_tc_allocate(int tc, int frequency)
/* Initialize the TC driver structure */ /* Initialize the TC driver structure */
priv->flags = 0; priv->flags = 0;
(void)nxsem_init(&priv->exclsem, 0, 1); nxsem_init(&priv->exclsem, 0, 1);
/* Enable clocking to the TC module in PCHCTRL */ /* Enable clocking to the TC module in PCHCTRL */

View File

@ -113,7 +113,7 @@ void up_timer_initialize(void)
/* Attach the timer interrupt vector */ /* Attach the timer interrupt vector */
(void)irq_attach(SAM_IRQ_SYSTICK, (xcpt_t)sam_timerisr, NULL); irq_attach(SAM_IRQ_SYSTICK, (xcpt_t)sam_timerisr, NULL);
/* Enable SysTick interrupts using the processor clock source. */ /* Enable SysTick interrupts using the processor clock source. */

View File

@ -457,7 +457,7 @@ void sam_wdt_initialize(FAR const char *devpath)
priv->started = false; priv->started = false;
sam_settimeout((FAR struct watchdog_lowerhalf_s *)priv, sam_settimeout((FAR struct watchdog_lowerhalf_s *)priv,
BOARD_SCLK_FREQUENCY / 2); BOARD_SCLK_FREQUENCY / 2);
(void)watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv); watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv);
} }
#endif /* CONFIG_WATCHDOG && CONFIG__WDT */ #endif /* CONFIG_WATCHDOG && CONFIG__WDT */

View File

@ -389,7 +389,7 @@ void sam_gpioirqenable(int irq)
{ {
/* Clear (all) pending interrupts and enable this pin interrupt */ /* Clear (all) pending interrupts and enable this pin interrupt */
/* (void)getreg32(base + SAM_PIO_ISR_OFFSET); */ /* getreg32(base + SAM_PIO_ISR_OFFSET); */
putreg32((1 << pin), base + SAM_PIO_IER_OFFSET); putreg32((1 << pin), base + SAM_PIO_IER_OFFSET);
} }

View File

@ -497,10 +497,11 @@ static inline void qspi_putreg(struct stm32h7_qspidev_s *priv,
#ifdef CONFIG_DEBUG_SPI_INFO #ifdef CONFIG_DEBUG_SPI_INFO
static void qspi_dumpregs(struct stm32h7_qspidev_s *priv, const char *msg) static void qspi_dumpregs(struct stm32h7_qspidev_s *priv, const char *msg)
{ {
uint32_t regval;
spiinfo("%s:\n", msg); spiinfo("%s:\n", msg);
#if 0 #if 0
uint32_t regval;
/* this extra verbose output may be helpful in some cases; you'll need /* this extra verbose output may be helpful in some cases; you'll need
* to make sure your syslog is large enough to accommodate extra output. * to make sure your syslog is large enough to accommodate extra output.
*/ */
@ -575,7 +576,6 @@ static void qspi_dumpregs(struct stm32h7_qspidev_s *priv, const char *msg)
spiinfo(" PIR:%08x LPTR:%08x\n", spiinfo(" PIR:%08x LPTR:%08x\n",
getreg32(priv->base + STM32_QUADSPI_PIR_OFFSET), /* Polling Interval Register */ getreg32(priv->base + STM32_QUADSPI_PIR_OFFSET), /* Polling Interval Register */
getreg32(priv->base + STM32_QUADSPI_LPTR_OFFSET)); /* Low-Power Timeout Register */ getreg32(priv->base + STM32_QUADSPI_LPTR_OFFSET)); /* Low-Power Timeout Register */
(void)regval;
#endif #endif
} }
#endif #endif

View File

@ -921,7 +921,7 @@ static int spi_lock(FAR struct spi_slave_ctrlr_s *ctrlr, bool lock)
} }
else else
{ {
(void)nxsem_post(&priv->exclsem); nxsem_post(&priv->exclsem);
ret = OK; ret = OK;
} }
@ -1156,8 +1156,8 @@ static void spi_bind(struct spi_slave_ctrlr_s *ctrlr,
/* Bind to NSS interrupt */ /* Bind to NSS interrupt */
(void)stm32_gpiosetevent(priv->nss_pin, false, true, false, stm32_gpiosetevent(priv->nss_pin, false, true, false,
spi_nssinterrupt, priv); spi_nssinterrupt, priv);
#ifdef CONFIG_PM #ifdef CONFIG_PM
/* Register to receive power management callbacks */ /* Register to receive power management callbacks */
@ -1196,15 +1196,15 @@ static int spi_nssinterrupt(int irq, void *context, void *arg)
{ {
/* Bind to NSS rising edge interrupt */ /* Bind to NSS rising edge interrupt */
(void)stm32_gpiosetevent(priv->nss_pin, true, false, false, stm32_gpiosetevent(priv->nss_pin, true, false, false,
spi_nssinterrupt, priv); spi_nssinterrupt, priv);
return OK; return OK;
} }
/* Disable NSS interrupt */ /* Disable NSS interrupt */
(void)stm32_gpiosetevent(priv->nss_pin, false, false, false, stm32_gpiosetevent(priv->nss_pin, false, false, false,
NULL, priv); NULL, priv);
/* Re-configure nss pin */ /* Re-configure nss pin */

View File

@ -141,7 +141,7 @@ static void stm32l5_dumpnvic(const char *msg, int irq)
#ifdef CONFIG_DEBUG_FEATURES #ifdef CONFIG_DEBUG_FEATURES
static int stm32l5_nmi(int irq, FAR void *context, FAR void *arg) static int stm32l5_nmi(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! NMI received\n"); _err("PANIC!!! NMI received\n");
PANIC(); PANIC();
return 0; return 0;
@ -149,7 +149,7 @@ static int stm32l5_nmi(int irq, FAR void *context, FAR void *arg)
static int stm32l5_busfault(int irq, FAR void *context, FAR void *arg) static int stm32l5_busfault(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Bus fault received: %08x\n", getreg32(NVIC_CFAULTS)); _err("PANIC!!! Bus fault received: %08x\n", getreg32(NVIC_CFAULTS));
PANIC(); PANIC();
return 0; return 0;
@ -157,7 +157,7 @@ static int stm32l5_busfault(int irq, FAR void *context, FAR void *arg)
static int stm32l5_usagefault(int irq, FAR void *context, FAR void *arg) static int stm32l5_usagefault(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Usage fault received: %08x\n", getreg32(NVIC_CFAULTS)); _err("PANIC!!! Usage fault received: %08x\n", getreg32(NVIC_CFAULTS));
PANIC(); PANIC();
return 0; return 0;
@ -165,7 +165,7 @@ static int stm32l5_usagefault(int irq, FAR void *context, FAR void *arg)
static int stm32l5_pendsv(int irq, FAR void *context, FAR void *arg) static int stm32l5_pendsv(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! PendSV received\n"); _err("PANIC!!! PendSV received\n");
PANIC(); PANIC();
return 0; return 0;
@ -173,7 +173,7 @@ static int stm32l5_pendsv(int irq, FAR void *context, FAR void *arg)
static int stm32l5_dbgmonitor(int irq, FAR void *context, FAR void *arg) static int stm32l5_dbgmonitor(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Debug Monitor received\n"); _err("PANIC!!! Debug Monitor received\n");
PANIC(); PANIC();
return 0; return 0;
@ -181,7 +181,7 @@ static int stm32l5_dbgmonitor(int irq, FAR void *context, FAR void *arg)
static int stm32l5_reserved(int irq, FAR void *context, FAR void *arg) static int stm32l5_reserved(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Reserved interrupt\n"); _err("PANIC!!! Reserved interrupt\n");
PANIC(); PANIC();
return 0; return 0;

View File

@ -181,6 +181,6 @@ void stm32l5_rcc_enablelse(void)
/* Disable backup domain access if it was disabled on entry */ /* Disable backup domain access if it was disabled on entry */
(void)stm32l5_pwr_enablebkp(writable); stm32l5_pwr_enablebkp(writable);
} }
} }

View File

@ -102,7 +102,7 @@ static inline void rcc_resetbkp(void)
* backup data registers and backup SRAM). * backup data registers and backup SRAM).
*/ */
(void)stm32l5_pwr_enablebkp(true); stm32l5_pwr_enablebkp(true);
/* We might be changing RTCSEL - to ensure such changes work, we must /* We might be changing RTCSEL - to ensure such changes work, we must
* reset the backup domain (having backed up the RTC_MAGIC token) * reset the backup domain (having backed up the RTC_MAGIC token)
@ -123,7 +123,7 @@ static inline void rcc_resetbkp(void)
putreg32(bkregs[i], STM32L5_RTC_BKR(i)); putreg32(bkregs[i], STM32L5_RTC_BKR(i));
} }
(void)stm32l5_pwr_enablebkp(false); stm32l5_pwr_enablebkp(false);
} }
} }
#else #else

View File

@ -1209,7 +1209,7 @@ static void stm32l5serial_setsuspend(struct uart_dev_s *dev, bool suspend)
#ifdef CONFIG_SERIAL_IFLOWCONTROL #ifdef CONFIG_SERIAL_IFLOWCONTROL
if (priv->iflow) if (priv->iflow)
{ {
(void)stm32l5serial_dmaiflowrestart(priv); stm32l5serial_dmaiflowrestart(priv);
} }
else else
#endif #endif
@ -2644,7 +2644,7 @@ static void stm32l5serial_dmarxint(FAR struct uart_dev_s *dev, bool enable)
{ {
/* Re-enable RX DMA. */ /* Re-enable RX DMA. */
(void)stm32l5serial_dmaiflowrestart(priv); stm32l5serial_dmaiflowrestart(priv);
} }
#endif #endif
} }
@ -2805,7 +2805,7 @@ static void stm32l5serial_dmarxcallback(DMA_HANDLE handle, uint8_t status,
{ {
/* Re-enable RX DMA. */ /* Re-enable RX DMA. */
(void)stm32l5serial_dmaiflowrestart(priv); stm32l5serial_dmaiflowrestart(priv);
} }
#endif #endif
} }
@ -3076,14 +3076,14 @@ void arm_serialinit(void)
/* Register the console */ /* Register the console */
#if CONSOLE_UART > 0 #if CONSOLE_UART > 0
(void)uart_register("/dev/console", &g_uart_devs[CONSOLE_UART - 1]->dev); uart_register("/dev/console", &g_uart_devs[CONSOLE_UART - 1]->dev);
#ifndef CONFIG_STM32L5_SERIAL_DISABLE_REORDERING #ifndef CONFIG_STM32L5_SERIAL_DISABLE_REORDERING
/* If not disabled, register the console UART to ttyS0 and exclude /* If not disabled, register the console UART to ttyS0 and exclude
* it from initializing it further down * it from initializing it further down
*/ */
(void)uart_register("/dev/ttyS0", &g_uart_devs[CONSOLE_UART - 1]->dev); uart_register("/dev/ttyS0", &g_uart_devs[CONSOLE_UART - 1]->dev);
minor = 1; minor = 1;
#endif #endif
@ -3119,7 +3119,7 @@ void arm_serialinit(void)
/* Register USARTs as devices in increasing order */ /* Register USARTs as devices in increasing order */
devname[9] = '0' + minor++; devname[9] = '0' + minor++;
(void)uart_register(devname, &g_uart_devs[i]->dev); uart_register(devname, &g_uart_devs[i]->dev);
} }
#endif /* HAVE UART */ #endif /* HAVE UART */
} }

View File

@ -689,7 +689,7 @@ static void spi_dmatxwait(FAR struct stm32l5_spidev_s *priv)
#ifdef CONFIG_STM32L5_SPI_DMA #ifdef CONFIG_STM32L5_SPI_DMA
static inline void spi_dmarxwakeup(FAR struct stm32l5_spidev_s *priv) static inline void spi_dmarxwakeup(FAR struct stm32l5_spidev_s *priv)
{ {
(void)nxsem_post(&priv->rxsem); nxsem_post(&priv->rxsem);
} }
#endif #endif
@ -704,7 +704,7 @@ static inline void spi_dmarxwakeup(FAR struct stm32l5_spidev_s *priv)
#ifdef CONFIG_STM32L5_SPI_DMA #ifdef CONFIG_STM32L5_SPI_DMA
static inline void spi_dmatxwakeup(FAR struct stm32l5_spidev_s *priv) static inline void spi_dmatxwakeup(FAR struct stm32l5_spidev_s *priv)
{ {
(void)nxsem_post(&priv->txsem); nxsem_post(&priv->txsem);
} }
#endif #endif
@ -953,7 +953,7 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock)
} }
else else
{ {
(void)nxsem_post(&priv->exclsem); nxsem_post(&priv->exclsem);
ret = OK; ret = OK;
} }

View File

@ -134,7 +134,7 @@ void up_timer_initialize(void)
/* Attach the timer interrupt vector */ /* Attach the timer interrupt vector */
(void)irq_attach(STM32L5_IRQ_SYSTICK, (xcpt_t)stm32l5_timerisr, NULL); irq_attach(STM32L5_IRQ_SYSTICK, (xcpt_t)stm32l5_timerisr, NULL);
/* Enable SysTick interrupts */ /* Enable SysTick interrupts */

View File

@ -141,7 +141,7 @@ static void stm32_dumpnvic(const char *msg, int irq)
#ifdef CONFIG_DEBUG_FEATURES #ifdef CONFIG_DEBUG_FEATURES
static int stm32_nmi(int irq, FAR void *context, FAR void *arg) static int stm32_nmi(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! NMI received\n"); _err("PANIC!!! NMI received\n");
PANIC(); PANIC();
return 0; return 0;
@ -149,7 +149,7 @@ static int stm32_nmi(int irq, FAR void *context, FAR void *arg)
static int stm32_busfault(int irq, FAR void *context, FAR void *arg) static int stm32_busfault(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Bus fault received: %08x\n", getreg32(NVIC_CFAULTS)); _err("PANIC!!! Bus fault received: %08x\n", getreg32(NVIC_CFAULTS));
PANIC(); PANIC();
return 0; return 0;
@ -157,7 +157,7 @@ static int stm32_busfault(int irq, FAR void *context, FAR void *arg)
static int stm32_usagefault(int irq, FAR void *context, FAR void *arg) static int stm32_usagefault(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Usage fault received: %08x\n", getreg32(NVIC_CFAULTS)); _err("PANIC!!! Usage fault received: %08x\n", getreg32(NVIC_CFAULTS));
PANIC(); PANIC();
return 0; return 0;
@ -165,7 +165,7 @@ static int stm32_usagefault(int irq, FAR void *context, FAR void *arg)
static int stm32_pendsv(int irq, FAR void *context, FAR void *arg) static int stm32_pendsv(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! PendSV received\n"); _err("PANIC!!! PendSV received\n");
PANIC(); PANIC();
return 0; return 0;
@ -173,7 +173,7 @@ static int stm32_pendsv(int irq, FAR void *context, FAR void *arg)
static int stm32_dbgmonitor(int irq, FAR void *context, FAR void *arg) static int stm32_dbgmonitor(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Debug Monitor received\n"); _err("PANIC!!! Debug Monitor received\n");
PANIC(); PANIC();
return 0; return 0;
@ -181,7 +181,7 @@ static int stm32_dbgmonitor(int irq, FAR void *context, FAR void *arg)
static int stm32_reserved(int irq, FAR void *context, FAR void *arg) static int stm32_reserved(int irq, FAR void *context, FAR void *arg)
{ {
(void)up_irq_save(); up_irq_save();
_err("PANIC!!! Reserved interrupt\n"); _err("PANIC!!! Reserved interrupt\n");
PANIC(); PANIC();
return 0; return 0;

View File

@ -181,6 +181,6 @@ void stm32_rcc_enablelse(void)
/* Disable backup domain access if it was disabled on entry */ /* Disable backup domain access if it was disabled on entry */
(void)stm32_pwr_enablebkp(writable); stm32_pwr_enablebkp(writable);
} }
} }

View File

@ -102,7 +102,7 @@ static inline void rcc_resetbkp(void)
* backup data registers and backup SRAM). * backup data registers and backup SRAM).
*/ */
(void)stm32_pwr_enablebkp(true); stm32_pwr_enablebkp(true);
/* We might be changing RTCSEL - to ensure such changes work, we must /* We might be changing RTCSEL - to ensure such changes work, we must
* reset the backup domain (having backed up the RTC_MAGIC token) * reset the backup domain (having backed up the RTC_MAGIC token)
@ -123,7 +123,7 @@ static inline void rcc_resetbkp(void)
putreg32(bkregs[i], STM32U5_RTC_BKR(i)); putreg32(bkregs[i], STM32U5_RTC_BKR(i));
} }
(void)stm32_pwr_enablebkp(false); stm32_pwr_enablebkp(false);
} }
} }
#else #else

View File

@ -1209,7 +1209,7 @@ static void stm32serial_setsuspend(struct uart_dev_s *dev, bool suspend)
#ifdef CONFIG_SERIAL_IFLOWCONTROL #ifdef CONFIG_SERIAL_IFLOWCONTROL
if (priv->iflow) if (priv->iflow)
{ {
(void)stm32serial_dmaiflowrestart(priv); stm32serial_dmaiflowrestart(priv);
} }
else else
#endif #endif
@ -2644,7 +2644,7 @@ static void stm32serial_dmarxint(FAR struct uart_dev_s *dev, bool enable)
{ {
/* Re-enable RX DMA. */ /* Re-enable RX DMA. */
(void)stm32serial_dmaiflowrestart(priv); stm32serial_dmaiflowrestart(priv);
} }
#endif #endif
} }
@ -2804,7 +2804,7 @@ static void stm32serial_dmarxcallback(DMA_HANDLE handle, uint8_t status,
{ {
/* Re-enable RX DMA. */ /* Re-enable RX DMA. */
(void)stm32serial_dmaiflowrestart(priv); stm32serial_dmaiflowrestart(priv);
} }
#endif #endif
} }
@ -3075,14 +3075,14 @@ void arm_serialinit(void)
/* Register the console */ /* Register the console */
#if CONSOLE_UART > 0 #if CONSOLE_UART > 0
(void)uart_register("/dev/console", &g_uart_devs[CONSOLE_UART - 1]->dev); uart_register("/dev/console", &g_uart_devs[CONSOLE_UART - 1]->dev);
#ifndef CONFIG_STM32U5_SERIAL_DISABLE_REORDERING #ifndef CONFIG_STM32U5_SERIAL_DISABLE_REORDERING
/* If not disabled, register the console UART to ttyS0 and exclude /* If not disabled, register the console UART to ttyS0 and exclude
* it from initializing it further down * it from initializing it further down
*/ */
(void)uart_register("/dev/ttyS0", &g_uart_devs[CONSOLE_UART - 1]->dev); uart_register("/dev/ttyS0", &g_uart_devs[CONSOLE_UART - 1]->dev);
minor = 1; minor = 1;
#endif #endif
@ -3118,7 +3118,7 @@ void arm_serialinit(void)
/* Register USARTs as devices in increasing order */ /* Register USARTs as devices in increasing order */
devname[9] = '0' + minor++; devname[9] = '0' + minor++;
(void)uart_register(devname, &g_uart_devs[i]->dev); uart_register(devname, &g_uart_devs[i]->dev);
} }
#endif /* HAVE UART */ #endif /* HAVE UART */
} }

View File

@ -134,7 +134,7 @@ void up_timer_initialize(void)
/* Attach the timer interrupt vector */ /* Attach the timer interrupt vector */
(void)irq_attach(STM32_IRQ_SYSTICK, (xcpt_t)stm32_timerisr, NULL); irq_attach(STM32_IRQ_SYSTICK, (xcpt_t)stm32_timerisr, NULL);
/* Enable SysTick interrupts */ /* Enable SysTick interrupts */

View File

@ -232,7 +232,7 @@ static int usart1_attach(struct uart_dev_s *dev)
irq_attach(AT90USB_IRQ_U1RX, usart1_rxinterrupt, NULL); irq_attach(AT90USB_IRQ_U1RX, usart1_rxinterrupt, NULL);
irq_attach(AT90USB_IRQ_U1DRE, usart1_txinterrupt, NULL); irq_attach(AT90USB_IRQ_U1DRE, usart1_txinterrupt, NULL);
/* (void)irq_attach(AT90USB_IRQ_U1TX, usart1_txinterrupt, NULL); */ /* irq_attach(AT90USB_IRQ_U1TX, usart1_txinterrupt, NULL); */
return OK; return OK;
} }
@ -258,7 +258,7 @@ static void usart1_detach(struct uart_dev_s *dev)
irq_detach(AT90USB_IRQ_U1RX); irq_detach(AT90USB_IRQ_U1RX);
irq_detach(AT90USB_IRQ_U1DRE); irq_detach(AT90USB_IRQ_U1DRE);
/* (void)irq_detach(AT90USB_IRQ_U1TX); */ /* irq_detach(AT90USB_IRQ_U1TX); */
} }
/**************************************************************************** /****************************************************************************

View File

@ -371,7 +371,7 @@ static int usart0_attach(struct uart_dev_s *dev)
irq_attach(ATMEGA_IRQ_U0RX, usart0_rxinterrupt, NULL); irq_attach(ATMEGA_IRQ_U0RX, usart0_rxinterrupt, NULL);
irq_attach(ATMEGA_IRQ_U0DRE, usart0_txinterrupt, NULL); irq_attach(ATMEGA_IRQ_U0DRE, usart0_txinterrupt, NULL);
/* (void)irq_attach(ATMEGA_IRQ_U0TX, usart0_txinterrupt, NULL); */ /* irq_attach(ATMEGA_IRQ_U0TX, usart0_txinterrupt, NULL); */
return OK; return OK;
} }
@ -395,7 +395,7 @@ static int usart1_attach(struct uart_dev_s *dev)
irq_attach(ATMEGA_IRQ_U1RX, usart1_rxinterrupt, NULL); irq_attach(ATMEGA_IRQ_U1RX, usart1_rxinterrupt, NULL);
irq_attach(ATMEGA_IRQ_U1DRE, usart1_txinterrupt, NULL); irq_attach(ATMEGA_IRQ_U1DRE, usart1_txinterrupt, NULL);
/* (void)irq_attach(ATMEGA_IRQ_U1TX, usart1_txinterrupt, NULL); */ /* irq_attach(ATMEGA_IRQ_U1TX, usart1_txinterrupt, NULL); */
return OK; return OK;
} }
@ -423,7 +423,7 @@ static void usart0_detach(struct uart_dev_s *dev)
irq_detach(ATMEGA_IRQ_U0RX); irq_detach(ATMEGA_IRQ_U0RX);
irq_detach(ATMEGA_IRQ_U0DRE); irq_detach(ATMEGA_IRQ_U0DRE);
/* (void)irq_detach(ATMEGA_IRQ_U0TX); */ /* irq_detach(ATMEGA_IRQ_U0TX); */
} }
#endif #endif
@ -439,7 +439,7 @@ static void usart1_detach(struct uart_dev_s *dev)
irq_detach(ATMEGA_IRQ_U1RX); irq_detach(ATMEGA_IRQ_U1RX);
irq_detach(ATMEGA_IRQ_U1DRE); irq_detach(ATMEGA_IRQ_U1DRE);
/* (void)irq_detach(ATMEGA_IRQ_U1TX); */ /* irq_detach(ATMEGA_IRQ_U1TX); */
} }
#endif #endif

View File

@ -163,7 +163,7 @@
*/ */
#define SYS_syscall_return (3) #define SYS_syscall_return (3)
#define up_syscall_return() (void)sys_call0(SYS_syscall_return) #define up_syscall_return() sys_call0(SYS_syscall_return)
#endif #endif
#endif /* __ASSEMBLY__ */ #endif /* __ASSEMBLY__ */

View File

@ -230,7 +230,7 @@ int up_swint0(int irq, void *context, void *arg)
*/ */
rtcb->flags &= ~TCB_FLAG_SYSCALL; rtcb->flags &= ~TCB_FLAG_SYSCALL;
(void)nxsig_unmask_pendingsignal(); nxsig_unmask_pendingsignal();
} }
break; break;
#endif #endif

View File

@ -90,7 +90,7 @@
*/ */
#define SYS_syscall_return (3) #define SYS_syscall_return (3)
#define up_syscall_return() (void)sys_call0(SYS_syscall_return) #define up_syscall_return() sys_call0(SYS_syscall_return)
#endif #endif

View File

@ -2008,7 +2008,7 @@ static void rx65n_riic_pre_end_set(FAR struct rx65n_i2c_priv_s *priv)
RIIC0.ICMR3.BIT.ACKBT = 1; RIIC0.ICMR3.BIT.ACKBT = 1;
RIIC0.ICMR3.BIT.ACKWP = 0; RIIC0.ICMR3.BIT.ACKWP = 0;
(void)rx65n_getreg(RX65N_RIIC0_ICMR3); rx65n_getreg(RX65N_RIIC0_ICMR3);
} }
else if (1 == priv->bus) else if (1 == priv->bus)
@ -2020,7 +2020,7 @@ static void rx65n_riic_pre_end_set(FAR struct rx65n_i2c_priv_s *priv)
RIIC1.ICMR3.BIT.ACKBT = 1; RIIC1.ICMR3.BIT.ACKBT = 1;
RIIC1.ICMR3.BIT.ACKWP = 0; RIIC1.ICMR3.BIT.ACKWP = 0;
(void)rx65n_getreg(RX65N_RIIC1_ICMR3); rx65n_getreg(RX65N_RIIC1_ICMR3);
} }
else else
@ -2032,7 +2032,7 @@ static void rx65n_riic_pre_end_set(FAR struct rx65n_i2c_priv_s *priv)
RIIC2.ICMR3.BIT.ACKBT = 1; RIIC2.ICMR3.BIT.ACKBT = 1;
RIIC2.ICMR3.BIT.ACKWP = 0; RIIC2.ICMR3.BIT.ACKWP = 0;
(void)rx65n_getreg(RX65N_RIIC2_ICMR3); rx65n_getreg(RX65N_RIIC2_ICMR3);
} }
} }

View File

@ -553,7 +553,7 @@ int rx65n_rtc_setdatetime(FAR const struct tm *tp)
* seconds) * seconds)
*/ */
/* (void)gmtime_r(&tp->tv_sec, &tp); */ /* gmtime_r(&tp->tv_sec, &tp); */
rtc_dumptime(&tp, "Setting time"); rtc_dumptime(&tp, "Setting time");
@ -706,7 +706,7 @@ int up_rtc_settime(FAR const struct timespec *tp)
* seconds) * seconds)
*/ */
(void)gmtime_r(&tp->tv_sec, &newtime); gmtime_r(&tp->tv_sec, &newtime);
rtc_dumptime(&newtime, "Setting time"); rtc_dumptime(&newtime, "Setting time");
/* Then write the broken out values to the RTC */ /* Then write the broken out values to the RTC */

View File

@ -467,7 +467,7 @@ static int rx65n_setrelative(FAR struct rtc_lowerhalf_s *lower,
/* And convert the time back to broken out format */ /* And convert the time back to broken out format */
(void)gmtime_r(&seconds, (FAR struct tm *)&setalarm.time); gmtime_r(&seconds, (FAR struct tm *)&setalarm.time);
/* The set the alarm using this absolute time */ /* The set the alarm using this absolute time */

View File

@ -278,7 +278,7 @@ static int rx65n_sbram_open(FAR struct file *filep)
static int rx65n_sbram_internal_close(FAR struct sbramfh_s *bbf) static int rx65n_sbram_internal_close(FAR struct sbramfh_s *bbf)
{ {
bbf->dirty = 0; bbf->dirty = 0;
(void)clock_gettime(CLOCK_REALTIME, &bbf->lastwrite); clock_gettime(CLOCK_REALTIME, &bbf->lastwrite);
bbf->crc = rx65n_sbram_crc(bbf); bbf->crc = rx65n_sbram_crc(bbf);
SBRAM_DUMP(bbf, "close done"); SBRAM_DUMP(bbf, "close done");

View File

@ -3925,7 +3925,7 @@ static uint16_t usb_cstd_is_set_frdy (uint16_t pipe, uint16_t fifosel,
buffer = hw_usb_read_syscfg(); buffer = hw_usb_read_syscfg();
buffer = hw_usb_read_syssts(); buffer = hw_usb_read_syssts();
(void)nxsig_usleep(1); nxsig_usleep(1);
} }
return (RX65N_USB_FIFO_ERROR); return (RX65N_USB_FIFO_ERROR);
@ -6322,7 +6322,7 @@ static void rx65n_usbhost_bottomhalf (void *arg)
else else
{ {
(void)nxsig_usleep(100); nxsig_usleep(100);
uwarn("WARNING: un known bottomhalf. Value is %d\n", uwarn("WARNING: un known bottomhalf. Value is %d\n",
bottom_half_processing); bottom_half_processing);
syslog (LOG_INFO, "WARNING: un known bottomhalf. Value is %d\n", syslog (LOG_INFO, "WARNING: un known bottomhalf. Value is %d\n",
@ -6480,13 +6480,13 @@ static int rx65n_usbhost_rh_enumerate(struct usbhost_connection_s *conn,
/* USB 2.0 spec says at least 50ms delay before port reset */ /* USB 2.0 spec says at least 50ms delay before port reset */
(void)nxsig_usleep(100 * 1000); nxsig_usleep(100 * 1000);
/* Put RH port 1 in reset. /* Put RH port 1 in reset.
* Currently supporting only single downstream port) * Currently supporting only single downstream port)
*/ */
(void)nxsig_usleep(200 * 1000); nxsig_usleep(200 * 1000);
return OK; return OK;
} }

View File

@ -888,9 +888,6 @@ void riscv_serialinit(void)
int up_putc(int ch) int up_putc(int ch)
{ {
#ifdef HAVE_SERIAL_CONSOLE #ifdef HAVE_SERIAL_CONSOLE
struct bl602_uart_s *priv = (struct bl602_uart_s *)CONSOLE_DEV.priv;
(void)priv;
irqstate_t flags = enter_critical_section(); irqstate_t flags = enter_critical_section();
/* Check for LF */ /* Check for LF */

View File

@ -120,7 +120,7 @@ void riscv_sigdeliver(void)
DEBUGASSERT(rtcb->irqcount == 0); DEBUGASSERT(rtcb->irqcount == 0);
while (rtcb->irqcount < saved_irqcount) while (rtcb->irqcount < saved_irqcount)
{ {
(void)enter_critical_section(); enter_critical_section();
} }
#endif #endif

View File

@ -297,7 +297,7 @@ int riscv_swint(int irq, void *context, void *arg)
*/ */
rtcb->flags &= ~TCB_FLAG_SYSCALL; rtcb->flags &= ~TCB_FLAG_SYSCALL;
(void)nxsig_unmask_pendingsignal(); nxsig_unmask_pendingsignal();
} }
break; break;
#endif #endif

View File

@ -214,7 +214,7 @@ void up_enable_irq(int irq)
/* Read INTPTEN back to make it sure */ /* Read INTPTEN back to make it sure */
(void)getreg32(RV32M1_EU_INTPTEN); getreg32(RV32M1_EU_INTPTEN);
} }
} }

View File

@ -67,7 +67,7 @@ allow_write(const void *start, const void *end)
* the OS version. * the OS version.
*/ */
(void)mprotect(p, sz, PROT_READ | PROT_WRITE); mprotect(p, sz, PROT_READ | PROT_WRITE);
} }
__attribute__((constructor)) __attribute__((constructor))

View File

@ -70,7 +70,7 @@
#define SYS_restore_context (1) #define SYS_restore_context (1)
#define up_fullcontextrestore(restoreregs) \ #define up_fullcontextrestore(restoreregs) \
(void)sys_call1(SYS_restore_context, (uintptr_t)restoreregs) sys_call1(SYS_restore_context, (uintptr_t)restoreregs)
/* SYS call 2: /* SYS call 2:
* *
@ -79,7 +79,7 @@
#define SYS_switch_context (2) #define SYS_switch_context (2)
#define up_switchcontext(saveregs, restoreregs) \ #define up_switchcontext(saveregs, restoreregs) \
(void)sys_call2(SYS_switch_context, (uintptr_t)saveregs, (uintptr_t)restoreregs) sys_call2(SYS_switch_context, (uintptr_t)saveregs, (uintptr_t)restoreregs)
#ifdef CONFIG_BUILD_KERNEL #ifdef CONFIG_BUILD_KERNEL
/* SYS call 3: /* SYS call 3:
@ -88,7 +88,7 @@
*/ */
#define SYS_syscall_return (3) #define SYS_syscall_return (3)
#define up_syscall_return() (void)sys_call0(SYS_syscall_return) #define up_syscall_return() sys_call0(SYS_syscall_return)
#endif #endif
#endif /* __ASSEMBLY__ */ #endif /* __ASSEMBLY__ */

View File

@ -855,14 +855,14 @@ void up_serialinit(void)
/* Register the console */ /* Register the console */
#ifdef HAVE_SERIAL_CONSOLE #ifdef HAVE_SERIAL_CONSOLE
(void)uart_register("/dev/console", &CONSOLE_DEV); uart_register("/dev/console", &CONSOLE_DEV);
#endif #endif
/* Register all UARTs */ /* Register all UARTs */
(void)uart_register("/dev/ttyS0", &TTYS0_DEV); uart_register("/dev/ttyS0", &TTYS0_DEV);
#ifdef TTYS1_DEV #ifdef TTYS1_DEV
(void)uart_register("/dev/ttyS1", &TTYS1_DEV); uart_register("/dev/ttyS1", &TTYS1_DEV);
#endif #endif
} }

View File

@ -123,12 +123,12 @@ void up_timer_initialize(void)
up_clrpend_irq(BM3803_IRQ_TIMER1); up_clrpend_irq(BM3803_IRQ_TIMER1);
#ifdef CONFIG_ARCH_IRQPRIO #ifdef CONFIG_ARCH_IRQPRIO
(void)up_prioritize_irq(BM3803_IRQ_TIMER1, CONFIG_BM3803_TIMER1PRIO); up_prioritize_irq(BM3803_IRQ_TIMER1, CONFIG_BM3803_TIMER1PRIO);
#endif #endif
/* Attach the timer interrupt vector */ /* Attach the timer interrupt vector */
(void)irq_attach(BM3803_IRQ_TIMER1, (xcpt_t)bm3803_timerisr, NULL); irq_attach(BM3803_IRQ_TIMER1, (xcpt_t)bm3803_timerisr, NULL);
/* And enable the timer interrupt */ /* And enable the timer interrupt */

View File

@ -217,7 +217,7 @@ int bm3803_oneshot_start(struct bm3803_oneshot_s *oneshot,
/* Yes.. then cancel it */ /* Yes.. then cancel it */
tmrinfo("Already running... cancelling\n"); tmrinfo("Already running... cancelling\n");
(void)bm3803_oneshot_cancel(oneshot, NULL); bm3803_oneshot_cancel(oneshot, NULL);
} }
/* Save the new handler and its argument */ /* Save the new handler and its argument */

View File

@ -427,7 +427,7 @@ void bm3803_wdginitialize(const char *devpath)
/* Register the watchdog driver as /dev/watchdog0 */ /* Register the watchdog driver as /dev/watchdog0 */
(void)watchdog_register(devpath, (struct watchdog_lowerhalf_s *)priv); watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv);
} }
#endif /* CONFIG_WATCHDOG && CONFIG_BM3803_WDG */ #endif /* CONFIG_WATCHDOG && CONFIG_BM3803_WDG */

View File

@ -847,14 +847,14 @@ void up_serialinit(void)
/* Register the console */ /* Register the console */
#ifdef HAVE_SERIAL_CONSOLE #ifdef HAVE_SERIAL_CONSOLE
(void)uart_register("/dev/console", &CONSOLE_DEV); uart_register("/dev/console", &CONSOLE_DEV);
#endif #endif
/* Register all UARTs */ /* Register all UARTs */
(void)uart_register("/dev/ttyS0", &TTYS0_DEV); uart_register("/dev/ttyS0", &TTYS0_DEV);
#ifdef TTYS1_DEV #ifdef TTYS1_DEV
(void)uart_register("/dev/ttyS1", &TTYS1_DEV); uart_register("/dev/ttyS1", &TTYS1_DEV);
#endif #endif
} }

View File

@ -124,12 +124,12 @@ void up_timer_initialize(void)
up_clrpend_irq(BM3823_IRQ_TIMER1); up_clrpend_irq(BM3823_IRQ_TIMER1);
#ifdef CONFIG_ARCH_IRQPRIO #ifdef CONFIG_ARCH_IRQPRIO
(void)up_prioritize_irq(BM3823_IRQ_TIMER1, CONFIG_BM3823_TIMER1PRIO); up_prioritize_irq(BM3823_IRQ_TIMER1, CONFIG_BM3823_TIMER1PRIO);
#endif #endif
/* Attach the timer interrupt vector */ /* Attach the timer interrupt vector */
(void)irq_attach(BM3823_IRQ_TIMER1, (xcpt_t)bm3823_timerisr, NULL); irq_attach(BM3823_IRQ_TIMER1, (xcpt_t)bm3823_timerisr, NULL);
/* And enable the timer interrupt */ /* And enable the timer interrupt */

View File

@ -67,13 +67,13 @@ static void _up_assert(int errorcode)
{ {
/* Flush any buffered SYSLOG data */ /* Flush any buffered SYSLOG data */
(void)syslog_flush(); syslog_flush();
/* Are we in an interrupt handler or the idle task? */ /* Are we in an interrupt handler or the idle task? */
if (g_current_regs || running_task()->flink == NULL) if (g_current_regs || running_task()->flink == NULL)
{ {
(void)up_irq_save(); up_irq_save();
for (; ; ) for (; ; )
{ {
#if CONFIG_BOARD_RESET_ON_ASSERT >= 1 #if CONFIG_BOARD_RESET_ON_ASSERT >= 1
@ -136,7 +136,7 @@ void up_assert(const char *filename, int lineno)
/* Flush any buffered SYSLOG data (prior to the assertion) */ /* Flush any buffered SYSLOG data (prior to the assertion) */
(void)syslog_flush(); syslog_flush();
#if CONFIG_TASK_NAME_SIZE > 0 #if CONFIG_TASK_NAME_SIZE > 0
_alert("Assertion failed at file:%s line: %d task: %s\n", _alert("Assertion failed at file:%s line: %d task: %s\n",
@ -150,7 +150,7 @@ void up_assert(const char *filename, int lineno)
/* Flush any buffered SYSLOG data (from the above) */ /* Flush any buffered SYSLOG data (from the above) */
(void)syslog_flush(); syslog_flush();
#ifdef CONFIG_BOARD_CRASHDUMP #ifdef CONFIG_BOARD_CRASHDUMP
board_crashdump(up_getsp(), running_task(), filename, lineno); board_crashdump(up_getsp(), running_task(), filename, lineno);
@ -159,7 +159,7 @@ void up_assert(const char *filename, int lineno)
#ifdef CONFIG_ARCH_USBDUMP #ifdef CONFIG_ARCH_USBDUMP
/* Dump USB trace data */ /* Dump USB trace data */
(void)usbtrace_enumerate(assert_tracecallback, NULL); usbtrace_enumerate(assert_tracecallback, NULL);
#endif #endif
_up_assert(EXIT_FAILURE); _up_assert(EXIT_FAILURE);

View File

@ -98,7 +98,7 @@ uint32_t *up_doirq(int irq, uint32_t *regs)
* thread at the head of the ready-to-run list. * thread at the head of the ready-to-run list.
*/ */
(void)group_addrenv(NULL); group_addrenv(NULL);
#endif #endif
} }
#endif #endif

View File

@ -91,7 +91,7 @@ void up_sigdeliver(void)
*/ */
sinfo("Resuming\n"); sinfo("Resuming\n");
(void)up_irq_save(); up_irq_save();
/* Modify the saved return state with the actual saved values in the /* Modify the saved return state with the actual saved values in the
* TCB. This depends on the fact that nested signal handling is * TCB. This depends on the fact that nested signal handling is

View File

@ -200,7 +200,7 @@ static void up_dumpstate(void)
#ifdef CONFIG_ARCH_USBDUMP #ifdef CONFIG_ARCH_USBDUMP
/* Dump USB trace data */ /* Dump USB trace data */
(void)usbtrace_enumerate(assert_tracecallback, NULL); usbtrace_enumerate(assert_tracecallback, NULL);
#endif #endif
} }
#else #else
@ -221,7 +221,7 @@ static void _up_assert(void)
if (g_current_regs || (running_task())->flink == NULL) if (g_current_regs || (running_task())->flink == NULL)
{ {
(void)up_irq_save(); up_irq_save();
for (; ; ) for (; ; )
{ {
#if CONFIG_BOARD_RESET_ON_ASSERT >= 1 #if CONFIG_BOARD_RESET_ON_ASSERT >= 1

View File

@ -147,7 +147,7 @@ void up_block_task(struct tcb_s *tcb, tstate_t task_state)
* thread at the head of the ready-to-run list. * thread at the head of the ready-to-run list.
*/ */
(void)group_addrenv(rtcb); group_addrenv(rtcb);
#endif #endif
/* Reset scheduler parameters */ /* Reset scheduler parameters */

View File

@ -116,7 +116,7 @@ void up_release_pending(void)
* thread at the head of the ready-to-run list. * thread at the head of the ready-to-run list.
*/ */
(void)group_addrenv(rtcb); group_addrenv(rtcb);
#endif #endif
/* Update scheduler parameters */ /* Update scheduler parameters */

View File

@ -170,7 +170,7 @@ void up_reprioritize_rtr(struct tcb_s *tcb, uint8_t priority)
* thread at the head of the ready-to-run list. * thread at the head of the ready-to-run list.
*/ */
(void)group_addrenv(rtcb); group_addrenv(rtcb);
#endif #endif
/* Update scheduler parameters */ /* Update scheduler parameters */

View File

@ -134,7 +134,7 @@ void up_unblock_task(struct tcb_s *tcb)
* thread at the head of the ready-to-run list. * thread at the head of the ready-to-run list.
*/ */
(void)group_addrenv(rtcb); group_addrenv(rtcb);
#endif #endif
/* Update scheduler parameters */ /* Update scheduler parameters */

View File

@ -99,7 +99,7 @@ static uint64_t *common_handler(int irq, uint64_t *regs)
* thread at the head of the ready-to-run list. * thread at the head of the ready-to-run list.
*/ */
(void)group_addrenv(NULL); group_addrenv(NULL);
#endif #endif
} }
#endif #endif

View File

@ -173,7 +173,7 @@ static ssize_t x86_rngread(struct file *filep, char *buffer, size_t buflen)
void devrandom_register(void) void devrandom_register(void)
{ {
x86_rng_initialize(); x86_rng_initialize();
(void)register_driver("/dev/random", &g_rngops, 0444, NULL); register_driver("/dev/random", &g_rngops, 0444, NULL);
} }
#endif #endif
@ -197,7 +197,7 @@ void devurandom_register(void)
#ifndef CONFIG_DEV_RANDOM #ifndef CONFIG_DEV_RANDOM
x86_rng_initialize(); x86_rng_initialize();
#endif #endif
(void)register_driver("/dev/urandom", &g_rngops, 0444, NULL); register_driver("/dev/urandom", &g_rngops, 0444, NULL);
} }
#endif #endif

View File

@ -129,9 +129,9 @@ void up_timer_initialize(void)
g_last_stop_time = g_start_tsc = rdtsc(); g_last_stop_time = g_start_tsc = rdtsc();
#ifndef CONFIG_SCHED_TICKLESS_ALARM #ifndef CONFIG_SCHED_TICKLESS_ALARM
(void)irq_attach(TMR_IRQ, (xcpt_t)up_timer_expire, NULL); irq_attach(TMR_IRQ, (xcpt_t)up_timer_expire, NULL);
#else #else
(void)irq_attach(TMR_IRQ, (xcpt_t)up_alarm_expire, NULL); irq_attach(TMR_IRQ, (xcpt_t)up_alarm_expire, NULL);
#endif #endif
return; return;

View File

@ -118,7 +118,7 @@ void up_timer_initialize(void)
unsigned long ecx; unsigned long ecx;
uint32_t vector = IRQ0; uint32_t vector = IRQ0;
(void)irq_attach(IRQ0, (xcpt_t)intel64_timerisr, NULL); irq_attach(IRQ0, (xcpt_t)intel64_timerisr, NULL);
#ifdef CONFIG_ARCH_INTEL64_HAVE_TSC_DEADLINE #ifdef CONFIG_ARCH_INTEL64_HAVE_TSC_DEADLINE
vector |= MSR_X2APIC_LVTT_TSC_DEADLINE; vector |= MSR_X2APIC_LVTT_TSC_DEADLINE;

View File

@ -100,7 +100,7 @@ void up_sigdeliver(void)
*/ */
sinfo("Resuming\n"); sinfo("Resuming\n");
(void)up_irq_save(); up_irq_save();
/* Modify the saved return state with the actual saved values in the /* Modify the saved return state with the actual saved values in the
* TCB. This depends on the fact that nested signal handling is * TCB. This depends on the fact that nested signal handling is

View File

@ -74,6 +74,6 @@ void board_late_initialize(void)
{ {
/* Perform board-specific initialization */ /* Perform board-specific initialization */
(void)nrf52_bringup(); nrf52_bringup();
} }
#endif #endif

View File

@ -80,6 +80,6 @@ void board_late_initialize(void)
{ {
/* Perform board-specific initialization */ /* Perform board-specific initialization */
(void)nrf52_bringup(); nrf52_bringup();
} }
#endif #endif

View File

@ -74,6 +74,6 @@ void board_late_initialize(void)
{ {
/* Perform board-specific initialization */ /* Perform board-specific initialization */
(void)nrf52_bringup(); nrf52_bringup();
} }
#endif #endif

View File

@ -94,6 +94,6 @@ void board_late_initialize(void)
{ {
/* Perform board initialization */ /* Perform board initialization */
(void)sam_bringup(); sam_bringup();
} }
#endif /* CONFIG_BOARD_LATE_INITIALIZE */ #endif /* CONFIG_BOARD_LATE_INITIALIZE */

View File

@ -81,6 +81,6 @@ void board_late_initialize(void)
{ {
/* Perform board initialization */ /* Perform board initialization */
(void)sam_bringup(); sam_bringup();
} }
#endif /* CONFIG_BOARD_LATE_INITIALIZE */ #endif /* CONFIG_BOARD_LATE_INITIALIZE */

View File

@ -201,7 +201,7 @@ static void sam_enable(FAR const struct automount_lower_s *lower,
if (state->handler) if (state->handler)
{ {
(void)state->handler(&config->lower, state->arg, true); state->handler(&config->lower, state->arg, true);
} }
state->pending = false; state->pending = false;
@ -320,7 +320,7 @@ void sam_automount_event(bool inserted)
{ {
/* No.. forward the event to the handler */ /* No.. forward the event to the handler */
(void)state->handler(&config->lower, state->arg, state->inserted); state->handler(&config->lower, state->arg, state->inserted);
} }
} }
} }

View File

@ -95,7 +95,7 @@ int sam_bringup(void)
#endif #endif
#if defined(CONFIG_SAMD5E5_WDT) && defined(CONFIG_WATCHDOG) #if defined(CONFIG_SAMD5E5_WDT) && defined(CONFIG_WATCHDOG)
(void)sam_wdt_initialize(CONFIG_WATCHDOG_DEVPATH); sam_wdt_initialize(CONFIG_WATCHDOG_DEVPATH);
#endif #endif
#ifdef CONFIG_SAMD5E5_SERCOM5_ISI2C #ifdef CONFIG_SAMD5E5_SERCOM5_ISI2C

View File

@ -287,7 +287,7 @@ int sam_gpio_initialize(void)
g_gpin[i].gpio.gp_pintype = GPIO_INPUT_PIN; g_gpin[i].gpio.gp_pintype = GPIO_INPUT_PIN;
g_gpin[i].gpio.gp_ops = &gpin_ops; g_gpin[i].gpio.gp_ops = &gpin_ops;
g_gpin[i].id = i; g_gpin[i].id = i;
(void)gpio_pin_register(&g_gpin[i].gpio, pincount); gpio_pin_register(&g_gpin[i].gpio, pincount);
/* Configure the pin that will be used as input */ /* Configure the pin that will be used as input */
@ -305,7 +305,7 @@ int sam_gpio_initialize(void)
g_gpout[i].gpio.gp_pintype = GPIO_OUTPUT_PIN; g_gpout[i].gpio.gp_pintype = GPIO_OUTPUT_PIN;
g_gpout[i].gpio.gp_ops = &gpout_ops; g_gpout[i].gpio.gp_ops = &gpout_ops;
g_gpout[i].id = i; g_gpout[i].id = i;
(void)gpio_pin_register(&g_gpout[i].gpio, pincount); gpio_pin_register(&g_gpout[i].gpio, pincount);
/* Configure the pin that will be used as output */ /* Configure the pin that will be used as output */
@ -322,7 +322,7 @@ int sam_gpio_initialize(void)
g_gpint[i].samgpio.gpio.gp_pintype = GPIO_INTERRUPT_PIN; g_gpint[i].samgpio.gpio.gp_pintype = GPIO_INTERRUPT_PIN;
g_gpint[i].samgpio.gpio.gp_ops = &gpint_ops; g_gpint[i].samgpio.gpio.gp_ops = &gpint_ops;
g_gpint[i].samgpio.id = i; g_gpint[i].samgpio.id = i;
(void)gpio_pin_register(&g_gpint[i].samgpio.gpio, pincount); gpio_pin_register(&g_gpint[i].samgpio.gpio, pincount);
/* Configure the pin that will be used as interrupt input */ /* Configure the pin that will be used as interrupt input */

View File

@ -185,7 +185,7 @@ static int led_pm_prepare(struct pm_callback_s *cb, int domain,
void board_autoled_initialize(void) void board_autoled_initialize(void)
{ {
(void)sam_portconfig(PORT_LED0); sam_portconfig(PORT_LED0);
} }
/**************************************************************************** /****************************************************************************

View File

@ -74,6 +74,6 @@ void board_late_initialize(void)
{ {
/* Perform board-specific initialization */ /* Perform board-specific initialization */
(void)sam_bringup(); sam_bringup();
} }
#endif #endif

View File

@ -190,7 +190,7 @@ static void sam_enable(FAR const struct automount_lower_s *lower,
if (state->handler) if (state->handler)
{ {
bool inserted = sam_cardinserted(config->hsmci); bool inserted = sam_cardinserted(config->hsmci);
(void)state->handler(&config->lower, state->arg, inserted); state->handler(&config->lower, state->arg, inserted);
} }
state->pending = false; state->pending = false;
@ -324,7 +324,7 @@ void sam_automount_event(int slotno, bool inserted)
{ {
/* No.. forward the event to the handler */ /* No.. forward the event to the handler */
(void)state->handler(&config->lower, state->arg, inserted); state->handler(&config->lower, state->arg, inserted);
} }
} }
} }

View File

@ -170,7 +170,7 @@ void up_vs1053initialize(FAR struct spi_dev_s * spi)
* until the RST line is asserted. * until the RST line is asserted.
*/ */
/* (void)stm32_configgpio(GPIO_VS1053_RST); */ /* stm32_configgpio(GPIO_VS1053_RST); */
/* Initialize the VS1053 DREQ GPIO line */ /* Initialize the VS1053 DREQ GPIO line */

View File

@ -88,8 +88,6 @@ int stm32_mmcsd_initialize(int minor);
#else #else
static inline int stm32_mmcsd_initialize(int minor) static inline int stm32_mmcsd_initialize(int minor)
{ {
(void)minor;
return 0; return 0;
} }
#endif #endif

View File

@ -277,7 +277,7 @@ int stm32_cs43l22_initialize(int minor)
/* Configure the CS43L22 interrupt pin */ /* Configure the CS43L22 interrupt pin */
/* TODO: (void)stm32_configgpio(PIO_INT_CS43L22); */ /* TODO: stm32_configgpio(PIO_INT_CS43L22); */
/* Get an instance of the I2C interface for the CS43L22 chip select */ /* Get an instance of the I2C interface for the CS43L22 chip select */

View File

@ -113,8 +113,8 @@ int stm32_sdio_initialize(void)
/* Register an interrupt handler for the card detect pin */ /* Register an interrupt handler for the card detect pin */
(void)stm32_gpiosetevent(GPIO_SDIO_NCD, true, true, true, stm32_gpiosetevent(GPIO_SDIO_NCD, true, true, true,
stm32_ncd_interrupt, NULL); stm32_ncd_interrupt, NULL);
#endif #endif
/* Mount the SDIO-based MMC/SD block driver */ /* Mount the SDIO-based MMC/SD block driver */

View File

@ -91,7 +91,7 @@ void board_late_initialize(void)
* board_app_initialize(). * board_app_initialize().
*/ */
(void)stm32_bringup(); stm32_bringup();
#endif #endif
} }
#endif #endif

View File

@ -76,6 +76,6 @@ void board_late_initialize(void)
{ {
/* Perform board-specific initialization here if so configured */ /* Perform board-specific initialization here if so configured */
(void)stm32_bringup(); stm32_bringup();
} }
#endif #endif

View File

@ -85,6 +85,6 @@ void board_late_initialize(void)
{ {
/* Perform board-specific initialization here if so configured */ /* Perform board-specific initialization here if so configured */
(void)stm32_bringup(); stm32_bringup();
} }
#endif #endif

View File

@ -76,6 +76,6 @@ void board_late_initialize(void)
{ {
/* Perform board-specific initialization here if so configured */ /* Perform board-specific initialization here if so configured */
(void)stm32_bringup(); stm32_bringup();
} }
#endif #endif

View File

@ -382,13 +382,13 @@ int rx65n_bringup(void)
#ifdef CONFIG_RX65N_SBRAM #ifdef CONFIG_RX65N_SBRAM
/* Initialize battery-backed RAM */ /* Initialize battery-backed RAM */
(void)rx65n_sbram_int(); rx65n_sbram_int();
#endif #endif
#ifdef HAVE_DTC_DRIVER #ifdef HAVE_DTC_DRIVER
/* Initialize DTC */ /* Initialize DTC */
(void)rx65n_dtc_initialize(); rx65n_dtc_initialize();
#endif #endif
#if defined(CONFIG_USBHOST) #if defined(CONFIG_USBHOST)
@ -396,7 +396,7 @@ int rx65n_bringup(void)
#endif #endif
#ifdef CONFIG_RX65N_RSPI #ifdef CONFIG_RX65N_RSPI
(void)rx65n_rspi_initialize(); rx65n_rspi_initialize();
#endif #endif
#if defined(CONFIG_CDCACM) && !defined(CONFIG_CDCACM_CONSOLE) #if defined(CONFIG_CDCACM) && !defined(CONFIG_CDCACM_CONSOLE)

View File

@ -242,7 +242,7 @@ static int hardfault_get_desc(struct sbramd_s *desc)
{ {
ret = file_ioctl(&filestruct, RX65N_SBRAM_GETDESC_IOCTL, ret = file_ioctl(&filestruct, RX65N_SBRAM_GETDESC_IOCTL,
(unsigned long)((uintptr_t)desc)); (unsigned long)((uintptr_t)desc));
(void)file_close(&filestruct); file_close(&filestruct);
if (ret < 0) if (ret < 0)
{ {
@ -340,7 +340,7 @@ void board_crashdump(uintptr_t currentsp, FAR void *tcb,
FAR struct tcb_s *rtcb; FAR struct tcb_s *rtcb;
int rv; int rv;
(void)enter_critical_section(); enter_critical_section();
rtcb = (FAR struct tcb_s *)tcb; rtcb = (FAR struct tcb_s *)tcb;

View File

@ -377,17 +377,17 @@ int rx65n_bringup(void)
#ifdef CONFIG_RX65N_SBRAM #ifdef CONFIG_RX65N_SBRAM
/* Initialize standby RAM */ /* Initialize standby RAM */
(void)rx65n_sbram_int(); rx65n_sbram_int();
#endif #endif
#ifdef HAVE_DTC_DRIVER #ifdef HAVE_DTC_DRIVER
/* Initialize DTC */ /* Initialize DTC */
(void)rx65n_dtc_initialize(); rx65n_dtc_initialize();
#endif #endif
#ifdef CONFIG_RX65N_RSPI #ifdef CONFIG_RX65N_RSPI
(void)rx65n_rspi_initialize(); rx65n_rspi_initialize();
#endif #endif
#if defined(CONFIG_USBHOST) #if defined(CONFIG_USBHOST)

View File

@ -240,7 +240,7 @@ static int hardfault_get_desc(struct sbramd_s *desc)
{ {
ret = file_ioctl(&filestruct, RX65N_SBRAM_GETDESC_IOCTL, ret = file_ioctl(&filestruct, RX65N_SBRAM_GETDESC_IOCTL,
(unsigned long)((uintptr_t)desc)); (unsigned long)((uintptr_t)desc));
(void)file_close(&filestruct); file_close(&filestruct);
if (ret < 0) if (ret < 0)
{ {
@ -338,7 +338,7 @@ void board_crashdump(uintptr_t currentsp, FAR void *tcb,
FAR struct tcb_s *rtcb; FAR struct tcb_s *rtcb;
int rv; int rv;
(void)enter_critical_section(); enter_critical_section();
rtcb = (FAR struct tcb_s *)tcb; rtcb = (FAR struct tcb_s *)tcb;

View File

@ -955,9 +955,9 @@ nxwm
/* Execute the startup script */ /* Execute the startup script */
#ifdef CONFIG_NSH_ROMFSETC #ifdef CONFIG_NSH_ROMFSETC
- (void)nsh_script(&pstate->cn_vtbl, "init", NSH_INITPATH); - nsh_script(&pstate->cn_vtbl, "init", NSH_INITPATH);
+// REMOVE ME +// REMOVE ME
+// (void)nsh_script(&pstate->cn_vtbl, "init", NSH_INITPATH); +// nsh_script(&pstate->cn_vtbl, "init", NSH_INITPATH);
#endif #endif
/* Then enter the command line parsing loop */ /* Then enter the command line parsing loop */

View File

@ -132,7 +132,7 @@ int xx3803_watchdog_initialize(void)
/* Close watchdog as it is not needed here anymore */ /* Close watchdog as it is not needed here anymore */
(void)file_close(&filestruct); file_close(&filestruct);
if (ret < 0) if (ret < 0)
{ {

View File

@ -3683,9 +3683,9 @@ static int cxd56_init_worker(FAR struct audio_lowerhalf_s *dev)
pthread_attr_init(&t_attr); pthread_attr_init(&t_attr);
sparam.sched_priority = sched_get_priority_max(SCHED_FIFO) - 3; sparam.sched_priority = sched_get_priority_max(SCHED_FIFO) - 3;
(void)pthread_attr_setschedparam(&t_attr, &sparam); pthread_attr_setschedparam(&t_attr, &sparam);
(void)pthread_attr_setstacksize(&t_attr, pthread_attr_setstacksize(&t_attr,
CONFIG_CXD56_AUDIO_WORKER_STACKSIZE); CONFIG_CXD56_AUDIO_WORKER_STACKSIZE);
ret = pthread_create(&priv->threadid, &t_attr, cxd56_workerthread, ret = pthread_create(&priv->threadid, &t_attr, cxd56_workerthread,
(pthread_addr_t)priv); (pthread_addr_t)priv);

View File

@ -462,9 +462,9 @@ int cxd56_src_init(FAR struct cxd56_dev_s *dev,
pthread_attr_init(&t_attr); pthread_attr_init(&t_attr);
sparam.sched_priority = sched_get_priority_max(SCHED_FIFO) - 3; sparam.sched_priority = sched_get_priority_max(SCHED_FIFO) - 3;
(void)pthread_attr_setschedparam(&t_attr, &sparam); pthread_attr_setschedparam(&t_attr, &sparam);
(void)pthread_attr_setstacksize(&t_attr, pthread_attr_setstacksize(&t_attr,
CONFIG_CXD56_AUDIO_SRC_STACKSIZE); CONFIG_CXD56_AUDIO_SRC_STACKSIZE);
ret = pthread_create(&g_src.threadid, &t_attr, cxd56_src_thread, ret = pthread_create(&g_src.threadid, &t_attr, cxd56_src_thread,
(pthread_addr_t)&g_src); (pthread_addr_t)&g_src);

View File

@ -796,8 +796,8 @@ static int wm8994_start(FAR struct audio_lowerhalf_s *dev)
pthread_attr_init(&tattr); pthread_attr_init(&tattr);
sparam.sched_priority = sched_get_priority_max(SCHED_FIFO) - 3; sparam.sched_priority = sched_get_priority_max(SCHED_FIFO) - 3;
(void)pthread_attr_setschedparam(&tattr, &sparam); pthread_attr_setschedparam(&tattr, &sparam);
(void)pthread_attr_setstacksize(&tattr, CONFIG_WM8994_WORKER_STACKSIZE); pthread_attr_setstacksize(&tattr, CONFIG_WM8994_WORKER_STACKSIZE);
audinfo("Starting worker thread\n"); audinfo("Starting worker thread\n");
ret = pthread_create(&priv->threadid, &tattr, wm8994_workerthread, ret = pthread_create(&priv->threadid, &tattr, wm8994_workerthread,
@ -837,9 +837,9 @@ static int wm8994_stop(FAR struct audio_lowerhalf_s *dev)
term_msg.msg_id = AUDIO_MSG_STOP; term_msg.msg_id = AUDIO_MSG_STOP;
term_msg.u.data = 0; term_msg.u.data = 0;
(void)file_mq_send(&priv->mq, (FAR const char *)&term_msg, file_mq_send(&priv->mq, (FAR const char *)&term_msg,
sizeof(term_msg), sizeof(term_msg),
CONFIG_WM8994_MSG_PRIO); CONFIG_WM8994_MSG_PRIO);
/* Join the worker thread */ /* Join the worker thread */

View File

@ -163,7 +163,7 @@ static int uart_takesem(FAR sem_t *sem, bool errout)
* Name: uart_givesem * Name: uart_givesem
****************************************************************************/ ****************************************************************************/
#define uart_givesem(sem) (void)nxsem_post(sem) #define uart_givesem(sem) nxsem_post(sem)
/**************************************************************************** /****************************************************************************
* Name: uart_pollnotify * Name: uart_pollnotify

Some files were not shown because too many files have changed in this diff Show More