Clean up various C source and headers to appease -Wstrict-prototypes

In C, func() is a function taking an unspecified number of arguments,
vs func(void) a function taking no arguments. In C++ both forms indicate
"no arguments."

Update these headers to use the (void) form, which is correct in both
languages and avoids complaints when -Wstrict-prototypes is specified.
This commit is contained in:
Brian Swetland 2021-02-07 14:04:25 -08:00 committed by graham sanderson
parent 93c600736e
commit a362925eda
34 changed files with 105 additions and 104 deletions

View File

@ -36,7 +36,7 @@ extern "C" {
#define hard_assert_if(x, test) ({if (PARAM_ASSERTIONS_ENABLED(x)) hard_assert(!(test));})
#ifdef NDEBUG
extern void hard_assertion_failure();
extern void hard_assertion_failure(void);
static inline void hard_assert(bool condition, ...) {
if (!condition)
hard_assertion_failure();

View File

@ -71,14 +71,14 @@ extern "C" {
* PICO_DEFAULT_UART_TX_PIN
* PICO_DEFAULT_UART_RX_PIN
*/
void setup_default_uart();
void setup_default_uart(void);
/*! \brief Initialise the system clock to 48MHz
* \ingroup pico_stdlib
*
* Set the system clock to 48MHz, and set the peripheral clock to match.
*/
void set_sys_clock_48mhz();
void set_sys_clock_48mhz(void);
/*! \brief Initialise the system clock
* \ingroup pico_stdlib

View File

@ -58,7 +58,7 @@ extern "C" {
* \sa sleep_until()
* \sa time_us_64()
*/
static inline absolute_time_t get_absolute_time() {
static inline absolute_time_t get_absolute_time(void) {
absolute_time_t t;
update_us_since_boot(&t, time_us_64());
return t;
@ -350,7 +350,7 @@ typedef struct alarm_pool alarm_pool_t;
* \brief Create the default alarm pool (if not already created or disabled)
* \ingroup alarm
*/
void alarm_pool_init_default();
void alarm_pool_init_default(void);
#if !PICO_TIME_DEFAULT_ALARM_POOL_DISABLED
/*!
@ -360,7 +360,7 @@ void alarm_pool_init_default();
* \ingroup alarm
* \sa #PICO_TIME_DEFAULT_ALARM_POOL_HARDWARE_ALARM_NUM
*/
alarm_pool_t *alarm_pool_get_default();
alarm_pool_t *alarm_pool_get_default(void);
#endif
/**

View File

@ -87,7 +87,7 @@ void hw_claim_clear(uint8_t *bits, uint bit_index);
*
* \return a token to pass to hw_claim_unlock()
*/
uint32_t hw_claim_lock();
uint32_t hw_claim_lock(void);
/*! \brief Release the runtime mutual exclusion lock provided by the `hardware_claim` library
* \ingroup hardware_claim

View File

@ -99,7 +99,7 @@ extern "C" {
*
* Must be called before any other clock function.
*/
void clocks_init();
void clocks_init(void);
/*! \brief Configure the specified clock
* \ingroup hardware_clocks

View File

@ -74,7 +74,7 @@ static inline void hw_divider_divmod_u32_start(uint32_t a, uint32_t b) {
*
* Wait for a divide to complete
*/
static inline void hw_divider_wait_ready() {
static inline void hw_divider_wait_ready(void) {
// this is #1 in lsr below
static_assert(SIO_DIV_CSR_READY_BITS == 1, "");
@ -99,7 +99,7 @@ static inline void hw_divider_wait_ready() {
*
* \return Current result. Most significant 32 bits are the remainder, lower 32 bits are the quotient.
*/
static inline divmod_result_t hw_divider_result_nowait() {
static inline divmod_result_t hw_divider_result_nowait(void) {
// as ugly as this looks it is actually quite efficient
divmod_result_t rc = (((divmod_result_t) sio_hw->div_remainder) << 32u) | sio_hw->div_quotient;
return rc;
@ -112,7 +112,7 @@ static inline divmod_result_t hw_divider_result_nowait() {
*
* \return Current result. Most significant 32 bits are the remainder, lower 32 bits are the quotient.
*/
static inline divmod_result_t hw_divider_result_wait() {
static inline divmod_result_t hw_divider_result_wait(void) {
hw_divider_wait_ready();
return hw_divider_result_nowait();
}
@ -124,7 +124,7 @@ static inline divmod_result_t hw_divider_result_wait() {
*
* \return Current unsigned quotient result.
*/
static inline uint32_t hw_divider_u32_quotient_wait() {
static inline uint32_t hw_divider_u32_quotient_wait(void) {
hw_divider_wait_ready();
return sio_hw->div_quotient;
}
@ -136,7 +136,7 @@ static inline uint32_t hw_divider_u32_quotient_wait() {
*
* \return Current signed quotient result.
*/
static inline int32_t hw_divider_s32_quotient_wait() {
static inline int32_t hw_divider_s32_quotient_wait(void) {
hw_divider_wait_ready();
return sio_hw->div_quotient;
}
@ -148,7 +148,7 @@ static inline int32_t hw_divider_s32_quotient_wait() {
*
* \return Current unsigned remainder result.
*/
static inline uint32_t hw_divider_u32_remainder_wait() {
static inline uint32_t hw_divider_u32_remainder_wait(void) {
hw_divider_wait_ready();
int32_t rc = sio_hw->div_remainder;
sio_hw->div_quotient; // must read quotient to cooperate with other SDK code
@ -162,7 +162,7 @@ static inline uint32_t hw_divider_u32_remainder_wait() {
*
* \return Current remainder results.
*/
static inline int32_t hw_divider_s32_remainder_wait() {
static inline int32_t hw_divider_s32_remainder_wait(void) {
hw_divider_wait_ready();
int32_t rc = sio_hw->div_remainder;
sio_hw->div_quotient; // must read quotient to cooperate with other SDK code
@ -290,7 +290,7 @@ static inline int32_t hw_divider_remainder_s32(int32_t a, int32_t b) {
/*! \brief Pause for exact amount of time needed for a asynchronous divide to complete
* \ingroup hardware_divider
*/
static inline void hw_divider_pause() {
static inline void hw_divider_pause(void) {
asm volatile (
"b _1_%=\n"
"_1_%=:\n"

View File

@ -595,7 +595,7 @@ inline static void dma_sniffer_set_byte_swap_enabled(bool swap) {
* \ingroup hardware_dma
*
*/
inline static void dma_sniffer_disable() {
inline static void dma_sniffer_disable(void) {
dma_hw->sniff_ctrl = 0;
}

View File

@ -33,7 +33,7 @@
static uint32_t boot2_copyout[BOOT2_SIZE_WORDS];
static bool boot2_copyout_valid = false;
static void __no_inline_not_in_flash_func(flash_init_boot2_copyout)() {
static void __no_inline_not_in_flash_func(flash_init_boot2_copyout)(void) {
if (boot2_copyout_valid)
return;
for (int i = 0; i < BOOT2_SIZE_WORDS; ++i)
@ -42,15 +42,15 @@ static void __no_inline_not_in_flash_func(flash_init_boot2_copyout)() {
boot2_copyout_valid = true;
}
static void __no_inline_not_in_flash_func(flash_enable_xip_via_boot2)() {
static void __no_inline_not_in_flash_func(flash_enable_xip_via_boot2)(void) {
((void (*)(void))boot2_copyout+1)();
}
#else
static void __no_inline_not_in_flash_func(flash_init_boot2_copyout)() {}
static void __no_inline_not_in_flash_func(flash_init_boot2_copyout)(void) {}
static void __no_inline_not_in_flash_func(flash_enable_xip_via_boot2)() {
static void __no_inline_not_in_flash_func(flash_enable_xip_via_boot2)(void) {
// Set up XIP for 03h read on bus access (slow but generic)
void (*flash_enter_cmd_xip)(void) = (void(*)(void))rom_func_lookup(rom_table_code('C', 'X'));
assert(flash_enter_cmd_xip);

View File

@ -335,7 +335,7 @@ static inline bool gpio_get(uint gpio) {
*
* \return Bitmask of raw GPIO values, as bits 0-29
*/
static inline uint32_t gpio_get_all() {
static inline uint32_t gpio_get_all(void) {
return sio_hw->gpio_in;
}
@ -490,7 +490,7 @@ static inline uint gpio_get_dir(uint gpio) {
return gpio_is_dir_out(gpio); // note GPIO_OUT is 1/true and GPIO_IN is 0/false anyway
}
extern void gpio_debug_pins_init();
extern void gpio_debug_pins_init(void);
#ifdef __cplusplus
}

View File

@ -231,7 +231,7 @@ static inline void interp_config_set_force_bits(interp_config *c, uint bits) {
*
* \return A default interpolation configuration
*/
static inline interp_config interp_default_config() {
static inline interp_config interp_default_config(void) {
interp_config c = {0};
// Just pass through everything
interp_config_set_mask(&c, 0, 31);

View File

@ -116,7 +116,7 @@ extern "C" {
*
* All interrupts handlers should be of this type, and follow normal ARM EABI register saving conventions
*/
typedef void (*irq_handler_t)();
typedef void (*irq_handler_t)(void);
/*! \brief Set specified interrupts priority
* \ingroup hardware_irq
@ -255,7 +255,7 @@ void irq_set_pending(uint num);
*
* \note This is an internal method and user should generally not call it.
*/
void irq_init_priorities();
void irq_init_priorities(void);
#ifdef __cplusplus
}
#endif

View File

@ -12,10 +12,10 @@
#include "pico/mutex.h"
#include "pico/assert.h"
extern void __unhandled_user_irq();
extern uint __get_current_exception();
extern void __unhandled_user_irq(void);
extern uint __get_current_exception(void);
static inline irq_handler_t *get_vtable() {
static inline irq_handler_t *get_vtable(void) {
return (irq_handler_t *) scb_hw->vtor;
}
@ -69,8 +69,8 @@ void irq_set_pending(uint num) {
static_assert(PICO_MAX_SHARED_IRQ_HANDLERS >= 1 && PICO_MAX_SHARED_IRQ_HANDLERS < 0x7f, "");
// note these are not real functions, they are code fragments (i.e. don't call them)
extern void irq_handler_chain_first_slot();
extern void irq_handler_chain_remove_tail();
extern void irq_handler_chain_first_slot(void);
extern void irq_handler_chain_remove_tail(void);
extern struct irq_handler_chain_slot {
// first 3 half words are executable code (raw vtable handler points to one slot, and inst3 will jump to next

View File

@ -354,7 +354,7 @@ static inline void sm_config_set_mov_status(pio_sm_config *c, enum pio_mov_statu
*
* \return the default state machine configuration which can then be modified.
*/
static inline pio_sm_config pio_get_default_sm_config() {
static inline pio_sm_config pio_get_default_sm_config(void) {
pio_sm_config c = {0, 0, 0};
sm_config_set_clkdiv_int_frac(&c, 1, 0);
sm_config_set_wrap(&c, 0, 31);

View File

@ -167,7 +167,7 @@ inline static uint pio_encode_set(enum pio_src_dest dest, uint value) {
return _pio_encode_instr_and_src_dest(pio_instr_bits_set, dest, value);
}
inline static uint pio_encode_nop() {
inline static uint pio_encode_nop(void) {
return pio_encode_mov(pio_y, pio_y);
}

View File

@ -199,7 +199,7 @@ static inline void pwm_init(uint slice_num, pwm_config *c, bool start) {
*
* \return Set of default values.
*/
static inline pwm_config pwm_get_default_config() {
static inline pwm_config pwm_get_default_config(void) {
pwm_config c = {0, 0, 0};
pwm_config_set_phase_correct(&c, false);
pwm_config_set_clkdiv_int(&c, 1);
@ -471,7 +471,7 @@ static inline void pwm_clear_irq(uint slice_num) {
*
* \return Bitmask of all PWM interrupts currently set
*/
static inline int32_t pwm_get_irq_status_mask() {
static inline int32_t pwm_get_irq_status_mask(void) {
return pwm_hw->ints;
}

View File

@ -81,7 +81,7 @@ typedef volatile uint32_t spin_lock_t;
* The SEV (send event) instruction sends an event to both cores.
*/
inline static void __sev() {
inline static void __sev(void) {
__asm volatile ("sev");
}
@ -91,7 +91,7 @@ inline static void __sev() {
* The WFE (wait for event) instruction waits until one of a number of
* events occurs, including events signalled by the SEV instruction on either core.
*/
inline static void __wfe() {
inline static void __wfe(void) {
__asm volatile ("wfe");
}
@ -100,7 +100,7 @@ inline static void __wfe() {
*
* The WFI (wait for interrupt) instruction waits for a interrupt to wake up the core.
*/
inline static void __wfi() {
inline static void __wfi(void) {
__asm volatile ("wfi");
}
@ -110,7 +110,7 @@ inline static void __wfi() {
* The DMB (data memory barrier) acts as a memory barrier, all memory accesses prior to this
* instruction will be observed before any explicit access after the instruction.
*/
inline static void __dmb() {
inline static void __dmb(void) {
__asm volatile ("dmb");
}
@ -121,14 +121,14 @@ inline static void __dmb() {
* so that all instructions following the ISB are fetched from cache or memory again, after
* the ISB instruction has been completed.
*/
inline static void __isb() {
inline static void __isb(void) {
__asm volatile ("isb");
}
/*! \brief Acquire a memory fence
* \ingroup hardware_sync
*/
inline static void __mem_fence_acquire() {
inline static void __mem_fence_acquire(void) {
// the original code below makes it hard for us to be included from C++ via a header
// which itself is in an extern "C", so just use __dmb instead, which is what
// is required on Cortex M0+
@ -144,7 +144,7 @@ inline static void __mem_fence_acquire() {
* \ingroup hardware_sync
*
*/
inline static void __mem_fence_release() {
inline static void __mem_fence_release(void) {
// the original code below makes it hard for us to be included from C++ via a header
// which itself is in an extern "C", so just use __dmb instead, which is what
// is required on Cortex M0+
@ -161,7 +161,7 @@ inline static void __mem_fence_release() {
*
* \return The prior interrupt enable status for restoration later via restore_interrupts()
*/
inline static uint32_t save_and_disable_interrupts() {
inline static uint32_t save_and_disable_interrupts(void) {
uint32_t status;
__asm volatile ("mrs %0, PRIMASK" : "=r" (status)::);
__asm volatile ("cpsid i");
@ -266,7 +266,7 @@ inline static void spin_unlock(spin_lock_t *lock, uint32_t saved_irq) {
*
* \return The core number the call was made from
*/
static inline uint get_core_num() {
static inline uint get_core_num(void) {
return (*(uint32_t *) (SIO_BASE + SIO_CPUID_OFFSET));
}
@ -286,7 +286,7 @@ spin_lock_t *spin_lock_init(uint lock_num);
void spin_locks_reset(void);
// this number is not claimed
uint next_striped_spin_lock_num();
uint next_striped_spin_lock_num(void);
/*! \brief Mark a spin lock as used
* \ingroup hardware_sync

View File

@ -62,7 +62,7 @@ static inline void check_hardware_alarm_num_param(uint alarm_num) {
*
* \return the 32 bit timestamp
*/
static inline uint32_t time_us_32() {
static inline uint32_t time_us_32(void) {
return timer_hw->timerawl;
}
@ -75,7 +75,7 @@ static inline uint32_t time_us_32() {
*
* \return the 64 bit timestamp
*/
uint64_t time_us_64();
uint64_t time_us_64(void);
/*! \brief Busy wait wasting cycles for the given (32 bit) number of microseconds
* \ingroup hardware_timer

View File

@ -92,7 +92,7 @@ static inline uint harware_alarm_irq_number(uint alarm_num) {
return TIMER_IRQ_0 + alarm_num;
}
static void hardware_alarm_irq_handler() {
static void hardware_alarm_irq_handler(void) {
// Determine which timer this IRQ is for
uint32_t ipsr;
__asm volatile ("mrs %0, ipsr" : "=r" (ipsr)::);

View File

@ -413,7 +413,7 @@ void uart_set_translate_crlf(uart_inst_t *uart, bool translate);
/*! \brief Wait for the default UART'S TX fifo to be drained
* \ingroup hardware_uart
*/
static inline void uart_default_tx_wait_blocking() {
static inline void uart_default_tx_wait_blocking(void) {
uart_tx_wait_blocking(uart_default);
}

View File

@ -17,9 +17,9 @@ static __attribute__((noreturn)) void missing_double_func_shim() {
panic("missing double function");
}
#endif
extern void double_table_shim_on_use_helper();
extern void double_table_shim_on_use_helper(void);
void __aeabi_double_init() {
void __aeabi_double_init(void) {
int rom_version = rp2040_rom_version();
#if PICO_DOUBLE_SUPPORT_ROM_V1
if (rom_version == 1) {

View File

@ -19,13 +19,13 @@ static __attribute__((noreturn)) void missing_float_func_shim() {
}
#endif
void __aeabi_float_init() {
void __aeabi_float_init(void) {
int rom_version = rp2040_rom_version();
void *rom_table = rom_data_lookup(rom_table_code('S', 'F'));
#if PICO_FLOAT_SUPPORT_ROM_V1
if (rom_version == 1) {
memcpy(&sf_table, rom_table, SF_TABLE_V1_SIZE);
extern void float_table_shim_on_use_helper();
extern void float_table_shim_on_use_helper(void);
// todo replace NDEBUG with a more exclusive assertion guard
#ifndef NDEBUG
if (*(uint16_t *)0x29ee != 0x0fc4 || // this is packx

View File

@ -36,7 +36,7 @@ extern "C" {
* \ingroup pico_multicore
*
*/
void multicore_reset_core1();
void multicore_reset_core1(void);
/*! \brief Run code on core 1
* \ingroup pico_multicore
@ -58,7 +58,7 @@ void multicore_launch_core1_with_stack(void (*entry)(void), uint32_t *stack_bott
* \ingroup pico_multicore
*
*/
void multicore_sleep_core1();
void multicore_sleep_core1(void);
/*! \brief Launch code on core 1 with no stack protection
* \ingroup pico_multicore
@ -85,7 +85,7 @@ void multicore_launch_core1_raw(void (*entry)(void), uint32_t *sp, uint32_t vect
*
* \return true if the FIFO has data in it, false otherwise
*/
static inline bool multicore_fifo_rvalid() {
static inline bool multicore_fifo_rvalid(void) {
return !!(sio_hw->fifo_st & SIO_FIFO_ST_VLD_BITS);
}
@ -94,7 +94,7 @@ static inline bool multicore_fifo_rvalid() {
*
* @return true if the FIFO is full, false otherwise
*/
static inline bool multicore_fifo_wready() {
static inline bool multicore_fifo_wready(void) {
return !!(sio_hw->fifo_st & SIO_FIFO_ST_RDY_BITS);
}
@ -120,7 +120,7 @@ bool multicore_fifo_push_timeout_us(uint32_t data, uint64_t timeout_us);
*
* \return 32 bit unsigned data from the FIFO.
*/
uint32_t multicore_fifo_pop_blocking();
uint32_t multicore_fifo_pop_blocking(void);
bool multicore_fifo_pop_timeout_us(uint64_t timeout_us, uint32_t *out);
@ -128,7 +128,7 @@ bool multicore_fifo_pop_timeout_us(uint64_t timeout_us, uint32_t *out);
* \ingroup multicore_fifo
*
*/
static inline void multicore_fifo_drain() {
static inline void multicore_fifo_drain(void) {
while (multicore_fifo_rvalid())
(void) sio_hw->fifo_rd;
}
@ -136,7 +136,7 @@ static inline void multicore_fifo_drain() {
/*! \brief Clear FIFO interrupt
* \ingroup multicore_fifo
*/
static inline void multicore_fifo_clear_irq() {
static inline void multicore_fifo_clear_irq(void) {
// Write any value to clear any interrupts
sio_hw->fifo_st = 0xff;
}
@ -153,19 +153,19 @@ static inline void multicore_fifo_clear_irq() {
* 1 | Value is 1 if this cores TX FIFO is not full (i.e. if FIFO_WR is ready for more data)
* 0 | Value is 1 if this cores RX FIFO is not empty (i.e. if FIFO_RD is valid)
*/
static inline int32_t multicore_fifo_get_status() {
static inline int32_t multicore_fifo_get_status(void) {
return sio_hw->fifo_st;
}
// call this from the lockout victim thread
void multicore_lockout_victim_init();
void multicore_lockout_victim_init(void);
// start locking out the other core (it will be
bool multicore_lockout_start_timeout_us(uint64_t timeout_us);
void multicore_lockout_start_blocking();
void multicore_lockout_start_blocking(void);
bool multicore_lockout_end_timeout_us(uint64_t timeout_us);
void multicore_lockout_end_blocking();
void multicore_lockout_end_blocking(void);
#ifdef __cplusplus
}

View File

@ -46,7 +46,7 @@ bool multicore_fifo_push_timeout_us(uint32_t data, uint64_t timeout_us) {
return true;
}
static inline uint32_t multicore_fifo_pop_blocking_inline() {
static inline uint32_t multicore_fifo_pop_blocking_inline(void) {
// If nothing there yet, we wait for an event first,
// to try and avoid too much busy waiting
while (!multicore_fifo_rvalid())
@ -75,7 +75,7 @@ bool multicore_fifo_pop_timeout_us(uint64_t timeout_us, uint32_t *out) {
// Default stack for core1 ... if multicore_launch_core1 is not included then .stack1 section will be garbage collected
static uint32_t __attribute__((section(".stack1"))) core1_stack[PICO_CORE1_STACK_SIZE / sizeof(uint32_t)];
static void __attribute__ ((naked)) core1_trampoline() {
static void __attribute__ ((naked)) core1_trampoline(void) {
__asm("pop {r0, r1, pc}");
}
@ -110,7 +110,7 @@ void multicore_sleep_core1() {
// note we give core1 an invalid stack pointer, as it should not be used
// note also if we ge simply passed a function that returned immediately, we'd end up in core1_hang anyway
// however that would waste 2 bytes for that function (the horror!)
extern void core1_hang(); // in crt0.S
extern void core1_hang(void); // in crt0.S
multicore_launch_core1_raw(core1_hang, (uint32_t *) -1, scb_hw->vtor);
}
@ -161,7 +161,7 @@ static bool lockout_in_progress;
// note this method is in RAM because lockout is used when writing to flash
// it only makes inline calls
static void __isr __not_in_flash_func(multicore_lockout_handler)() {
static void __isr __not_in_flash_func(multicore_lockout_handler)(void) {
multicore_fifo_clear_irq();
while (multicore_fifo_rvalid()) {
if (sio_hw->fifo_rd == LOCKOUT_MAGIC_START) {
@ -176,7 +176,7 @@ static void __isr __not_in_flash_func(multicore_lockout_handler)() {
}
}
static void check_lockout_mutex_init() {
static void check_lockout_mutex_init(void) {
// use known available lock - we only need it briefly
uint32_t save = hw_claim_lock();
if (!mutex_is_initialzed(&lockout_mutex)) {

View File

@ -50,7 +50,7 @@ extern "C" {
#define __uninitialized_ram(group) __attribute__((section(".uninitialized_ram." #group))) group
inline static void __breakpoint() {
inline static void __breakpoint(void) {
__asm__("bkpt #0");
}
@ -59,7 +59,7 @@ inline static void __breakpoint() {
// we provide this macro which allows that code to provide a 64->32 bit mapping in host mode
#define host_safe_hw_ptr(x) ((uintptr_t)(x))
void __attribute__((noreturn)) panic_unsupported();
void __attribute__((noreturn)) panic_unsupported(void);
void __attribute__((noreturn)) panic(const char *fmt, ...);
@ -69,19 +69,19 @@ void __attribute__((noreturn)) panic(const char *fmt, ...);
#endif
#if PICO_NO_FPGA_CHECK
static inline bool running_on_fpga() {return false;}
static inline bool running_on_fpga(void) {return false;}
#else
bool running_on_fpga();
bool running_on_fpga(void);
#endif
uint8_t rp2040_chip_version();
uint8_t rp2040_chip_version(void);
static inline uint8_t rp2040_rom_version() {
static inline uint8_t rp2040_rom_version(void) {
return *(uint8_t*)0x13;
}
// called by any tight hardware polling loop... nominally empty, but can be modified for debugging
static inline void tight_loop_contents() {}
static inline void tight_loop_contents(void) {}
// return a 32 bit handle for a raw ptr; DMA chaining for example embeds pointers in 32 bit values
// which of course does not work if we're running the code natively on a 64 bit platform for testing.

View File

@ -87,13 +87,13 @@ void runtime_init(void) {
// Start and end points of the constructor list,
// defined by the linker script.
extern void (*__preinit_array_start)();
extern void (*__preinit_array_end)();
extern void (*__preinit_array_start)(void);
extern void (*__preinit_array_end)(void);
// Call each function in the list.
// We have to take the address of the symbols, as __preinit_array_start *is*
// the first function pointer, not the address of it.
for (void (**p)() = &__preinit_array_start; p < &__preinit_array_end; ++p) {
for (void (**p)(void) = &__preinit_array_start; p < &__preinit_array_end; ++p) {
(*p)();
}
@ -144,13 +144,13 @@ void runtime_init(void) {
// Start and end points of the constructor list,
// defined by the linker script.
extern void (*__init_array_start)();
extern void (*__init_array_end)();
extern void (*__init_array_start)(void);
extern void (*__init_array_end)(void);
// Call each function in the list.
// We have to take the address of the symbols, as __init_array_start *is*
// the first function pointer, not the address of it.
for (void (**p)() = &__init_array_start; p < &__init_array_end; ++p) {
for (void (**p)(void) = &__init_array_start; p < &__init_array_end; ++p) {
(*p)();
}

View File

@ -51,7 +51,7 @@ typedef struct stdio_driver stdio_driver_t;
*
* \see stdio_uart, stdio_usb, stdio_semihosting
*/
void stdio_init_all();
void stdio_init_all(void);
/*! \brief Initialize all of the present standard stdio types that are linked into the binary.
* \ingroup pico_stdio
@ -61,7 +61,7 @@ void stdio_init_all();
*
* \see stdio_uart, stdio_usb, stdio_semihosting
*/
void stdio_flush();
void stdio_flush(void);
/*! \brief Return a character from stdin if there is one available within a timeout
* \ingroup pico_stdio

View File

@ -12,7 +12,7 @@
struct stdio_driver {
void (*out_chars)(const char *buf, int len);
void (*out_flush)();
void (*out_flush)(void);
int (*in_chars)(char *buf, int len);
stdio_driver_t *next;
#if PICO_STDIO_ENABLE_CRLF_SUPPORT

View File

@ -33,7 +33,7 @@ static stdio_driver_t *filter;
#if PICO_STDOUT_MUTEX
auto_init_mutex(print_mutex);
bool stdout_serialize_begin() {
bool stdout_serialize_begin(void) {
int core_num = get_core_num();
uint32_t owner;
if (!mutex_try_enter(&print_mutex, &owner)) {
@ -46,15 +46,15 @@ bool stdout_serialize_begin() {
return true;
}
void stdout_serialize_end() {
void stdout_serialize_end(void) {
mutex_exit(&print_mutex);
}
#else
static bool print_serialize_begin() {
static bool print_serialize_begin(void) {
return true;
}
static void print_serialize_end() {
static void print_serialize_end(void) {
}
#endif
@ -255,7 +255,7 @@ void stdio_init_all() {
#endif
}
int WRAPPER_FUNC(getchar)() {
int WRAPPER_FUNC(getchar)(void) {
char buf[1];
if (0 == stdio_get_until(buf, sizeof(buf), at_the_end_of_time)) {
return PICO_ERROR_TIMEOUT;

View File

@ -29,6 +29,6 @@ extern stdio_driver_t stdio_semihosting;
*
* \note this method is automatically called by \ref stdio_init_all() if `pico_stdio_semihosting` is included in the build
*/
void stdio_semihosting_init();
void stdio_semihosting_init(void);
#endif

View File

@ -33,21 +33,21 @@ extern stdio_driver_t stdio_uart;
*
* \note this method is automatically called by \ref stdio_init_all() if `pico_stdio_uart` is included in the build
*/
void stdio_uart_init();
void stdio_uart_init(void);
/*! \brief Explicitly initialize stdout only (no stdin) over UART and add it to the current set of stdout drivers
* \ingroup pico_stdio_uart
*
* This method sets up PICO_DEFAULT_UART_TX_PIN for UART output (if defined) , and configures the baud rate as PICO_DEFAULT_UART_BAUD_RATE
*/
void stdout_uart_init();
void stdout_uart_init(void);
/*! \brief Explicitly initialize stdin only (no stdout) over UART and add it to the current set of stdin drivers
* \ingroup pico_stdio_uart
*
* This method sets up PICO_DEFAULT_UART_RX_PIN for UART input (if defined) , and configures the baud rate as PICO_DEFAULT_UART_BAUD_RATE
*/
void stdin_uart_init();
void stdin_uart_init(void);
/*! \brief Perform custom initialization initialize stdin/stdout over UART and add it to the current set of stdin/stdout drivers
* \ingroup pico_stdio_uart

View File

@ -47,6 +47,6 @@ extern stdio_driver_t stdio_usb;
/*! \brief Explicitly initialize USB stdio and add it to the current set of stdin drivers
* \ingroup pico_stdio_uart
*/
bool stdio_usb_init();
bool stdio_usb_init(void);
#endif

View File

@ -11,7 +11,7 @@ static_assert(PICO_UNIQUE_BOARD_ID_SIZE_BYTES == FLASH_UNIQUE_ID_SIZE_BYTES, "Bo
static pico_unique_board_id_t retrieved_id;
static void __attribute__((constructor)) _retrieve_unique_id_on_boot() {
static void __attribute__((constructor)) _retrieve_unique_id_on_boot(void) {
#if PICO_NO_FLASH
// The hardware_flash call will panic() if called directly on a NO_FLASH
// build. Since this constructor is pre-main it would be annoying to

View File

@ -59,6 +59,7 @@ target_compile_options(kitchen_sink_options INTERFACE
-Wfloat-equal
-Wmissing-format-attribute
-Wno-long-long
$<$<COMPILE_LANGUAGE:C>:-Wstrict-prototypes>
# todo not sure these are true, but investigate
#-Wpacked

View File

@ -39,7 +39,7 @@ uint32_t *foo = (uint32_t *) 200;
uint32_t dma_to = 0;
uint32_t dma_from = 0xaaaa5555;
void spiggle() {
void spiggle(void) {
dma_channel_config c = dma_channel_get_default_config(1);
channel_config_set_bswap(&c, true);
channel_config_set_transfer_data_size(&c, DMA_SIZE_16);
@ -48,7 +48,7 @@ void spiggle() {
dma_channel_transfer_from_buffer_now(1, foo, 23);
}
void __isr dma_handler_a() {
void __isr dma_handler_a(void) {
printf("HELLO A\n");
if (dma_hw->ints1 & 1) {
dma_hw->ints1 = 1;
@ -57,7 +57,7 @@ void __isr dma_handler_a() {
}
}
void __isr dma_handler_b() {
void __isr dma_handler_b(void) {
printf("HELLO B\n");
if (dma_hw->ints1 & 1) {
dma_hw->ints1 = 1;
@ -68,7 +68,7 @@ void __isr dma_handler_b() {
//#pragma GCC pop_options
int main() {
int main(void) {
spiggle();
stdio_init_all();