Commit be2bd234 authored by Alessandro Rubini's avatar Alessandro Rubini

general cleanup of wrong prototypes

I added -Wstrict-prototypes, that used to be included in -Wall settings
but is not.  Actually, I think it should be an error to not specify an
argument list by now.  If any, -traditional is there for old timers.

Fortunately no bug was exposed by the missing prototypes.
Signed-off-by: Alessandro Rubini's avatarAlessandro Rubini <rubini@gnudd.com>
parent 3a3c3806
...@@ -61,9 +61,11 @@ include pp_printf/printf.mk ...@@ -61,9 +61,11 @@ include pp_printf/printf.mk
include dev/dev.mk include dev/dev.mk
include softpll/softpll.mk include softpll/softpll.mk
# ppsi already has div64 (the same one), so only pick it if not using ppsi # ppsi already has div64 (the same one), so only pick it if not using ppsi.
ifndef CONFIG_PPSI ifndef CONFIG_PPSI
obj-y += pp_printf/div64.o obj-y += pp_printf/div64.o
# unfortunately, we need a prototype there
cflags-y += -include include/wrc.h
endif endif
# And always complain if we pick the libgcc division: 64/32 = 32 is enough here. # And always complain if we pick the libgcc division: 64/32 = 32 is enough here.
obj-y += check-error.o obj-y += check-error.o
...@@ -74,7 +76,7 @@ obj-y += system_checks.o ...@@ -74,7 +76,7 @@ obj-y += system_checks.o
obj-$(CONFIG_WR_NODE) += sdb-lib/libsdbfs.a obj-$(CONFIG_WR_NODE) += sdb-lib/libsdbfs.a
cflags-$(CONFIG_WR_NODE) += -Isdb-lib cflags-$(CONFIG_WR_NODE) += -Isdb-lib
CFLAGS = $(CFLAGS_PLATFORM) $(cflags-y) -Wall \ CFLAGS = $(CFLAGS_PLATFORM) $(cflags-y) -Wall -Wstrict-prototypes \
-ffunction-sections -fdata-sections -Os \ -ffunction-sections -fdata-sections -Os \
-include include/trace.h -ggdb -include include/trace.h -ggdb
......
...@@ -8,7 +8,7 @@ ...@@ -8,7 +8,7 @@
*/ */
#include "irq.h" #include "irq.h"
void disable_irq() void disable_irq(void)
{ {
unsigned int ie, im; unsigned int ie, im;
unsigned int Mask = ~1; unsigned int Mask = ~1;
...@@ -25,7 +25,7 @@ void disable_irq() ...@@ -25,7 +25,7 @@ void disable_irq()
} }
void enable_irq() void enable_irq(void)
{ {
unsigned int ie, im; unsigned int ie, im;
unsigned int Mask = 1; unsigned int Mask = 1;
......
...@@ -68,7 +68,7 @@ struct ad9516_reg { ...@@ -68,7 +68,7 @@ struct ad9516_reg {
static void *oc_spi_base; static void *oc_spi_base;
int oc_spi_init(void *base_addr) static int oc_spi_init(void *base_addr)
{ {
oc_spi_base = base_addr; oc_spi_base = base_addr;
...@@ -76,7 +76,7 @@ int oc_spi_init(void *base_addr) ...@@ -76,7 +76,7 @@ int oc_spi_init(void *base_addr)
return 0; return 0;
} }
int oc_spi_txrx(int ss, int nbits, uint32_t in, uint32_t *out) static int oc_spi_txrx(int ss, int nbits, uint32_t in, uint32_t *out)
{ {
uint32_t rval; uint32_t rval;
...@@ -129,14 +129,14 @@ static void ad9516_load_regset(const struct ad9516_reg *regs, int n_regs, int co ...@@ -129,14 +129,14 @@ static void ad9516_load_regset(const struct ad9516_reg *regs, int n_regs, int co
} }
static void ad9516_wait_lock() static void ad9516_wait_lock(void)
{ {
while ((ad9516_read_reg(0x1f) & 1) == 0); while ((ad9516_read_reg(0x1f) & 1) == 0);
} }
#define SECONDARY_DIVIDER 0x100 #define SECONDARY_DIVIDER 0x100
int ad9516_set_output_divider(int output, int ratio, int phase_offset) static int ad9516_set_output_divider(int output, int ratio, int phase_offset)
{ {
uint8_t lcycles = (ratio/2) - 1; uint8_t lcycles = (ratio/2) - 1;
uint8_t hcycles = (ratio - (ratio / 2)) - 1; uint8_t hcycles = (ratio - (ratio / 2)) - 1;
...@@ -188,7 +188,7 @@ int ad9516_set_output_divider(int output, int ratio, int phase_offset) ...@@ -188,7 +188,7 @@ int ad9516_set_output_divider(int output, int ratio, int phase_offset)
return 0; return 0;
} }
int ad9516_set_vco_divider(int ratio) /* Sets the VCO divider (2..6) or 0 to enable static output */ static int ad9516_set_vco_divider(int ratio) /* Sets the VCO divider (2..6) or 0 to enable static output */
{ {
if(ratio == 0) if(ratio == 0)
ad9516_write_reg(0x1e0, 0x5); /* static mode */ ad9516_write_reg(0x1e0, 0x5); /* static mode */
...@@ -198,7 +198,7 @@ int ad9516_set_vco_divider(int ratio) /* Sets the VCO divider (2..6) or 0 to ena ...@@ -198,7 +198,7 @@ int ad9516_set_vco_divider(int ratio) /* Sets the VCO divider (2..6) or 0 to ena
return 0; return 0;
} }
void ad9516_sync_outputs() static void ad9516_sync_outputs(void)
{ {
/* VCO divider: static mode */ /* VCO divider: static mode */
ad9516_write_reg(0x1E0, 0x7); ad9516_write_reg(0x1E0, 0x7);
......
...@@ -14,6 +14,7 @@ ...@@ -14,6 +14,7 @@
#include "storage.h" #include "storage.h"
#include "board.h" #include "board.h"
#include "syscon.h" #include "syscon.h"
#include "onewire.h"
/* /*
* The SFP section is placed somewhere inside FMC EEPROM and it really does not * The SFP section is placed somewhere inside FMC EEPROM and it really does not
......
...@@ -98,12 +98,12 @@ static int code_pos; ...@@ -98,12 +98,12 @@ static int code_pos;
static uint64_t code_buf[32]; static uint64_t code_buf[32];
/* begins assembling a new packet filter program */ /* begins assembling a new packet filter program */
static void pfilter_new() static void pfilter_new(void)
{ {
code_pos = 0; code_pos = 0;
} }
static void check_size() static void check_size(void)
{ {
if (code_pos == PFILTER_MAX_CODE_SIZE - 1) { if (code_pos == PFILTER_MAX_CODE_SIZE - 1) {
pfilter_dbg("microcode: code too big (max size: %d)\n", pfilter_dbg("microcode: code too big (max size: %d)\n",
...@@ -144,7 +144,7 @@ static void pfilter_cmp(int offset, int value, int mask, pfilter_op_t op, ...@@ -144,7 +144,7 @@ static void pfilter_cmp(int offset, int value, int mask, pfilter_op_t op,
code_buf[code_pos++] = ir; code_buf[code_pos++] = ir;
} }
static void pfilter_nop() static void pfilter_nop(void)
{ {
uint64_t ir; uint64_t ir;
check_size(); check_size();
...@@ -185,7 +185,7 @@ static void pfilter_logic3(int rd, int ra, pfilter_op_t op, int rb, ...@@ -185,7 +185,7 @@ static void pfilter_logic3(int rd, int ra, pfilter_op_t op, int rb,
} }
/* Terminates the microcode, loads it to the endpoint and enables the pfilter */ /* Terminates the microcode, loads it to the endpoint and enables the pfilter */
static void pfilter_load() static void pfilter_load(void)
{ {
int i; int i;
code_buf[code_pos++] = (1ULL << 35); // insert FIN instruction code_buf[code_pos++] = (1ULL << 35); // insert FIN instruction
......
...@@ -16,7 +16,7 @@ ...@@ -16,7 +16,7 @@
/* /*
* Delay function - limit SPI clock speed to 10 MHz * Delay function - limit SPI clock speed to 10 MHz
*/ */
static void delay() static void delay(void)
{ {
int i; int i;
for (i = 0; i < (int)(CPU_CLOCK/10000000); i++) for (i = 0; i < (int)(CPU_CLOCK/10000000); i++)
......
...@@ -13,7 +13,7 @@ ...@@ -13,7 +13,7 @@
#define I2C_DELAY 300 #define I2C_DELAY 300
void mi2c_delay() void mi2c_delay(void)
{ {
int i; int i;
for (i = 0; i < I2C_DELAY; i++) for (i = 0; i < I2C_DELAY; i++)
......
...@@ -117,7 +117,7 @@ static uint8_t *minic_rx_memset(uint8_t * mem, uint8_t c, uint32_t size) ...@@ -117,7 +117,7 @@ static uint8_t *minic_rx_memset(uint8_t * mem, uint8_t c, uint32_t size)
return (uint8_t *) src; return (uint8_t *) src;
} }
static void minic_new_rx_buffer() static void minic_new_rx_buffer(void)
{ {
minic_writel(MINIC_REG_MCR, 0); minic_writel(MINIC_REG_MCR, 0);
minic.rx_base = dma_rx_buf; minic.rx_base = dma_rx_buf;
...@@ -137,7 +137,7 @@ static void minic_rxbuf_free(uint32_t words) ...@@ -137,7 +137,7 @@ static void minic_rxbuf_free(uint32_t words)
minic_writel(MINIC_REG_RX_AVAIL, words); minic_writel(MINIC_REG_RX_AVAIL, words);
} }
static void minic_new_tx_buffer() static void minic_new_tx_buffer(void)
{ {
minic.tx_base = dma_tx_buf; minic.tx_base = dma_tx_buf;
minic.tx_size = MINIC_DMA_TX_BUF_SIZE >> 2; minic.tx_size = MINIC_DMA_TX_BUF_SIZE >> 2;
......
...@@ -117,7 +117,7 @@ static int cal_cur_phase; ...@@ -117,7 +117,7 @@ static int cal_cur_phase;
ptpnetif's check lock function when the PLL has already locked, to avoid ptpnetif's check lock function when the PLL has already locked, to avoid
complicating the API of ptp-noposix/ppsi. */ complicating the API of ptp-noposix/ppsi. */
void rxts_calibration_start() void rxts_calibration_start(void)
{ {
cal_cur_phase = 0; cal_cur_phase = 0;
det_rising.prev_val = det_falling.prev_val = -1; det_rising.prev_val = det_falling.prev_val = -1;
......
...@@ -15,7 +15,7 @@ ...@@ -15,7 +15,7 @@
#include "i2c.h" #include "i2c.h"
#include "sfp.h" #include "sfp.h"
int sfp_present() int sfp_present(void)
{ {
return !gpio_in(GPIO_SFP_DET); return !gpio_in(GPIO_SFP_DET);
} }
......
...@@ -27,7 +27,7 @@ void __attribute__((weak)) uart_init_hw(void) ...@@ -27,7 +27,7 @@ void __attribute__((weak)) uart_init_hw(void)
{} {}
void uart_sw_write_byte(int b) static void uart_sw_write_byte(int b)
{ {
int index; int index;
...@@ -50,7 +50,7 @@ int uart_sw_write_string(const char *s) ...@@ -50,7 +50,7 @@ int uart_sw_write_string(const char *s)
return s - t; return s - t;
} }
int uart_sw_read_byte() static int uart_sw_read_byte(void)
{ {
int index; int index;
...@@ -68,6 +68,6 @@ void uart_write_byte(int b) ...@@ -68,6 +68,6 @@ void uart_write_byte(int b)
__attribute__((alias("uart_sw_write_byte"), weak)); __attribute__((alias("uart_sw_write_byte"), weak));
int uart_write_string(const char *s) int uart_write_string(const char *s)
__attribute__((alias("uart_sw_write_string"), weak)); __attribute__((alias("uart_sw_write_string"), weak));
int uart_read_byte() int uart_read_byte(void)
__attribute__((alias("uart_sw_read_byte"), weak)); __attribute__((alias("uart_sw_read_byte"), weak));
...@@ -46,12 +46,12 @@ int uart_write_string(const char *s) ...@@ -46,12 +46,12 @@ int uart_write_string(const char *s)
return s - t; return s - t;
} }
static int uart_poll() static int uart_poll(void)
{ {
return uart->SR & UART_SR_RX_RDY; return uart->SR & UART_SR_RX_RDY;
} }
int uart_read_byte() int uart_read_byte(void)
{ {
if (!uart_poll()) if (!uart_poll())
return -1; return -1;
......
...@@ -29,8 +29,8 @@ ...@@ -29,8 +29,8 @@
/* Number of auxillary clock channels - usually equal to the number of FMCs */ /* Number of auxillary clock channels - usually equal to the number of FMCs */
#define NUM_AUX_CLOCKS 1 #define NUM_AUX_CLOCKS 1
int board_init(); int board_init(void);
int board_update(); int board_update(void);
/* spll parameter that are board-specific */ /* spll parameter that are board-specific */
#define BOARD_DIVIDE_DMTD_CLOCKS 1 #define BOARD_DIVIDE_DMTD_CLOCKS 1
......
...@@ -22,13 +22,13 @@ void get_mac_addr(uint8_t dev_addr[]); ...@@ -22,13 +22,13 @@ void get_mac_addr(uint8_t dev_addr[]);
void set_mac_addr(uint8_t dev_addr[]); void set_mac_addr(uint8_t dev_addr[]);
int ep_enable(int enabled, int autoneg); int ep_enable(int enabled, int autoneg);
int ep_link_up(uint16_t * lpa); int ep_link_up(uint16_t * lpa);
int ep_get_bitslide(); int ep_get_bitslide(void);
int ep_get_deltas(uint32_t * delta_tx, uint32_t * delta_rx); int ep_get_deltas(uint32_t * delta_tx, uint32_t * delta_rx);
int ep_get_psval(int32_t * psval); int ep_get_psval(int32_t * psval);
int ep_cal_pattern_enable(); int ep_cal_pattern_enable(void);
int ep_cal_pattern_disable(); int ep_cal_pattern_disable(void);
int ep_timestamper_cal_pulse(); int ep_timestamper_cal_pulse(void);
void pfilter_init_default(); void pfilter_init_default(void);
#endif #endif
...@@ -9,7 +9,7 @@ void mi2c_stop(uint8_t i2cif); ...@@ -9,7 +9,7 @@ void mi2c_stop(uint8_t i2cif);
void mi2c_get_byte(uint8_t i2cif, unsigned char *data, uint8_t last); void mi2c_get_byte(uint8_t i2cif, unsigned char *data, uint8_t last);
unsigned char mi2c_put_byte(uint8_t i2cif, unsigned char data); unsigned char mi2c_put_byte(uint8_t i2cif, unsigned char data);
void mi2c_delay(); void mi2c_delay(void);
//void mi2c_scan(uint8_t i2cif); //void mi2c_scan(uint8_t i2cif);
#endif #endif
#ifndef __IRQ_H #ifndef __IRQ_H
#define __IRQ_H #define __IRQ_H
static inline void clear_irq() static inline void clear_irq(void)
{ {
unsigned int val = 1; unsigned int val = 1;
asm volatile ("wcsr ip, %0"::"r" (val)); asm volatile ("wcsr ip, %0"::"r" (val));
} }
void disable_irq(); void disable_irq(void);
void enable_irq(); void enable_irq(void);
#endif #endif
...@@ -9,9 +9,9 @@ ...@@ -9,9 +9,9 @@
#define WRPC_FID 0 #define WRPC_FID 0
void minic_init(); void minic_init(void);
void minic_disable(); void minic_disable(void);
int minic_poll_rx(); int minic_poll_rx(void);
void minic_get_stats(int *tx_frames, int *rx_frames); void minic_get_stats(int *tx_frames, int *rx_frames);
int minic_rx_frame(uint8_t * hdr, uint8_t * payload, uint32_t buf_size, int minic_rx_frame(uint8_t * hdr, uint8_t * payload, uint32_t buf_size,
......
...@@ -94,7 +94,7 @@ typedef struct _wr_timestamp wr_timestamp_t; ...@@ -94,7 +94,7 @@ typedef struct _wr_timestamp wr_timestamp_t;
// - opens devices // - opens devices
// - does necessary ioctls() // - does necessary ioctls()
// - initializes connection with the mighty HAL daemon // - initializes connection with the mighty HAL daemon
int ptpd_netif_init(); int ptpd_netif_init(void);
// Creates UDP or Ethernet RAW socket (determined by sock_type) bound to bind_addr. If PTPD_FLAG_MULTICAST is set, the socket is // Creates UDP or Ethernet RAW socket (determined by sock_type) bound to bind_addr. If PTPD_FLAG_MULTICAST is set, the socket is
// automatically added to multicast group. User can specify physical_port field to bind the socket to specific switch port only. // automatically added to multicast group. User can specify physical_port field to bind the socket to specific switch port only.
...@@ -219,12 +219,12 @@ int ptpd_netif_get_ifName(char *ifname, int number); ...@@ -219,12 +219,12 @@ int ptpd_netif_get_ifName(char *ifname, int number);
* HEXP_LOCK_STATUS_BUSY 1 * HEXP_LOCK_STATUS_BUSY 1
* HEXP_EXTSRC_STATUS_NOSRC 2 * HEXP_EXTSRC_STATUS_NOSRC 2
*/ */
int ptpd_netif_extsrc_detection(); int ptpd_netif_extsrc_detection(void);
/* Timebase adjustment functions - the servo should not call the HAL directly */ /* Timebase adjustment functions - the servo should not call the HAL directly */
int ptpd_netif_adjust_counters(int64_t adjust_sec, int32_t adjust_nsec); int ptpd_netif_adjust_counters(int64_t adjust_sec, int32_t adjust_nsec);
int ptpd_netif_adjust_phase(int32_t phase_ps); int ptpd_netif_adjust_phase(int32_t phase_ps);
int ptpd_netif_adjust_in_progress(); int ptpd_netif_adjust_in_progress(void);
void ptpd_netif_linearize_rx_timestamp(wr_timestamp_t * ts, int32_t dmtd_phase, void ptpd_netif_linearize_rx_timestamp(wr_timestamp_t * ts, int32_t dmtd_phase,
int cntr_ahead, int transition_point, int cntr_ahead, int transition_point,
int clock_period); int clock_period);
......
...@@ -10,7 +10,7 @@ ...@@ -10,7 +10,7 @@
#ifndef __RXTS_CALIBRATOR_H #ifndef __RXTS_CALIBRATOR_H
#define __RXTS_CALIBRATOR_H #define __RXTS_CALIBRATOR_H
void rxts_calibration_start(); void rxts_calibration_start(void);
int rxts_calibration_update(int *t24p_value); int rxts_calibration_update(int *t24p_value);
int measure_t24p(uint32_t *value); int measure_t24p(uint32_t *value);
int calib_t24p(int mode, uint32_t *value); int calib_t24p(int mode, uint32_t *value);
......
...@@ -6,7 +6,7 @@ ...@@ -6,7 +6,7 @@
#include <stdint.h> #include <stdint.h>
/* Returns 1 if there's a SFP transceiver inserted in the socket. */ /* Returns 1 if there's a SFP transceiver inserted in the socket. */
int sfp_present(); int sfp_present(void);
/* Reads the part ID of the SFP from its configuration EEPROM */ /* Reads the part ID of the SFP from its configuration EEPROM */
int sfp_read_part_id(char *part_id); int sfp_read_part_id(char *part_id);
......
...@@ -23,10 +23,10 @@ extern struct wrc_shell_cmd __cmd_begin[], __cmd_end[]; ...@@ -23,10 +23,10 @@ extern struct wrc_shell_cmd __cmd_begin[], __cmd_end[];
char *env_get(const char *var); char *env_get(const char *var);
int env_set(const char *var, const char *value); int env_set(const char *var, const char *value);
void env_init(); void env_init(void);
int shell_exec(const char *buf); int shell_exec(const char *buf);
void shell_interactive(); void shell_interactive(void);
int shell_boot_script(void); int shell_boot_script(void);
......
...@@ -24,6 +24,10 @@ static inline void timer_delay_ms(int ms) ...@@ -24,6 +24,10 @@ static inline void timer_delay_ms(int ms)
timer_delay(ms * TICS_PER_SECOND / 1000); timer_delay(ms * TICS_PER_SECOND / 1000);
} }
/* usleep.c */
extern void usleep_init(void);
extern int usleep(useconds_t usec);
#ifdef CONFIG_WR_NODE #ifdef CONFIG_WR_NODE
...@@ -62,10 +66,6 @@ extern struct s_i2c_if i2c_if[2]; ...@@ -62,10 +66,6 @@ extern struct s_i2c_if i2c_if[2];
void timer_init(uint32_t enable); void timer_init(uint32_t enable);
/* usleep.c */
extern void usleep_init(void);
extern int usleep(useconds_t usec);
extern volatile struct SYSCON_WB *syscon; extern volatile struct SYSCON_WB *syscon;
...@@ -86,7 +86,7 @@ static inline int gpio_in(int pin) ...@@ -86,7 +86,7 @@ static inline int gpio_in(int pin)
return syscon->GPSR & pin ? 1 : 0; return syscon->GPSR & pin ? 1 : 0;
} }
static inline int sysc_get_memsize() static inline int sysc_get_memsize(void)
{ {
return (SYSC_HWFR_MEMSIZE_R(syscon->HWFR) + 1) * 16; return (SYSC_HWFR_MEMSIZE_R(syscon->HWFR) + 1) * 16;
} }
......
...@@ -20,6 +20,6 @@ void cprintf(int color, const char *fmt, ...); ...@@ -20,6 +20,6 @@ void cprintf(int color, const char *fmt, ...);
void pcprintf(int row, int col, int color, const char *fmt, ...); void pcprintf(int row, int col, int color, const char *fmt, ...);
/* Clears the terminal scree. */ /* Clears the terminal scree. */
void term_clear(); void term_clear(void);
#endif #endif
...@@ -21,7 +21,7 @@ ...@@ -21,7 +21,7 @@
static struct rts_pll_state pstate; static struct rts_pll_state pstate;
static void clear_state() static void clear_state(void)
{ {
int i; int i;
for(i=0;i<RTS_PLL_CHANNELS;i++) for(i=0;i<RTS_PLL_CHANNELS;i++)
......
...@@ -100,7 +100,7 @@ struct rts_pll_state { ...@@ -100,7 +100,7 @@ struct rts_pll_state {
/* API */ /* API */
/* Connects to the RT CPU */ /* Connects to the RT CPU */
int rts_connect(); int rts_connect(void);
/* Queries the RT CPU PLL state */ /* Queries the RT CPU PLL state */
int rts_get_state(struct rts_pll_state *state); int rts_get_state(struct rts_pll_state *state);
......
...@@ -99,7 +99,7 @@ void pcprintf(int row, int col, int color, const char *fmt, ...) ...@@ -99,7 +99,7 @@ void pcprintf(int row, int col, int color, const char *fmt, ...)
mprintf("\e[m"); mprintf("\e[m");
} }
void term_clear() void term_clear(void)
{ {
mprintf("\e[2J\e[1;1H"); mprintf("\e[2J\e[1;1H");
} }
...@@ -47,7 +47,7 @@ char* print64(uint64_t x) ...@@ -47,7 +47,7 @@ char* print64(uint64_t x)
} }
int wrc_mon_status() int wrc_mon_status(void)
{ {
struct wr_servo_state *s = struct wr_servo_state *s =
&((struct wr_data *)ppi->ext_data)->servo_state; &((struct wr_data *)ppi->ext_data)->servo_state;
......
...@@ -71,7 +71,7 @@ static void esc(char code) ...@@ -71,7 +71,7 @@ static void esc(char code)
mprintf("\033[1%c", code); mprintf("\033[1%c", code);
} }
static int _shell_exec() static int _shell_exec(void)
{ {
char *tokptr[SH_MAX_ARGS + 1]; char *tokptr[SH_MAX_ARGS + 1];
struct wrc_shell_cmd *p; struct wrc_shell_cmd *p;
......
...@@ -253,7 +253,7 @@ static inline void update_loops(struct softpll_state *s, int tag_value, int tag_ ...@@ -253,7 +253,7 @@ static inline void update_loops(struct softpll_state *s, int tag_value, int tag_
} }
} }
void _irq_entry() void _irq_entry(void)
{ {
struct softpll_state *s = (struct softpll_state *)&softpll; struct softpll_state *s = (struct softpll_state *)&softpll;
...@@ -395,7 +395,7 @@ void spll_stop_channel(int channel) ...@@ -395,7 +395,7 @@ void spll_stop_channel(int channel)
mpll_stop(&s->aux[channel - 1].pll.dmtd); mpll_stop(&s->aux[channel - 1].pll.dmtd);
} }
int spll_ext_locked() int spll_ext_locked(void)
{ {
return external_locked( (struct spll_external_state *) &softpll.ext); return external_locked( (struct spll_external_state *) &softpll.ext);
} }
...@@ -531,7 +531,7 @@ static inline void aux_set_channel_status(int channel, int locked) ...@@ -531,7 +531,7 @@ static inline void aux_set_channel_status(int channel, int locked)
SPLL->OCCR |= (SPLL_OCCR_OUT_LOCK_W((1 << channel))); SPLL->OCCR |= (SPLL_OCCR_OUT_LOCK_W((1 << channel)));
} }
int spll_update_aux_clocks() int spll_update_aux_clocks(void)
{ {
int ch; int ch;
......
...@@ -60,10 +60,10 @@ Initializes the SoftPLL to work in mode (mode). Extra parameters depend on choic ...@@ -60,10 +60,10 @@ Initializes the SoftPLL to work in mode (mode). Extra parameters depend on choic
- for SPLL_MODE_SLAVE: (ref_channel) indicates the reference channel to which we are locking our PLL. - for SPLL_MODE_SLAVE: (ref_channel) indicates the reference channel to which we are locking our PLL.
*/ */
void spll_init(int mode, int ref_channel, int align_pps); void spll_init(int mode, int ref_channel, int align_pps);
void spll_very_init(); void spll_very_init(void);
/* Disables the SoftPLL and cleans up stuff */ /* Disables the SoftPLL and cleans up stuff */
void spll_shutdown(); void spll_shutdown(void);
/* Returns number of reference and output channels implemented in HW. */ /* Returns number of reference and output channels implemented in HW. */
void spll_get_num_channels(int *n_ref, int *n_out); void spll_get_num_channels(int *n_ref, int *n_out);
...@@ -109,7 +109,7 @@ int spll_read_ptracker(int ref_channel, int32_t *phase_ps, int *enabled); ...@@ -109,7 +109,7 @@ int spll_read_ptracker(int ref_channel, int32_t *phase_ps, int *enabled);
/* Calls non-realtime update state machine. Must be called regularly (although /* Calls non-realtime update state machine. Must be called regularly (although
* it is not time-critical) in the main loop of the program if aux clocks or * it is not time-critical) in the main loop of the program if aux clocks or
* external reference are used in the design. */ * external reference are used in the design. */
void spll_update(); void spll_update(void);
/* Returns the status of given aux clock output (SPLL_AUX_) */ /* Returns the status of given aux clock output (SPLL_AUX_) */
int spll_get_aux_status(int out_channel); int spll_get_aux_status(int out_channel);
...@@ -118,7 +118,7 @@ const char *spll_get_aux_status_string(int channel); ...@@ -118,7 +118,7 @@ const char *spll_get_aux_status_string(int channel);
/* Debug/testing functions */ /* Debug/testing functions */
/* Returns how many time the PLL has de-locked since last call of spll_init() */ /* Returns how many time the PLL has de-locked since last call of spll_init() */
int spll_get_delock_count(); int spll_get_delock_count(void);
void spll_show_stats(void); void spll_show_stats(void);
...@@ -128,7 +128,7 @@ void spll_set_dac(int out_channel, int value); ...@@ -128,7 +128,7 @@ void spll_set_dac(int out_channel, int value);
/* Returns current DAC sample value for output (out_channel) */ /* Returns current DAC sample value for output (out_channel) */
int spll_get_dac(int out_channel); int spll_get_dac(int out_channel);
void check_vco_frequencies(); void check_vco_frequencies(void);
#define SPLL_STATS_VER 2 #define SPLL_STATS_VER 2
......
...@@ -44,7 +44,7 @@ int32_t sfp_deltaTx = 0; ...@@ -44,7 +44,7 @@ int32_t sfp_deltaTx = 0;
int32_t sfp_deltaRx = 0; int32_t sfp_deltaRx = 0;
uint32_t cal_phase_transition = 2389; uint32_t cal_phase_transition = 2389;
static void wrc_initialize() static void wrc_initialize(void)
{ {
uint8_t mac_addr[6]; uint8_t mac_addr[6];
...@@ -105,7 +105,7 @@ static void wrc_initialize() ...@@ -105,7 +105,7 @@ static void wrc_initialize()
#define LINK_UP 3 #define LINK_UP 3
#define LINK_DOWN 4 #define LINK_DOWN 4
static int wrc_check_link() static int wrc_check_link(void)
{ {
static int prev_link_state = -1; static int prev_link_state = -1;
int link_state = ep_link_up(NULL); int link_state = ep_link_up(NULL);
...@@ -143,7 +143,7 @@ void wrc_debug_printf(int subsys, const char *fmt, ...) ...@@ -143,7 +143,7 @@ void wrc_debug_printf(int subsys, const char *fmt, ...)
int wrc_man_phase = 0; int wrc_man_phase = 0;
static void ui_update() static void ui_update(void)
{ {
if (wrc_ui_mode == UI_GUI_MODE) { if (wrc_ui_mode == UI_GUI_MODE) {
......
...@@ -7,11 +7,11 @@ ...@@ -7,11 +7,11 @@
#define WRC_MODE_SLAVE 3 #define WRC_MODE_SLAVE 3
extern int ptp_mode; extern int ptp_mode;
int wrc_ptp_init(); int wrc_ptp_init(void);
int wrc_ptp_set_mode(int mode); int wrc_ptp_set_mode(int mode);
int wrc_ptp_get_mode(); int wrc_ptp_get_mode(void);
int wrc_ptp_start(); int wrc_ptp_start(void);
int wrc_ptp_stop(); int wrc_ptp_stop(void);
int wrc_ptp_update(); int wrc_ptp_update(void);
#endif #endif
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment