Commit 56e00c1a authored by Alessandro Rubini's avatar Alessandro Rubini

Merge branch 'adam-libmerge'

parents 52704b1f 5e04f092
......@@ -766,9 +766,6 @@ A plain @i{make} in
@t{userspace/ppsi} will likely fail, because of
missing environment variables.
Additionally, the script installs headers for the HAL
and @i{libptpnetif}.
@c --------------------------------------------------------------------------
@node User Space Applications
@subsection User Space Applications
......@@ -790,7 +787,7 @@ The main components are:
to exchange information among themselves or query the LM32
that is running on the FPGA.
@item libswitchhw
@item libwr
A series of utility functions to access the switch itself.
......@@ -1757,7 +1754,7 @@ version. This setup is then read by the software in order to load
the correct FPGA binaries and use the proper I/Os. Please be aware
that if you upgrade your SCB from LX130T to LX240T but keep the same
backplane you might need to change the DIP switch configuration.
Check the code from @code{userspace/libswitchhw/i2c_io.c} code to
Check the code from @code{userspace/libwr/i2c_io.c} code to
know how to reconfigure the DIP switch for you upgraded device.
For example, the v3.3 backplane with v3.3 LX240T SCB must be configured as bellow:
......@@ -1812,6 +1809,6 @@ on the mailing list if you don't find help there.
@c LocalWords: Tomasz Wlostowski buildroot distclean defconfig wrswitch REPO
@c LocalWords: menuconfig config dataflash whiterabbit stdout stderr svnsync
@c LocalWords: filesystem diff ohwr http mkdir linux rubini itemize PTPd VHDL
@c LocalWords: noposix ptpd userspace libswitchhw DataFlash NAND barebox FPGA
@c LocalWords: noposix ptpd userspace libwr DataFlash NAND barebox FPGA
@c LocalWords: Atmel Kconfig minicom tinyserial ttyUSB bootloader logfile
@c LocalWords: nandflash gateware TFTP init wrboot wiki
......@@ -213,12 +213,6 @@ As a side effect, a file-based interface allows off-switch simulation
and development (which includes simulating errors to test error paths in
the actual code).
@item Whether or not we port some stuff in kernel space, we need to have
a single @i{libwr}, to merge and replace @i{libptpnetif} and
@i{libswitchhw}. The role of each of them is not really clear to
developers at this point, and using a single library will simplify
building the tools;
@item While merging the libraries, we should seriously audit them.
Some functions do nothing, some are never called, and some are only
used withing the @i{hal} process, so there's no need to have them
......
......@@ -685,6 +685,6 @@ on the mailing list if you don't find help there.
@c LocalWords: Tomasz Wlostowski buildroot distclean defconfig wrswitch REPO
@c LocalWords: menuconfig config dataflash whiterabbit stdout stderr svnsync
@c LocalWords: filesystem diff ohwr http mkdir linux rubini itemize PTPd VHDL
@c LocalWords: noposix ptpd userspace libswitchhw DataFlash NAND barebox FPGA
@c LocalWords: noposix ptpd userspace libwr DataFlash NAND barebox FPGA
@c LocalWords: Atmel Kconfig minicom tinyserial ttyUSB bootloader logfile
@c LocalWords: nandflash gateware TFTP init wrboot wiki
......@@ -12,7 +12,7 @@ WR_INSTALL_ROOT ?= $(WRS_OUTPUT_DIR)/images/wr
WRDEV_DIR ?= $(WRS_BASE_DIR)/..
# subdirectories we want to compile
SUBDIRS = libptpnetif mini-rpc libswitchhw libsdb \
SUBDIRS = libwr mini-rpc libsdb \
wrsw_hal wrsw_rtud tools snmpd
# all variables are exported
......
......@@ -7,12 +7,4 @@
int shw_init_fans();
void shw_update_fans();
void shw_pwm_speed(int enable_mask, float rate);
void shw_pwm_update_timeout(int tout_100ms);
int shw_init_i2c_sensors();
float tmp100_read_temp(int dev_addr);
void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value);
float tmp100_read_temp(int dev_addr);
#endif
......@@ -4,7 +4,7 @@
#include <stdint.h>
/* Base addresses of all FPGA peripherals used in libswitchhw */
/* Base addresses of all FPGA peripherals used in libwr */
/* PPS Generator */
#define FPGA_BASE_PPS_GEN 0x10500
......
......@@ -59,7 +59,6 @@ void shw_set_fp_led(int led, int state);
int shw_pio_mmap_init();
void shw_pio_toggle_pin(pio_pin_t* pin, uint32_t udelay);
void shw_pio_configure_all();
void shw_pio_configure(const pio_pin_t *pin);
static inline void shw_pio_set(const pio_pin_t *pin, int state)
......
......@@ -14,6 +14,7 @@
/* System reference clock rate (in Hertz). Update together with REF_CLOCK_PERIOD_PS */
#define REF_CLOCK_RATE_HZ 62500000
/* return 0 on success */
int shw_init(void);
int shw_fpga_mmap_init(void);
#endif
......@@ -10,5 +10,6 @@ void shw_udelay(uint32_t microseconds);
void *shw_malloc(size_t nbytes);
void shw_free(void *ptr);
const char *shw_2binary(uint8_t x);
uint64_t shw_get_tics();
#endif
AS = $(CROSS_COMPILE)as
LD = $(CROSS_COMPILE)ld
CC = $(CROSS_COMPILE)gcc
CPP = $(CC) -E
AR = $(CROSS_COMPILE)ar
NM = $(CROSS_COMPILE)nm
STRIP = $(CROSS_COMPILE)strip
OBJCOPY = $(CROSS_COMPILE)objcopy
OBJDUMP = $(CROSS_COMPILE)objdump
CFLAGS = -Wall -ggdb -O2 -I../wrsw_hal -I../mini-rpc
all: libptpnetif.a
libptpnetif.a: ptpd_netif.o hal_client.o
$(AR) r $@ $^
clean:
rm -f *.a *.o *~
install:
@echo "We have no install rule by now"
CC = $(CROSS_COMPILE)gcc
AR = $(CROSS_COMPILE)ar
CFLAGS = -I. -O2 -I../include -DDEBUG -g
OBJS = trace.o init.o fpga_io.o util.o pps_gen.o i2c.o shw_io.o i2c_bitbang.o i2c_fpga_reg.o pio.o libshw_i2c.o i2c_sfp.o fan.o i2c_io.o hwiu.o
SCAN_OBJS = i2cscan.o
LIB = libswitchhw.a
LDFLAGS += -lm -ldl liblua.a
all: $(LIB)
$(LIB): $(OBJS)
$(AR) rc $@ $^
i2cscan: $(OBJS) $(LIB) $(SCAN_OBJS)
$(CC) $(CFLAGS) $(SCAN_OBJS) -o $(I2CSCAN_TARGET) $(LDFLAGS) $(LIB) $(LDFLAGS)
I2CSCAN_TARGET=i2cscan
#all: $(LIB) i2cscan
#$(LIB): $(OBJS)
# $(AR) rc $@ $^
#i2cscan: $(LIB) i2cscan.o
# $(CC) $(CFLAGS) liblua.a i2cscan.o liblua.a -o $(I2CSCAN_TARGET) $(LDFLAGS) -lm
dbload: dbload.o
$(CC) -Wall -ggdb -Ilua-5.2.0/src dbload.c liblua.a -o dbload -lm
install: all
install -d $(WR_INSTALL_ROOT)/lib
install $(LIB) $(WR_INSTALL_ROOT)/lib
clean:
rm -f $(LIB) $(OBJS) $(I2CSCAN_TARGET) dbload dbload.o
ctt:
scp i2cscan root@192.168.10.9:/bart_i2cscan
cp: clean $(LIB) i2cscan
cp i2cscan /tftpboot/rootfs/mvanga_i2cscan
cp sfpdb.lua /tftpboot/rootfs/root/
ssh root@192.168.1.11
Switch V2 Hardware Library (libswitchhw)
-------------------------------
Libswitchhw is a collection of low-level userspace drivers for various
peripherals in the switch, which do not need kernel modules. These are:
- Main FPGA (fpga_io.c) and CPU GPIO ports (pio.c), pin definitions (pio_pins.c)
- AD9516 PLL and clock distribution chip (ad9516.c)
- SPI master for communication with the timing FPGA (clkb_io.c)
- DMTD phase shifter PLL (dmpll.c, main clock recovery PLL - obsolete in V3,
to be replaced by the SoftPLL)
- Helper PLL (hpll.c, producing the "slightly offset" frequency for the DMTDs -
obsolete in V3, to be replaced by the SoftPLL)
- PPS generator (pps_gen.c, adjustment of time)
- Watchdog SPI link (watchdog.c)
- PHY calibrators (phy_calibration.c, xpoint.c, DS90LVxx buffers in the
MiniBackplane V2, ADN4600 crosspoint for clock feedback) and the calibration DMTDs
- Altera FPGA bootloader & revision management (mblaster.c, fpgaboot.c)
Libswitchhw also provides a single routine to initialize all that stuff (see init.c)
and some utility/tracing functions (trace.c, util.c)
#include "sfp.h"
#define MUX_ADDR(sel) ((0xE << 3) | (sel & 0x7))
static const pio_pin_t mux_sda = {PIOB, 0, PIO_MODE_GPIO, PIO_OUT_1};
static const pio_pin_t mux_scl = {PIOB, 1, PIO_MODE_GPIO, PIO_OUT_1};
struct i2c_bus_t *mux_bus;
struct wr_i2c_mux sfp_mux = {
.address = {
MUX_ADDR(0),
MUX_ADDR(1)
},
.reset = {
.port = PIOD,
.pin = 12,
.mode = PIO_MODE_GPIO,
.dir = PIO_OUT_1
}
};
struct i2c_bus_t *sfp_bus0;
struct i2c_bus_t *sfp_bus1;
struct pca9554d wr_sfp_gpio[] = {
{
/* 0 */
}, {
/* 1 */
}, {
/* 2 */
}, {
/* 3 */
}, {
/* 4 */
}, {
/* 5 */
}, {
/* 6 */
}, {
/* 7 */
}, {
/* 8 */
},
};
struct wr_sfp_module[18]
void sfp_init(void)
{
/* Create a bit-banged i2c for the muxes */
mux_bus = i2c_cpu_bb_new_bus(&mux_scl, &mux_sda);
/* Set the bus to be used for the mux control */
sfp_mux.bus = mux_bus;
}
#ifndef SFP_H
#define SFP_H
/* This structure describes the pair of PCA9548A chip used as muxes for i2c */
struct wr_i2c_mux {
/* I2C bus */
struct i2c_bus *bus;
/* I2C addresses of the two PCA9548 chips */
int address[2];
/* Reset pin */
struct pio_pin_t reset;
};
int wr_i2c_mux_set_channel(struct wr_i2c_mux *, int);
/* This structure describes a single PCA9554D chip */
struct pca9554d {
/* The i2c bus used for access */
struct i2c_bus_t *bus;
/* The address of this PCA9554D (set by A0,A1,A2 pins) */
int address;
int (*init)(struct pca9554d *);
int (*exit)(struct pca9554d *);
};
int pca9554d_get_input_reg(struct pca9554d *);
int pca9554d_set_output_reg(struct pca9554d *);
int pca9554d_set_polarity_reg(struct pca9554d *);
int pca9554d_set_config_reg(struct pca9554d *);
#define GPIO_BITS_LOWER 0
#define GPIO_BITS_UPPER 1
#define WRLINK_LED_LINK(m) \
(1 << (((m->bits_type == GPIO_BITS_LOWER) ? 0 : 2) + 4*m->bits_type))
#define WRLINK_LED_WRMODE(m) \
(1 << (((m->bits_type == GPIO_BITS_LOWER) ? 1 : 0) + 4*m->bits_type))
#define WRLINK_LED_SYNCED(m) \
(1 << (((m->bits_type == GPIO_BITS_LOWER) ? 3 : 1) + 4*m->bits_type))
#define SFP_TX_DISABLE(m) \
(1 << (((m->bits_type == GPIO_BITS_LOWER) ? 2 : 3) + 4*m->bits_type))
struct wr_sfp_module {
/*
* The PCA9554D associated with this device. Use a pointer here
* as a single PCA9554D controls the pins for two SFP modules
* each.
*/
struct pca9554d *gpio_ctl;
/* One of PCA9554_BITS_LOWER or PCA9554_BITS_UPPER */
int bits_type;
/* The PCA9548 chip for accessing this SFP module */
struct wr_i2c_mux *mux;
/*
* The channel for writing to control register of the
* PCA9548 chips.
*/
int channel;
};
#endif
CC = $(CROSS_COMPILE)gcc
AR = $(CROSS_COMPILE)ar
CFLAGS = -Wall -I. -O2 -DDEBUG -ggdb -I../include -I../wrsw_hal -I../mini-rpc
OBJS = trace.o init.o fpga_io.o util.o pps_gen.o i2c.o shw_io.o i2c_bitbang.o \
i2c_fpga_reg.o pio.o libshw_i2c.o i2c_sfp.o fan.o i2c_io.o hwiu.o \
ptpd_netif.o hal_client.o
LIB = libwr.a
all: $(LIB)
$(LIB): $(OBJS)
$(AR) rc $@ $^
install: all
install -d $(WR_INSTALL_ROOT)/lib
install $(LIB) $(WR_INSTALL_ROOT)/lib
clean:
rm -f $(LIB) $(OBJS)
Switch V3 Hardware Library (libwr)
-------------------------------
Libwr is a collection of low-level userspace drivers for various
peripherals in the switch, which do not need kernel modules. These are:
- Main FPGA (fpga_io.c) and CPU GPIO ports (pio.c), pin definitions (shw_io.c)
- PPS generator (pps_gen.c, adjustment of time)
- fan control (fan.c)
- i2c communication (i2c.c)
- SFP communication (i2c_sfp.c)
- Network API for WR-PTPd (ptpd_netif.c)
Libwr also provides a single routine to initialize all that stuff (see init.c)
and some utility/tracing functions (trace.c, util.c)
......@@ -32,11 +32,12 @@
#include <at91_softpwm.h>
#include "i2c.h"
#include "i2c_io.h"
#include "i2c_fpga_reg.h"
#include "fpga_io.h"
#include "shw_io.h"
#include "spwm-regs.h"
#include "util.h"
#define FAN_TEMP_SENSOR_ADDR 0x4c
......@@ -80,7 +81,7 @@ static int pwm_fd;
static volatile struct SPWM_WB *spwm_wbr;
//----------------------------------------
void shw_pwm_update_timeout(int tout_100ms)
static void shw_pwm_update_timeout(int tout_100ms)
{
fan_update_timeout=tout_100ms*100000;
TRACE(TRACE_INFO,"Fan tick timeout is =%d",fan_update_timeout);
......@@ -122,7 +123,7 @@ static inline void pi_init(pi_controller_t *pi)
}
/* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */
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;
if(pin==0) return;
......@@ -138,7 +139,7 @@ void pwm_configure_pin(const pio_pin_t *pin, int enable, int rate)
/* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */
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));
......@@ -147,7 +148,7 @@ void pwm_configure_fpga(int enmask, float rate)
}
/* Configures a PWM output. Rate accepts range is from 0 (0%) to 1 (100%) */
void shw_pwm_speed(int enmask, float rate)
static void shw_pwm_speed(int enmask, float rate)
{
//TRACE(TRACE_INFO,"%x %f",enmask,rate);
if(is_cpu_pwn)
......@@ -162,7 +163,7 @@ void shw_pwm_speed(int enmask, float rate)
/* Texas Instruments TMP100 temperature sensor driver */
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];
uint32_t rv=0, i;
......@@ -182,7 +183,7 @@ uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes)
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];
......@@ -192,25 +193,24 @@ void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value)
}
float tmp100_read_temp(int dev_addr)
static float tmp100_read_temp(int dev_addr)
{
int temp = tmp100_read_reg(dev_addr, 0, 2);
return ((float) (temp >> 4)) / 16.0;
}
int shw_init_i2c_sensors()
static int shw_init_i2c_sensors()
{
if (i2c_init_bus(&fpga_sensors_i2c) < 0) {
TRACE(TRACE_FATAL, "can't initialize temperature sensors I2C bus.\n");
return -1;
}
return 0;
}
int shw_init_fans()
{
uint8_t dev_map[128];
uint32_t val=0;
int detect, i;
//Set the type of PWM
if(shw_get_hw_ver()<330) is_cpu_pwn=1;
......
......@@ -11,29 +11,6 @@
static struct minipc_ch *hal_ch;
int halexp_check_running()
{
//int res_int;
//return wripc_call(hal_ipc, "halexp_check_running", ;
return 0;
}
int halexp_reset_port(const char *port_name)
{
// TRACE(TRACE_INFO, "resetting port %s\n", port_name);
return 0;
}
int halexp_calibration_cmd(const char *port_name, int command, int on_off)
{
int ret, rval;
ret = minipc_call(hal_ch, DEFAULT_TO, &__rpcdef_calibration_cmd,
&rval, port_name, command, on_off);
if (ret < 0)
return ret;
return rval;
}
int halexp_lock_cmd(const char *port_name, int command, int priority)
{
int ret, rval;
......
......@@ -11,7 +11,7 @@
#define hwiu_read(reg) \
_fpga_readl(FPGA_BASE_HWIU + offsetof(struct HWIU_WB, reg))
int hwiu_read_word(uint32_t adr, uint32_t *data)
static int hwiu_read_word(uint32_t adr, uint32_t *data)
{
uint32_t temp;
int timeout = 0;
......
......@@ -6,7 +6,8 @@
#include "i2c_bitbang.h"
#include "i2c_fpga_reg.h"
#include <trace.h>
#include "trace.h"
#include "util.h"
int i2c_init_bus(struct i2c_bus *bus)
{
......
......@@ -10,6 +10,9 @@
#include "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_scan(struct i2c_bus* bus, uint32_t address);
int i2c_bitbang_init_bus(struct i2c_bus *bus)
{
struct i2c_bitbang *priv;
......@@ -37,7 +40,7 @@ int i2c_bitbang_init_bus(struct i2c_bus *bus)
#define I2C_DELAY 4
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_udelay(I2C_DELAY);
......@@ -49,6 +52,7 @@ static void mi2c_start(struct i2c_bitbang* bus)
mi2c_pin_out(bus->scl, 0);
}
/* not used right now
static void mi2c_restart(struct i2c_bitbang* bus)
{
mi2c_pin_out(bus->sda, 1);
......@@ -56,7 +60,7 @@ static void mi2c_restart(struct i2c_bitbang* bus)
mi2c_pin_out(bus->sda, 0);
mi2c_pin_out(bus->scl, 0);
}
*/
static void mi2c_stop(struct i2c_bitbang* bus)
{
......@@ -133,7 +137,7 @@ static uint8_t mi2c_get_byte(struct i2c_bitbang *bus, int ack)
* \input address chip address on the bus
* \output Return 1 (true) or 0 (false) if the bus has replied correctly
*/
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)
return I2C_NULL_PARAM;
......@@ -154,7 +158,7 @@ int32_t i2c_bitbang_scan(struct i2c_bus* bus, uint32_t address)
return state ? 1: 0;
}
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)
return I2C_NULL_PARAM;
......
......@@ -17,7 +17,5 @@ struct i2c_bitbang {
};
int i2c_bitbang_init_bus(struct i2c_bus *bus);
int32_t i2c_bitbang_transfer(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data);
int32_t i2c_bitbang_scan(struct i2c_bus* bus, uint32_t address);
#endif //I2C_CPU_BB_H
......@@ -8,6 +8,10 @@
#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_scan(struct i2c_bus* bus, uint32_t i2c_address);
int i2c_fpga_reg_init_bus(struct i2c_bus *bus)
{
i2c_fpga_reg_t *priv;
......@@ -103,7 +107,7 @@ static int mi2c_read_byte(uint32_t fpga_address, uint32_t last)
}
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)
return I2C_NULL_PARAM;
......@@ -133,7 +137,7 @@ int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address)
return 0;
}
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)
return I2C_NULL_PARAM;
......
......@@ -41,7 +41,5 @@ typedef struct
} i2c_fpga_reg_t;
int i2c_fpga_reg_init_bus(struct i2c_bus *bus);
int32_t i2c_fpga_reg_transfer(struct i2c_bus* bus, uint32_t address, uint32_t to_write, uint32_t to_read, uint8_t* data);
int32_t i2c_fpga_reg_scan(struct i2c_bus* bus, uint32_t i2c_address);
#endif //I2C_FPGA_REG_H
......@@ -69,8 +69,6 @@ struct i2c_bus i2c_io_bus = {
int shw_i2c_io_init(void)
{
int i;
TRACE(TRACE_INFO, "Initializing IO I2C bus...%s",__TIME__);
if (i2c_init_bus(&i2c_io_bus) < 0) {
TRACE(TRACE_ERROR,"init failed: %s", i2c_io_bus.name);
......@@ -148,10 +146,3 @@ uint8_t shw_get_fpga_type()
if(access("/wr/etc/lx240t.conf", F_OK) == 0) return SHW_FPGA_LX240T;
return SHW_FPGA_LX130T;
}
struct i2c_bus* shw_i2c_io_get_bus()
{
return &i2c_io_bus;
}
......@@ -22,8 +22,6 @@ extern struct i2c_bus i2c_io_bus;
int shw_i2c_io_init(void);
int shw_i2c_io_scan(uint8_t *dev_map);
uint8_t shw_i2c_read(const *i2c_bus, uint8_t addr);
uint8_t shw_i2c_write(const *i2c_bus, uint8_t addr, uint8_t value, uint8_t mask);
int shw_get_hw_ver();
uint8_t shw_get_fpga_type();
......
......@@ -13,8 +13,9 @@
#include <lauxlib.h>
#include <lualib.h>
#include <pio.h>
#include <trace.h>
#include "pio.h"
#include "trace.h"
#include "util.h"
#include "i2c.h"
#include "i2c_sfp.h"
......@@ -285,7 +286,7 @@ void shw_sfp_print_header(struct shw_sfp_header *head)
for (i = 0; i < 16; i++)
printf("%c", head->vendor_serial[i]);
printf("\n");
uint8_t *date = (uint8_t *)&head->date_code;
printf("Date Code: ");
for (i = 0; i < 8; i++)
printf("%c", head->date_code[i]);
......@@ -429,7 +430,6 @@ void shw_sfp_gpio_set(int num, uint8_t state)
struct i2c_bus *bus;
uint8_t addr = 0x20;
uint8_t send[2];
uint8_t out = 0;
uint8_t curr;
id = shw_sfp_id(num);
......@@ -568,11 +568,11 @@ int shw_sfp_read_db(char *filename)
lua_pop( L, 1 );
continue;
}
int i = 0;
const char *sfp_pn = 0;
const char *sfp_vs = 0;
int vals[2];
double alpha;
int vals[2] = {0, 0};
double alpha = 0;
lua_pushnil(L);
while (lua_next(L, -2)) {
const char *key = lua_tostring(L, -2);
......
......@@ -31,6 +31,7 @@ int shw_init()
assert_init(shw_init_fans());
TRACE(TRACE_INFO, "HW initialization done!");
return 0;
}
int shw_exit_fatal()
......
......@@ -4,9 +4,7 @@ int wrswhw_pca9554_configure(struct i2c_bus* bus, uint32_t address,uint8_t value
{
//config initial port dir
uint8_t config_outputs[2] = {PCA9554_CMD_DIR_REG, value};
int result = i2c_transfer(bus, address, sizeof(config_outputs), 0, config_outputs);
if (result < 0)
return result;
return i2c_transfer(bus, address, sizeof(config_outputs), 0, config_outputs);
}
......
......@@ -13,6 +13,7 @@
#include "pio.h"
#include "trace.h"
#include "shw_io.h"
#include "util.h"
volatile uint8_t *_pio_base[4][NUM_PIO_BANKS+1];
volatile uint8_t *_sys_base;
......@@ -27,7 +28,7 @@ volatile uint8_t *_sys_base;
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
// printf("ClkStat: %x\n", _readl(_sys_base + AT91C_BASE_PMC_RAW - AT91C_BASE_SYS_RAW + 0x18));
......@@ -97,18 +98,6 @@ void shw_pio_toggle_pin(pio_pin_t* pin, uint32_t udelay)
}
}
void shw_pio_configure_all()
{
int i;
const shw_io_t* all_io=(shw_io_t*)_all_shw_io;
for(i=0;i<NUM_SHW_IO_ID;i++)
{
if(all_io[i].type==SHW_CPU_PIO)
shw_pio_configure(all_io[i].ptr);
}
}
void shw_pio_configure(const pio_pin_t *pin)
{
uint32_t mask = (1<<pin->pin);
......
......@@ -3,6 +3,7 @@
/* Warning: references to "UTC" in the registers DO NOT MEAN actual UTC time, it's just a plain second counter
It doesn't care about leap seconds. */
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <stddef.h>
......@@ -40,13 +41,12 @@ int shw_pps_gen_init()
ppsg_write(CR, cr | PPSG_CR_CNT_SET);
ppsg_write(CR, cr);
ppsg_write(ESCR, 0x6); /* enable PPS output */
return 0;
}
/* Adjusts the nanosecond (refclk cycle) counter by atomically adding (how_much) cycles. */
int shw_pps_gen_adjust(int counter, int64_t how_much)
{
uint32_t cr;
TRACE(TRACE_INFO, "Adjust: counter = %s [%c%lld]",
counter == PPSG_ADJUST_SEC ? "seconds" : "nanoseconds", how_much<0?'-':'+', abs(how_much));
......
......@@ -504,193 +504,6 @@ int ptpd_netif_recvfrom(wr_socket_t *sock, wr_sockaddr_t *from, void *data,
return ret - sizeof(struct ethhdr);
}
/*
* Turns on locking
*/
int ptpd_netif_locking_enable(int txrx, const char *ifaceName, int priority)
{
netif_dbg("(PTPD_NETIF): start locking\n");
int ret = halexp_lock_cmd(ifaceName, HEXP_LOCK_CMD_START, 0);
return (ret < 0 ? PTPD_NETIF_ERROR : PTPD_NETIF_OK);
}
int ptpd_netif_locking_disable(int txrx, const char *ifaceName, int priority)
{
return PTPD_NETIF_OK;
}
int ptpd_netif_locking_poll(int txrx, const char *ifaceName, int priority)
{
if( halexp_lock_cmd(ifaceName, HEXP_LOCK_CMD_CHECK, 0) == HEXP_LOCK_STATUS_LOCKED)
return PTPD_NETIF_READY;
else
return PTPD_NETIF_NOT_READY;
}
/* We don't need these functions in V3/spec anymore - the transceivers are deterministic! */
int ptpd_netif_calibration_pattern_enable(const char *ifaceName,
unsigned int calibrationPeriod,
unsigned int calibrationPattern,
unsigned int calibrationPatternLen)
{
return PTPD_NETIF_OK;
}
int ptpd_netif_calibrating_disable(int txrx, const char *ifaceName)
{
return PTPD_NETIF_OK;
}
int ptpd_netif_calibrating_enable(int txrx, const char *ifaceName)
{
return PTPD_NETIF_OK;
}
int ptpd_netif_calibrating_poll(int txrx, const char *ifaceName,
uint64_t *delta)
{
uint64_t delta_rx, delta_tx;
ptpd_netif_read_calibration_data(ifaceName, &delta_tx, &delta_rx, NULL, NULL);
if(txrx == PTPD_NETIF_TX)
*delta = delta_tx;
else
*delta = delta_rx;
return PTPD_NETIF_READY;
}
int ptpd_netif_calibration_pattern_disable(const char *ifaceName)
{
return PTPD_NETIF_OK;
}
int ptpd_netif_read_calibration_data(const char *ifaceName, uint64_t *deltaTx,
uint64_t *deltaRx, int32_t *fix_alpha, int32_t *clock_period)
{
hexp_port_state_t state;
//read the port state
halexp_get_port_state(&state, ifaceName);
// check if the data is available
if(state.valid && state.tx_calibrated && state.rx_calibrated)
{
fprintf(stderr, "servo:ifaceName: %s (%d / %d)\n", ifaceName, state.delta_tx ,state.delta_rx);
if(deltaTx)
*deltaTx = state.delta_tx;
if(deltaRx)
*deltaRx = state.delta_rx;
if(fix_alpha)
*fix_alpha = state.fiber_fix_alpha;
if(clock_period)
*clock_period = state.clock_period;
return PTPD_NETIF_OK;
}
return PTPD_NETIF_NOT_FOUND;
}
int ptpd_netif_select( wr_socket_t *wrSock)
{
struct my_socket *s = (struct my_socket *)wrSock;
int ret;
fd_set readfds;
FD_ZERO(&readfds);
FD_SET(s->fd, &readfds);
ret = select(s->fd + 1, &readfds, 0, 0, 0) > 0;
if(ret < 0)
{
if(errno == EAGAIN || errno == EINTR)
return 0;
}
return 1;
}
int ptpd_netif_get_hw_addr(wr_socket_t *sock, mac_addr_t *mac)
{
struct my_socket *s = (struct my_socket *)sock;
memcpy(mac, s->local_mac, 6);
return 0;
}
int ptpd_netif_get_port_state(const char *ifaceName)
{
hexp_port_state_t state;
//read the port state
halexp_get_port_state(&state, ifaceName);
// check if the data is available
if(state.valid)
{
//check if link is UP
if(state.up > 0)
return PTPD_NETIF_OK;
else
{
// if(!strcmp(ifaceName,"wru1") || !strcmp(ifaceName,"wru0"))
// printf("(ptpd_netif) linkdown detected on port: %s\n",ifaceName);
return PTPD_NETIF_ERROR;
}
}
/* printf("(ptpd_netif) linkdown detected on port: %s "
"[no valid port state data)\n",ifaceName);*/
//should not get here
return PTPD_NETIF_ERROR;
}
int ptpd_netif_extsrc_detection()
{
return 0;
}
int ptpd_netif_get_ifName(char *ifname, int number)
{
int i;
int j = 0;
hexp_port_list_t list;
halexp_query_ports(&list);
for( i = 0; i < list.num_ports; i++)
{
if(j == number)
{
strcpy(ifname,list.port_names[i]);
return PTPD_NETIF_OK;
}
else
j++;
}
return PTPD_NETIF_ERROR;
}
uint64_t ptpd_netif_get_msec_tics()
{
// printf("getmsec: %lld\n", get_tics() / 1000ULL);
return get_tics() / 1000ULL;
}
int ptpd_netif_adjust_counters(int64_t adjust_sec, int32_t adjust_nsec)
{
hexp_pps_params_t p;
......@@ -719,42 +532,3 @@ int ptpd_netif_adjust_counters(int64_t adjust_sec, int32_t adjust_nsec)
return PTPD_NETIF_ERROR;
}
int ptpd_netif_adjust_phase(int32_t phase_ps)
{
hexp_pps_params_t p;
p.adjust_phase_shift = phase_ps;
if(!halexp_pps_cmd(HEXP_PPSG_CMD_ADJUST_PHASE, &p))
return PTPD_NETIF_OK;
return PTPD_NETIF_ERROR;
}
int ptpd_netif_adjust_in_progress()
{
hexp_pps_params_t p;
if(halexp_pps_cmd(HEXP_PPSG_CMD_POLL, &p))
return PTPD_NETIF_OK;
else
return PTPD_NETIF_NOT_READY;
}
int ptpd_netif_enable_timing_output(int enable)
{
hexp_pps_params_t p;
p.pps_valid = enable;
if(halexp_pps_cmd(HEXP_PPSG_CMD_SET_VALID, &p))
return PTPD_NETIF_OK;
else
return PTPD_NETIF_NOT_READY;
}
int ptpd_netif_enable_phase_tracking(const char *if_name)
{
int ret = halexp_lock_cmd(if_name, HEXP_LOCK_CMD_ENABLE_TRACKING, 0);
return (ret < 0 ? PTPD_NETIF_ERROR : PTPD_NETIF_OK);
}
......@@ -119,106 +119,6 @@ int ptpd_netif_close_socket(wr_socket_t *sock);
int ptpd_netif_poll(wr_socket_t*);
int ptpd_netif_get_hw_addr(wr_socket_t *sock, mac_addr_t *mac);
/*
* Function start HW locking of freq on WR Slave
* return:
* PTPD_NETIF_ERROR - locking not started
* PTPD_NETIF_OK - locking started
*/
int ptpd_netif_locking_enable(int txrx, const char *ifaceName, int priority);
/*
*
* return:
*
* PTPD_NETIF_OK - locking started
*/
int ptpd_netif_locking_disable(int txrx, const char *ifaceName, int priority);
int ptpd_netif_locking_poll(int txrx, const char *ifaceName, int priority);
/*
* Function turns on calibration (measurement of delay)
* Tx or Rx depending on the txrx param
* return:
* PTPD_NETIF_NOT_READY - if there is calibratin going on on another port
* PTPD_NETIF_OK - calibration started
*/
int ptpd_netif_calibrating_enable(int txrx, const char *ifaceName);
/*
* Function turns off calibration (measurement of delay)
* Tx or Rx depending on the txrx param
* return:
* PTPD_NETIF_ERROR - if there is calibratin going on on another port
* PTPD_NETIF_OK - calibration started
*/
int ptpd_netif_calibrating_disable(int txrx, const char *ifaceName);
/*
* Function checks if Rx/Tx (depending on the param) calibration is finished
* if finished, returns measured delay in delta
* return:
*
* PTPD_NETIF_OK - locking started
*/
int ptpd_netif_calibrating_poll(int txrx, const char *ifaceName, uint64_t *delta);
/*
* Function turns on calibration pattern.
* return:
* PTPD_NETIF_NOT_READY - if WRSW is busy with calibration on other switch or error occured
* PTPD_NETIF_OK - calibration started
*/
int ptpd_netif_calibration_pattern_enable(const char *ifaceName, unsigned int calibrationPeriod, unsigned int calibrationPattern, unsigned int calibrationPatternLen);
/*
* Function turns off calibration pattern
* return:
* PTPD_NETIF_ERROR - turning off not successful
* PTPD_NETIF_OK - turning off successful
*/
int ptpd_netif_calibration_pattern_disable(const char *ifaceName);
/*
* Function reads calibration data if it's available, used at the beginning of PTPWRd to check if
* HW knows already the interface's deltax, and therefore no need for calibration
* return:
* PTPD_NETIF_NOT_FOUND - if deltas are not known
* PTPD_NETIF_OK - if deltas are known, in such case, deltaTx and deltaRx have valid data
*/
int ptpd_netif_read_calibration_data(const char *ifaceName, uint64_t *deltaTx,
uint64_t *deltaRx, int32_t *fix_alpha, int32_t *clock_period);
int ptpd_netif_select(wr_socket_t*);
int ptpd_netif_get_hw_addr(wr_socket_t *sock, mac_addr_t *mac);
/*
* Function reads state of the given port (interface in our case), if the port is up, everything is OK, otherwise ERROR
* return:
* PTPD_NETIF_ERROR - if the port is down
* PTPD_NETIF_OK - if the port is up
*/
int ptpd_netif_get_port_state(const char *ifaceName);
/*
* Function looks for a port (interface) for the port number 'number'
* it will return in the argument ifname the port name
* return:
* PTPD_NETIF_ERROR - port not found
* PTPD_NETIF_OK - if the port found
*/
int ptpd_netif_get_ifName(char *ifname, int number);
/* Returns the millisecond "tics" counter value */
uint64_t ptpd_netif_get_msec_tics();
/*
* Function detects external source lock,
......@@ -228,15 +128,10 @@ uint64_t ptpd_netif_get_msec_tics();
* HEXP_LOCK_STATUS_BUSY 1
* HEXP_EXTSRC_STATUS_NOSRC 2
*/
int ptpd_netif_extsrc_detection();
/* 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_phase(int32_t phase_ps);
int ptpd_netif_adjust_in_progress();
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);
int ptpd_netif_enable_timing_output(int enable);
int ptpd_netif_enable_phase_tracking(const char *if_name);
#endif
......@@ -70,7 +70,7 @@ const shw_io_t _all_shw_io[NUM_SHW_IO_ID];
int shw_io_init()
{
int ret, ver;
int ver;
//Remove const for writing
shw_io_t* all_shw_io=(shw_io_t*)_all_shw_io;
......@@ -148,6 +148,7 @@ const pio_pin_t* get_pio_pin(shw_io_id_t id)
const shw_io_t *wrpin=get_shw_io(id);
if(wrpin && wrpin->type==SHW_CPU_PIO)
return (wrpin)?(const pio_pin_t*)wrpin->ptr:0;
return NULL;
}
const shw_io_t* get_shw_io(shw_io_id_t id)
......@@ -158,15 +159,13 @@ const shw_io_t* get_shw_io(shw_io_id_t id)
else TRACE(TRACE_ERROR,"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 0;
return NULL;
}
uint32_t shw_io_read(shw_io_id_t id)
{
uint32_t ret;
int32_t i32data;
uint8_t u8data[2];
const shw_io_t* io=&_all_shw_io[id];
const shw_io_bus_t *iobus;
......@@ -189,14 +188,12 @@ uint32_t shw_io_read(shw_io_id_t id)
TRACE(TRACE_ERROR,"Unknow type %d for io #%d",io->type,id); break;
}
}
return ret;
return 0;
}
int shw_io_write(shw_io_id_t id, uint32_t value)
{
int ret=-1;
int32_t i32data;
uint8_t u8data[2];
const shw_io_t* io=&_all_shw_io[id];
const shw_io_bus_t *iobus;
......
......@@ -25,7 +25,7 @@ GIT_USR = $(shell git config --get-all user.name)
CFLAGS = -O2 -g -Wall \
-I$(LINUX)/include \
-I$(LINUX)/arch/arm/mach-at91/include \
-I../libptpnetif \
-I../libwr \
-I../wrsw_hal \
-I../wrsw_rtud \
-I../mini-rpc \
......@@ -37,10 +37,9 @@ ifdef WRS_TOOLS_DEBUG
endif
LDFLAGS = -L../mini-rpc \
-L../libptpnetif \
-L../libswitchhw \
-L../libwr \
-L../libsdb \
-lminipc -lptpnetif -lswitchhw -lsdbfs -llua -lm -ldl
-lminipc -lwr -lsdbfs -llua -lm -ldl
all: $(TOOLS)
......
......@@ -115,7 +115,7 @@ int fetch_rtu_vd(rtudexp_vd_entry_t *d, int *n_entries)
/**
* \brief Write mac address into a buffer to avoid concurrent access on static variable.
*/
//TODO: already defined in wrsw_rtud lib but we do not link to it. 3 opts: make it inline, move to libswitchhw or link to the rtud lib?
//TODO: already defined in wrsw_rtud lib but we do not link to it. 3 opts: make it inline, move to libwr or link to the rtud lib?
char *mac_to_buffer(uint8_t mac[ETH_ALEN],char buffer[ETH_ALEN_STR])
{
if(mac && buffer)
......
......@@ -18,8 +18,8 @@ ifdef WRS_HAL_DEBUG
CFLAGS += -DDEBUG
endif
LDFLAGS = -L../libswitchhw -L../mini-rpc \
-lminipc -llua -lm -ldl -lswitchhw
LDFLAGS = -L../libwr -L../mini-rpc \
-lminipc -llua -lm -ldl -lwr
all: $(BINARY)
......
......@@ -60,7 +60,7 @@ int hal_setup_fpga_images()
// shw_set_fpga_firmware_path(fpga_dir);
/* check if the config demands a particular bitstream (otherwise libswitchhw will load the default ones) */
/* check if the config demands a particular bitstream (otherwise libwr will load the default ones) */
/* if( !hal_config_get_string("global.main_firmware", fw_name, sizeof(fw_name)))
shw_request_fpga_firmware(FPGA_ID_MAIN, fw_name);
......
......@@ -13,7 +13,7 @@ WR_INCLUDE = $(WR_INSTALL_ROOT)/include
WR_LIB = $(WR_INSTALL_ROOT)/lib
CFLAGS = -O2 -Wall -ggdb \
-I../libptpnetif -I../wrsw_hal \
-I../libwr -I../wrsw_hal \
-I../mini-rpc -I../include -I$(WR_INCLUDE) -I$(LINUX)/include
# -I$(CROSS_COMPILE_ARM_PATH)/../include
......@@ -22,8 +22,8 @@ ifdef WRS_RTUD_DEBUG
endif
LDFLAGS := -L../libptpnetif -L../libswitchhw -L../mini-rpc\
-lswitchhw -lptpnetif -lpthread -lminipc
LDFLAGS := -L../libwr -L../mini-rpc\
-lwr -lpthread -lminipc
RM := rm -f
......
......@@ -85,7 +85,7 @@ wr_rtu.h:
============
../include
../libswitchhw
../libwr
../../kernel/include/
The support for the RTU IRQ is implemented in the package "wr_rtu" at
......
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