Skip to content

Commit

Permalink
Add printflike and scanflike to all printf/scanf like functions
Browse files Browse the repository at this point in the history
Signed-off-by: Xiang Xiao <[email protected]>
  • Loading branch information
xiaoxiang781216 authored and pkarashchenko committed Jul 18, 2022
1 parent 2721e01 commit 2166c98
Show file tree
Hide file tree
Showing 15 changed files with 39 additions and 33 deletions.
9 changes: 5 additions & 4 deletions arch/arm/src/phy62xx/log.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@ extern "C"
****************************************************************************/

#include "uart.h"
void dbg_printf_(const char *format, ...);
void dbg_printf_(const char *format, ...) printflike(1, 2);
void dbg_printf_init(void);
void my_dump_byte(uint8_t *pData, int dlen);
void my_dump_byte(uint8_t *pdata, int dlen);
#ifndef DEBUG_INFO
#error "DEBUG_INFO undefined!"
#endif
Expand Down Expand Up @@ -125,8 +125,9 @@ extern volatile uint32_t s_rom_debug_level;

typedef void(*std_putc)(char *data, int size);

void log_vsprintf(std_putc putc, const char *fmt, va_list args);
void log_printf(const char *format, ...);
void log_vsprintf(std_putc putc, const char *fmt, va_list args)
printflike(2, 0);
void log_printf(const char *format, ...) printflike(1, 2);
void log_set_putc(std_putc putc);
void log_clr_putc(std_putc putc);
int log_debug_level(uint8_t level);
Expand Down
4 changes: 2 additions & 2 deletions arch/risc-v/src/bl602/bl602_os_hal.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ extern "C"
* Public Function Prototypes
****************************************************************************/

void bl_os_printf(const char *__fmt, ...);
void bl_os_printf(const char *__fmt, ...) printflike(1, 2);

void bl_os_assert_func(const char *file,
int line,
Expand Down Expand Up @@ -175,7 +175,7 @@ void bl_os_log_write(uint32_t level,
const char *file,
int line,
const char *format,
...);
...) printflike(5, 6);

#undef EXTERN
#if defined(__cplusplus)
Expand Down
2 changes: 1 addition & 1 deletion arch/risc-v/src/esp32c3/esp32c3_start.c
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ extern uint32_t _image_drom_size;
****************************************************************************/

#ifdef CONFIG_ESP32C3_APP_FORMAT_MCUBOOT
extern int ets_printf(const char *fmt, ...);
extern int ets_printf(const char *fmt, ...) printflike(1, 2);
extern uint32_t cache_suspend_icache(void);
extern void cache_resume_icache(uint32_t val);
extern void cache_invalidate_icache_all(void);
Expand Down
6 changes: 4 additions & 2 deletions arch/risc-v/src/esp32c3/esp32c3_wifi_adapter.c
Original file line number Diff line number Diff line change
Expand Up @@ -344,7 +344,8 @@ static int esp_get_random(uint8_t *buf, size_t len);
static int esp_get_time(void *t);
static uint32_t esp_clk_slowclk_cal_get_wrapper(void);
static void esp_log_writev(uint32_t level, const char *tag,
const char *format, va_list args);
const char *format, va_list args)
printflike(3, 0);
static void *esp_malloc_internal(size_t size);
static void *esp_realloc_internal(void *ptr, size_t size);
static void *esp_calloc_internal(size_t n, size_t size);
Expand Down Expand Up @@ -398,7 +399,8 @@ void ets_timer_arm_us(void *timer, uint32_t us, bool repeat);

int64_t esp_timer_get_time(void);
void esp_fill_random(void *buf, size_t len);
void esp_log_write(uint32_t level, const char *tag, const char *format, ...);
void esp_log_write(uint32_t level, const char *tag, const char *format, ...)
printflike(3, 4);
uint32_t esp_log_timestamp(void);
uint8_t esp_crc8(const uint8_t *p, uint32_t len);

Expand Down
2 changes: 1 addition & 1 deletion arch/xtensa/src/esp32/esp32_start.c
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ extern uint32_t _image_drom_size;
****************************************************************************/

#ifdef CONFIG_ESP32_APP_FORMAT_MCUBOOT
extern int ets_printf(const char *fmt, ...);
extern int ets_printf(const char *fmt, ...) printflike(1, 2);
extern void cache_read_enable(int cpu);
extern void cache_read_disable(int cpu);
extern void cache_flush(int cpu);
Expand Down
6 changes: 4 additions & 2 deletions arch/xtensa/src/esp32/esp32_wifi_adapter.c
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,8 @@ static int32_t esp_nvs_erase_key(uint32_t handle, const char *key);
static int32_t esp_get_random(uint8_t *buf, size_t len);
static int32_t esp_get_time(void *t);
static void esp_log_writev(uint32_t level, const char *tag,
const char *format, va_list args);
const char *format, va_list args)
printflike(3, 0);
static void *esp_malloc_internal(size_t size);
static void *esp_realloc_internal(void *ptr, size_t size);
static void *esp_calloc_internal(size_t n, size_t size);
Expand Down Expand Up @@ -366,7 +367,8 @@ extern void coex_bt_high_prio(void);

int64_t esp_timer_get_time(void);
void esp_fill_random(void *buf, size_t len);
void esp_log_write(uint32_t level, const char *tag, const char *format, ...);
void esp_log_write(uint32_t level, const char *tag, const char *format, ...)
printflike(3, 4);
uint32_t esp_log_timestamp(void);
uint8_t esp_crc8(const uint8_t *p, uint32_t len);
void intr_matrix_set(int cpu_no, uint32_t model_num, uint32_t intr_num);
Expand Down
2 changes: 1 addition & 1 deletion arch/xtensa/src/esp32s2/esp32s2_start.c
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ typedef enum
****************************************************************************/

#ifdef CONFIG_ESP32S2_APP_FORMAT_MCUBOOT
extern int ets_printf(const char *fmt, ...);
extern int ets_printf(const char *fmt, ...) printflike(1, 2);
extern int cache_ibus_mmu_set(uint32_t ext_ram, uint32_t vaddr,
uint32_t paddr, uint32_t psize, uint32_t num,
uint32_t fixed);
Expand Down
4 changes: 2 additions & 2 deletions drivers/usbdev/usbdev_trprintf.c
Original file line number Diff line number Diff line change
Expand Up @@ -97,10 +97,10 @@ void usbtrace_trprintf(trprintf_t trprintf, uint16_t event, uint16_t value)
case TRACE_DEVINIT:
#ifdef CONFIG_USBDEV_TRACE_STRINGS
trprintf("%-18s : %-40s %04x\n", "DCD initialize",
TRACE_DATA(event), "Initialized", value);
"Initialized", value);
#else
trprintf("%-18s : %04x\n", "DCD initialize",
TRACE_DATA(event), value);
value);
#endif
break;

Expand Down
4 changes: 2 additions & 2 deletions fs/mount/fs_procfs_mount.c
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ struct mount_info_s
/* Helpers */

static void mount_sprintf(FAR struct mount_info_s *info,
FAR const char *fmt, ...);
FAR const char *fmt, ...) printflike(2, 3);
#ifndef CONFIG_FS_PROCFS_EXCLUDE_MOUNT
static int mount_entry(FAR const char *mountpoint,
FAR struct statfs *statbuf, FAR void *arg);
Expand Down Expand Up @@ -256,7 +256,7 @@ static int blocks_entry(FAR const char *mountpoint,

/* Generate blocks list one line at a time */

mount_sprintf(info, "%6lu %10" PRIuOFF " %10" PRIuOFF
mount_sprintf(info, "%6zu %10" PRIuOFF " %10" PRIuOFF
" %10" PRIuOFF " %s\n",
statbuf->f_bsize, statbuf->f_blocks,
statbuf->f_blocks - statbuf->f_bavail, statbuf->f_bavail,
Expand Down
8 changes: 4 additions & 4 deletions include/debug.h
Original file line number Diff line number Diff line change
Expand Up @@ -1092,19 +1092,19 @@ void lib_dumpvbuffer(FAR const char *msg, FAR const struct iovec *iov,

#ifndef CONFIG_CPP_HAVE_VARARGS
#ifdef CONFIG_DEBUG_ALERT
void _alert(const char *format, ...);
void _alert(const char *format, ...) sysloglike(1, 2);
#endif

#ifdef CONFIG_DEBUG_ERROR
void _err(const char *format, ...);
void _err(const char *format, ...) sysloglike(1, 2);
#endif

#ifdef CONFIG_DEBUG_WARN
void _warn(const char *format, ...);
void _warn(const char *format, ...) sysloglike(1, 2);
#endif

#ifdef CONFIG_DEBUG_INFO
void _info(const char *format, ...);
void _info(const char *format, ...) sysloglike(1, 2);
#endif
#endif /* CONFIG_CPP_HAVE_VARARGS */

Expand Down
16 changes: 8 additions & 8 deletions include/err.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,20 +38,20 @@
* and a newline, on stderr.
*/

void warn(FAR const char *fmt, ...);
void vwarn(FAR const char *fmt, va_list ap);
void warn(FAR const char *fmt, ...) printflike(1, 2);
void vwarn(FAR const char *fmt, va_list ap) printflike(1, 0);

/* Likewise, but without ": " and the standard error string. */

void warnx(FAR const char *fmt, ...);
void vwarnx(FAR const char *fmt, va_list ap);
void warnx(FAR const char *fmt, ...) printflike(1, 2);
void vwarnx(FAR const char *fmt, va_list ap) printflike(1, 0);

/* Likewise, and then exit with STATUS. */

void err(int status, FAR const char *fmt, ...);
void verr(int status, FAR const char *fmt, va_list ap);
void errx(int status, FAR const char *fmt, ...);
void verrx(int status, FAR const char *, va_list ap);
void err(int status, FAR const char *fmt, ...) printflike(2, 3);
void verr(int status, FAR const char *fmt, va_list ap) printflike(2, 0);
void errx(int status, FAR const char *fmt, ...) printflike(2, 3);
void verrx(int status, FAR const char *, va_list ap) printflike(2, 0);

#endif /* CONFIG_LIBC_ERR */
#endif /* __INCLUDE_ERR_H */
2 changes: 1 addition & 1 deletion include/nuttx/fs/procfs.h
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ size_t procfs_memcpy(FAR const char *src, size_t srclen,
****************************************************************************/

int procfs_snprintf(FAR char *buf, size_t size,
FAR const IPTR char *format, ...);
FAR const IPTR char *format, ...) printflike(3, 4);

/****************************************************************************
* Name: procfs_register
Expand Down
2 changes: 1 addition & 1 deletion include/nuttx/usb/usbdev_trace.h
Original file line number Diff line number Diff line change
Expand Up @@ -419,7 +419,7 @@ typedef uint16_t usbtrace_idset_t;

/* Print routine to use for usbdev_trprint() output */

typedef CODE int (*trprintf_t)(const char *fmt, ...);
typedef CODE int (*trprintf_t)(const char *fmt, ...) printflike(1, 2);

/****************************************************************************
* Public Data
Expand Down
3 changes: 2 additions & 1 deletion libs/libc/stdio/lib_libvsprintf.c
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,8 @@ static const char g_nullstring[] = "(null)";

static int vsprintf_internal(FAR struct lib_outstream_s *stream,
FAR struct arg_s *arglist, int numargs,
FAR const IPTR char *fmt, va_list ap);
FAR const IPTR char *fmt, va_list ap)
printflike(4, 0);

/****************************************************************************
* Private Functions
Expand Down
2 changes: 1 addition & 1 deletion net/procfs/net_procfs_route.c
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ struct route_info_s
/* Helpers */

static void route_sprintf(FAR struct route_info_s *info,
FAR const char *fmt, ...);
FAR const char *fmt, ...) printflike(2, 3);
#ifdef CONFIG_NET_IPv4
static int route_ipv4_entry(FAR struct net_route_ipv4_s *route,
FAR void *arg);
Expand Down

0 comments on commit 2166c98

Please sign in to comment.