Commit 6ae2239e authored by Grzegorz Daniluk's avatar Grzegorz Daniluk

more fixes to compilation warnings pt.2

parent 905118c4
Pipeline #311 failed with stages
in 9 seconds
......@@ -22,6 +22,7 @@
#include "board.h"
#include "dev/gpio.h"
#include "dev/74x595.h"
#define X595_GPIO_MAX 2
......
......@@ -38,7 +38,7 @@ void ad9520_write(struct ad9520_device *dev, uint32_t reg, uint8_t value)
uint8_t ad9520_read(struct ad9520_device *dev, uint32_t reg) {
uint8_t rv;
bb_i2c_start( dev->bus );
int ack = bb_i2c_put_byte( dev->bus, dev->addr << 1 );
bb_i2c_put_byte( dev->bus, dev->addr << 1 );
bb_i2c_put_byte( dev->bus, reg >> 8);
bb_i2c_put_byte( dev->bus, reg & 0xff);
bb_i2c_repeat_start( dev->bus );
......
......@@ -151,11 +151,11 @@ void bb_spi_xfer(struct spi_bus *bus, uint64_t din, uint64_t *d_out, int n_bits)
* set SPI speed by configuring bit delay
*/
int bb_spi_create( struct spi_bus *bus,
struct gpio_pin *pin_cs,
struct gpio_pin *pin_mosi,
struct gpio_pin *pin_miso,
struct gpio_pin *pin_sck,
void bb_spi_create( struct spi_bus *bus,
const struct gpio_pin *pin_cs,
const struct gpio_pin *pin_mosi,
const struct gpio_pin *pin_miso,
const struct gpio_pin *pin_sck,
int bit_delay
)
{
......
......@@ -21,11 +21,11 @@ void wb_cm_set_ref_frequency( struct wb_clock_monitor_device *dev, int ref_freq
int wb_cm_restart( struct wb_clock_monitor_device *dev )
{
uint32_t cr = readl( dev->base + CM_REG_CR );
uint32_t cr = readl( (void *) (dev->base + CM_REG_CR) );
cr |= CM_CR_CNT_RST;
dev->freq_valid_mask = 0;
writel( cr, dev->base + CM_REG_CR );
writel( cr, (void *) (dev->base + CM_REG_CR) );
return 0;
}
......@@ -37,8 +37,8 @@ int wb_cm_configure( struct wb_clock_monitor_device *dev, int ref_sel, int pres
dev->gate_freq = gate_freq;
writel( (dev->ref_sel << CM_CR_REFSEL_SHIFT)
| (dev->prescaler << CM_CR_PRESC_SHIFT), dev->base + CM_REG_CR );
writel( dev->gate_freq, dev->base + CM_REG_REFDR );
| (dev->prescaler << CM_CR_PRESC_SHIFT), (void *) (dev->base + CM_REG_CR) );
writel( dev->gate_freq, (void *) (dev->base + CM_REG_REFDR) );
return wb_cm_restart(dev);
}
......@@ -51,8 +51,8 @@ int wb_cm_read(struct wb_clock_monitor_device *dev)
//pp_printf("CmRead\n");
for(i = 0; i < dev->n_channels; i++)
{
writel( i, dev->base + CM_REG_CNT_SEL );
rv = readl ( dev->base + CM_REG_CNT_VAL );
writel( i, (void *) (dev->base + CM_REG_CNT_SEL) );
rv = readl ( (void *) (dev->base + CM_REG_CNT_VAL) );
if( rv & CM_CNT_VAL_VALID )
{
// pp_printf("f%d %d\n", i, rv & 0x7fffffff);
......@@ -60,7 +60,7 @@ int wb_cm_read(struct wb_clock_monitor_device *dev)
dev->freq_valid_mask |= (1<<i);
n_new++;
}
writel( CM_CNT_VAL_VALID, dev->base + CM_REG_CNT_VAL );
writel( CM_CNT_VAL_VALID, (void *) (dev->base + CM_REG_CNT_VAL) );
}
//pp_printf("Nn %d\n", n_new );
......
......@@ -76,8 +76,8 @@ void pfilter_init_default(void)
return;
}
vini = s->ini;
vend = s->ini + s->size;
vini = (uint32_t *) s->ini;
vend = (uint32_t *) (s->ini + s->size);
/*
* The array of words starts with 0x11223344 so we
......
......@@ -21,7 +21,7 @@
struct spi_bus spi_wrc_flash;
struct spi_flash_device wrc_flash_dev;
void flash_init(void)
void flash_init(void)
{
bb_spi_create( &spi_wrc_flash,
&pin_sysc_spi_ncs,
......@@ -30,6 +30,4 @@ void flash_init(void)
&pin_sysc_spi_sclk, 10 );
spi_flash_create( &wrc_flash_dev, &spi_wrc_flash, 16384, 0 );
return 0;
}
......@@ -34,13 +34,13 @@
#include <hw/wb_insn_uart.h>
#include <hw/wb_uart.h>
void
static void
iuart_writel(struct iuart_device *dev, uint32_t val, uint32_t reg)
{
writel( val, (void*) (dev->base + reg) );
}
uint32_t
static uint32_t
iuart_readl(struct iuart_device *dev, uint32_t reg)
{
return readl( (void*) dev->base + reg );
......@@ -61,7 +61,7 @@ iuart_fifo_space(struct iuart_device *dev, uint16_t fifo_size, uint16_t fifo_cnt
return (fifo_size - fifo_cnt);
}
void
static void
iuart_uart_en(struct iuart_device *dev, uint8_t val)
{
iuart_writel(dev, val, IUART_REG_UART_EN);
......@@ -290,7 +290,7 @@ iuart_da_cpl(struct iuart_device *dev, uint32_t cpldata)
unsigned
static unsigned
iuart_rxd_start(uint8_t rxbyte, uint8_t pchar)
{
if (pchar != ESC_CHAR_VAL)
......@@ -303,7 +303,7 @@ iuart_rxd_start(uint8_t rxbyte, uint8_t pchar)
}
unsigned
static unsigned
iuart_rxd_end(uint8_t rxbyte, uint8_t pchar)
{
if (pchar != ESC_CHAR_VAL)
......@@ -586,4 +586,4 @@ int iuart_init_hosted(struct iuart_device *dev)
return 0;
}
#endif
\ No newline at end of file
#endif
......@@ -161,7 +161,7 @@ const struct storage_rwops spi_w1_rwops = {
};
/* The methods for W1 access */
/* The methods for I2C access */
static int sdb_i2c_eeprom_read(struct storage_device *dev, int offset, void *buf, int count)
{
struct storage_i2c_eeprom_priv *priv = (struct storage_i2c_eeprom_priv* ) dev->priv;
......@@ -180,17 +180,23 @@ static int sdb_i2c_eeprom_erase(struct storage_device *dev, int offset, int coun
return i2c_eeprom_erase(priv->dev, offset, count);
}
const struct storage_rwops i2c_eeprom_rwops = {
sdb_i2c_eeprom_read,
sdb_i2c_eeprom_write,
sdb_i2c_eeprom_erase
};
void storage_spiflash_create(struct storage_device *dev, struct spi_flash_device *flash)
{
static const char* spi_flash_str = "spi-flash";
dev->name = (char *) spi_flash_str;
dev->priv = flash;
dev->rwops = &spi_flash_rwops;
dev->rwops = (struct storage_rwops *) &spi_flash_rwops;
dev->size = flash->size;
dev->cfg_entry = flash->cfg_entry;
dev->block_size = flash->sector_size;
dev->entry_points = spi_flash_default_entry_points;
dev->entry_points = (int32_t *) spi_flash_default_entry_points;
dev->flags = STORAGE_FLAG_DEVICE_OK;
}
......@@ -652,7 +658,7 @@ static wrc_cal_data_t cal_data;
static int calc_checksum( wrc_cal_data_t* cal )
{
int i;
uint32_t cksum;
uint32_t cksum = 0;
cksum += cal->magic;
cksum += cal->param_count;
for(i = 0; i < cal->param_count; i++)
......@@ -821,8 +827,8 @@ int storage_phtrans(uint32_t *valp, uint8_t write)
int storage_get_persistent_mac(uint8_t *mac)
{
int ret = 0;
int i;
struct w1_dev *d;
//int i;
//struct w1_dev *d;
// fixme: we should mock entire storage in a host process, not put
// such compile-time ifs() in target code
......@@ -1055,7 +1061,7 @@ static int sdbfs_erase_callback(struct sdbfs *fs, int offset, int count)
int storage_mount( struct storage_device *dev )
{
uint32_t magic = 0;
int i, ret;
int i;
/* Check if there is SDBFS in the memory */
......@@ -1115,6 +1121,8 @@ int storage_sdbfs_erase( struct storage_device *dev, uint32_t addr, int force_ba
sdbfs_erase_callback( &wrc_sdbfs, base_addr + count, wrc_sdbfs.blocksize );
count += wrc_sdbfs.blocksize;
}
return 0;
}
int storage_sdbfs_format( struct storage_device *dev, uint32_t addr, int force_base )
......@@ -1128,7 +1136,6 @@ int storage_sdbfs_format( struct storage_device *dev, uint32_t addr, int force_b
int i;
char buf[19] = {0};
int cur_adr, size;
uint32_t val;
uint32_t base_addr;
if (force_base)
......@@ -1166,7 +1173,8 @@ int storage_sdbfs_format( struct storage_device *dev, uint32_t addr, int force_b
}
pp_printf("Formatting SDBFS in %s (base 0x%08x, size 0x%08x)...\n", dev->name, base_addr, SDBFS_REC * wrc_sdbfs.blocksize );
pp_printf("Formatting SDBFS in %s (base 0x%08x, size 0x%08x)...\n", dev->name,
base_addr, (uint32_t) (SDBFS_REC * wrc_sdbfs.blocksize) );
storage_sdbfs_erase(dev, addr, force_base);
......
......@@ -28,7 +28,7 @@ static int w1_reset(struct w1_bus *bus)
IOWR_SOCKIT_OWM_CTL(BASE_ONEWIRE, (portnum << SOCKIT_OWM_CTL_SEL_OFST)
| (SOCKIT_OWM_CTL_CYC_MSK)
| (SOCKIT_OWM_CTL_RST_MSK));
reg = __wait_cycle(BASE_ONEWIRE);
reg = __wait_cycle((void *) BASE_ONEWIRE);
/* return presence-detect pulse (1 if true) */
return (reg & SOCKIT_OWM_CTL_DAT_MSK) ? 0 : 1;
}
......@@ -41,7 +41,7 @@ static int w1_read_bit(struct w1_bus *bus)
IOWR_SOCKIT_OWM_CTL(BASE_ONEWIRE, (portnum << SOCKIT_OWM_CTL_SEL_OFST)
| (SOCKIT_OWM_CTL_CYC_MSK)
| (SOCKIT_OWM_CTL_DAT_MSK));
reg = __wait_cycle(BASE_ONEWIRE);
reg = __wait_cycle((void *) BASE_ONEWIRE);
return (reg & SOCKIT_OWM_CTL_DAT_MSK) ? 1 : 0;
}
......@@ -52,7 +52,7 @@ static void w1_write_bit(struct w1_bus *bus, int bit)
IOWR_SOCKIT_OWM_CTL(BASE_ONEWIRE, (portnum << SOCKIT_OWM_CTL_SEL_OFST)
| (SOCKIT_OWM_CTL_CYC_MSK)
| (bit ? SOCKIT_OWM_CTL_DAT_MSK : 0));
__wait_cycle(BASE_ONEWIRE);
__wait_cycle((void *) BASE_ONEWIRE);
}
struct w1_ops wrpc_w1_ops = {
......
......@@ -21,6 +21,6 @@
#ifndef __SN74x595_H
#define __SN74x595_H
int x595_gpio_create(struct gpio_device *device, int n_regs, const struct gpio_pin *pin_rclk, const struct gpio_pin *pin_srclk, const struct gpio_pin *pin_srclr_n, const struct gpio_pin *pin_ser);
int x595_gpio_create(struct gpio_device *device, int n_regs, const struct gpio_pin *pin_rclk, const struct gpio_pin *pin_srclk, struct gpio_pin *pin_srclr_n, struct gpio_pin *pin_ser);
#endif
......@@ -38,5 +38,7 @@ uint8_t ad9520_read(struct ad9520_device *dev, uint32_t reg);
void ad9520_soft_reset(struct ad9520_device *dev);
int ad9520_init(struct ad9520_device *dev, struct i2c_bus *bus, uint8_t addr);
int ad9520_configure(struct ad9520_device *dev, struct ad95xx_config *cfg);
int ad9520_enable_output(struct ad9520_device *dev, int channel, int enabled );
int ad9520_set_output_divider( struct ad9520_device *dev, int channel, int divider);
#endif
......@@ -24,5 +24,6 @@ void bb_i2c_stop(struct i2c_bus *bus);
void bb_i2c_get_byte(struct i2c_bus *bus, uint8_t *data, uint8_t last);
uint8_t bb_i2c_put_byte(struct i2c_bus *bus, uint8_t data);
void bb_i2c_delay(uint32_t delay);
void bb_i2c_scan(struct i2c_bus *bus);
#endif
......@@ -32,11 +32,11 @@ struct spi_bus
int rd_falling_edge;
};
int bb_spi_create( struct spi_bus *bus,
struct gpio_pin *pin_cs,
struct gpio_pin *pin_mosi,
struct gpio_pin *pin_miso,
struct gpio_pin *pin_sck,
void bb_spi_create( struct spi_bus *bus,
const struct gpio_pin *pin_cs,
const struct gpio_pin *pin_mosi,
const struct gpio_pin *pin_miso,
const struct gpio_pin *pin_sck,
int bit_delay
);
......
......@@ -43,7 +43,7 @@ struct fine_pulse_gen_channel {
};
struct fine_pulse_gen_device {
uint32_t base;
void *base;
struct fine_pulse_gen_channel channels[FINE_PULSE_GEN_MAX_CHANNELS];
};
......
......@@ -90,6 +90,7 @@ void iuart_da_write_ctrl(struct iuart_device *dev, uint8_t val);
void iuart_da_write(struct iuart_device *dev, uint8_t *buf, uint32_t addr, uint32_t size);
void iuart_da_read(struct iuart_device *dev, uint32_t addr, uint32_t size);
void iuart_da_cpl(struct iuart_device *dev, uint32_t cpldata);
void iuart_da_read_ctrl(struct iuart_device *dev);
int iuart_da_wait_completion( struct iuart_device *dev, uint8_t* data, int size );
int iuart_da_read_blocking(struct iuart_device *dev, uint32_t addr, uint8_t *data, uint32_t size);
......
......@@ -34,13 +34,14 @@ static int cmd_diag(const char *args[])
for(i=0; i<nro; i++ )
{
ret = diag_read_word(i, DIAG_RO_BANK, &val);
pp_printf("RO word %-03d = 0x%08x\n", i, val );
pp_printf("RO word %-3d = 0x%08x\n", i, val );
}
for(i=0; i<nrw; i++ )
{
ret = diag_read_word(i, DIAG_RW_BANK, &val);
pp_printf("RW word %-03d = 0x%08x\n", i, val );
pp_printf("RW word %-3d = 0x%08x\n", i, val );
}
return ret;
}
if (!strcasecmp(args[0], "ro") && args[1]) {
......
......@@ -295,7 +295,7 @@ void spll_very_init()
PPSG->ESCR = 0;
PPSG->CR = PPSG_CR_CNT_EN | PPSG_CR_CNT_RST | PPSG_CR_PWIDTH_W(PPS_WIDTH);
memset( &softpll, 0, sizeof(struct softpll_state ));
memset( (void *) &softpll, 0, sizeof(struct softpll_state ));
softpll.mode = SPLL_MODE_DISABLED;
}
......
......@@ -14,7 +14,7 @@
#include <wrc.h>
#include "softpll_ng.h"
int gen_dither( int pi_shift )
static int gen_dither( int pi_shift )
{
static const uint32_t lcg_m = 1103515245;
static const uint32_t lcg_i = 12345;
......
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