Commit ef74eb64 authored by Alessandro Rubini's avatar Alessandro Rubini

userspace/libwr: massive Lindent pass

This is a completely automatic pass, before we start making order
in this library (note: there is a missing semicolon in pps_gen.c:82
but it will be fixed in a later commit -- the bug is in the macro
being called, so the missing semicolon is ok for the compiler).
Signed-off-by: Alessandro Rubini's avatarAlessandro Rubini <rubini@gnudd.com>
parent f2b39316
...@@ -48,32 +48,31 @@ static int is_cpu_pwn = 0; ...@@ -48,32 +48,31 @@ static int is_cpu_pwn = 0;
static int enable_d0 = 0; static int enable_d0 = 0;
static i2c_fpga_reg_t fpga_sensors_bus_master = { static i2c_fpga_reg_t fpga_sensors_bus_master = {
.base_address = FPGA_I2C_ADDRESS, .base_address = FPGA_I2C_ADDRESS,
.if_num = FPGA_I2C_SENSORS_IFNUM, .if_num = FPGA_I2C_SENSORS_IFNUM,
.prescaler = 500, .prescaler = 500,
}; };
static struct i2c_bus fpga_sensors_i2c = { static struct i2c_bus fpga_sensors_i2c = {
.name = "fpga_sensors", .name = "fpga_sensors",
.type = I2C_BUS_TYPE_FPGA_REG, .type = I2C_BUS_TYPE_FPGA_REG,
.type_specific = &fpga_sensors_bus_master, .type_specific = &fpga_sensors_bus_master,
}; };
#define PI_FRACBITS 8 #define PI_FRACBITS 8
/* PI regulator state */ /* PI regulator state */
typedef struct { typedef struct {
float ki, kp; /* integral and proportional gains (1<<PI_FRACBITS == 1.0f) */ float ki, kp; /* integral and proportional gains (1<<PI_FRACBITS == 1.0f) */
float integrator; /* current integrator value */ float integrator; /* current integrator value */
float bias; /* DC offset always added to the output */ float bias; /* DC offset always added to the output */
int anti_windup; /* when non-zero, anti-windup is enabled */ int anti_windup; /* when non-zero, anti-windup is enabled */
float y_min; /* min/max output range, used by clapming and antiwindup algorithms */ float y_min; /* min/max output range, used by clapming and antiwindup algorithms */
float y_max; float y_max;
float x, y; /* Current input (x) and output value (y) */ float x, y; /* Current input (x) and output value (y) */
} pi_controller_t; } pi_controller_t;
static pi_controller_t fan_pi; static pi_controller_t fan_pi;
//----------------------------------------- //-----------------------------------------
//-- Old CPU PWM system (<3.3) //-- Old CPU PWM system (<3.3)
static int pwm_fd; static int pwm_fd;
...@@ -83,13 +82,13 @@ static volatile struct SPWM_WB *spwm_wbr; ...@@ -83,13 +82,13 @@ static volatile struct SPWM_WB *spwm_wbr;
static void shw_pwm_update_timeout(int tout_100ms) static void shw_pwm_update_timeout(int tout_100ms)
{ {
fan_update_timeout=tout_100ms*100000; fan_update_timeout = tout_100ms * 100000;
TRACE(TRACE_INFO,"Fan tick timeout is =%d",fan_update_timeout); TRACE(TRACE_INFO, "Fan tick timeout is =%d", fan_update_timeout);
} }
/* Processes a single sample (x) with Proportional Integrator control algorithm (pi). Returns the value (y) to /* Processes a single sample (x) with Proportional Integrator control algorithm (pi). Returns the value (y) to
drive the actuator. */ drive the actuator. */
static inline float pi_update(pi_controller_t *pi, float x) static inline float pi_update(pi_controller_t * pi, float x)
{ {
float i_new, y; float i_new, y;
pi->x = x; pi->x = x;
...@@ -100,80 +99,79 @@ static inline float pi_update(pi_controller_t *pi, float x) ...@@ -100,80 +99,79 @@ static inline float pi_update(pi_controller_t *pi, float x)
/* clamping (output has to be in <y_min, y_max>) and anti-windup: /* clamping (output has to be in <y_min, y_max>) and anti-windup:
stop the integrator if the output is already out of range and the output stop the integrator if the output is already out of range and the output
is going further away from y_min/y_max. */ is going further away from y_min/y_max. */
if(y < pi->y_min) if (y < pi->y_min) {
{
y = pi->y_min; y = pi->y_min;
if((pi->anti_windup && (i_new > pi->integrator)) || !pi->anti_windup) if ((pi->anti_windup && (i_new > pi->integrator))
|| !pi->anti_windup)
pi->integrator = i_new; pi->integrator = i_new;
} else if (y > pi->y_max) { } else if (y > pi->y_max) {
y = pi->y_max; y = pi->y_max;
if((pi->anti_windup && (i_new < pi->integrator)) || !pi->anti_windup) if ((pi->anti_windup && (i_new < pi->integrator))
pi->integrator = i_new; || !pi->anti_windup)
} else /* No antiwindup/clamping? */
pi->integrator = i_new; pi->integrator = i_new;
} else /* No antiwindup/clamping? */
pi->integrator = i_new;
pi->y = y; pi->y = y;
return y; return y;
} }
/* initializes the PI controller state. Currently almost a stub. */ /* initializes the PI controller state. Currently almost a stub. */
static inline void pi_init(pi_controller_t *pi) static inline void pi_init(pi_controller_t * pi)
{ {
pi->integrator = 0; pi->integrator = 0;
} }
/* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */ /* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */
static void pwm_configure_pin(const pio_pin_t *pin, int enable, int rate) static void pwm_configure_pin(const pio_pin_t * pin, int enable, int rate)
{ {
int index = pin->port * 32 + pin->pin; int index = pin->port * 32 + pin->pin;
if(pin==0) return; if (pin == 0)
return;
if(enable && !enable_d0) if (enable && !enable_d0)
ioctl(pwm_fd, AT91_SOFTPWM_ENABLE, index); ioctl(pwm_fd, AT91_SOFTPWM_ENABLE, index);
else if(!enable && enable_d0) else if (!enable && enable_d0)
ioctl(pwm_fd, AT91_SOFTPWM_DISABLE, index); ioctl(pwm_fd, AT91_SOFTPWM_DISABLE, index);
enable_d0 = enable; enable_d0 = enable;
ioctl(pwm_fd, AT91_SOFTPWM_SETPOINT, rate); ioctl(pwm_fd, AT91_SOFTPWM_SETPOINT, rate);
} }
/* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */ /* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */
static void pwm_configure_fpga(int enmask, float rate) static void pwm_configure_fpga(int enmask, float rate)
{ {
uint8_t u8speed=(uint8_t)((rate>=1)?0xff:(rate*255.0)); uint8_t u8speed = (uint8_t) ((rate >= 1) ? 0xff : (rate * 255.0));
if((enmask & 0x1)>0) spwm_wbr->DR0=u8speed; if ((enmask & 0x1) > 0)
if((enmask & 0x2)>0) spwm_wbr->DR1=u8speed; spwm_wbr->DR0 = u8speed;
if ((enmask & 0x2) > 0)
spwm_wbr->DR1 = u8speed;
} }
/* Configures a PWM output. Rate accepts range is from 0 (0%) to 1 (100%) */ /* Configures a PWM output. Rate accepts range is from 0 (0%) to 1 (100%) */
static void shw_pwm_speed(int enmask, float rate) static void shw_pwm_speed(int enmask, float rate)
{ {
//TRACE(TRACE_INFO,"%x %f",enmask,rate); //TRACE(TRACE_INFO,"%x %f",enmask,rate);
if(is_cpu_pwn) if (is_cpu_pwn) {
{ pwm_configure_pin(get_pio_pin(shw_io_box_fan_en), enmask,
pwm_configure_pin(get_pio_pin(shw_io_box_fan_en), enmask, rate*1000); rate * 1000);
} } else {
else pwm_configure_fpga(enmask, rate);
{
pwm_configure_fpga(enmask,rate);
} }
} }
/* Texas Instruments TMP100 temperature sensor driver */ /* Texas Instruments TMP100 temperature sensor driver */
static uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes) static uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes)
{ {
uint8_t data[8]; uint8_t data[8];
uint32_t rv=0, i; uint32_t rv = 0, i;
data[0] = reg_addr; data[0] = reg_addr;
i2c_write(&fpga_sensors_i2c, dev_addr, 1, data); i2c_write(&fpga_sensors_i2c, dev_addr, 1, data);
i2c_read(&fpga_sensors_i2c, dev_addr, n_bytes, data); i2c_read(&fpga_sensors_i2c, dev_addr, n_bytes, data);
for(i=0; i<n_bytes;i++) for (i = 0; i < n_bytes; i++) {
{
rv <<= 8; rv <<= 8;
rv |= data[i]; rv |= data[i];
} }
...@@ -181,8 +179,6 @@ static uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes) ...@@ -181,8 +179,6 @@ static uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes)
return rv; return rv;
} }
static void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value) static void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value)
{ {
uint8_t data[2]; uint8_t data[2];
...@@ -192,17 +188,17 @@ static void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value) ...@@ -192,17 +188,17 @@ static void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value)
i2c_write(&fpga_sensors_i2c, dev_addr, 2, data); i2c_write(&fpga_sensors_i2c, dev_addr, 2, data);
} }
static float tmp100_read_temp(int dev_addr) static float tmp100_read_temp(int dev_addr)
{ {
int temp = tmp100_read_reg(dev_addr, 0, 2); int temp = tmp100_read_reg(dev_addr, 0, 2);
return ((float) (temp >> 4)) / 16.0; return ((float)(temp >> 4)) / 16.0;
} }
static int shw_init_i2c_sensors() static int shw_init_i2c_sensors()
{ {
if (i2c_init_bus(&fpga_sensors_i2c) < 0) { if (i2c_init_bus(&fpga_sensors_i2c) < 0) {
TRACE(TRACE_FATAL, "can't initialize temperature sensors I2C bus.\n"); TRACE(TRACE_FATAL,
"can't initialize temperature sensors I2C bus.\n");
return -1; return -1;
} }
return 0; return 0;
...@@ -210,20 +206,23 @@ static int shw_init_i2c_sensors() ...@@ -210,20 +206,23 @@ static int shw_init_i2c_sensors()
int shw_init_fans() int shw_init_fans()
{ {
uint32_t val=0; uint32_t val = 0;
//Set the type of PWM //Set the type of PWM
if(shw_get_hw_ver()<330) is_cpu_pwn=1; if (shw_get_hw_ver() < 330)
else is_cpu_pwn=0; is_cpu_pwn = 1;
else
is_cpu_pwn = 0;
TRACE(TRACE_INFO, "Configuring %s PWMs for fans (desired temperature = %.1f degC)...",is_cpu_pwn?"CPU":"FPGA",DESIRED_TEMPERATURE); TRACE(TRACE_INFO,
"Configuring %s PWMs for fans (desired temperature = %.1f degC)...",
is_cpu_pwn ? "CPU" : "FPGA", DESIRED_TEMPERATURE);
if(is_cpu_pwn) if (is_cpu_pwn) {
{
pwm_fd = open("/dev/at91_softpwm", O_RDWR); pwm_fd = open("/dev/at91_softpwm", O_RDWR);
if(pwm_fd < 0) if (pwm_fd < 0) {
{ TRACE(TRACE_FATAL,
TRACE(TRACE_FATAL, "at91_softpwm driver not installed or device not created.\n"); "at91_softpwm driver not installed or device not created.\n");
return -1; return -1;
} }
...@@ -232,15 +231,15 @@ int shw_init_fans() ...@@ -232,15 +231,15 @@ int shw_init_fans()
fan_pi.y_min = 200; fan_pi.y_min = 200;
fan_pi.bias = 200; fan_pi.bias = 200;
fan_pi.y_max = 800; fan_pi.y_max = 800;
} } else {
else
{
//Point to the corresponding WB direction //Point to the corresponding WB direction
spwm_wbr= (volatile struct SPWM_WB *) (FPGA_BASE_ADDR + FPGA_BASE_SPWM); spwm_wbr =
(volatile struct SPWM_WB *)(FPGA_BASE_ADDR +
FPGA_BASE_SPWM);
//Configure SPWM register the 30~=(62.5MHz÷(8kHz×2^8))−1 //Configure SPWM register the 30~=(62.5MHz÷(8kHz×2^8))−1
val= SPWM_CR_PRESC_W(30) | SPWM_CR_PERIOD_W(255); val = SPWM_CR_PRESC_W(30) | SPWM_CR_PERIOD_W(255);
spwm_wbr->CR=val; spwm_wbr->CR = val;
fan_pi.ki = 1.0; fan_pi.ki = 1.0;
fan_pi.kp = 4.0; fan_pi.kp = 4.0;
...@@ -251,7 +250,7 @@ int shw_init_fans() ...@@ -251,7 +250,7 @@ int shw_init_fans()
shw_init_i2c_sensors(); shw_init_i2c_sensors();
tmp100_write_reg(FAN_TEMP_SENSOR_ADDR, 1, 0x60); // 12-bit resolution tmp100_write_reg(FAN_TEMP_SENSOR_ADDR, 1, 0x60); // 12-bit resolution
pi_init(&fan_pi); pi_init(&fan_pi);
...@@ -260,7 +259,6 @@ int shw_init_fans() ...@@ -260,7 +259,6 @@ int shw_init_fans()
return 0; return 0;
} }
/* /*
* Reads out the temperature and drives the fan accordingly * Reads out the temperature and drives the fan accordingly
* note: This call is done by hal_main.c:hal_update() * note: This call is done by hal_main.c:hal_update()
...@@ -270,13 +268,12 @@ void shw_update_fans() ...@@ -270,13 +268,12 @@ void shw_update_fans()
static int64_t last_tics = -1; static int64_t last_tics = -1;
int64_t cur_tics = shw_get_tics(); int64_t cur_tics = shw_get_tics();
if(fan_update_timeout>0 && (last_tics < 0 || (cur_tics - last_tics) > fan_update_timeout)) if (fan_update_timeout > 0
{ && (last_tics < 0 || (cur_tics - last_tics) > fan_update_timeout)) {
float t_cur = tmp100_read_temp(FAN_TEMP_SENSOR_ADDR); float t_cur = tmp100_read_temp(FAN_TEMP_SENSOR_ADDR);
float drive = pi_update(&fan_pi, t_cur - DESIRED_TEMPERATURE); float drive = pi_update(&fan_pi, t_cur - DESIRED_TEMPERATURE);
//TRACE(TRACE_INFO,"t=%f,pwm=%f",t_cur , drive); //TRACE(TRACE_INFO,"t=%f,pwm=%f",t_cur , drive);
shw_pwm_speed(0xFF, drive/1000); //enable two and one shw_pwm_speed(0xFF, drive / 1000); //enable two and one
last_tics = cur_tics; last_tics = cur_tics;
} }
} }
...@@ -22,25 +22,27 @@ volatile uint8_t *_fpga_base_virt; ...@@ -22,25 +22,27 @@ volatile uint8_t *_fpga_base_virt;
/* Initializes the mapping of the Main FPGA to the CPU address space. */ /* Initializes the mapping of the Main FPGA to the CPU address space. */
int shw_fpga_mmap_init() int shw_fpga_mmap_init()
{ {
int fd; int fd;
TRACE(TRACE_INFO, "Initializing FPGA memory mapping."); TRACE(TRACE_INFO, "Initializing FPGA memory mapping.");
fd = open("/dev/mem", O_RDWR | O_SYNC); fd = open("/dev/mem", O_RDWR | O_SYNC);
if (fd < 0) { if (fd < 0) {
perror("/dev/mem"); perror("/dev/mem");
return -1; return -1;
} }
_fpga_base_virt = mmap(NULL, SMC_CS0_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED, fd, SMC_CS0_BASE); _fpga_base_virt =
close(fd); mmap(NULL, SMC_CS0_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED, fd,
SMC_CS0_BASE);
close(fd);
if(_fpga_base_virt == MAP_FAILED) { if (_fpga_base_virt == MAP_FAILED) {
perror("mmap()"); perror("mmap()");
return -1; return -1;
} }
TRACE(TRACE_INFO, "FPGA virtual base = 0x%08x", _fpga_base_virt); TRACE(TRACE_INFO, "FPGA virtual base = 0x%08x", _fpga_base_virt);
return 0; return 0;
} }
...@@ -7,7 +7,7 @@ ...@@ -7,7 +7,7 @@
#define HAL_EXPORT_STRUCTURES #define HAL_EXPORT_STRUCTURES
#include "hal_exports.h" #include "hal_exports.h"
#define DEFAULT_TO 200000 /* ms */ #define DEFAULT_TO 200000 /* ms */
static struct minipc_ch *hal_ch; static struct minipc_ch *hal_ch;
...@@ -21,56 +21,56 @@ int halexp_lock_cmd(const char *port_name, int command, int priority) ...@@ -21,56 +21,56 @@ int halexp_lock_cmd(const char *port_name, int command, int priority)
return rval; return rval;
} }
int halexp_query_ports(hexp_port_list_t *list) int halexp_query_ports(hexp_port_list_t * list)
{ {
int ret; int ret;
ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_query_ports, ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_query_ports,
list /* return val */); list /* return val */ );
return ret; return ret;
} }
int halexp_get_port_state(hexp_port_state_t *state, const char *port_name) int halexp_get_port_state(hexp_port_state_t * state, const char *port_name)
{ {
int ret; int ret;
ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_get_port_state, ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_get_port_state,
state /* retval */, port_name); state /* retval */ , port_name);
return ret; return ret;
} }
int halexp_pps_cmd(int cmd, hexp_pps_params_t *params) int halexp_pps_cmd(int cmd, hexp_pps_params_t * params)
{ {
int ret, rval; int ret, rval;
ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_pps_cmd, ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_pps_cmd,
&rval, cmd, params); &rval, cmd, params);
if (ret < 0) if (ret < 0)
return ret; return ret;
return rval; return rval;
} }
int halexp_get_timing_state(hexp_timing_state_t *tstate) int halexp_get_timing_state(hexp_timing_state_t * tstate)
{ {
int ret; int ret;
ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_get_timing_state, ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_get_timing_state,
tstate); tstate);
if (ret < 0) if (ret < 0)
return ret; return ret;
return 0; return 0;
} }
int halexp_client_try_connect(int retries, int timeout) int halexp_client_try_connect(int retries, int timeout)
{ {
for(;;) { for (;;) {
hal_ch = minipc_client_create(WRSW_HAL_SERVER_ADDR, MINIPC_FLAG_VERBOSE); hal_ch =
minipc_client_create(WRSW_HAL_SERVER_ADDR,
MINIPC_FLAG_VERBOSE);
if (hal_ch == 0) if (hal_ch == 0)
retries--; retries--;
else else
return 0; return 0;
if(!retries) if (!retries)
return -1; return -1;
usleep(timeout); usleep(timeout);
...@@ -79,8 +79,7 @@ int halexp_client_try_connect(int retries, int timeout) ...@@ -79,8 +79,7 @@ int halexp_client_try_connect(int retries, int timeout)
return -1; return -1;
} }
int halexp_client_init() int halexp_client_init()
{ {
return halexp_client_try_connect(0, 0); return halexp_client_try_connect(0, 0);
} }
\ No newline at end of file
...@@ -11,49 +11,49 @@ ...@@ -11,49 +11,49 @@
#define hwiu_read(reg) \ #define hwiu_read(reg) \
_fpga_readl(FPGA_BASE_HWIU + offsetof(struct HWIU_WB, reg)) _fpga_readl(FPGA_BASE_HWIU + offsetof(struct HWIU_WB, reg))
static int hwiu_read_word(uint32_t adr, uint32_t *data) static int hwiu_read_word(uint32_t adr, uint32_t * data)
{ {
uint32_t temp; uint32_t temp;
int timeout = 0; int timeout = 0;
temp = HWIU_CR_RD_EN | HWIU_CR_ADR_W(adr); temp = HWIU_CR_RD_EN | HWIU_CR_ADR_W(adr);
hwiu_write(CR, temp); hwiu_write(CR, temp);
do { do {
temp = hwiu_read(CR); temp = hwiu_read(CR);
++timeout; ++timeout;
} while( temp & HWIU_CR_RD_EN && timeout < HWIU_RD_TIMEOUT ); } while (temp & HWIU_CR_RD_EN && timeout < HWIU_RD_TIMEOUT);
if( timeout == HWIU_RD_TIMEOUT || temp & HWIU_CR_RD_ERR ) if (timeout == HWIU_RD_TIMEOUT || temp & HWIU_CR_RD_ERR)
return -1; return -1;
*data = hwiu_read(REG_VAL); *data = hwiu_read(REG_VAL);
return 0; return 0;
} }
int shw_hwiu_gwver(struct gw_info *info) int shw_hwiu_gwver(struct gw_info *info)
{ {
uint32_t data[HWIU_INFO_WORDS+1]; uint32_t data[HWIU_INFO_WORDS + 1];
struct gw_info *s_data; struct gw_info *s_data;
int i; int i;
//read first word of info struct //read first word of info struct
if( hwiu_read_word(HWIU_INFO_START, data) < 0 ) if (hwiu_read_word(HWIU_INFO_START, data) < 0)
return -1; return -1;
s_data = (struct gw_info *)data; s_data = (struct gw_info *)data;
*info = *s_data; *info = *s_data;
if( info->nwords != HWIU_INFO_WORDS ) { if (info->nwords != HWIU_INFO_WORDS) {
printf("nwords: sw=%u, hw=%u, ver=%u, data=%x\n", info->nwords, HWIU_INFO_WORDS, info->struct_ver, data[0]); printf("nwords: sw=%u, hw=%u, ver=%u, data=%x\n", info->nwords,
return -1; HWIU_INFO_WORDS, info->struct_ver, data[0]);
} return -1;
}
//now read info words //now read info words
for(i=0; i<info->nwords; ++i) { for (i = 0; i < info->nwords; ++i) {
if( hwiu_read_word(HWIU_INFO_WORDS_START+i, data+i+1) < 0 ) if (hwiu_read_word(HWIU_INFO_WORDS_START + i, data + i + 1) < 0)
return -1; return -1;
} }
*info = *( (struct gw_info*) data); *info = *((struct gw_info *)data);
return 0; return 0;
} }
...@@ -23,65 +23,64 @@ int i2c_init_bus(struct i2c_bus *bus) ...@@ -23,65 +23,64 @@ int i2c_init_bus(struct i2c_bus *bus)
return ret; return ret;
} }
int32_t i2c_transfer(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data) int32_t i2c_transfer(struct i2c_bus * bus, uint32_t address, uint32_t to_write,
uint32_t to_read, uint8_t * data)
{ {
return bus->transfer(bus, address, to_write, to_read, data); return bus->transfer(bus, address, to_write, to_read, data);
} }
void i2c_free(struct i2c_bus *bus)
void i2c_free(struct i2c_bus* bus)
{ {
if (!bus) if (!bus)
return; return;
if (bus->type_specific) if (bus->type_specific)
shw_free(bus->type_specific); shw_free(bus->type_specific);
shw_free(bus); shw_free(bus);
} }
int32_t i2c_write(struct i2c_bus *bus, uint32_t address, uint32_t to_write,
int32_t i2c_write(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint8_t* data) uint8_t * data)
{ {
//TRACE(TRACE_INFO,"%s (0x%X): 0x%X 2w:%d 2r:%d %d",bus->name,bus,address,to_write,0,data[0]); //TRACE(TRACE_INFO,"%s (0x%X): 0x%X 2w:%d 2r:%d %d",bus->name,bus,address,to_write,0,data[0]);
return bus->transfer(bus, address, to_write, 0, data); return bus->transfer(bus, address, to_write, 0, data);
} }
int32_t i2c_read(struct i2c_bus * bus, uint32_t address, uint32_t to_read,
int32_t i2c_read (struct i2c_bus* bus, uint32_t address, uint32_t to_read, uint8_t* data) uint8_t * data)
{ {
return bus->transfer(bus, address, 0, to_read, data); return bus->transfer(bus, address, 0, to_read, data);
//TRACE(TRACE_INFO,"%s (0x%X): 0x%X 2w:%d 2r:%d %d",bus->name,bus,address,0,to_read,data[0]); //TRACE(TRACE_INFO,"%s (0x%X): 0x%X 2w:%d 2r:%d %d",bus->name,bus,address,0,to_read,data[0]);
} }
int32_t i2c_scan(struct i2c_bus * bus, uint8_t * data)
int32_t i2c_scan(struct i2c_bus* bus, uint8_t* data)
{ {
if (!bus) if (!bus)
return I2C_NULL_PARAM; return I2C_NULL_PARAM;
// const int devices = 128; // const int devices = 128;
int address; int address;
const int first_valid_address = 0; const int first_valid_address = 0;
const int last_valid_address = 0x7f; const int last_valid_address = 0x7f;
memset((void*)data, 0, 16); //16 bytes * 8 addresses per byte == 128 addresses memset((void *)data, 0, 16); //16 bytes * 8 addresses per byte == 128 addresses
int found = 0; int found = 0;
for (address = first_valid_address; address <= last_valid_address; address++) for (address = first_valid_address; address <= last_valid_address;
{ address++) {
int res = bus->scan(bus, address); int res = bus->scan(bus, address);
if (res) //device present if (res) //device present
{ {
int offset = address >> 3; //choose proper byte int offset = address >> 3; //choose proper byte
int bit = (1 << (address%8)); //choose proper bit int bit = (1 << (address % 8)); //choose proper bit
data[offset] |= bit; data[offset] |= bit;
found++; found++;
}
} }
} TRACE(TRACE_INFO, "%s (0x%X): ndev=%d", bus->name, bus, found);
TRACE(TRACE_INFO,"%s (0x%X): ndev=%d",bus->name,bus,found); return found;
return found;
} }
...@@ -21,26 +21,27 @@ ...@@ -21,26 +21,27 @@
#define I2C_WRITE 0 #define I2C_WRITE 0
#define I2C_READ 1 #define I2C_READ 1
typedef struct i2c_bus typedef struct i2c_bus {
{ const char *name;
const char *name; int type;
int type; void *type_specific;
void* type_specific; int32_t(*transfer) (struct i2c_bus * bus, uint32_t address,
int32_t (*transfer)(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data); uint32_t to_write, uint32_t to_read,
int32_t (*scan)(struct i2c_bus* bus, uint32_t address); uint8_t * data);
int err; int32_t(*scan) (struct i2c_bus * bus, uint32_t address);
int err;
} i2c_bus_t; } i2c_bus_t;
int i2c_init_bus(struct i2c_bus *bus); int i2c_init_bus(struct i2c_bus *bus);
int32_t i2c_transfer(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data); int32_t i2c_transfer(struct i2c_bus *bus, uint32_t address, uint32_t to_write,
uint32_t to_read, uint8_t * data);
int32_t i2c_write(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint8_t* data); int32_t i2c_write(struct i2c_bus *bus, uint32_t address, uint32_t to_write,
int32_t i2c_read (struct i2c_bus* bus, uint32_t address, uint32_t to_read, uint8_t* data); uint8_t * data);
int32_t i2c_read(struct i2c_bus *bus, uint32_t address, uint32_t to_read,
uint8_t * data);
int32_t i2c_scan(struct i2c_bus* bus, uint8_t* data); int32_t i2c_scan(struct i2c_bus *bus, uint8_t * data);
#endif //I2C_H
#endif //I2C_H
...@@ -10,20 +10,21 @@ ...@@ -10,20 +10,21 @@
#include <libwr/trace.h> #include <libwr/trace.h>
static int32_t i2c_bitbang_transfer(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data); static int32_t i2c_bitbang_transfer(struct i2c_bus *bus, uint32_t address,
static int32_t i2c_bitbang_scan(struct i2c_bus* bus, uint32_t address); uint32_t to_write, uint32_t to_read,
uint8_t * data);
static int32_t i2c_bitbang_scan(struct i2c_bus *bus, uint32_t address);
int i2c_bitbang_init_bus(struct i2c_bus *bus) int i2c_bitbang_init_bus(struct i2c_bus *bus)
{ {
struct i2c_bitbang *priv; struct i2c_bitbang *priv;
if (!bus && !bus->type_specific && bus->type != I2C_TYPE_BITBANG) if (!bus && !bus->type_specific && bus->type != I2C_TYPE_BITBANG)
return -1; return -1;
priv = (struct i2c_bitbang *)bus->type_specific; priv = (struct i2c_bitbang *)bus->type_specific;
TRACE(TRACE_INFO,"init: %s (0x%x) ",bus->name,bus); TRACE(TRACE_INFO, "init: %s (0x%x) ", bus->name, bus);
shw_pio_configure(priv->scl); shw_pio_configure(priv->scl);
shw_pio_configure(priv->sda); shw_pio_configure(priv->sda);
shw_pio_setdir(priv->scl, 0); shw_pio_setdir(priv->scl, 0);
...@@ -40,16 +41,16 @@ int i2c_bitbang_init_bus(struct i2c_bus *bus) ...@@ -40,16 +41,16 @@ int i2c_bitbang_init_bus(struct i2c_bus *bus)
#define I2C_DELAY 4 #define I2C_DELAY 4
static void mi2c_pin_out(pio_pin_t* pin, int state) static void mi2c_pin_out(pio_pin_t * pin, int state)
{ {
shw_pio_setdir(pin, state ? 0 : 1); shw_pio_setdir(pin, state ? 0 : 1);
shw_udelay(I2C_DELAY); shw_udelay(I2C_DELAY);
} }
static void mi2c_start(struct i2c_bitbang* bus) static void mi2c_start(struct i2c_bitbang *bus)
{ {
mi2c_pin_out(bus->sda, 0); mi2c_pin_out(bus->sda, 0);
mi2c_pin_out(bus->scl, 0); mi2c_pin_out(bus->scl, 0);
} }
/* not used right now /* not used right now
...@@ -62,53 +63,48 @@ static void mi2c_restart(struct i2c_bitbang* bus) ...@@ -62,53 +63,48 @@ static void mi2c_restart(struct i2c_bitbang* bus)
} }
*/ */
static void mi2c_stop(struct i2c_bitbang* bus) static void mi2c_stop(struct i2c_bitbang *bus)
{ {
mi2c_pin_out(bus->sda,0); mi2c_pin_out(bus->sda, 0);
mi2c_pin_out(bus->scl,1); mi2c_pin_out(bus->scl, 1);
mi2c_pin_out(bus->sda,1); mi2c_pin_out(bus->sda, 1);
} }
static int mi2c_write_byte(struct i2c_bitbang *bus, uint8_t data)
static int mi2c_write_byte(struct i2c_bitbang* bus, uint8_t data)
{ {
int ack = 0; int ack = 0;
int b; int b;
for (b = 0; b < 8; b++) for (b = 0; b < 8; b++) {
{ mi2c_pin_out(bus->sda, data & 0x80); //set MSB to SDA
mi2c_pin_out(bus->sda, data & 0x80); //set MSB to SDA mi2c_pin_out(bus->scl, 1); //toggle clock
mi2c_pin_out(bus->scl, 1); //toggle clock mi2c_pin_out(bus->scl, 0);
mi2c_pin_out(bus->scl, 0); data <<= 1;
data <<= 1; }
}
mi2c_pin_out(bus->sda, 1); //go high mi2c_pin_out(bus->sda, 1); //go high
mi2c_pin_out(bus->scl, 1); //toggle clock mi2c_pin_out(bus->scl, 1); //toggle clock
shw_pio_setdir(bus->sda, PIO_IN); //let SDA float shw_pio_setdir(bus->sda, PIO_IN); //let SDA float
shw_udelay(I2C_DELAY); shw_udelay(I2C_DELAY);
ack = shw_pio_get(bus->sda); ack = shw_pio_get(bus->sda);
mi2c_pin_out(bus->scl, 0); mi2c_pin_out(bus->scl, 0);
// shw_pio_setdir(bus->sda, PIO_OUT_1); //turn on output // shw_pio_setdir(bus->sda, PIO_OUT_1); //turn on output
shw_udelay(I2C_DELAY); shw_udelay(I2C_DELAY);
return (ack == 0) ? 1: 0; return (ack == 0) ? 1 : 0;
} }
static uint8_t mi2c_get_byte(struct i2c_bitbang *bus, int ack) static uint8_t mi2c_get_byte(struct i2c_bitbang *bus, int ack)
{ {
int i; int i;
unsigned char result = 0; unsigned char result = 0;
mi2c_pin_out(bus->scl, 0); mi2c_pin_out(bus->scl, 0);
shw_pio_setdir(bus->sda, PIO_IN); //let SDA float so we can read it shw_pio_setdir(bus->sda, PIO_IN); //let SDA float so we can read it
for (i=0;i<8;i++) for (i = 0; i < 8; i++) {
{
mi2c_pin_out(bus->scl, 1); mi2c_pin_out(bus->scl, 1);
result <<= 1; result <<= 1;
if (shw_pio_get(bus->sda)) if (shw_pio_get(bus->sda))
...@@ -120,7 +116,7 @@ static uint8_t mi2c_get_byte(struct i2c_bitbang *bus, int ack) ...@@ -120,7 +116,7 @@ static uint8_t mi2c_get_byte(struct i2c_bitbang *bus, int ack)
mi2c_pin_out(bus->sda, ack ? 0 : 1); mi2c_pin_out(bus->sda, ack ? 0 : 1);
shw_udelay(I2C_DELAY); shw_udelay(I2C_DELAY);
mi2c_pin_out(bus->scl, 1); //generate SCL pulse for slave to read ACK/NACK mi2c_pin_out(bus->scl, 1); //generate SCL pulse for slave to read ACK/NACK
mi2c_pin_out(bus->scl, 0); mi2c_pin_out(bus->scl, 0);
return result; return result;
...@@ -137,28 +133,31 @@ static uint8_t mi2c_get_byte(struct i2c_bitbang *bus, int ack) ...@@ -137,28 +133,31 @@ static uint8_t mi2c_get_byte(struct i2c_bitbang *bus, int ack)
* \input address chip address on the bus * \input address chip address on the bus
* \output Return 1 (true) or 0 (false) if the bus has replied correctly * \output Return 1 (true) or 0 (false) if the bus has replied correctly
*/ */
static int32_t i2c_bitbang_scan(struct i2c_bus* bus, uint32_t address) static int32_t i2c_bitbang_scan(struct i2c_bus *bus, uint32_t address)
{ {
if (!bus) if (!bus)
return I2C_NULL_PARAM; return I2C_NULL_PARAM;
uint8_t state; uint8_t state;
struct i2c_bitbang* ts = (struct i2c_bitbang*)bus->type_specific; struct i2c_bitbang *ts = (struct i2c_bitbang *)bus->type_specific;
//Check if we have pull up on the data line of iic bus //Check if we have pull up on the data line of iic bus
shw_pio_setdir(ts->sda, PIO_IN); shw_pio_setdir(ts->sda, PIO_IN);
state=shw_pio_get(ts->sda); state = shw_pio_get(ts->sda);
if(state!=1) return 0; if (state != 1)
return 0;
//Then write address and check acknowledge //Then write address and check acknowledge
mi2c_start(ts); mi2c_start(ts);
state = mi2c_write_byte(ts, (address << 1) | 0); state = mi2c_write_byte(ts, (address << 1) | 0);
mi2c_stop(ts); mi2c_stop(ts);
return state ? 1: 0; return state ? 1 : 0;
} }
static int i2c_bitbang_transfer(i2c_bus_t* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data) static int i2c_bitbang_transfer(i2c_bus_t * bus, uint32_t address,
uint32_t to_write, uint32_t to_read,
uint8_t * data)
{ {
if (!bus) if (!bus)
return I2C_NULL_PARAM; return I2C_NULL_PARAM;
...@@ -168,7 +167,7 @@ static int i2c_bitbang_transfer(i2c_bus_t* bus, uint32_t address, uint32_t to_wr ...@@ -168,7 +167,7 @@ static int i2c_bitbang_transfer(i2c_bus_t* bus, uint32_t address, uint32_t to_wr
//TRACE(TRACE_INFO,"%s (0x%x) @ 0x%x: w=%d/r=%d; cmd=%d d=%d (0b%s)",bus->name,bus,address,to_write,to_read,data[0],data[1],shw_2binary(data[1])); //TRACE(TRACE_INFO,"%s (0x%x) @ 0x%x: w=%d/r=%d; cmd=%d d=%d (0b%s)",bus->name,bus,address,to_write,to_read,data[0],data[1],shw_2binary(data[1]));
struct i2c_bitbang* ts = (struct i2c_bitbang*)bus->type_specific; struct i2c_bitbang *ts = (struct i2c_bitbang *)bus->type_specific;
int sent = 0; int sent = 0;
int rcvd = 0; int rcvd = 0;
...@@ -176,20 +175,16 @@ static int i2c_bitbang_transfer(i2c_bus_t* bus, uint32_t address, uint32_t to_wr ...@@ -176,20 +175,16 @@ static int i2c_bitbang_transfer(i2c_bus_t* bus, uint32_t address, uint32_t to_wr
uint32_t i; uint32_t i;
if (to_write > 0) if (to_write > 0) {
{
mi2c_start(ts); mi2c_start(ts);
ack = mi2c_write_byte(ts, address << 1); //add W bit at the end of address ack = mi2c_write_byte(ts, address << 1); //add W bit at the end of address
if (!ack) if (!ack) {
{
mi2c_stop(ts); mi2c_stop(ts);
return I2C_DEV_NOT_FOUND; //the device did not ack it's address return I2C_DEV_NOT_FOUND; //the device did not ack it's address
} }
for (i=0; i < to_write; i++) for (i = 0; i < to_write; i++) {
{ ack = mi2c_write_byte(ts, data[i]); //write data
ack = mi2c_write_byte(ts, data[i]); //write data if (!ack) {
if (!ack)
{
mi2c_stop(ts); mi2c_stop(ts);
return I2C_NO_ACK_RCVD; return I2C_NO_ACK_RCVD;
} }
...@@ -198,26 +193,22 @@ static int i2c_bitbang_transfer(i2c_bus_t* bus, uint32_t address, uint32_t to_wr ...@@ -198,26 +193,22 @@ static int i2c_bitbang_transfer(i2c_bus_t* bus, uint32_t address, uint32_t to_wr
mi2c_stop(ts); mi2c_stop(ts);
} }
if (to_read) if (to_read) {
{
mi2c_start(ts); mi2c_start(ts);
ack = mi2c_write_byte(ts, (address << 1) | 1); //add R bit at the end of address ack = mi2c_write_byte(ts, (address << 1) | 1); //add R bit at the end of address
if (!ack) if (!ack) {
{
mi2c_stop(ts); mi2c_stop(ts);
return I2C_DEV_NOT_FOUND; //the device did not ack it's address return I2C_DEV_NOT_FOUND; //the device did not ack it's address
} }
uint32_t last_byte = to_read - 1; uint32_t last_byte = to_read - 1;
for (i=0; i < to_read; i++) for (i = 0; i < to_read; i++) {
{ data[i] = mi2c_get_byte(ts, i != last_byte); //read data, ack until the last byte
data[i] = mi2c_get_byte(ts, i != last_byte); //read data, ack until the last byte
rcvd++; rcvd++;
} }
mi2c_stop(ts); mi2c_stop(ts);
} }
return sent+rcvd; return sent + rcvd;
} }
...@@ -10,12 +10,12 @@ ...@@ -10,12 +10,12 @@
#include "i2c.h" #include "i2c.h"
struct i2c_bitbang { struct i2c_bitbang {
pio_pin_t* scl; pio_pin_t *scl;
pio_pin_t* sda; pio_pin_t *sda;
int udelay; int udelay;
int timeout; int timeout;
}; };
int i2c_bitbang_init_bus(struct i2c_bus *bus); int i2c_bitbang_init_bus(struct i2c_bus *bus);
#endif //I2C_CPU_BB_H #endif //I2C_CPU_BB_H
...@@ -4,13 +4,14 @@ ...@@ -4,13 +4,14 @@
#include <stdlib.h> #include <stdlib.h>
#include <string.h> #include <string.h>
#include <libwr/util.h> //for shw_udelay(); #include <libwr/util.h> //for shw_udelay();
#include "i2c_fpga_reg.h" #include "i2c_fpga_reg.h"
static int32_t i2c_fpga_reg_transfer(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data); static int32_t i2c_fpga_reg_transfer(struct i2c_bus *bus, uint32_t address,
static int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address); uint32_t to_write, uint32_t to_read,
uint8_t * data);
static int32_t i2c_fpga_reg_scan(struct i2c_bus *bus, uint32_t i2c_address);
int i2c_fpga_reg_init_bus(struct i2c_bus *bus) int i2c_fpga_reg_init_bus(struct i2c_bus *bus)
{ {
...@@ -21,18 +22,21 @@ int i2c_fpga_reg_init_bus(struct i2c_bus *bus) ...@@ -21,18 +22,21 @@ int i2c_fpga_reg_init_bus(struct i2c_bus *bus)
return -1; return -1;
} }
if (bus->type != I2C_BUS_TYPE_FPGA_REG) { if (bus->type != I2C_BUS_TYPE_FPGA_REG) {
printf("type doesn't match I2C_BUS_TYPE_FPGA_REG(%d): %d\n", I2C_BUS_TYPE_FPGA_REG, bus->type); printf("type doesn't match I2C_BUS_TYPE_FPGA_REG(%d): %d\n",
I2C_BUS_TYPE_FPGA_REG, bus->type);
return -1; return -1;
} }
priv = (i2c_fpga_reg_t *)bus->type_specific; priv = (i2c_fpga_reg_t *) bus->type_specific;
bus->transfer = i2c_fpga_reg_transfer; bus->transfer = i2c_fpga_reg_transfer;
bus->scan = i2c_fpga_reg_scan; bus->scan = i2c_fpga_reg_scan;
_fpga_writel(priv->base_address + FPGA_I2C_REG_CTR, 0); _fpga_writel(priv->base_address + FPGA_I2C_REG_CTR, 0);
_fpga_writel(priv->base_address + FPGA_I2C_REG_PREL, priv->prescaler & 0xFF); _fpga_writel(priv->base_address + FPGA_I2C_REG_PREL,
_fpga_writel(priv->base_address + FPGA_I2C_REG_PREH, priv->prescaler >> 8); priv->prescaler & 0xFF);
_fpga_writel(priv->base_address + FPGA_I2C_REG_PREH,
priv->prescaler >> 8);
_fpga_writel(priv->base_address + FPGA_I2C_REG_CTR, CTR_EN); _fpga_writel(priv->base_address + FPGA_I2C_REG_CTR, CTR_EN);
if (!(_fpga_readl(priv->base_address + FPGA_I2C_REG_CTR) & CTR_EN)) { if (!(_fpga_readl(priv->base_address + FPGA_I2C_REG_CTR) & CTR_EN)) {
...@@ -45,30 +49,30 @@ int i2c_fpga_reg_init_bus(struct i2c_bus *bus) ...@@ -45,30 +49,30 @@ int i2c_fpga_reg_init_bus(struct i2c_bus *bus)
static void mi2c_sel_if(uint32_t fpga_address, int num, int use) static void mi2c_sel_if(uint32_t fpga_address, int num, int use)
{ {
if (use) {//assign i2c i/f to i2c master if (use) { //assign i2c i/f to i2c master
_fpga_writel(fpga_address + FPGA_I2C_REG_IFS, IFS_BUSY | (num & 0x0F)); _fpga_writel(fpga_address + FPGA_I2C_REG_IFS,
} IFS_BUSY | (num & 0x0F));
else { //release i2c i/f } else { //release i2c i/f
_fpga_writel(fpga_address + FPGA_I2C_REG_IFS, 0); _fpga_writel(fpga_address + FPGA_I2C_REG_IFS, 0);
} }
} }
static void mi2c_wait_busy(uint32_t fpga_address) static void mi2c_wait_busy(uint32_t fpga_address)
{ {
while (_fpga_readl(fpga_address + FPGA_I2C_REG_SR) & SR_TIP); //read from status register transfer in progress flag while (_fpga_readl(fpga_address + FPGA_I2C_REG_SR) & SR_TIP) ; //read from status register transfer in progress flag
} }
//@return: 1 - ACK, 0 - NAK //@return: 1 - ACK, 0 - NAK
static int mi2c_start(uint32_t fpga_address, uint32_t i2c_address, uint32_t mode) static int mi2c_start(uint32_t fpga_address, uint32_t i2c_address,
uint32_t mode)
{ {
i2c_address = (i2c_address << 1) & 0xFF; i2c_address = (i2c_address << 1) & 0xFF;
if (mode == I2C_READ) if (mode == I2C_READ)
i2c_address |= 1; i2c_address |= 1;
_fpga_writel(fpga_address + FPGA_I2C_REG_TXR, i2c_address); //set address _fpga_writel(fpga_address + FPGA_I2C_REG_TXR, i2c_address); //set address
_fpga_writel(fpga_address + FPGA_I2C_REG_CR, CR_STA | CR_WR); //write to control register start write _fpga_writel(fpga_address + FPGA_I2C_REG_CR, CR_STA | CR_WR); //write to control register start write
mi2c_wait_busy(fpga_address); //wait till transfer is completed mi2c_wait_busy(fpga_address); //wait till transfer is completed
uint32_t result = _fpga_readl(fpga_address + FPGA_I2C_REG_SR); uint32_t result = _fpga_readl(fpga_address + FPGA_I2C_REG_SR);
// printf("addr = %02x, result = %02x\n", i2c_address>>1, result); // printf("addr = %02x, result = %02x\n", i2c_address>>1, result);
...@@ -76,17 +80,16 @@ static int mi2c_start(uint32_t fpga_address, uint32_t i2c_address, uint32_t mode ...@@ -76,17 +80,16 @@ static int mi2c_start(uint32_t fpga_address, uint32_t i2c_address, uint32_t mode
return (result & SR_RXACK) ? 0 : 1; return (result & SR_RXACK) ? 0 : 1;
} }
//0 - nak, 1 - ack //0 - nak, 1 - ack
static int mi2c_write_byte(uint32_t fpga_address, uint8_t data, uint32_t last) static int mi2c_write_byte(uint32_t fpga_address, uint8_t data, uint32_t last)
{ {
uint32_t cmd = CR_WR; uint32_t cmd = CR_WR;
if (last) if (last)
cmd |= CR_STO; //if it's last byte issue stop condition after sending byte cmd |= CR_STO; //if it's last byte issue stop condition after sending byte
_fpga_writel(fpga_address + FPGA_I2C_REG_TXR, data); //write into txd register the byte _fpga_writel(fpga_address + FPGA_I2C_REG_TXR, data); //write into txd register the byte
_fpga_writel(fpga_address + FPGA_I2C_REG_CR, cmd); //write command _fpga_writel(fpga_address + FPGA_I2C_REG_CR, cmd); //write command
mi2c_wait_busy(fpga_address); mi2c_wait_busy(fpga_address);
...@@ -98,16 +101,15 @@ static int mi2c_read_byte(uint32_t fpga_address, uint32_t last) ...@@ -98,16 +101,15 @@ static int mi2c_read_byte(uint32_t fpga_address, uint32_t last)
uint32_t cmd = CR_RD; uint32_t cmd = CR_RD;
if (last) if (last)
cmd |= CR_STO | CR_ACK; //CR_ACK means DO NOT SEND ACK cmd |= CR_STO | CR_ACK; //CR_ACK means DO NOT SEND ACK
_fpga_writel(fpga_address + FPGA_I2C_REG_CR, cmd); _fpga_writel(fpga_address + FPGA_I2C_REG_CR, cmd);
mi2c_wait_busy(fpga_address); mi2c_wait_busy(fpga_address);
return _fpga_readl(fpga_address + FPGA_I2C_REG_RXR); //read byte from rx register return _fpga_readl(fpga_address + FPGA_I2C_REG_RXR); //read byte from rx register
} }
static int32_t i2c_fpga_reg_scan(struct i2c_bus *bus, uint32_t i2c_address)
static int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address)
{ {
if (!bus) if (!bus)
return I2C_NULL_PARAM; return I2C_NULL_PARAM;
...@@ -115,7 +117,7 @@ static int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address) ...@@ -115,7 +117,7 @@ static int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address)
if (bus->type != I2C_BUS_TYPE_FPGA_REG) if (bus->type != I2C_BUS_TYPE_FPGA_REG)
return I2C_BUS_MISMATCH; return I2C_BUS_MISMATCH;
i2c_fpga_reg_t* ts = (i2c_fpga_reg_t*)bus->type_specific; i2c_fpga_reg_t *ts = (i2c_fpga_reg_t *) bus->type_specific;
uint32_t fpga_address = ts->base_address; uint32_t fpga_address = ts->base_address;
//set the i2c i/f num //set the i2c i/f num
...@@ -129,22 +131,24 @@ static int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address) ...@@ -129,22 +131,24 @@ static int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address)
_fpga_writel(fpga_address + FPGA_I2C_REG_CR, CR_STO | CR_WR); _fpga_writel(fpga_address + FPGA_I2C_REG_CR, CR_STO | CR_WR);
mi2c_wait_busy(fpga_address); mi2c_wait_busy(fpga_address);
//printf("address: %02X has a device\n", i2c_address); //printf("address: %02X has a device\n", i2c_address);
mi2c_sel_if(fpga_address, ts->if_num, 0); //detach I2C master from I2C i/f mi2c_sel_if(fpga_address, ts->if_num, 0); //detach I2C master from I2C i/f
return 1; return 1;
} }
mi2c_sel_if(fpga_address, ts->if_num, 0); //detach I2C master from I2C i/f mi2c_sel_if(fpga_address, ts->if_num, 0); //detach I2C master from I2C i/f
return 0; return 0;
} }
static int32_t i2c_fpga_reg_transfer(struct i2c_bus* bus, uint32_t i2c_address, uint32_t to_write, uint32_t to_read, uint8_t* data) static int32_t i2c_fpga_reg_transfer(struct i2c_bus *bus, uint32_t i2c_address,
uint32_t to_write, uint32_t to_read,
uint8_t * data)
{ {
if (!bus) if (!bus)
return I2C_NULL_PARAM; return I2C_NULL_PARAM;
if (bus->type != I2C_BUS_TYPE_FPGA_REG) if (bus->type != I2C_BUS_TYPE_FPGA_REG)
return I2C_BUS_MISMATCH; return I2C_BUS_MISMATCH;
i2c_fpga_reg_t* ts = (i2c_fpga_reg_t*)bus->type_specific; i2c_fpga_reg_t *ts = (i2c_fpga_reg_t *) bus->type_specific;
uint32_t fpga_address = ts->base_address; uint32_t fpga_address = ts->base_address;
int ack = 0; int ack = 0;
...@@ -156,12 +160,12 @@ static int32_t i2c_fpga_reg_transfer(struct i2c_bus* bus, uint32_t i2c_address, ...@@ -156,12 +160,12 @@ static int32_t i2c_fpga_reg_transfer(struct i2c_bus* bus, uint32_t i2c_address,
if (to_write) { if (to_write) {
ack = mi2c_start(fpga_address, i2c_address, I2C_WRITE); ack = mi2c_start(fpga_address, i2c_address, I2C_WRITE);
if (!ack) { //NAK if (!ack) { //NAK
mi2c_sel_if(fpga_address, ts->if_num, 0); mi2c_sel_if(fpga_address, ts->if_num, 0);
return I2C_DEV_NOT_FOUND; return I2C_DEV_NOT_FOUND;
} }
int last = to_write-1; int last = to_write - 1;
for (b = 0; b < to_write; b++) { for (b = 0; b < to_write; b++) {
ack = mi2c_write_byte(fpga_address, data[b], b == last); ack = mi2c_write_byte(fpga_address, data[b], b == last);
if (!ack) { if (!ack) {
...@@ -174,14 +178,13 @@ static int32_t i2c_fpga_reg_transfer(struct i2c_bus* bus, uint32_t i2c_address, ...@@ -174,14 +178,13 @@ static int32_t i2c_fpga_reg_transfer(struct i2c_bus* bus, uint32_t i2c_address,
if (to_read) { if (to_read) {
ack = mi2c_start(fpga_address, i2c_address, I2C_READ); ack = mi2c_start(fpga_address, i2c_address, I2C_READ);
if (!ack) { //NAK if (!ack) { //NAK
mi2c_sel_if(fpga_address, ts->if_num, 0); mi2c_sel_if(fpga_address, ts->if_num, 0);
return I2C_DEV_NOT_FOUND; return I2C_DEV_NOT_FOUND;
} }
int last = to_read-1; int last = to_read - 1;
for (b = 0; b < to_read; b++) for (b = 0; b < to_read; b++) {
{
data[b] = mi2c_read_byte(fpga_address, b == last); data[b] = mi2c_read_byte(fpga_address, b == last);
rcvd++; rcvd++;
} }
......
...@@ -33,13 +33,12 @@ ...@@ -33,13 +33,12 @@
#define FPGA_I2C1_IFNUM 1 #define FPGA_I2C1_IFNUM 1
#define FPGA_I2C_SENSORS_IFNUM 2 #define FPGA_I2C_SENSORS_IFNUM 2
typedef struct typedef struct {
{ uint32_t base_address;
uint32_t base_address; uint32_t if_num;
uint32_t if_num; uint32_t prescaler;
uint32_t prescaler;
} i2c_fpga_reg_t; } i2c_fpga_reg_t;
int i2c_fpga_reg_init_bus(struct i2c_bus *bus); int i2c_fpga_reg_init_bus(struct i2c_bus *bus);
#endif //I2C_FPGA_REG_H #endif //I2C_FPGA_REG_H
...@@ -38,14 +38,14 @@ ...@@ -38,14 +38,14 @@
#define I2C_SCB_VER_ADDR 0x20 #define I2C_SCB_VER_ADDR 0x20
//Connected to miniBP to PB6>PB4>PB24 //Connected to miniBP to PB6>PB4>PB24
pio_pin_t wr_i2c_io_sda = { pio_pin_t wr_i2c_io_sda = {
.port = PIOB, .port = PIOB,
.pin = 24, .pin = 24,
.mode = PIO_MODE_GPIO, //PullUp by i2c when miniBP >v3.3, PullDown in miniBP v3.2 .mode = PIO_MODE_GPIO, //PullUp by i2c when miniBP >v3.3, PullDown in miniBP v3.2
.dir = PIO_OUT_0, .dir = PIO_OUT_0,
}; };
//Connected to miniBP to PB7>PB0>PB20 //Connected to miniBP to PB7>PB0>PB20
pio_pin_t wr_i2c_io_scl = { pio_pin_t wr_i2c_io_scl = {
.port = PIOB, .port = PIOB,
...@@ -53,78 +53,73 @@ pio_pin_t wr_i2c_io_scl = { ...@@ -53,78 +53,73 @@ pio_pin_t wr_i2c_io_scl = {
.mode = PIO_MODE_GPIO, //PullUp by i2c when miniBP >v3.3, PullDown in miniBP v3.2 .mode = PIO_MODE_GPIO, //PullUp by i2c when miniBP >v3.3, PullDown in miniBP v3.2
.dir = PIO_OUT_0, .dir = PIO_OUT_0,
}; };
struct i2c_bitbang wr_i2c_io_reg = { struct i2c_bitbang wr_i2c_io_reg = {
.scl = &wr_i2c_io_scl, .scl = &wr_i2c_io_scl,
.sda = &wr_i2c_io_sda, .sda = &wr_i2c_io_sda,
}; };
struct i2c_bus i2c_io_bus = { struct i2c_bus i2c_io_bus = {
.name = "wr_scb_ver", .name = "wr_scb_ver",
.type = I2C_TYPE_BITBANG, .type = I2C_TYPE_BITBANG,
.type_specific = &wr_i2c_io_reg, .type_specific = &wr_i2c_io_reg,
.err = I2C_NULL_PARAM, .err = I2C_NULL_PARAM,
}; };
int shw_i2c_io_init(void) int shw_i2c_io_init(void)
{ {
TRACE(TRACE_INFO, "Initializing IO I2C bus...%s",__TIME__); TRACE(TRACE_INFO, "Initializing IO I2C bus...%s", __TIME__);
if (i2c_init_bus(&i2c_io_bus) < 0) { if (i2c_init_bus(&i2c_io_bus) < 0) {
TRACE(TRACE_ERROR,"init failed: %s", i2c_io_bus.name); TRACE(TRACE_ERROR, "init failed: %s", i2c_io_bus.name);
return -1; return -1;
} }
TRACE(TRACE_INFO,"init: success: %s", i2c_io_bus.name); TRACE(TRACE_INFO, "init: success: %s", i2c_io_bus.name);
return 0; return 0;
} }
int shw_i2c_io_scan(uint8_t * dev_map)
int shw_i2c_io_scan(uint8_t *dev_map)
{ {
int i; int i;
int detect; int detect;
if (i2c_io_bus.err) if (i2c_io_bus.err)
return -1; return -1;
detect = i2c_scan(&i2c_io_bus, dev_map); detect = i2c_scan(&i2c_io_bus, dev_map);
printf("\ni2c_bus: %s: %d devices\n", i2c_io_bus.name, detect); printf("\ni2c_bus: %s: %d devices\n", i2c_io_bus.name, detect);
for (i = 0; i < 128; i++) for (i = 0; i < 128; i++)
if (dev_map[i/8] & (1 << (i%8))) if (dev_map[i / 8] & (1 << (i % 8)))
printf("device at: 0x%02X\n", i); printf("device at: 0x%02X\n", i);
return detect; return detect;
} }
int shw_get_hw_ver() int shw_get_hw_ver()
{ {
uint8_t ret; uint8_t ret;
struct i2c_bus *bus= &i2c_io_bus; struct i2c_bus *bus = &i2c_io_bus;
//Check if i2c module exists (>=3.3) //Check if i2c module exists (>=3.3)
if(bus && bus->scan(bus,I2C_SCB_VER_ADDR)) if (bus && bus->scan(bus, I2C_SCB_VER_ADDR)) {
{
//The 0b00001110 bits are used for SCB HW version //The 0b00001110 bits are used for SCB HW version
ret= wrswhw_pca9554_get_input(bus,I2C_SCB_VER_ADDR); ret = wrswhw_pca9554_get_input(bus, I2C_SCB_VER_ADDR);
switch((ret >> 1) & 0x7) switch ((ret >> 1) & 0x7) {
{ case 0:
case 0: return 330; return 330;
case 1: return 340; //version is not available case 1:
case 2: return 341; return 340; //version is not available
default: case 2:
TRACE(TRACE_FATAL,"Unknown HW version (0x%x), check the DIP switch under the SCB",(ret >> 1) & 0x7); return 341;
return -1; default:
TRACE(TRACE_FATAL,
"Unknown HW version (0x%x), check the DIP switch under the SCB",
(ret >> 1) & 0x7);
return -1;
} }
} } else {
else
{
return 320; return 320;
} }
...@@ -132,17 +127,17 @@ int shw_get_hw_ver() ...@@ -132,17 +127,17 @@ int shw_get_hw_ver()
uint8_t shw_get_fpga_type() uint8_t shw_get_fpga_type()
{ {
struct i2c_bus *bus= &i2c_io_bus; struct i2c_bus *bus = &i2c_io_bus;
if(bus && bus->scan(bus,I2C_SCB_VER_ADDR)) if (bus && bus->scan(bus, I2C_SCB_VER_ADDR)) {
{ //The 0b00000001 bit is used for FPGA type
//The 0b00000001 bit is used for FPGA type if (wrswhw_pca9554_get_input(bus, I2C_SCB_VER_ADDR) & 0x1)
if(wrswhw_pca9554_get_input(bus,I2C_SCB_VER_ADDR) & 0x1)
return SHW_FPGA_LX240T; return SHW_FPGA_LX240T;
else else
return SHW_FPGA_LX130T; return SHW_FPGA_LX130T;
} }
//HACK: Check if file exists. This enable v3.2 miniBP and v3.3 SCB with LX240T //HACK: Check if file exists. This enable v3.2 miniBP and v3.3 SCB with LX240T
if(access("/wr/etc/lx240t.conf", F_OK) == 0) return SHW_FPGA_LX240T; if (access("/wr/etc/lx240t.conf", F_OK) == 0)
return SHW_FPGA_LX240T;
return SHW_FPGA_LX130T; return SHW_FPGA_LX130T;
} }
...@@ -3,7 +3,6 @@ ...@@ -3,7 +3,6 @@
#include "i2c.h" #include "i2c.h"
//address from AT24C01 datasheet (1k, all address lines shorted to the ground) //address from AT24C01 datasheet (1k, all address lines shorted to the ground)
#define I2C_SFP_ADDRESS 0x50 #define I2C_SFP_ADDRESS 0x50
...@@ -21,9 +20,9 @@ ...@@ -21,9 +20,9 @@
extern struct i2c_bus i2c_io_bus; extern struct i2c_bus i2c_io_bus;
int shw_i2c_io_init(void); int shw_i2c_io_init(void);
int shw_i2c_io_scan(uint8_t *dev_map); int shw_i2c_io_scan(uint8_t * dev_map);
int shw_get_hw_ver(); int shw_get_hw_ver();
uint8_t shw_get_fpga_type(); uint8_t shw_get_fpga_type();
#endif //I2C_SFP_H #endif //I2C_SFP_H
This diff is collapsed.
...@@ -38,7 +38,7 @@ void shw_sfp_gpio_init(void); ...@@ -38,7 +38,7 @@ void shw_sfp_gpio_init(void);
* 128 possible addresses. The dev_map is set to a bitmask representing * 128 possible addresses. The dev_map is set to a bitmask representing
* which devices are present. * which devices are present.
*/ */
int shw_sfp_bus_scan(int num, uint8_t *dev_map); int shw_sfp_bus_scan(int num, uint8_t * dev_map);
/* Read a header from a specific port (num = 0..17) */ /* Read a header from a specific port (num = 0..17) */
int shw_sfp_read_header(int num, struct shw_sfp_header *head); int shw_sfp_read_header(int num, struct shw_sfp_header *head);
...@@ -63,11 +63,11 @@ void shw_sfp_header_dump(struct shw_sfp_header *head); ...@@ -63,11 +63,11 @@ void shw_sfp_header_dump(struct shw_sfp_header *head);
* *
* @return number of bytes sent+received * @return number of bytes sent+received
*/ */
int32_t shw_sfp_read(int num, uint32_t addr, int off, int len, uint8_t *buf); int32_t shw_sfp_read(int num, uint32_t addr, int off, int len, uint8_t * buf);
int32_t shw_sfp_write(int num, uint32_t addr, int off, int len, uint8_t *buf); int32_t shw_sfp_write(int num, uint32_t addr, int off, int len, uint8_t * buf);
/* Set/get the 4 GPIO's connected to PCA9554's for a particular SFP */ /* Set/get the 4 GPIO's connected to PCA9554's for a particular SFP */
void shw_sfp_gpio_set(int num, uint8_t state); void shw_sfp_gpio_set(int num, uint8_t state);
uint8_t shw_sfp_gpio_get(int num); uint8_t shw_sfp_gpio_get(int num);
#endif //I2C_SFP_H #endif //I2C_SFP_H
...@@ -3,7 +3,6 @@ ...@@ -3,7 +3,6 @@
#define SHW_FAN_UPDATETO_DEFAULT 5 #define SHW_FAN_UPDATETO_DEFAULT 5
int shw_init_fans(); int shw_init_fans();
void shw_update_fans(); void shw_update_fans();
......
...@@ -7,5 +7,4 @@ ...@@ -7,5 +7,4 @@
int halexp_client_init(); int halexp_client_init();
int halexp_client_try_connect(int retries, int timeout); int halexp_client_try_connect(int retries, int timeout);
#endif /* __LIBWR_HAL_CLIENT_H */ #endif /* __LIBWR_HAL_CLIENT_H */
...@@ -8,15 +8,14 @@ ...@@ -8,15 +8,14 @@
#define HWIU_STRUCT_VERSION 1 #define HWIU_STRUCT_VERSION 1
struct gw_info { struct gw_info {
uint8_t ver_minor, ver_major; uint8_t ver_minor, ver_major;
uint8_t nwords; uint8_t nwords;
uint8_t struct_ver; uint8_t struct_ver;
uint8_t build_no, build_year, build_month, build_day; uint8_t build_no, build_year, build_month, build_day;
uint32_t switch_hdl_hash; uint32_t switch_hdl_hash;
uint32_t general_cores_hash; uint32_t general_cores_hash;
uint32_t wr_cores_hash; uint32_t wr_cores_hash;
} __attribute__((packed)); } __attribute__ ((packed));
int shw_hwiu_gwver(struct gw_info *info); int shw_hwiu_gwver(struct gw_info *info);
......
...@@ -27,8 +27,7 @@ ...@@ -27,8 +27,7 @@
#define _writel(reg, val) *(volatile uint32_t *)(reg) = (val) #define _writel(reg, val) *(volatile uint32_t *)(reg) = (val)
#define _readl(reg) (*(volatile uint32_t *)(reg)) #define _readl(reg) (*(volatile uint32_t *)(reg))
typedef struct pio_pin typedef struct pio_pin {
{
int port; int port;
int pin; int pin;
int mode; int mode;
...@@ -46,54 +45,55 @@ typedef struct pio_pin ...@@ -46,54 +45,55 @@ typedef struct pio_pin
#define FPGA_PIO_REG_PSR 0xC #define FPGA_PIO_REG_PSR 0xC
extern volatile uint8_t *_sys_base; extern volatile uint8_t *_sys_base;
extern volatile uint8_t *_pio_base[4][NUM_PIO_BANKS+1]; extern volatile uint8_t *_pio_base[4][NUM_PIO_BANKS + 1];
void shw_pio_configure(const pio_pin_t *pin); void shw_pio_configure(const pio_pin_t * pin);
void shw_pio_configure_pins(const pio_pin_t *pins); void shw_pio_configure_pins(const pio_pin_t * pins);
int shw_clock_out_enable(int pck_num, int prescaler, int source); int shw_clock_out_enable(int pck_num, int prescaler, int source);
volatile uint8_t *shw_pio_get_sys_base(); volatile uint8_t *shw_pio_get_sys_base();
volatile uint8_t *shw_pio_get_port_base(int port); volatile uint8_t *shw_pio_get_port_base(int port);
void shw_set_fp_led(int led, int state); void shw_set_fp_led(int led, int state);
int shw_pio_mmap_init(); int shw_pio_mmap_init();
void shw_pio_toggle_pin(pio_pin_t* pin, uint32_t udelay); void shw_pio_toggle_pin(pio_pin_t * pin, uint32_t udelay);
void shw_pio_configure(const pio_pin_t *pin); void shw_pio_configure(const pio_pin_t * pin);
static inline void shw_pio_set(const pio_pin_t *pin, int state) static inline void shw_pio_set(const pio_pin_t * pin, int state)
{ {
if(state) if (state)
_writel(_pio_base[IDX_REG_SODR][pin->port], (1<<pin->pin)); _writel(_pio_base[IDX_REG_SODR][pin->port], (1 << pin->pin));
else else
_writel(_pio_base[IDX_REG_CODR][pin->port], (1<<pin->pin)); _writel(_pio_base[IDX_REG_CODR][pin->port], (1 << pin->pin));
} }
static inline void shw_pio_set1(const pio_pin_t *pin) static inline void shw_pio_set1(const pio_pin_t * pin)
{ {
_writel(_pio_base[IDX_REG_SODR][pin->port], (1<<pin->pin)); _writel(_pio_base[IDX_REG_SODR][pin->port], (1 << pin->pin));
} }
static inline void shw_pio_set0(const pio_pin_t *pin) static inline void shw_pio_set0(const pio_pin_t * pin)
{ {
_writel(_pio_base[IDX_REG_CODR][pin->port], (1<<pin->pin)); _writel(_pio_base[IDX_REG_CODR][pin->port], (1 << pin->pin));
} }
static inline int shw_pio_get(const pio_pin_t *pin) static inline int shw_pio_get(const pio_pin_t * pin)
{ {
return (_readl(_pio_base[IDX_REG_PDSR][pin->port]) & (1<<pin->pin)) ? 1 : 0; return (_readl(_pio_base[IDX_REG_PDSR][pin->port]) & (1 << pin->pin)) ?
1 : 0;
} }
static inline int shw_pio_setdir(const pio_pin_t *pin, int dir) static inline int shw_pio_setdir(const pio_pin_t * pin, int dir)
{ {
if(dir == PIO_OUT) if (dir == PIO_OUT)
_writel((_pio_base[IDX_REG_BASE][pin->port] + PIO_OER), (1<<pin->pin)); _writel((_pio_base[IDX_REG_BASE][pin->port] + PIO_OER),
else (1 << pin->pin));
_writel((_pio_base[IDX_REG_BASE][pin->port] + PIO_ODR), (1<<pin->pin)); else
_writel((_pio_base[IDX_REG_BASE][pin->port] + PIO_ODR),
(1 << pin->pin));
return 0; return 0;
} }
#endif /* __LIBWR_CPU_IO_H */ #endif /* __LIBWR_CPU_IO_H */
...@@ -22,6 +22,6 @@ int shw_pps_gen_busy(); ...@@ -22,6 +22,6 @@ int shw_pps_gen_busy();
int shw_pps_gen_enable_output(int enable); int shw_pps_gen_enable_output(int enable);
/* Reads the current time and stores at <seconds,nanoseconds>. */ /* Reads the current time and stores at <seconds,nanoseconds>. */
void shw_pps_gen_read_time(uint64_t *seconds, uint32_t *nanoseconds); void shw_pps_gen_read_time(uint64_t * seconds, uint32_t * nanoseconds);
#endif /* __LIBWR_PPS_GEN_H */ #endif /* __LIBWR_PPS_GEN_H */
...@@ -29,14 +29,12 @@ ...@@ -29,14 +29,12 @@
#define IFACE_NAME_LEN 16 #define IFACE_NAME_LEN 16
#define SLAVE_PRIORITY_0 0 #define SLAVE_PRIORITY_0 0
#define SLAVE_PRIORITY_1 1 #define SLAVE_PRIORITY_1 1
#define SLAVE_PRIORITY_2 2 #define SLAVE_PRIORITY_2 2
#define SLAVE_PRIORITY_3 3 #define SLAVE_PRIORITY_3 3
#define SLAVE_PRIORITY_4 4 #define SLAVE_PRIORITY_4 4
// Some system-independent definitions // Some system-independent definitions
typedef uint8_t mac_addr_t[6]; typedef uint8_t mac_addr_t[6];
typedef uint32_t ipv4_addr_t; typedef uint32_t ipv4_addr_t;
...@@ -47,48 +45,46 @@ typedef void *wr_socket_t; ...@@ -47,48 +45,46 @@ typedef void *wr_socket_t;
// Socket address for ptp_netif_ functions // Socket address for ptp_netif_ functions
typedef struct { typedef struct {
// Network interface name (eth0, ...) // Network interface name (eth0, ...)
char if_name[IFACE_NAME_LEN]; char if_name[IFACE_NAME_LEN];
// Socket family (RAW ethernet/UDP) // Socket family (RAW ethernet/UDP)
int family; int family;
// MAC address // MAC address
mac_addr_t mac; mac_addr_t mac;
// Destination MASC address, filled by recvfrom() function on interfaces bound to multiple addresses // Destination MASC address, filled by recvfrom() function on interfaces bound to multiple addresses
mac_addr_t mac_dest; mac_addr_t mac_dest;
// IP address // IP address
ipv4_addr_t ip; ipv4_addr_t ip;
// UDP port // UDP port
uint16_t port; uint16_t port;
// RAW ethertype // RAW ethertype
uint16_t ethertype; uint16_t ethertype;
// physical port to bind socket to // physical port to bind socket to
uint16_t physical_port; uint16_t physical_port;
} wr_sockaddr_t; } wr_sockaddr_t;
PACKED struct _wr_timestamp { PACKED struct _wr_timestamp {
// Seconds // Seconds
int64_t sec; int64_t sec;
// Nanoseconds // Nanoseconds
int32_t nsec; int32_t nsec;
// Phase (in picoseconds), linearized for receive timestamps, zero for send timestamps // Phase (in picoseconds), linearized for receive timestamps, zero for send timestamps
int32_t phase; // phase(picoseconds) int32_t phase; // phase(picoseconds)
/* Raw time (non-linearized) for debugging purposes */ /* Raw time (non-linearized) for debugging purposes */
int32_t raw_phase; int32_t raw_phase;
int32_t raw_nsec; int32_t raw_nsec;
int32_t raw_ahead; int32_t raw_ahead;
// correctness flag: when 0, the timestamp MAY be incorrect (e.g. generated during timebase adjustment) // correctness flag: when 0, the timestamp MAY be incorrect (e.g. generated during timebase adjustment)
int correct; int correct;
//int cntr_ahead; //int cntr_ahead;
}; };
typedef struct _wr_timestamp wr_timestamp_t; typedef struct _wr_timestamp wr_timestamp_t;
/* OK. These functions we'll develop along with network card driver. You can write your own UDP-based stubs for testing purposes. */ /* OK. These functions we'll develop along with network card driver. You can write your own UDP-based stubs for testing purposes. */
// Initialization of network interface: // Initialization of network interface:
...@@ -99,26 +95,27 @@ int ptpd_netif_init(); ...@@ -99,26 +95,27 @@ int ptpd_netif_init();
// 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.
wr_socket_t *ptpd_netif_create_socket(int sock_type, int flags, wr_sockaddr_t *bind_addr); wr_socket_t *ptpd_netif_create_socket(int sock_type, int flags,
wr_sockaddr_t * bind_addr);
// Sends a UDP/RAW packet (data, data_length) to address provided in wr_sockaddr_t. // Sends a UDP/RAW packet (data, data_length) to address provided in wr_sockaddr_t.
// For raw frames, mac/ethertype needs to be provided, for UDP - ip/port. // For raw frames, mac/ethertype needs to be provided, for UDP - ip/port.
// Every transmitted frame has assigned a tag value, stored at tag parameter. This value is later used // Every transmitted frame has assigned a tag value, stored at tag parameter. This value is later used
// for recovering the precise transmit timestamp. If user doesn't need it, tag parameter can be left NULL. // for recovering the precise transmit timestamp. If user doesn't need it, tag parameter can be left NULL.
int ptpd_netif_sendto(wr_socket_t *sock, wr_sockaddr_t *to, void *data, size_t data_length, wr_timestamp_t *tx_ts); int ptpd_netif_sendto(wr_socket_t * sock, wr_sockaddr_t * to, void *data,
size_t data_length, wr_timestamp_t * tx_ts);
// Receives an UDP/RAW packet. Data is written to (data) and length is returned. Maximum buffer length can be specified // Receives an UDP/RAW packet. Data is written to (data) and length is returned. Maximum buffer length can be specified
// by data_length parameter. Sender information is stored in structure specified in 'from'. All RXed packets are timestamped and the timestamp // by data_length parameter. Sender information is stored in structure specified in 'from'. All RXed packets are timestamped and the timestamp
// is stored in rx_timestamp (unless it's NULL). // is stored in rx_timestamp (unless it's NULL).
int ptpd_netif_recvfrom(wr_socket_t *sock, wr_sockaddr_t *from, void *data, size_t data_length, wr_timestamp_t *rx_timestamp); int ptpd_netif_recvfrom(wr_socket_t * sock, wr_sockaddr_t * from, void *data,
size_t data_length, wr_timestamp_t * rx_timestamp);
// Closes the socket. // Closes the socket.
int ptpd_netif_close_socket(wr_socket_t *sock); int ptpd_netif_close_socket(wr_socket_t * sock);
int ptpd_netif_poll(wr_socket_t*);
int ptpd_netif_poll(wr_socket_t *);
/* /*
* Function detects external source lock, * Function detects external source lock,
...@@ -131,7 +128,9 @@ int ptpd_netif_poll(wr_socket_t*); ...@@ -131,7 +128,9 @@ int ptpd_netif_poll(wr_socket_t*);
/* 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_get_dmtd_phase(wr_socket_t *sock, int32_t *phase); int ptpd_netif_get_dmtd_phase(wr_socket_t * sock, int32_t * phase);
void ptpd_netif_linearize_rx_timestamp(wr_timestamp_t *ts, int32_t dmtd_phase, int cntr_ahead, int transition_point, int clock_period); void ptpd_netif_linearize_rx_timestamp(wr_timestamp_t * ts, int32_t dmtd_phase,
int cntr_ahead, int transition_point,
int clock_period);
#endif /* __LIBWR_PTPD_NETIF_H */ #endif /* __LIBWR_PTPD_NETIF_H */
...@@ -62,8 +62,7 @@ struct shw_sfp_header { ...@@ -62,8 +62,7 @@ struct shw_sfp_header {
uint8_t date_code[8]; uint8_t date_code[8];
uint8_t reserved[3]; uint8_t reserved[3];
uint8_t cc_ext; uint8_t cc_ext;
} __attribute__((packed)); } __attribute__ ((packed));
/* Public API */ /* Public API */
......
...@@ -28,76 +28,64 @@ ...@@ -28,76 +28,64 @@
#include <libwr/shw_io.h> #include <libwr/shw_io.h>
#include <libwr/pio.h> #include <libwr/pio.h>
#define assert_init(proc) { int ret; if((ret = proc) < 0) return ret; } #define assert_init(proc) { int ret; if((ret = proc) < 0) return ret; }
/** /**
* List of type of IO. * List of type of IO.
*/ */
typedef enum { typedef enum {
SHW_UNDEF=0, //undefined type SHW_UNDEF = 0, //undefined type
SHW_CPU_PIO, SHW_CPU_PIO,
SHW_I2C, SHW_I2C,
SHW_WB_PIO, SHW_WB_PIO,
SHW_WB_SYSM SHW_WB_SYSM
} shw_io_type_t; } shw_io_type_t;
/** /**
* List of ID for the various IO. * List of ID for the various IO.
*/ */
typedef enum { typedef enum {
shw_io_reset_n=1, //start at 1 (0 <=> undef) shw_io_reset_n = 1, //start at 1 (0 <=> undef)
shw_io_box_fan_en, //(< v3.3) shw_io_box_fan_en, //(< v3.3)
shw_io_box_fan_tacho, //(< v3.3) shw_io_box_fan_tacho, //(< v3.3)
shw_io_fpga_fan_en, //(< v3.3) shw_io_fpga_fan_en, //(< v3.3)
shw_io_led_cpu1, shw_io_led_cpu1,
shw_io_led_cpu2, shw_io_led_cpu2,
shw_io_arm_boot_sel, //(>= v3.2) shw_io_arm_boot_sel, //(>= v3.2)
shw_io_led_state_g, //(>= v3.3) shw_io_led_state_g, //(>= v3.3)
shw_io_led_state_o, //(>= v3.3) shw_io_led_state_o, //(>= v3.3)
shw_io_arm_gen_but, //(>= v3.3) shw_io_arm_gen_but, //(>= v3.3)
NUM_SHW_IO_ID NUM_SHW_IO_ID
} shw_io_id_t; } shw_io_id_t;
/** /**
* Structure to setup name and ID * Structure to setup name and ID
*/ */
typedef struct typedef struct {
{ uint8_t ID;
uint8_t ID; uint8_t type;
uint8_t type; const char *name;
const char *name; void *ptr;
void *ptr;
} shw_io_t; } shw_io_t;
/* /*
* Parameters to a chip * Parameters to a chip
*/ */
typedef struct typedef struct {
{
void *bus; void *bus;
uint32_t addr; uint32_t addr;
uint32_t config; uint32_t config;
uint32_t type; uint32_t type;
} shw_chip_t; } shw_chip_t;
/* /*
* Structure to fake an I/O using on a bus * Structure to fake an I/O using on a bus
*/ */
typedef struct typedef struct {
{
const shw_chip_t *chip; const shw_chip_t *chip;
uint8_t mask; //Mask of the interesting bit uint8_t mask; //Mask of the interesting bit
uint8_t shift; //Shift masking bit uint8_t shift; //Shift masking bit
} shw_io_bus_t; } shw_io_bus_t;
/** /**
* Exported structure to use them (Same size as enum) * Exported structure to use them (Same size as enum)
...@@ -107,15 +95,11 @@ extern const shw_io_t _all_shw_io[]; ...@@ -107,15 +95,11 @@ extern const shw_io_t _all_shw_io[];
//Functions //Functions
int shw_io_init(); int shw_io_init();
int shw_io_configure_all(); int shw_io_configure_all();
const shw_io_t* get_shw_io(shw_io_id_t id); const shw_io_t *get_shw_io(shw_io_id_t id);
const pio_pin_t* get_pio_pin(shw_io_id_t id); const pio_pin_t *get_pio_pin(shw_io_id_t id);
uint32_t shw_io_read(shw_io_id_t id); uint32_t shw_io_read(shw_io_id_t id);
int shw_io_write(shw_io_id_t, uint32_t value); int shw_io_write(shw_io_id_t, uint32_t value);
const char* get_shw_info(const char cmd); const char *get_shw_info(const char cmd);
#endif /* _LIBWR_SHW_IO_H_ */ #endif /* _LIBWR_SHW_IO_H_ */
...@@ -16,6 +16,7 @@ ...@@ -16,6 +16,7 @@
void trace_log_stderr(); void trace_log_stderr();
void trace_log_file(const char *filename); void trace_log_file(const char *filename);
void trace_printf(const char *fname, int lineno, int level, const char *fmt, ...); void trace_printf(const char *fname, int lineno, int level, const char *fmt,
...);
#endif /* __LIBWR_TRACE_H */ #endif /* __LIBWR_TRACE_H */
...@@ -7,10 +7,11 @@ ...@@ -7,10 +7,11 @@
#include "i2c_sfp.h" #include "i2c_sfp.h"
#include <libwr/shw_io.h> #include <libwr/shw_io.h>
int shw_init() int shw_init()
{ {
TRACE(TRACE_INFO,"%s\n=========================================================",__TIME__); TRACE(TRACE_INFO,
"%s\n=========================================================",
__TIME__);
/* Init input/output (GPIO & CPU I2C) */ /* Init input/output (GPIO & CPU I2C) */
assert_init(shw_io_init()); assert_init(shw_io_init());
...@@ -39,4 +40,3 @@ int shw_exit_fatal() ...@@ -39,4 +40,3 @@ int shw_exit_fatal()
TRACE(TRACE_FATAL, "exiting due to fatal error."); TRACE(TRACE_FATAL, "exiting due to fatal error.");
exit(-1); exit(-1);
} }
#include "libshw_i2c.h" #include "libshw_i2c.h"
int wrswhw_pca9554_configure(struct i2c_bus* bus, uint32_t address,uint8_t value) int wrswhw_pca9554_configure(struct i2c_bus *bus, uint32_t address,
uint8_t value)
{ {
//config initial port dir //config initial port dir
uint8_t config_outputs[2] = {PCA9554_CMD_DIR_REG, value}; uint8_t config_outputs[2] = { PCA9554_CMD_DIR_REG, value };
return i2c_transfer(bus, address, sizeof(config_outputs), 0, config_outputs); return i2c_transfer(bus, address, sizeof(config_outputs), 0,
config_outputs);
} }
int wrswhw_pca9554_set_output_reg(struct i2c_bus *bus, uint32_t address,
int wrswhw_pca9554_set_output_reg(struct i2c_bus* bus, uint32_t address, uint8_t value) uint8_t value)
{ {
//set initial output state //set initial output state
uint8_t set_outputs[2] = {PCA9554_CMD_OUTPUT_REG, value}; uint8_t set_outputs[2] = { PCA9554_CMD_OUTPUT_REG, value };
return i2c_transfer(bus, address, sizeof(set_outputs), 0, set_outputs); return i2c_transfer(bus, address, sizeof(set_outputs), 0, set_outputs);
} }
int32_t wrswhw_pca9554_get_input(struct i2c_bus* bus, uint32_t address) int32_t wrswhw_pca9554_get_input(struct i2c_bus *bus, uint32_t address)
{ {
//set read address //set read address
uint8_t r = PCA9554_CMD_INPUT_REG; uint8_t r = PCA9554_CMD_INPUT_REG;
int result = i2c_transfer(bus, address, 1, 0, &r); int result = i2c_transfer(bus, address, 1, 0, &r);
if (result < 0) if (result < 0)
return result; return result;
//read one byte //read one byte
result = i2c_transfer(bus,address, 0, 1, &r); result = i2c_transfer(bus, address, 0, 1, &r);
if (result < 0) if (result < 0)
return result; return result;
return r; return r;
} }
int wrswhw_pca9554_set_output_bits(struct i2c_bus* bus, uint32_t address, uint8_t value) int wrswhw_pca9554_set_output_bits(struct i2c_bus *bus, uint32_t address,
uint8_t value)
{ {
int result = wrswhw_pca9554_get_input(bus, address); int result = wrswhw_pca9554_get_input(bus, address);
if (result < 0) if (result < 0)
return result; return result;
result |= value; //or input bits result |= value; //or input bits
result &= 0xFF; //leave only 8 LSBs result &= 0xFF; //leave only 8 LSBs
return wrswhw_pca9554_set_output_reg(bus, address, result); return wrswhw_pca9554_set_output_reg(bus, address, result);
} }
int wrswhw_pca9554_clear_output_bits(struct i2c_bus* bus, uint32_t address, uint8_t value) int wrswhw_pca9554_clear_output_bits(struct i2c_bus *bus, uint32_t address,
uint8_t value)
{ {
int result = wrswhw_pca9554_get_input(bus, address); int result = wrswhw_pca9554_get_input(bus, address);
if (result < 0) if (result < 0)
return result; return result;
result &= ~value; //remove bits we don't need result &= ~value; //remove bits we don't need
result &= 0xFF; //leave only 8 LSBs result &= 0xFF; //leave only 8 LSBs
return wrswhw_pca9554_set_output_reg(bus, address, result); return wrswhw_pca9554_set_output_reg(bus, address, result);
} }
...@@ -27,11 +27,15 @@ ...@@ -27,11 +27,15 @@
//initial state for outputs //initial state for outputs
#define WRSWHW_INITIAL_OUTPUT_STATE (LINK1_SFP_TX_DISABLE | LINK0_SFP_TX_DISABLE) #define WRSWHW_INITIAL_OUTPUT_STATE (LINK1_SFP_TX_DISABLE | LINK0_SFP_TX_DISABLE)
int wrswhw_pca9554_configure(struct i2c_bus* bus, uint32_t address,uint8_t value); int wrswhw_pca9554_configure(struct i2c_bus *bus, uint32_t address,
int wrswhw_pca9554_set_output_reg(struct i2c_bus* bus, uint32_t address, uint8_t value); uint8_t value);
int wrswhw_pca9554_set_output_reg(struct i2c_bus *bus, uint32_t address,
int wrswhw_pca9554_get_input(struct i2c_bus* bus, uint32_t address); uint8_t value);
int wrswhw_pca9554_set_output_bits (struct i2c_bus* bus, uint32_t address, uint8_t value);
int wrswhw_pca9554_clear_output_bits(struct i2c_bus* bus, uint32_t address, uint8_t value); int wrswhw_pca9554_get_input(struct i2c_bus *bus, uint32_t address);
int wrswhw_pca9554_set_output_bits(struct i2c_bus *bus, uint32_t address,
uint8_t value);
int wrswhw_pca9554_clear_output_bits(struct i2c_bus *bus, uint32_t address,
uint8_t value);
#endif //LIBSHW_I2C_H #endif //LIBSHW_I2C_H
...@@ -15,7 +15,7 @@ ...@@ -15,7 +15,7 @@
#include <libwr/shw_io.h> #include <libwr/shw_io.h>
#include <libwr/util.h> #include <libwr/util.h>
volatile uint8_t *_pio_base[4][NUM_PIO_BANKS+1]; volatile uint8_t *_pio_base[4][NUM_PIO_BANKS + 1];
volatile uint8_t *_sys_base; volatile uint8_t *_sys_base;
#define AT91C_BASE_PIOA_RAW 0xFFFFF200 #define AT91C_BASE_PIOA_RAW 0xFFFFF200
...@@ -26,148 +26,136 @@ volatile uint8_t *_sys_base; ...@@ -26,148 +26,136 @@ volatile uint8_t *_sys_base;
#define AT91C_BASE_SYS_RAW 0xFFFFC000 #define AT91C_BASE_SYS_RAW 0xFFFFC000
#define AT91C_BASE_PMC_RAW 0xFFFFFC00 #define AT91C_BASE_PMC_RAW 0xFFFFFC00
static void pmc_enable_clock(int clock) static void pmc_enable_clock(int clock)
{ {
_writel(_sys_base + AT91C_BASE_PMC_RAW - AT91C_BASE_SYS_RAW + 0x10, (1<<clock)); // fucking atmel headers _writel(_sys_base + AT91C_BASE_PMC_RAW - AT91C_BASE_SYS_RAW + 0x10, (1 << clock)); // fucking atmel headers
// printf("ClkStat: %x\n", _readl(_sys_base + AT91C_BASE_PMC_RAW - AT91C_BASE_SYS_RAW + 0x18)); // printf("ClkStat: %x\n", _readl(_sys_base + AT91C_BASE_PMC_RAW - AT91C_BASE_SYS_RAW + 0x18));
} }
int shw_pio_mmap_init() int shw_pio_mmap_init()
{ {
int i; int i;
int fd = open("/dev/mem", O_RDWR); int fd = open("/dev/mem", O_RDWR);
if (!fd) if (!fd) {
{ TRACE(TRACE_FATAL, "can't open /dev/mem! (no root?)");
TRACE(TRACE_FATAL, "can't open /dev/mem! (no root?)"); exit(-1);
exit(-1); }
}
_sys_base = mmap(NULL, 0x4000, PROT_READ | PROT_WRITE, MAP_SHARED, fd, (off_t)AT91C_BASE_SYS); _sys_base =
mmap(NULL, 0x4000, PROT_READ | PROT_WRITE, MAP_SHARED, fd,
(off_t) AT91C_BASE_SYS);
if (_sys_base == NULL) if (_sys_base == NULL) {
{ TRACE(TRACE_FATAL, "can't mmap CPU GPIO regs");
TRACE(TRACE_FATAL, "can't mmap CPU GPIO regs"); close(fd);
close(fd); exit(-1);
exit(-1); }
}
TRACE(TRACE_INFO, "AT91_SYS virtual base = 0x%08x", _sys_base); TRACE(TRACE_INFO, "AT91_SYS virtual base = 0x%08x", _sys_base);
pmc_enable_clock(2); /* enable PIO clocks */ pmc_enable_clock(2); /* enable PIO clocks */
pmc_enable_clock(3); pmc_enable_clock(3);
pmc_enable_clock(4); pmc_enable_clock(4);
pmc_enable_clock(5); pmc_enable_clock(5);
// fprintf(stderr,"AT91_SYS mmapped to: 0x%08x\n", _sys_base); // fprintf(stderr,"AT91_SYS mmapped to: 0x%08x\n", _sys_base);
// printf("PIOA offset %08X\n", AT91C_BASE_PIOA_RAW - AT91C_BASE_SYS_RAW); // printf("PIOA offset %08X\n", AT91C_BASE_PIOA_RAW - AT91C_BASE_SYS_RAW);
// printf("Sys base: %08X\n", _sys_base); // printf("Sys base: %08X\n", _sys_base);
_pio_base[IDX_REG_BASE][PIOA] = _sys_base + AT91C_BASE_PIOA_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS _pio_base[IDX_REG_BASE][PIOA] = _sys_base + AT91C_BASE_PIOA_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS
_pio_base[IDX_REG_BASE][PIOB] = _sys_base + AT91C_BASE_PIOB_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS _pio_base[IDX_REG_BASE][PIOB] = _sys_base + AT91C_BASE_PIOB_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS
_pio_base[IDX_REG_BASE][PIOC] = _sys_base + AT91C_BASE_PIOC_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS _pio_base[IDX_REG_BASE][PIOC] = _sys_base + AT91C_BASE_PIOC_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS
_pio_base[IDX_REG_BASE][PIOD] = _sys_base + AT91C_BASE_PIOD_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS _pio_base[IDX_REG_BASE][PIOD] = _sys_base + AT91C_BASE_PIOD_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS
_pio_base[IDX_REG_BASE][PIOE] = _sys_base + AT91C_BASE_PIOE_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS _pio_base[IDX_REG_BASE][PIOE] = _sys_base + AT91C_BASE_PIOE_RAW - AT91C_BASE_SYS_RAW; //offset counting from AT91C_BASE_SYS
for (i=1; i<=5; i++) for (i = 1; i <= 5; i++) {
{ _pio_base[IDX_REG_CODR][i] =
_pio_base [IDX_REG_CODR][i] = _pio_base[IDX_REG_BASE][i] + PIO_CODR; _pio_base[IDX_REG_BASE][i] + PIO_CODR;
_pio_base [IDX_REG_SODR][i] = _pio_base[IDX_REG_BASE][i] + PIO_SODR; _pio_base[IDX_REG_SODR][i] =
_pio_base [IDX_REG_PDSR][i] = _pio_base[IDX_REG_BASE][i] + PIO_PDSR; _pio_base[IDX_REG_BASE][i] + PIO_SODR;
} _pio_base[IDX_REG_PDSR][i] =
_pio_base[IDX_REG_BASE][i] + PIO_PDSR;
return 0; }
return 0;
} }
extern const pio_pin_t *_all_cpu_gpio_pins[];
extern const pio_pin_t *_all_fpga_gpio_pins[];
extern const pio_pin_t* _all_cpu_gpio_pins[]; void shw_pio_toggle_pin(pio_pin_t * pin, uint32_t udelay)
extern const pio_pin_t* _all_fpga_gpio_pins[];
void shw_pio_toggle_pin(pio_pin_t* pin, uint32_t udelay)
{ {
while (1) while (1) {
{ shw_pio_set(pin, 0);
shw_pio_set(pin, 0); shw_udelay(udelay);
shw_udelay(udelay); shw_pio_set(pin, 1);
shw_pio_set(pin, 1); shw_udelay(udelay);
shw_udelay(udelay); }
}
} }
void shw_pio_configure(const pio_pin_t *pin) void shw_pio_configure(const pio_pin_t * pin)
{ {
uint32_t mask = (1<<pin->pin); uint32_t mask = (1 << pin->pin);
uint32_t ddr; uint32_t ddr;
volatile uint8_t *base = (_pio_base[IDX_REG_BASE][pin->port]); volatile uint8_t *base = (_pio_base[IDX_REG_BASE][pin->port]);
switch (pin->port) switch (pin->port) {
{ case PIOA:
case PIOA: case PIOB:
case PIOB: case PIOC:
case PIOC: case PIOD:
case PIOD: case PIOE:
case PIOE:
// printf("-- configure CPU PIO PIN: P%c.%d base=0x%x\n\n", pin->port-PIOA+'A', pin->pin, base);
// printf("-- configure CPU PIO PIN: P%c.%d base=0x%x\n\n", pin->port-PIOA+'A', pin->pin, base);
_writel(base + PIO_IDR, mask); // disable irq
_writel(base + PIO_IDR, mask); // disable irq
if (pin->mode & PIO_MODE_PULLUP)
if (pin->mode & PIO_MODE_PULLUP) _writel(base + PIO_PUER, mask); // enable pullup
_writel(base + PIO_PUER, mask);// enable pullup else
else _writel(base + PIO_PUDR, mask); // disable pullup
_writel(base + PIO_PUDR, mask); // disable pullup
switch (pin->mode & 0x3) {
switch (pin->mode & 0x3) case PIO_MODE_GPIO:
{ _writel(base + PIO_PER, mask); // enable gpio mode
case PIO_MODE_GPIO: break;
_writel(base + PIO_PER, mask); // enable gpio mode case PIO_MODE_PERIPH_A:
break; _writel(base + PIO_PDR, mask); // disable gpio mode
case PIO_MODE_PERIPH_A: _writel(base + PIO_ASR, mask); // select peripheral A
_writel(base + PIO_PDR, mask); // disable gpio mode break;
_writel(base + PIO_ASR, mask); // select peripheral A case PIO_MODE_PERIPH_B:
break; _writel(base + PIO_PDR, mask); // disable gpio mode
case PIO_MODE_PERIPH_B: _writel(base + PIO_BSR, mask); // select peripheral B
_writel(base + PIO_PDR, mask); // disable gpio mode break;
_writel(base + PIO_BSR, mask); // select peripheral B }
break;
} if (pin->dir == PIO_OUT_1) {
_writel(base + PIO_SODR, mask);
if (pin->dir == PIO_OUT_1) _writel(base + PIO_OER, mask); // select output, set it to 1
{ } else if (pin->dir == PIO_OUT_0) {
_writel(base + PIO_SODR, mask); _writel(base + PIO_CODR, mask);
_writel(base + PIO_OER, mask); // select output, set it to 1 _writel(base + PIO_OER, mask); // select output, set it to 0
} else if (pin->dir == PIO_OUT_0) } else {
{ _writel(base + PIO_ODR, mask); // select input
_writel(base + PIO_CODR, mask); }
_writel(base + PIO_OER, mask); // select output, set it to 0 break;
} else {
_writel(base + PIO_ODR, mask); // select input case PIO_FPGA:
} ddr = _readl(base + FPGA_PIO_REG_DDR);
break;
if (pin->dir == PIO_OUT_1) {
_writel(base + FPGA_PIO_REG_SODR, mask);
case PIO_FPGA: ddr |= mask;
ddr = _readl(base + FPGA_PIO_REG_DDR); } else if (pin->dir == PIO_OUT_0) {
_writel(base + FPGA_PIO_REG_CODR, mask);
if (pin->dir == PIO_OUT_1) ddr |= mask;
{ } else
_writel(base + FPGA_PIO_REG_SODR, mask); ddr &= ~mask;
ddr |= mask;
} else if (pin->dir == PIO_OUT_0) _writel(base + FPGA_PIO_REG_DDR, ddr);
{ break;
_writel(base + FPGA_PIO_REG_CODR, mask);
ddr |= mask; } //switch
} else
ddr &= ~mask;
_writel(base + FPGA_PIO_REG_DDR, ddr);
break;
} //switch
} }
...@@ -30,38 +30,40 @@ int shw_pps_gen_init() ...@@ -30,38 +30,40 @@ int shw_pps_gen_init()
uint32_t cr; uint32_t cr;
cr = PPSG_CR_CNT_EN | PPSG_CR_PWIDTH_W(PPS_WIDTH); cr = PPSG_CR_CNT_EN | PPSG_CR_PWIDTH_W(PPS_WIDTH);
TRACE(TRACE_INFO, "Initializing PPS generator..."); TRACE(TRACE_INFO, "Initializing PPS generator...");
ppsg_write(CR, cr); ppsg_write(CR, cr);
ppsg_write(ADJ_UTCLO, 0); ppsg_write(ADJ_UTCLO, 0);
ppsg_write(ADJ_UTCHI, 0); ppsg_write(ADJ_UTCHI, 0);
ppsg_write(ADJ_NSEC, 0); ppsg_write(ADJ_NSEC, 0);
ppsg_write(CR, cr | PPSG_CR_CNT_SET); ppsg_write(CR, cr | PPSG_CR_CNT_SET);
ppsg_write(CR, cr); ppsg_write(CR, cr);
ppsg_write(ESCR, 0x6); /* enable PPS output */ ppsg_write(ESCR, 0x6); /* enable PPS output */
return 0; return 0;
} }
/* Adjusts the nanosecond (refclk cycle) counter by atomically adding (how_much) cycles. */ /* Adjusts the nanosecond (refclk cycle) counter by atomically adding (how_much) cycles. */
int shw_pps_gen_adjust(int counter, int64_t how_much) int shw_pps_gen_adjust(int counter, int64_t how_much)
{ {
TRACE(TRACE_INFO, "Adjust: counter = %s [%c%lld]", TRACE(TRACE_INFO, "Adjust: counter = %s [%c%lld]",
counter == PPSG_ADJUST_SEC ? "seconds" : "nanoseconds", how_much<0?'-':'+', abs(how_much)); counter == PPSG_ADJUST_SEC ? "seconds" : "nanoseconds",
how_much < 0 ? '-' : '+', abs(how_much));
if(counter == PPSG_ADJUST_NSEC)
{ if (counter == PPSG_ADJUST_NSEC) {
ppsg_write(ADJ_UTCLO, 0); ppsg_write(ADJ_UTCLO, 0);
ppsg_write(ADJ_UTCHI, 0); ppsg_write(ADJ_UTCHI, 0);
ppsg_write(ADJ_NSEC, (int32_t) ((int64_t) how_much * 1000LL / (int64_t)REF_CLOCK_PERIOD_PS)); ppsg_write(ADJ_NSEC,
(int32_t) ((int64_t) how_much * 1000LL /
(int64_t) REF_CLOCK_PERIOD_PS));
} else { } else {
ppsg_write(ADJ_UTCLO, (uint32_t ) (how_much & 0xffffffffLL)); ppsg_write(ADJ_UTCLO, (uint32_t) (how_much & 0xffffffffLL));
ppsg_write(ADJ_UTCHI, (uint32_t ) (how_much >> 32) & 0xff); ppsg_write(ADJ_UTCHI, (uint32_t) (how_much >> 32) & 0xff);
ppsg_write(ADJ_NSEC, 0); ppsg_write(ADJ_NSEC, 0);
} }
ppsg_write(CR, ppsg_read(CR) | PPSG_CR_CNT_ADJ); ppsg_write(CR, ppsg_read(CR) | PPSG_CR_CNT_ADJ);
return 0; return 0;
} }
...@@ -69,32 +71,38 @@ int shw_pps_gen_adjust(int counter, int64_t how_much) ...@@ -69,32 +71,38 @@ int shw_pps_gen_adjust(int counter, int64_t how_much)
int shw_pps_gen_busy() int shw_pps_gen_busy()
{ {
uint32_t cr = ppsg_read(CR); uint32_t cr = ppsg_read(CR);
return cr & PPSG_CR_CNT_ADJ ? 0 : 1; return cr & PPSG_CR_CNT_ADJ ? 0 : 1;
} }
/* Enables/disables PPS output */ /* Enables/disables PPS output */
int shw_pps_gen_enable_output(int enable) int shw_pps_gen_enable_output(int enable)
{ {
uint32_t escr = ppsg_read(ESCR); uint32_t escr = ppsg_read(ESCR);
if(enable) if (enable)
ppsg_write(ESCR, escr | PPSG_ESCR_PPS_VALID) ppsg_write(ESCR, escr | PPSG_ESCR_PPS_VALID)
else else
ppsg_write(ESCR, escr & ~PPSG_ESCR_PPS_VALID); ppsg_write(ESCR, escr & ~PPSG_ESCR_PPS_VALID);
return 0; return 0;
} }
void shw_pps_gen_read_time(uint64_t *seconds, uint32_t *nanoseconds) void shw_pps_gen_read_time(uint64_t * seconds, uint32_t * nanoseconds)
{ {
uint32_t ns_cnt; uint32_t ns_cnt;
uint64_t sec1, sec2; uint64_t sec1, sec2;
do { do {
sec1 = (uint64_t)ppsg_read(CNTR_UTCLO) | (uint64_t)ppsg_read(CNTR_UTCHI) << 32; sec1 =
(uint64_t) ppsg_read(CNTR_UTCLO) | (uint64_t)
ppsg_read(CNTR_UTCHI) << 32;
ns_cnt = ppsg_read(CNTR_NSEC); ns_cnt = ppsg_read(CNTR_NSEC);
sec2 = (uint64_t)ppsg_read(CNTR_UTCLO) | (uint64_t)ppsg_read(CNTR_UTCHI) << 32; sec2 =
} while(sec2 != sec1); (uint64_t) ppsg_read(CNTR_UTCLO) | (uint64_t)
ppsg_read(CNTR_UTCHI) << 32;
if(seconds) *seconds = sec2; } while (sec2 != sec1);
if(nanoseconds) *nanoseconds = ns_cnt;
if (seconds)
*seconds = sec2;
if (nanoseconds)
*nanoseconds = ns_cnt;
} }
This diff is collapsed.
...@@ -42,52 +42,56 @@ ...@@ -42,52 +42,56 @@
all_shw_io[_name].name=#_name; \ all_shw_io[_name].name=#_name; \
all_shw_io[_name].ptr=(void*)PIN_##_name; } all_shw_io[_name].ptr=(void*)PIN_##_name; }
// definitions of commonly IO pins used with through all the versions (static memory) // definitions of commonly IO pins used with through all the versions (static memory)
// reset signal for main FPGA // reset signal for main FPGA
//const pio_pin_t PIN_main_fpga_nrst[] = {{ PIOA, 5, PIO_MODE_GPIO, PIO_OUT }, {0}}; //const pio_pin_t PIN_main_fpga_nrst[] = {{ PIOA, 5, PIO_MODE_GPIO, PIO_OUT }, {0}};
const pio_pin_t PIN_shw_io_reset_n[] = {{PIOE, 1, PIO_MODE_GPIO, PIO_OUT_1}, {0}}; const pio_pin_t PIN_shw_io_reset_n[] =
const pio_pin_t PIN_shw_io_box_fan_en[] = {{PIOB, 20, PIO_MODE_GPIO, PIO_OUT_0}, {0}}; //<3.3 (then used for i2c io) { {PIOE, 1, PIO_MODE_GPIO, PIO_OUT_1}, {0} };
const pio_pin_t PIN_shw_io_box_fan_tacho[] = {{PIOE, 7, PIO_MODE_GPIO, PIO_IN}, {0}}; const pio_pin_t PIN_shw_io_box_fan_en[] = { {PIOB, 20, PIO_MODE_GPIO, PIO_OUT_0}, {0} }; //<3.3 (then used for i2c io)
const pio_pin_t PIN_shw_io_fpga_fan_en[] = {{PIOB, 24, PIO_MODE_GPIO, PIO_OUT}, {0}}; const pio_pin_t PIN_shw_io_box_fan_tacho[] =
const pio_pin_t PIN_shw_io_led_cpu1[] = {{PIOA, 0, PIO_MODE_GPIO, PIO_OUT}, {0}}; { {PIOE, 7, PIO_MODE_GPIO, PIO_IN}, {0} };
const pio_pin_t PIN_shw_io_led_cpu2[] = {{PIOA, 1, PIO_MODE_GPIO, PIO_OUT}, {0}}; const pio_pin_t PIN_shw_io_fpga_fan_en[] =
const pio_pin_t PIN_shw_io_arm_boot_sel[] = {{PIOC, 7, PIO_MODE_GPIO, PIO_IN}, {0}}; { {PIOB, 24, PIO_MODE_GPIO, PIO_OUT}, {0} };
const pio_pin_t PIN_shw_io_arm_gen_but[] = {{PIOE, 9, PIO_MODE_GPIO, PIO_IN}, {0}}; const pio_pin_t PIN_shw_io_led_cpu1[] =
{ {PIOA, 0, PIO_MODE_GPIO, PIO_OUT}, {0} };
const shw_chip_t I2C_pca9554_ver = {(void*)&i2c_io_bus, 0x20, 0x0F, I2C_CHIP_PCA9554}; const pio_pin_t PIN_shw_io_led_cpu2[] =
{ {PIOA, 1, PIO_MODE_GPIO, PIO_OUT}, {0} };
const pio_pin_t PIN_shw_io_arm_boot_sel[] =
const shw_io_bus_t I2C_shw_io_led_state_g[] = { {&I2C_pca9554_ver, (1<<4),4}, {0}}; { {PIOC, 7, PIO_MODE_GPIO, PIO_IN}, {0} };
const shw_io_bus_t I2C_shw_io_led_state_o[] = { {&I2C_pca9554_ver, (1<<5),5}, {0}}; const pio_pin_t PIN_shw_io_arm_gen_but[] =
{ {PIOE, 9, PIO_MODE_GPIO, PIO_IN}, {0} };
const shw_chip_t I2C_pca9554_ver =
{ (void *)&i2c_io_bus, 0x20, 0x0F, I2C_CHIP_PCA9554 };
const shw_io_bus_t I2C_shw_io_led_state_g[] =
{ {&I2C_pca9554_ver, (1 << 4), 4}, {0} };
const shw_io_bus_t I2C_shw_io_led_state_o[] =
{ {&I2C_pca9554_ver, (1 << 5), 5}, {0} };
//Declaration of the array //Declaration of the array
const shw_io_t _all_shw_io[NUM_SHW_IO_ID]; const shw_io_t _all_shw_io[NUM_SHW_IO_ID];
int shw_io_init() int shw_io_init()
{ {
int ver; int ver;
//Remove const for writing //Remove const for writing
shw_io_t* all_shw_io=(shw_io_t*)_all_shw_io; shw_io_t *all_shw_io = (shw_io_t *) _all_shw_io;
//Map CPU's pin into memory space //Map CPU's pin into memory space
assert_init(shw_pio_mmap_init()); assert_init(shw_pio_mmap_init());
//then init the i2c (if it was not done) //then init the i2c (if it was not done)
if(i2c_io_bus.err==I2C_NULL_PARAM) if (i2c_io_bus.err == I2C_NULL_PARAM)
assert_init(shw_i2c_io_init()); assert_init(shw_i2c_io_init());
//then obtain the serial number //then obtain the serial number
ver=shw_get_hw_ver(); ver = shw_get_hw_ver();
//Finally assigned the input/ouput according to version number. //Finally assigned the input/ouput according to version number.
if(ver<330) if (ver < 330) {
{
IOARR_SET_GPIO(shw_io_reset_n); IOARR_SET_GPIO(shw_io_reset_n);
IOARR_SET_GPIO(shw_io_box_fan_en); IOARR_SET_GPIO(shw_io_box_fan_en);
IOARR_SET_GPIO(shw_io_box_fan_tacho); IOARR_SET_GPIO(shw_io_box_fan_tacho);
...@@ -96,19 +100,19 @@ int shw_io_init() ...@@ -96,19 +100,19 @@ int shw_io_init()
IOARR_SET_GPIO(shw_io_led_cpu2); IOARR_SET_GPIO(shw_io_led_cpu2);
IOARR_SET_GPIO(shw_io_arm_boot_sel); IOARR_SET_GPIO(shw_io_arm_boot_sel);
IOARR_SET_GPIO(shw_io_arm_gen_but); IOARR_SET_GPIO(shw_io_arm_gen_but);
} } else {
else
{
IOARR_SET_GPIO(shw_io_reset_n); IOARR_SET_GPIO(shw_io_reset_n);
IOARR_SET_GPIO(shw_io_led_cpu1); IOARR_SET_GPIO(shw_io_led_cpu1);
IOARR_SET_GPIO(shw_io_led_cpu2); IOARR_SET_GPIO(shw_io_led_cpu2);
IOARR_SET_GPIO(shw_io_arm_boot_sel); IOARR_SET_GPIO(shw_io_arm_boot_sel);
IOARR_SET_IO(shw_io_led_state_g,SHW_I2C,I2C_shw_io_led_state_g); IOARR_SET_IO(shw_io_led_state_g, SHW_I2C,
IOARR_SET_IO(shw_io_led_state_o,SHW_I2C,I2C_shw_io_led_state_o); I2C_shw_io_led_state_g);
IOARR_SET_IO(shw_io_led_state_o, SHW_I2C,
I2C_shw_io_led_state_o);
} }
TRACE(TRACE_INFO, "version=%d (CPUPWN=%d)",ver, ver<330); TRACE(TRACE_INFO, "version=%d (CPUPWN=%d)", ver, ver < 330);
return 0; return 0;
} }
...@@ -116,76 +120,84 @@ int shw_io_configure_all() ...@@ -116,76 +120,84 @@ int shw_io_configure_all()
{ {
int i; int i;
const shw_io_bus_t *iobus; const shw_io_bus_t *iobus;
const shw_io_t* all_io=(shw_io_t*)_all_shw_io; const shw_io_t *all_io = (shw_io_t *) _all_shw_io;
for(i=0;i<NUM_SHW_IO_ID;i++) for (i = 0; i < NUM_SHW_IO_ID; i++) {
{ const shw_io_t *io = (const shw_io_t *)&_all_shw_io[i];
const shw_io_t* io=(const shw_io_t*)&_all_shw_io[i]; switch (io->type) {
switch(io->type) case SHW_CPU_PIO:
{ shw_pio_configure(all_io[i].ptr);
case SHW_CPU_PIO: break;
shw_pio_configure(all_io[i].ptr); case SHW_I2C:
break; iobus = (const shw_io_bus_t *)io->ptr;
case SHW_I2C: if (iobus->chip
iobus = (const shw_io_bus_t *)io->ptr; && iobus->chip->type == I2C_CHIP_PCA9554)
if(iobus->chip && iobus->chip->type==I2C_CHIP_PCA9554) wrswhw_pca9554_configure(iobus->chip->bus,
wrswhw_pca9554_configure(iobus->chip->bus,iobus->chip->addr,iobus->chip->config); iobus->chip->addr,
break; iobus->chip->config);
case SHW_UNDEF: break;
//Do nothing for undefined type case SHW_UNDEF:
break; //Do nothing for undefined type
default: break;
TRACE(TRACE_INFO,"Config not implemented for type %d for io #%d",io->type,i); break; default:
TRACE(TRACE_INFO,
"Config not implemented for type %d for io #%d",
io->type, i);
break;
} }
} }
return 0; return 0;
} }
const pio_pin_t *get_pio_pin(shw_io_id_t id)
const pio_pin_t* get_pio_pin(shw_io_id_t id)
{ {
const shw_io_t *wrpin=get_shw_io(id); const shw_io_t *wrpin = get_shw_io(id);
if(wrpin && wrpin->type==SHW_CPU_PIO) if (wrpin && wrpin->type == SHW_CPU_PIO)
return (wrpin)?(const pio_pin_t*)wrpin->ptr:0; return (wrpin) ? (const pio_pin_t *)wrpin->ptr : 0;
return NULL; return NULL;
} }
const shw_io_t* get_shw_io(shw_io_id_t id) const shw_io_t *get_shw_io(shw_io_id_t id)
{ {
if(0< id && id < NUM_SHW_IO_ID) if (0 < id && id < NUM_SHW_IO_ID) {
{ if (_all_shw_io[id].ID == id)
if(_all_shw_io[id].ID==id) return &(_all_shw_io[id]); return &(_all_shw_io[id]);
else TRACE(TRACE_ERROR,"IO %d does not correspond to its ID %s",id,_all_shw_io[id].name); else
} TRACE(TRACE_ERROR,
else TRACE(TRACE_ERROR,"IO %d does not exist",id); "IO %d does not correspond to its ID %s", id,
_all_shw_io[id].name);
} else
TRACE(TRACE_ERROR, "IO %d does not exist", id);
return NULL; return NULL;
} }
uint32_t shw_io_read(shw_io_id_t id) uint32_t shw_io_read(shw_io_id_t id)
{ {
int32_t i32data; int32_t i32data;
const shw_io_t* io=&_all_shw_io[id]; const shw_io_t *io = &_all_shw_io[id];
const shw_io_bus_t *iobus; const shw_io_bus_t *iobus;
if(0< id && id < NUM_SHW_IO_ID && io->ID==id && io->ptr) if (0 < id && id < NUM_SHW_IO_ID && io->ID == id && io->ptr) {
{ switch (io->type) {
switch(io->type)
{
case SHW_CPU_PIO: case SHW_CPU_PIO:
return shw_pio_get((const pio_pin_t*)io->ptr); return shw_pio_get((const pio_pin_t *)io->ptr);
case SHW_I2C: case SHW_I2C:
iobus = (const shw_io_bus_t *)io->ptr; iobus = (const shw_io_bus_t *)io->ptr;
if(iobus->chip && iobus->chip->type==I2C_CHIP_PCA9554) if (iobus->chip
{ && iobus->chip->type == I2C_CHIP_PCA9554) {
i32data = wrswhw_pca9554_get_input(iobus->chip->bus,iobus->chip->addr); i32data =
return ((i32data & iobus->mask) >> iobus->shift); wrswhw_pca9554_get_input(iobus->chip->bus,
iobus->chip->addr);
return ((i32data & iobus->mask) >> iobus->
shift);
} }
case SHW_UNDEF: case SHW_UNDEF:
TRACE(TRACE_ERROR,"IO #%d is undef",id); break; TRACE(TRACE_ERROR, "IO #%d is undef", id);
break;
default: default:
TRACE(TRACE_ERROR,"Unknow type %d for io #%d",io->type,id); break; TRACE(TRACE_ERROR, "Unknow type %d for io #%d",
io->type, id);
break;
} }
} }
return 0; return 0;
...@@ -194,52 +206,56 @@ uint32_t shw_io_read(shw_io_id_t id) ...@@ -194,52 +206,56 @@ uint32_t shw_io_read(shw_io_id_t id)
int shw_io_write(shw_io_id_t id, uint32_t value) int shw_io_write(shw_io_id_t id, uint32_t value)
{ {
int32_t i32data; int32_t i32data;
const shw_io_t* io=&_all_shw_io[id]; const shw_io_t *io = &_all_shw_io[id];
const shw_io_bus_t *iobus; const shw_io_bus_t *iobus;
if(0< id && id < NUM_SHW_IO_ID && io->ID==id && io->ptr) if (0 < id && id < NUM_SHW_IO_ID && io->ID == id && io->ptr) {
{ switch (io->type) {
switch(io->type)
{
case SHW_CPU_PIO: case SHW_CPU_PIO:
shw_pio_set((const pio_pin_t*)io->ptr,value); shw_pio_set((const pio_pin_t *)io->ptr, value);
return 0; return 0;
case SHW_I2C: case SHW_I2C:
iobus = (const shw_io_bus_t *)io->ptr; iobus = (const shw_io_bus_t *)io->ptr;
if(iobus->chip && iobus->chip->type==I2C_CHIP_PCA9554) if (iobus->chip
{ && iobus->chip->type == I2C_CHIP_PCA9554) {
i32data = wrswhw_pca9554_get_input(iobus->chip->bus,iobus->chip->addr); i32data =
wrswhw_pca9554_get_input(iobus->chip->bus,
iobus->chip->addr);
i32data &= ~iobus->mask; i32data &= ~iobus->mask;
value <<= iobus->shift; value <<= iobus->shift;
value &= iobus->mask; value &= iobus->mask;
return wrswhw_pca9554_set_output_reg(iobus->chip->bus,iobus->chip->addr,value | i32data); return wrswhw_pca9554_set_output_reg(iobus->
chip->bus,
iobus->
chip->addr,
value |
i32data);
} }
case SHW_UNDEF: case SHW_UNDEF:
TRACE(TRACE_ERROR,"Pin #%d is undef",id); break; TRACE(TRACE_ERROR, "Pin #%d is undef", id);
break;
default: default:
TRACE(TRACE_ERROR,"Unknow type %d for io #%d",io->type,id); break; TRACE(TRACE_ERROR, "Unknow type %d for io #%d",
io->type, id);
break;
} }
} }
return -1; return -1;
} }
const char *get_shw_info(const char cmd) const char *get_shw_info(const char cmd)
{ {
static char str_hwver[10]; static char str_hwver[10];
int tmp; int tmp;
switch(cmd) switch (cmd) {
{
case 'p': case 'p':
tmp = shw_get_hw_ver(); tmp = shw_get_hw_ver();
snprintf(str_hwver,10,"%d.%d",tmp/100,tmp%100); snprintf(str_hwver, 10, "%d.%d", tmp / 100, tmp % 100);
return str_hwver; return str_hwver;
case 'f': case 'f':
return (shw_get_fpga_type()==SHW_FPGA_LX240T)?"LX240T":"LX130T"; return (shw_get_fpga_type() ==
SHW_FPGA_LX240T) ? "LX240T" : "LX130T";
} }
return ""; return "";
} }
...@@ -30,7 +30,6 @@ ...@@ -30,7 +30,6 @@
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value)) #define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif #endif
/* definitions for register: Control Register */ /* definitions for register: Control Register */
/* definitions for field: Prescaler Ratio in reg: Control Register */ /* definitions for field: Prescaler Ratio in reg: Control Register */
...@@ -70,26 +69,26 @@ ...@@ -70,26 +69,26 @@
/* definitions for register: Channel 7 Drive Register */ /* definitions for register: Channel 7 Drive Register */
PACKED struct SPWM_WB { PACKED struct SPWM_WB {
/* [0x0]: REG Control Register */ /* [0x0]: REG Control Register */
uint32_t CR; uint32_t CR;
/* [0x4]: REG Status Register */ /* [0x4]: REG Status Register */
uint32_t SR; uint32_t SR;
/* [0x8]: REG Channel 0 Drive Register */ /* [0x8]: REG Channel 0 Drive Register */
uint32_t DR0; uint32_t DR0;
/* [0xc]: REG Channel 1 Drive Register */ /* [0xc]: REG Channel 1 Drive Register */
uint32_t DR1; uint32_t DR1;
/* [0x10]: REG Channel 2 Drive Register */ /* [0x10]: REG Channel 2 Drive Register */
uint32_t DR2; uint32_t DR2;
/* [0x14]: REG Channel 3 Drive Register */ /* [0x14]: REG Channel 3 Drive Register */
uint32_t DR3; uint32_t DR3;
/* [0x18]: REG Channel 4 Drive Register */ /* [0x18]: REG Channel 4 Drive Register */
uint32_t DR4; uint32_t DR4;
/* [0x1c]: REG Channel 5 Drive Register */ /* [0x1c]: REG Channel 5 Drive Register */
uint32_t DR5; uint32_t DR5;
/* [0x20]: REG Channel 6 Drive Register */ /* [0x20]: REG Channel 6 Drive Register */
uint32_t DR6; uint32_t DR6;
/* [0x24]: REG Channel 7 Drive Register */ /* [0x24]: REG Channel 7 Drive Register */
uint32_t DR7; uint32_t DR7;
}; };
#endif #endif
...@@ -10,46 +10,52 @@ static int trace_to_stderr = 0; ...@@ -10,46 +10,52 @@ static int trace_to_stderr = 0;
void trace_log_stderr() void trace_log_stderr()
{ {
trace_to_stderr = 1; trace_to_stderr = 1;
} }
void trace_log_file(const char *filename) void trace_log_file(const char *filename)
{ {
trace_file = fopen(filename, "wb"); trace_file = fopen(filename, "wb");
} }
void trace_printf(const char *fname, int lineno, int level, const char *fmt, ...) void trace_printf(const char *fname, int lineno, int level, const char *fmt,
...)
{ {
char linestr[40]; char linestr[40];
char typestr[10]; char typestr[10];
va_list vargs; va_list vargs;
switch (level) switch (level) {
{ case TRACE_INFO:
case TRACE_INFO: strcpy(typestr, "(I)"); break; strcpy(typestr, "(I)");
case TRACE_ERROR: strcpy(typestr, "(E)"); break; break;
case TRACE_FATAL: strcpy(typestr, "(!)"); break; case TRACE_ERROR:
default: strcpy(typestr, "(?)"); break; strcpy(typestr, "(E)");
} break;
case TRACE_FATAL:
snprintf(linestr, 40, "%s [%s:%d]", typestr, fname, lineno); strcpy(typestr, "(!)");
break;
va_start(vargs, fmt); default:
strcpy(typestr, "(?)");
if(trace_file) break;
{
fprintf(trace_file, "%-24s ", linestr);
vfprintf(trace_file, fmt, vargs);
fflush(trace_file);
fprintf(trace_file,"\n");
} }
if(trace_to_stderr) snprintf(linestr, 40, "%s [%s:%d]", typestr, fname, lineno);
{
fprintf(stderr, "%-24s ", linestr);
vfprintf(stderr, fmt, vargs);
fprintf(stderr,"\n");
}
va_end(vargs); va_start(vargs, fmt);
if (trace_file) {
fprintf(trace_file, "%-24s ", linestr);
vfprintf(trace_file, fmt, vargs);
fflush(trace_file);
fprintf(trace_file, "\n");
}
if (trace_to_stderr) {
fprintf(stderr, "%-24s ", linestr);
vfprintf(stderr, fmt, vargs);
fprintf(stderr, "\n");
}
va_end(vargs);
} }
...@@ -7,62 +7,58 @@ ...@@ -7,62 +7,58 @@
void shw_udelay(uint32_t microseconds) void shw_udelay(uint32_t microseconds)
{ {
uint64_t t_start, t_cur; uint64_t t_start, t_cur;
struct timeval tv; struct timeval tv;
gettimeofday(&tv, NULL); gettimeofday(&tv, NULL);
t_start = (uint64_t) tv.tv_sec * 1000000ULL + (uint64_t)tv.tv_usec; t_start = (uint64_t) tv.tv_sec * 1000000ULL + (uint64_t) tv.tv_usec;
do { do {
gettimeofday(&tv, NULL); gettimeofday(&tv, NULL);
t_cur = (uint64_t) tv.tv_sec * 1000000ULL + (uint64_t)tv.tv_usec; t_cur =
(uint64_t) tv.tv_sec * 1000000ULL + (uint64_t) tv.tv_usec;
} while (t_cur <= t_start + (uint64_t) microseconds);
} while(t_cur <= t_start + (uint64_t) microseconds);
} }
void *shw_malloc(size_t nbytes) void *shw_malloc(size_t nbytes)
{ {
void *p = malloc(nbytes); void *p = malloc(nbytes);
if(!p) if (!p) {
{ TRACE(TRACE_FATAL, "malloc(%d) failed!", nbytes);
TRACE(TRACE_FATAL, "malloc(%d) failed!", nbytes); exit(-1);
exit(-1); }
} return p;
return p;
} }
void shw_free(void *ptr) void shw_free(void *ptr)
{ {
free(ptr); free(ptr);
} }
uint64_t shw_get_tics() uint64_t shw_get_tics()
{ {
struct timeval tv; struct timeval tv;
struct timezone tz={0,0}; struct timezone tz = { 0, 0 };
gettimeofday(&tv, &tz); gettimeofday(&tv, &tz);
return (uint64_t)tv.tv_usec + (uint64_t)tv.tv_sec * 1000000ULL; return (uint64_t) tv.tv_usec + (uint64_t) tv.tv_sec * 1000000ULL;
} }
/** /**
* \brief Helper function to quickly display byte into binary code. * \brief Helper function to quickly display byte into binary code.
* WARNING: this returns static storage * WARNING: this returns static storage
*/ */
const char *shw_2binary(uint8_t x) const char *shw_2binary(uint8_t x)
{ {
static char b[9]; static char b[9];
int z; int z;
char *p=b; char *p = b;
for (z=0x80; z > 0; z >>= 1) for (z = 0x80; z > 0; z >>= 1) {
{ *p++ = (((x & z) == z) ? '1' : '0');
*p++=(((x & z) == z) ? '1' : '0'); }
} *p = '\0';
*p='\0';
return b; return b;
} }
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