Skip to content

Commit

Permalink
coccicnelle: Ignore return of memset
Browse files Browse the repository at this point in the history
The return of memset is never checked. This patch explicitly ignore
the return to avoid MISRA-C violations.

The only directory excluded directory was ext/* since it contains
only imported code.

Signed-off-by: Flavio Ceolin <flavio.ceolin@intel.com>
  • Loading branch information
ceolin authored and nashif committed Sep 14, 2018
1 parent 5884c7f commit da49f2e
Show file tree
Hide file tree
Showing 220 changed files with 577 additions and 550 deletions.
5 changes: 2 additions & 3 deletions arch/posix/core/posix_core.c
Original file line number Diff line number Diff line change
Expand Up @@ -347,9 +347,8 @@ static int ttable_get_empty_slot(void)
}

/* Clear new piece of table */
memset(&threads_table[threads_table_size],
0,
PC_ALLOC_CHUNK_SIZE * sizeof(struct threads_table_el));
(void)memset(&threads_table[threads_table_size], 0,
PC_ALLOC_CHUNK_SIZE * sizeof(struct threads_table_el));

threads_table_size += PC_ALLOC_CHUNK_SIZE;

Expand Down
3 changes: 2 additions & 1 deletion arch/xtensa/core/thread.c
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,8 @@ void _new_thread(struct k_thread *thread, k_thread_stack_t *stack,
#if XCHAL_CP_NUM > 0
/* Ensure CP state descriptor is correctly initialized */
cpStack = thread->arch.preempCoprocReg.cpStack; /* short hand alias */
memset(cpStack, 0, XT_CP_ASA); /* Set to zero to avoid bad surprises */
/* Set to zero to avoid bad surprises */
(void)memset(cpStack, 0, XT_CP_ASA);
/* Coprocessor's stack is allocated just after the k_thread */
cpSA = (u32_t *)(thread->arch.preempCoprocReg.cpStack + XT_CP_ASA);
/* Coprocessor's save area alignment is at leat 16 bytes */
Expand Down
2 changes: 1 addition & 1 deletion arch/xtensa/core/xtensa-asm2.c
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ void *xtensa_init_stack(int *stack_top,
const int bsasz = BASE_SAVE_AREA_SIZE - 16;
void **bsa = (void **) (((char *) stack_top) - bsasz);

memset(bsa, 0, bsasz);
(void)memset(bsa, 0, bsasz);

bsa[BSA_PC_OFF/4] = _thread_entry;
bsa[BSA_PS_OFF/4] = (void *)(PS_WOE | PS_UM | PS_CALLINC(1));
Expand Down
2 changes: 1 addition & 1 deletion drivers/adc/adc_ti_adc108s102.c
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ static int ti_adc108s102_read(struct device *dev,
s32_t delay;

/* Resetting all internal channel data */
memset(adc->chans, 0, ADC108S102_CHANNELS_SIZE);
(void)memset(adc->chans, 0, ADC108S102_CHANNELS_SIZE);

if (_verify_entries(seq_table) == 0) {
return -EINVAL;
Expand Down
2 changes: 1 addition & 1 deletion drivers/bluetooth/hci/h5.c
Original file line number Diff line number Diff line change
Expand Up @@ -286,7 +286,7 @@ static void h5_send(const u8_t *payload, u8_t type, int len)

hexdump("<= ", payload, len);

memset(hdr, 0, sizeof(hdr));
(void)memset(hdr, 0, sizeof(hdr));

/* Set ACK for outgoing packet and stop delayed work */
H5_SET_ACK(hdr, h5.tx_ack);
Expand Down
2 changes: 1 addition & 1 deletion drivers/bluetooth/hci/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ static void bt_spi_rx_thread(void)
u8_t size = 0;
int ret;

memset(&txmsg, 0xFF, SPI_MAX_MSG_LEN);
(void)memset(&txmsg, 0xFF, SPI_MAX_MSG_LEN);

while (true) {
k_sem_take(&sem_request, K_FOREVER);
Expand Down
2 changes: 1 addition & 1 deletion drivers/bluetooth/hci/userchan.c
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ static int user_chan_open(u16_t index)
return -errno;
}

memset(&addr, 0, sizeof(addr));
(void)memset(&addr, 0, sizeof(addr));
addr.hci_family = AF_BLUETOOTH;
addr.hci_dev = index;
addr.hci_channel = HCI_CHANNEL_USER;
Expand Down
9 changes: 5 additions & 4 deletions drivers/can/stm32_can.c
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,8 @@ static int can_stm32_init(struct device *dev)
data->mb2.tx_callback = NULL;

data->filter_usage = (1ULL << CAN_MAX_NUMBER_OF_FILTES) - 1ULL;
memset(data->rx_response, 0, sizeof(void *) * CONFIG_CAN_MAX_FILTER);
(void)memset(data->rx_response, 0,
sizeof(void *) * CONFIG_CAN_MAX_FILTER);
data->response_type = 0;

clock = device_get_binding(STM32_CLOCK_CONTROL_NAME);
Expand Down Expand Up @@ -418,7 +419,7 @@ static int can_stm32_shift_arr(void **arr, int start, int count)
cnt = (CONFIG_CAN_MAX_FILTER - start - count) * sizeof(void *);
move_dest = start_ptr + count;
memmove(move_dest, start_ptr, cnt);
memset(start_ptr, 0, count * sizeof(void *));
(void)memset(start_ptr, 0, count * sizeof(void *));
} else if (count < 0) {
count = -count;

Expand All @@ -428,8 +429,8 @@ static int can_stm32_shift_arr(void **arr, int start, int count)

cnt = (CONFIG_CAN_MAX_FILTER - start) * sizeof(void *);
memmove(start_ptr - count, start_ptr, cnt);
memset(arr + CONFIG_CAN_MAX_FILTER - count, 0,
count * sizeof(void *));
(void)memset(arr + CONFIG_CAN_MAX_FILTER - count, 0,
count * sizeof(void *));
}

return 0;
Expand Down
2 changes: 1 addition & 1 deletion drivers/crypto/crypto_ataes132a.c
Original file line number Diff line number Diff line change
Expand Up @@ -632,7 +632,7 @@ int ataes132a_aes_ecb_block(struct device *dev,
param_buffer[1] = key_id;
param_buffer[2] = 0x0;
memcpy(param_buffer + 3, pkt->in_buf, buf_len);
memset(param_buffer + 3 + buf_len, 0x0, 16 - buf_len);
(void)memset(param_buffer + 3 + buf_len, 0x0, 16 - buf_len);

return_code = ataes132a_send_command(dev, ATAES_LEGACY_OP, 0x00,
param_buffer, buf_len + 3,
Expand Down
2 changes: 1 addition & 1 deletion drivers/crypto/crypto_tc_shim.c
Original file line number Diff line number Diff line change
Expand Up @@ -294,7 +294,7 @@ static int tc_session_free(struct device *dev, struct cipher_ctx *sessn)
struct tc_shim_drv_state *data = sessn->drv_sessn_state;

ARG_UNUSED(dev);
memset(data, 0, sizeof(struct tc_shim_drv_state));
(void)memset(data, 0, sizeof(struct tc_shim_drv_state));
data->in_use = 0;

return 0;
Expand Down
3 changes: 2 additions & 1 deletion drivers/dma/dma_cavs.c
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,8 @@ static int dw_dma_config(struct device *dev, u32_t channel,
return -ENOMEM;
}

memset(chan_data->lli, 0, (sizeof(struct dw_lli2) * cfg->block_count));
(void)memset(chan_data->lli, 0,
(sizeof(struct dw_lli2) * cfg->block_count));
lli_desc = chan_data->lli;
lli_desc_tail = lli_desc + cfg->block_count - 1;

Expand Down
2 changes: 1 addition & 1 deletion drivers/dma/dma_sam_xdmac.c
Original file line number Diff line number Diff line change
Expand Up @@ -255,7 +255,7 @@ static int sam_xdmac_config(struct device *dev, u32_t channel,

dev_data->dma_channels[channel].callback = cfg->dma_callback;

memset(&transfer_cfg, 0, sizeof(transfer_cfg));
(void)memset(&transfer_cfg, 0, sizeof(transfer_cfg));
transfer_cfg.sa = cfg->head_block->source_address;
transfer_cfg.da = cfg->head_block->dest_address;
transfer_cfg.ublen = cfg->head_block->block_size >> data_size;
Expand Down
2 changes: 1 addition & 1 deletion drivers/ethernet/eth_mcux.c
Original file line number Diff line number Diff line change
Expand Up @@ -785,7 +785,7 @@ static int eth_0_init(struct device *dev)
#if defined(CONFIG_PTP_CLOCK_MCUX)
ts_tx_rd = 0;
ts_tx_wr = 0;
memset(ts_tx_pkt, 0, sizeof(ts_tx_pkt));
(void)memset(ts_tx_pkt, 0, sizeof(ts_tx_pkt));
#endif

k_sem_init(&context->tx_buf_sem,
Expand Down
2 changes: 1 addition & 1 deletion drivers/ethernet/eth_native_posix_adapt.c
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ int eth_iface_create(const char *if_name, bool tun_only)
return -errno;
}

memset(&ifr, 0, sizeof(ifr));
(void)memset(&ifr, 0, sizeof(ifr));

#ifdef __linux
ifr.ifr_flags = (tun_only ? IFF_TUN : IFF_TAP) | IFF_NO_PI;
Expand Down
2 changes: 1 addition & 1 deletion drivers/i2s/i2s_cavs.c
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,7 @@ static int i2s_cavs_configure(struct device *dev, enum i2s_dir dir,

if (i2s_cfg->frame_clk_freq == 0) {
strm->queue_drop(strm);
memset(&strm->cfg, 0, sizeof(struct i2s_config));
(void)memset(&strm->cfg, 0, sizeof(struct i2s_config));
strm->state = I2S_STATE_NOT_READY;
return 0;
}
Expand Down
4 changes: 2 additions & 2 deletions drivers/i2s/i2s_sam_ssc.c
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ static int start_dma(struct device *dev_dma, u32_t channel,
struct dma_block_config blk_cfg;
int ret;

memset(&blk_cfg, 0, sizeof(blk_cfg));
(void)memset(&blk_cfg, 0, sizeof(blk_cfg));
blk_cfg.block_size = blk_size;
blk_cfg.source_address = (u32_t)src;
blk_cfg.dest_address = (u32_t)dst;
Expand Down Expand Up @@ -557,7 +557,7 @@ static int i2s_sam_configure(struct device *dev, enum i2s_dir dir,

if (i2s_cfg->frame_clk_freq == 0) {
stream->queue_drop(stream);
memset(&stream->cfg, 0, sizeof(struct i2s_config));
(void)memset(&stream->cfg, 0, sizeof(struct i2s_config));
stream->state = I2S_STATE_NOT_READY;
return 0;
}
Expand Down
2 changes: 1 addition & 1 deletion drivers/ieee802154/ieee802154_uart_pipe.c
Original file line number Diff line number Diff line change
Expand Up @@ -320,7 +320,7 @@ static int upipe_init(struct device *dev)
{
struct upipe_context *upipe = dev->driver_data;

memset(upipe, 0, sizeof(struct upipe_context));
(void)memset(upipe, 0, sizeof(struct upipe_context));

uart_pipe_register(upipe->uart_pipe_buf, 1, upipe_rx);

Expand Down
2 changes: 1 addition & 1 deletion drivers/interrupt_controller/ioapic_intr.c
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ int ioapic_suspend(struct device *port)
u32_t rte_lo;

ARG_UNUSED(port);
memset(ioapic_suspend_buf, 0, (SUSPEND_BITS_REQD >> 3));
(void)memset(ioapic_suspend_buf, 0, (SUSPEND_BITS_REQD >> 3));
for (irq = 0; irq < CONFIG_IOAPIC_NUM_RTES; irq++) {
/*
* The following check is to figure out the registered
Expand Down
2 changes: 1 addition & 1 deletion drivers/interrupt_controller/loapic_intr.c
Original file line number Diff line number Diff line change
Expand Up @@ -432,7 +432,7 @@ static int loapic_suspend(struct device *port)

ARG_UNUSED(port);

memset(loapic_suspend_buf, 0, (LOPIC_SUSPEND_BITS_REQD >> 3));
(void)memset(loapic_suspend_buf, 0, (LOPIC_SUSPEND_BITS_REQD >> 3));

for (loapic_irq = 0; loapic_irq < LOAPIC_IRQ_COUNT; loapic_irq++) {

Expand Down
2 changes: 1 addition & 1 deletion drivers/led_strip/lpd880x.c
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ static int lpd880x_update(struct device *dev, void *data, size_t size)
};
size_t rc;

memset(reset_buf, 0x00, reset_size);
(void)memset(reset_buf, 0x00, reset_size);

rc = spi_write(drv_data->spi, &drv_data->config, &tx);
if (rc) {
Expand Down
2 changes: 1 addition & 1 deletion drivers/led_strip/ws2812.c
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ static int ws2812_reset_strip(struct ws2812_data *data)
.count = 1
};

memset(reset_buf, 0x00, sizeof(reset_buf));
(void)memset(reset_buf, 0x00, sizeof(reset_buf));

return spi_write(data->spi, &data->config, &tx);
}
Expand Down
14 changes: 7 additions & 7 deletions drivers/modem/wncm14a2a.c
Original file line number Diff line number Diff line change
Expand Up @@ -304,8 +304,8 @@ static void socket_put(struct wncm14a2a_socket *sock)

sock->context = NULL;
sock->socket_id = 0;
memset(&sock->src, 0, sizeof(struct sockaddr));
memset(&sock->dst, 0, sizeof(struct sockaddr));
(void)memset(&sock->src, 0, sizeof(struct sockaddr));
(void)memset(&sock->dst, 0, sizeof(struct sockaddr));
}

char *wncm14a2a_sprint_ip_addr(const struct sockaddr *addr)
Expand Down Expand Up @@ -512,7 +512,7 @@ static int net_pkt_setup_ip_data(struct net_pkt *pkt,

net_buf_add(pkt->frags, NET_UDPH_LEN);
udp = net_udp_get_hdr(pkt, &hdr);
memset(udp, 0, NET_UDPH_LEN);
(void)memset(udp, 0, NET_UDPH_LEN);

/* Setup UDP header */
udp->src_port = src_port;
Expand All @@ -527,7 +527,7 @@ static int net_pkt_setup_ip_data(struct net_pkt *pkt,

net_buf_add(pkt->frags, NET_TCPH_LEN);
tcp = net_tcp_get_hdr(pkt, &hdr);
memset(tcp, 0, NET_TCPH_LEN);
(void)memset(tcp, 0, NET_TCPH_LEN);

/* Setup TCP header */
tcp->src_port = src_port;
Expand Down Expand Up @@ -621,7 +621,7 @@ static void on_cmd_atcmdinfo_rssi(struct net_buf **buf, u16_t len)
char value[64];

value_size = sizeof(value);
memset(value, 0, value_size);
(void)memset(value, 0, value_size);
while (*buf && len > 0 && i < value_size) {
value[i] = net_buf_pull_u8(*buf);
if (!(*buf)->len) {
Expand Down Expand Up @@ -777,7 +777,7 @@ static void on_cmd_sockread(struct net_buf **buf, u16_t len)
/* first comma marks the end of actual_length */
i = 0;
value_size = sizeof(value);
memset(value, 0, value_size);
(void)memset(value, 0, value_size);
while (*buf && i < value_size) {
value[i++] = net_buf_pull_u8(*buf);
len--;
Expand Down Expand Up @@ -1444,7 +1444,7 @@ static int wncm14a2a_init(struct device *dev)
__ASSERT(sizeof(pinconfig) == MAX_MDM_CONTROL_PINS,
"Incorrect modem pinconfig!");

memset(&ictx, 0, sizeof(ictx));
(void)memset(&ictx, 0, sizeof(ictx));
for (i = 0; i < MDM_MAX_SOCKETS; i++) {
k_work_init(&ictx.sockets[i].recv_cb_work,
sockreadrecv_cb_work);
Expand Down
2 changes: 1 addition & 1 deletion drivers/pci/pci_interface.c
Original file line number Diff line number Diff line change
Expand Up @@ -385,7 +385,7 @@ void pci_header_get(u32_t controller,

/* clear out the header */

memset(pci_dev_header, 0, sizeof(*pci_dev_header));
(void)memset(pci_dev_header, 0, sizeof(*pci_dev_header));

/* fill in the PCI header from the device */

Expand Down
2 changes: 1 addition & 1 deletion drivers/sensor/dht/dht.c
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ static int dht_sample_fetch(struct device *dev, enum sensor_channel chan)

/* store bits in buf */
j = 0;
memset(buf, 0, sizeof(buf));
(void)memset(buf, 0, sizeof(buf));
for (i = 0; i < DHT_DATA_BITS_NUM; i++) {
if (signal_duration[i] >= avg_duration) {
buf[j] = (buf[j] << 1) | 1;
Expand Down
2 changes: 1 addition & 1 deletion drivers/sensor/lis2dh/lis2dh.c
Original file line number Diff line number Diff line change
Expand Up @@ -324,7 +324,7 @@ int lis2dh_init(struct device *dev)
* pin. Register values are retained if power is not removed.
* Default values see LIS2DH documentation page 30, chapter 6.
*/
memset(raw, 0, sizeof(raw));
(void)memset(raw, 0, sizeof(raw));
raw[LIS2DH_DATA_OFS] = LIS2DH_ACCEL_EN_BITS;

status = lis2dh_burst_write(dev, LIS2DH_REG_CTRL1, raw,
Expand Down
2 changes: 1 addition & 1 deletion drivers/sensor/lis2dh/lis2dh_trigger.c
Original file line number Diff line number Diff line change
Expand Up @@ -406,7 +406,7 @@ int lis2dh_init_interrupt(struct device *dev)
return status;
}

memset(raw, 0, sizeof(raw));
(void)memset(raw, 0, sizeof(raw));
status = lis2dh_burst_write(dev, LIS2DH_REG_INT2_THS, raw, sizeof(raw));
if (status < 0) {
SYS_LOG_ERR("Burst write to INT2 THS failed (%d)", status);
Expand Down
2 changes: 1 addition & 1 deletion drivers/sensor/vl53l0x/vl53l0x.c
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ static int vl53l0x_init(struct device *dev)
drv_data->vl53l0x.I2cDevAddr = CONFIG_VL53L0X_I2C_ADDR;

/* Get info from sensor */
memset(&vl53l0x_dev_info, 0, sizeof(VL53L0X_DeviceInfo_t));
(void)memset(&vl53l0x_dev_info, 0, sizeof(VL53L0X_DeviceInfo_t));

ret = VL53L0X_GetDeviceInfo(&drv_data->vl53l0x, &vl53l0x_dev_info);
if (ret < 0) {
Expand Down
2 changes: 1 addition & 1 deletion drivers/usb/device/usb_dc_dw.c
Original file line number Diff line number Diff line change
Expand Up @@ -801,7 +801,7 @@ int usb_dc_reset(void)
ret = usb_dw_reset();

/* Clear private data */
memset(&usb_dw_ctrl, 0, sizeof(usb_dw_ctrl));
(void)memset(&usb_dw_ctrl, 0, sizeof(usb_dw_ctrl));

return ret;
}
Expand Down
8 changes: 4 additions & 4 deletions drivers/usb/device/usb_dc_kinetis.c
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ int usb_dc_reset(void)
for (u8_t i = 0; i < 16; i++) {
USB0->ENDPOINT[i].ENDPT = 0;
}
memset(bdt, 0, sizeof(bdt));
(void)memset(bdt, 0, sizeof(bdt));
dev_data.bd_active = 0;
dev_data.address = 0;

Expand Down Expand Up @@ -333,11 +333,11 @@ int usb_dc_ep_configure(const struct usb_dc_ep_cfg_data * const cfg)
}

USB0->ENDPOINT[ep_idx].ENDPT = 0;
memset(&bdt[idx_even], 0, sizeof(struct buf_descriptor));
memset(&bdt[idx_odd], 0, sizeof(struct buf_descriptor));
(void)memset(&bdt[idx_even], 0, sizeof(struct buf_descriptor));
(void)memset(&bdt[idx_odd], 0, sizeof(struct buf_descriptor));

if (k_mem_pool_alloc(&ep_buf_pool, block, cfg->ep_mps * 2, 10) == 0) {
memset(block->data, 0, cfg->ep_mps * 2);
(void)memset(block->data, 0, cfg->ep_mps * 2);
} else {
SYS_LOG_ERR("Memory allocation time-out");
return -ENOMEM;
Expand Down
8 changes: 4 additions & 4 deletions drivers/usb/device/usb_dc_nrf5.c
Original file line number Diff line number Diff line change
Expand Up @@ -1671,28 +1671,28 @@ static void endpoint_ctx_deinit(void)
ep_ctx = in_endpoint_ctx(i);
__ASSERT_NO_MSG(ep_ctx);
k_mem_pool_free(&ep_ctx->buf.block);
memset(ep_ctx, 0, sizeof(*ep_ctx));
(void)memset(ep_ctx, 0, sizeof(*ep_ctx));
}

for (i = 0; i < CFG_EPOUT_CNT; i++) {
ep_ctx = out_endpoint_ctx(i);
__ASSERT_NO_MSG(ep_ctx);
k_mem_pool_free(&ep_ctx->buf.block);
memset(ep_ctx, 0, sizeof(*ep_ctx));
(void)memset(ep_ctx, 0, sizeof(*ep_ctx));
}

if (CFG_EP_ISOIN_CNT) {
ep_ctx = in_endpoint_ctx(NRF_USBD_EPIN(8));
__ASSERT_NO_MSG(ep_ctx);
k_mem_pool_free(&ep_ctx->buf.block);
memset(ep_ctx, 0, sizeof(*ep_ctx));
(void)memset(ep_ctx, 0, sizeof(*ep_ctx));
}

if (CFG_EP_ISOOUT_CNT) {
ep_ctx = out_endpoint_ctx(NRF_USBD_EPOUT(8));
__ASSERT_NO_MSG(ep_ctx);
k_mem_pool_free(&ep_ctx->buf.block);
memset(ep_ctx, 0, sizeof(*ep_ctx));
(void)memset(ep_ctx, 0, sizeof(*ep_ctx));
}
}

Expand Down
2 changes: 1 addition & 1 deletion drivers/usb/device/usb_dc_sam0.c
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ int usb_dc_attach(void)
regs->CTRLA.reg = USB_CTRLA_MODE_DEVICE | USB_CTRLA_RUNSTDBY;
regs->CTRLB.reg = USB_DEVICE_CTRLB_SPDCONF_HS;

memset(data->descriptors, 0, sizeof(data->descriptors));
(void)memset(data->descriptors, 0, sizeof(data->descriptors));
regs->DESCADD.reg = (uintptr_t)&data->descriptors[0];

regs->INTENSET.reg = USB_DEVICE_INTENSET_EORST;
Expand Down
Loading

0 comments on commit da49f2e

Please sign in to comment.