Commit 4cb937ab authored by Alessandro Rubini's avatar Alessandro Rubini

Merge branch 'restyle' into proposed2

parents a2721762 e625cbd9
# choose your board here.
# choose your board here.
BOARD = spec
# 1 enables Etherbone support
......@@ -81,8 +81,8 @@ OBJS_PTPD = $(PTP_NOPOSIX)/PTPWRd/arith.o \
$(PTP_NOPOSIX)/libposix/net.o \
$(PTP_NOPOSIX)/softpll/softpll_ng.o
CFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled
LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -nostdlib -T arch/lm32/ram.ld
CFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled
LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -nostdlib -T arch/lm32/ram.ld
OBJS_PLATFORM=arch/lm32/crt0.o arch/lm32/irq.o arch/lm32/debug.o
......@@ -96,14 +96,14 @@ CC=$(CROSS_COMPILE)gcc
OBJDUMP=$(CROSS_COMPILE)objdump
OBJCOPY=$(CROSS_COMPILE)objcopy
SIZE=$(CROSS_COMPILE)size
CFLAGS= $(CFLAGS_PLATFORM) $(CFLAGS_EB) $(CFLAGS_PTPD) $(INCLUDE_DIRS) -ffunction-sections -fdata-sections -Os -Iinclude -include include/trace.h $(PTPD_CFLAGS) -I$(PTP_NOPOSIX)/PTPWRd -I. -Isoftpll
LDFLAGS= $(LDFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Wl,--gc-sections -Os -Iinclude
OBJS=$(OBJS_PLATFORM) $(OBJS_WRC) $(OBJS_PTPD) $(OBJS_SHELL) $(OBJS_TESTS) $(OBJS_LIB) $(OBJS_SOCKITOWM) $(OBJS_SOFTPLL) $(OBJS_DEV)
OUTPUT=wrc
REVISION=$(shell git rev-parse HEAD)
$(shell ln -sf ../boards/$(BOARD)/board.h include/board.h)
$(shell ln -sf ../boards/$(BOARD)/board.h include/board.h)
all: tools wrc
......@@ -112,14 +112,14 @@ wrc: $(OBJS)
echo "const char *build_date = __DATE__ \" \" __TIME__;" >> revision.c
$(CC) $(CFLAGS) -c revision.c
$(SIZE) -t $(OBJS)
${CC} -o $(OUTPUT).elf revision.o $(OBJS) $(LDFLAGS)
${CC} -o $(OUTPUT).elf revision.o $(OBJS) $(LDFLAGS)
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
${OBJDUMP} -d $(OUTPUT).elf > $(OUTPUT)_disasm.S
cd tools; $(MAKE)
./tools/genraminit $(OUTPUT).bin 0 > $(OUTPUT).ram
./tools/genramvhd -s 90112 $(OUTPUT).bin > $(OUTPUT).vhd
clean:
clean:
rm -f $(OBJS) $(OUTPUT).elf $(OUTPUT).bin $(OUTPUT).ram
%.o: %.c
......
......@@ -3,7 +3,7 @@
* Load this code anywhere in memory and point DEBA at it.
* When DC=1 it chain loads the exception handlers at EBA.
* User exception handlers must save to the stack.
*
*
* Copyright (C) 2011 by Wesley W. Terpstra <w.terpstra@gsi.de>
*/
......@@ -289,7 +289,7 @@ handle_debug_trap:
calli jtag_put_byte
_get_command:
/* Input: [Wxxxxxxx]
/* Input: [Wxxxxxxx]
* W=0, x=0: quit debug trap
* W=1, x=0: report register dump location
* W=0, x>0: read 'x' bytes
......@@ -306,7 +306,7 @@ _get_command:
/* Load memory access address */
calli jtag_get_word
mv r11, r1
/* Either read or write */
bne r10, r0, _read_mem
......
......@@ -2,38 +2,36 @@
void disable_irq()
{
unsigned int ie, im;
unsigned int Mask = ~1;
unsigned int ie, im;
unsigned int Mask = ~1;
/* disable peripheral interrupts in case they were enabled */
asm volatile ("rcsr %0,ie":"=r"(ie));
ie &= (~0x1);
asm volatile ("wcsr ie, %0"::"r"(ie));
/* disable peripheral interrupts in case they were enabled */
asm volatile ("rcsr %0,ie":"=r" (ie));
ie &= (~0x1);
asm volatile ("wcsr ie, %0"::"r" (ie));
/* disable mask-bit in im */
asm volatile ("rcsr %0, im":"=r"(im));
im &= Mask;
asm volatile ("wcsr im, %0"::"r"(im));
/* disable mask-bit in im */
asm volatile ("rcsr %0, im":"=r" (im));
im &= Mask;
asm volatile ("wcsr im, %0"::"r" (im));
}
void enable_irq()
{
unsigned int ie, im;
unsigned int Mask = 1;
unsigned int ie, im;
unsigned int Mask = 1;
/* disable peripheral interrupts in-case they were enabled*/
asm volatile ("rcsr %0,ie":"=r"(ie));
ie &= (~0x1);
asm volatile ("wcsr ie, %0"::"r"(ie));
/* disable peripheral interrupts in-case they were enabled */
asm volatile ("rcsr %0,ie":"=r" (ie));
ie &= (~0x1);
asm volatile ("wcsr ie, %0"::"r" (ie));
/* enable mask-bit in im */
asm volatile ("rcsr %0, im":"=r"(im));
im |= Mask;
asm volatile ("wcsr im, %0"::"r"(im));
/* enable mask-bit in im */
asm volatile ("rcsr %0, im":"=r" (im));
im |= Mask;
asm volatile ("wcsr im, %0"::"r" (im));
ie |= 0x1;
asm volatile ("wcsr ie, %0"::"r"(ie));
ie |= 0x1;
asm volatile ("wcsr ie, %0"::"r" (ie));
}
......@@ -38,7 +38,7 @@ SECTIONS
{
.boot : { *(.boot) } > ram
/* Code */
.text :
{
......@@ -60,26 +60,26 @@ SECTIONS
KEEP (*(.dtors))
KEEP (*(.jcr))
_etext = .;
} > ram =0
} > ram =0
/* Exception handlers */
.eh_frame_hdr : { *(.eh_frame_hdr) } > ram
.eh_frame : { KEEP (*(.eh_frame)) } > ram
.gcc_except_table : { *(.gcc_except_table) *(.gcc_except_table.*) } > ram
/* Read-only data */
.rodata :
{
.rodata :
{
. = ALIGN(4);
_frodata = .;
_frodata_rom = LOADADDR(.rodata);
*(.rodata .rodata.* .gnu.linkonce.r.*)
*(.rodata .rodata.* .gnu.linkonce.r.*)
*(.rodata1)
_erodata = .;
} > ram
/* Data */
.data :
.data :
{
. = ALIGN(4);
_fdata = .;
......@@ -90,8 +90,8 @@ SECTIONS
_gp = ALIGN(16) + 0x7ff0;
*(.sdata .sdata.* .gnu.linkonce.s.*)
_edata = .;
} > ram
} > ram
/* BSS */
.bss :
{
......@@ -108,10 +108,10 @@ SECTIONS
_end = .;
PROVIDE (end = .);
} > ram
/* First location in stack is highest address in RAM */
PROVIDE(_fstack = ORIGIN(ram) + LENGTH(ram) - 4);
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
......@@ -120,7 +120,7 @@ SECTIONS
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections.
Symbols in the DWARF debugging sections are relative to the beginning
of the section so we begin them at 0. */
......
......@@ -10,4 +10,4 @@ int board_init()
int board_update()
{
}
\ No newline at end of file
}
......@@ -10,4 +10,4 @@ int board_init()
int board_update()
{
}
\ No newline at end of file
}
......@@ -6,45 +6,45 @@
#define DNA_SHIFT 3
#define DNA_READ 2
void dna_read(uint32_t *lo, uint32_t *hi)
void dna_read(uint32_t * lo, uint32_t * hi)
{
uint64_t dna = 0;
int i;
gpio_out(DNA_DATA, 0);
delay(10);
gpio_out(DNA_CLK, 0);
delay(10);
gpio_out(DNA_READ, 1);
delay(10);
gpio_out(DNA_SHIFT, 0);
delay(10);
delay(10);
gpio_out(DNA_CLK, 1);
delay(10);
if(gpio_in(DNA_DATA)) dna |= 1;
delay(10);
gpio_out(DNA_CLK, 0);
delay(10);
gpio_out(DNA_READ, 0);
gpio_out(DNA_SHIFT, 1);
delay(10);
uint64_t dna = 0;
int i;
gpio_out(DNA_DATA, 0);
delay(10);
gpio_out(DNA_CLK, 0);
delay(10);
gpio_out(DNA_READ, 1);
delay(10);
gpio_out(DNA_SHIFT, 0);
delay(10);
delay(10);
gpio_out(DNA_CLK, 1);
delay(10);
if (gpio_in(DNA_DATA))
dna |= 1;
delay(10);
gpio_out(DNA_CLK, 0);
delay(10);
gpio_out(DNA_READ, 0);
gpio_out(DNA_SHIFT, 1);
delay(10);
for (i = 0; i < 57; i++) {
dna <<= 1;
delay(10);
delay(10);
gpio_out(DNA_CLK, 1);
delay(10);
if (gpio_in(DNA_DATA))
dna |= 1;
delay(10);
gpio_out(DNA_CLK, 0);
delay(10);
}
for(i=0;i<57;i++)
{
dna <<= 1;
delay(10);
delay(10);
gpio_out(DNA_CLK, 1);
delay(10);
if(gpio_in(DNA_DATA)) dna |= 1;
delay(10);
gpio_out(DNA_CLK, 0);
delay(10);
}
*hi = (uint32_t) (dna >> 32);
*lo = (uint32_t) dna;
}
This diff is collapsed.
/*
WR Endpoint (WR-compatible Ethernet MAC driver
WR Endpoint (WR-compatible Ethernet MAC driver
Tomasz Wlostowski/CERN 2011
......@@ -18,7 +18,6 @@ LGPL 2.1
#include <hw/endpoint_regs.h>
#include <hw/endpoint_mdio.h>
/* Length of a single bit on the gigabit serial link in picoseconds. Used for calculating deltaRx/deltaTx
from the serdes bitslip value */
#define PICOS_PER_SERIAL_BIT 800
......@@ -33,150 +32,150 @@ volatile struct EP_WB *EP;
/* functions for accessing PCS (MDIO) registers */
uint16_t pcs_read(int location)
{
EP->MDIO_CR = EP_MDIO_CR_ADDR_W(location >> 2);
while ((EP->MDIO_ASR & EP_MDIO_ASR_READY) == 0);
return EP_MDIO_ASR_RDATA_R(EP->MDIO_ASR) & 0xffff;
EP->MDIO_CR = EP_MDIO_CR_ADDR_W(location >> 2);
while ((EP->MDIO_ASR & EP_MDIO_ASR_READY) == 0) ;
return EP_MDIO_ASR_RDATA_R(EP->MDIO_ASR) & 0xffff;
}
void pcs_write(int location, int value)
{
EP->MDIO_CR = EP_MDIO_CR_ADDR_W(location >> 2)
| EP_MDIO_CR_DATA_W(value)
| EP_MDIO_CR_RW;
EP->MDIO_CR = EP_MDIO_CR_ADDR_W(location >> 2)
| EP_MDIO_CR_DATA_W(value)
| EP_MDIO_CR_RW;
while ((EP->MDIO_ASR & EP_MDIO_ASR_READY) == 0);
while ((EP->MDIO_ASR & EP_MDIO_ASR_READY) == 0) ;
}
/* MAC address setting */
void set_mac_addr(uint8_t dev_addr[])
{
EP->MACL = ((uint32_t)dev_addr[2] << 24)
| ((uint32_t)dev_addr[3] << 16)
| ((uint32_t)dev_addr[4] << 8)
| ((uint32_t)dev_addr[5]);
EP->MACL = ((uint32_t) dev_addr[2] << 24)
| ((uint32_t) dev_addr[3] << 16)
| ((uint32_t) dev_addr[4] << 8)
| ((uint32_t) dev_addr[5]);
EP->MACH = ((uint32_t)dev_addr[0] << 8)
| ((uint32_t)dev_addr[1]);
EP->MACH = ((uint32_t) dev_addr[0] << 8)
| ((uint32_t) dev_addr[1]);
}
void get_mac_addr(uint8_t dev_addr[])
{
dev_addr[5] = (EP->MACL & 0x000000ff);
dev_addr[4] = (EP->MACL & 0x0000ff00) >> 8;
dev_addr[3] = (EP->MACL & 0x00ff0000) >> 16;
dev_addr[2] = (EP->MACL & 0xff000000) >> 24;
dev_addr[1] = (EP->MACH & 0x000000ff);
dev_addr[0] = (EP->MACH & 0x0000ff00) >> 8;
dev_addr[5] = (EP->MACL & 0x000000ff);
dev_addr[4] = (EP->MACL & 0x0000ff00) >> 8;
dev_addr[3] = (EP->MACL & 0x00ff0000) >> 16;
dev_addr[2] = (EP->MACL & 0xff000000) >> 24;
dev_addr[1] = (EP->MACH & 0x000000ff);
dev_addr[0] = (EP->MACH & 0x0000ff00) >> 8;
}
/* Initializes the endpoint and sets its local MAC address */
void ep_init(uint8_t mac_addr[])
{
EP = (volatile struct EP_WB *) BASE_EP;
set_mac_addr(mac_addr);
EP = (volatile struct EP_WB *)BASE_EP;
set_mac_addr(mac_addr);
*(unsigned int *)(0x62000) = 0x2; // reset network stuff (cleanup required!)
*(unsigned int *)(0x62000) = 0;
*(unsigned int *)(0x62000) = 0x2; // reset network stuff (cleanup required!)
*(unsigned int *)(0x62000) = 0;
EP->ECR = 0; /* disable Endpoint */
EP->VCR0 = EP_VCR0_QMODE_W(3); /* disable VLAN unit - not used by WRPC */
EP->RFCR = EP_RFCR_MRU_W(1518); /* Set the max RX packet size */
EP->TSCR = EP_TSCR_EN_TXTS | EP_TSCR_EN_RXTS; /* Enable timestamping */
EP->ECR = 0; /* disable Endpoint */
EP->VCR0 = EP_VCR0_QMODE_W(3); /* disable VLAN unit - not used by WRPC */
EP->RFCR = EP_RFCR_MRU_W(1518); /* Set the max RX packet size */
EP->TSCR = EP_TSCR_EN_TXTS | EP_TSCR_EN_RXTS; /* Enable timestamping */
/* Configure DMTD phase tracking */
EP->DMCR = EP_DMCR_EN | EP_DMCR_N_AVG_W(DMTD_AVG_SAMPLES);
EP->DMCR = EP_DMCR_EN | EP_DMCR_N_AVG_W(DMTD_AVG_SAMPLES);
}
/* Enables/disables transmission and reception. When autoneg is set to 1,
starts up 802.3 autonegotiation process */
int ep_enable(int enabled, int autoneg)
{
uint16_t mcr;
uint16_t mcr;
if(!enabled)
{
EP->ECR = 0;
return 0;
}
if (!enabled) {
EP->ECR = 0;
return 0;
}
/* Disable the endpoint */
EP->ECR = 0;
EP->ECR = 0;
mprintf("ID: %x\n", EP->IDCODE);
mprintf("ID: %x\n", EP->IDCODE);
/* Load default packet classifier rules - see ep_pfilter.c for details */
pfilter_init_default();
pfilter_init_default();
/* Enable TX/RX paths, reset RMON counters */
EP->ECR = EP_ECR_TX_EN | EP_ECR_RX_EN | EP_ECR_RST_CNT;
EP->ECR = EP_ECR_TX_EN | EP_ECR_RX_EN | EP_ECR_RST_CNT;
autoneg_enabled = autoneg;
autoneg_enabled = autoneg;
/* Reset the GTP Transceiver - it's important to do the GTP phase alignment every time
we start up the software, otherwise the calibration RX/TX deltas may not be correct */
pcs_write(MDIO_REG_MCR, MDIO_MCR_PDOWN); /* reset the PHY */
timer_delay(200);
pcs_write(MDIO_REG_MCR, MDIO_MCR_RESET); /* reset the PHY */
pcs_write(MDIO_REG_MCR, 0); /* reset the PHY */
pcs_write(MDIO_REG_MCR, MDIO_MCR_PDOWN); /* reset the PHY */
timer_delay(200);
pcs_write(MDIO_REG_MCR, MDIO_MCR_RESET); /* reset the PHY */
pcs_write(MDIO_REG_MCR, 0); /* reset the PHY */
/* Don't advertise anything - we don't want flow control */
pcs_write(MDIO_REG_ADVERTISE, 0);
pcs_write(MDIO_REG_ADVERTISE, 0);
mcr = MDIO_MCR_SPEED1000_MASK | MDIO_MCR_FULLDPLX_MASK;
if(autoneg)
mcr |= MDIO_MCR_ANENABLE | MDIO_MCR_ANRESTART;
mcr = MDIO_MCR_SPEED1000_MASK | MDIO_MCR_FULLDPLX_MASK;
if (autoneg)
mcr |= MDIO_MCR_ANENABLE | MDIO_MCR_ANRESTART;
pcs_write(MDIO_REG_MCR, mcr);
return 0;
pcs_write(MDIO_REG_MCR, mcr);
return 0;
}
/* Checks the link status. If the link is up, returns non-zero
and stores the Link Partner Ability (LPA) autonegotiation register at *lpa */
int ep_link_up(uint16_t *lpa)
int ep_link_up(uint16_t * lpa)
{
uint16_t flags = MDIO_MSR_LSTATUS;
volatile uint16_t msr;
uint16_t flags = MDIO_MSR_LSTATUS;
volatile uint16_t msr;
if(autoneg_enabled)
flags |= MDIO_MSR_ANEGCOMPLETE;
if (autoneg_enabled)
flags |= MDIO_MSR_ANEGCOMPLETE;
msr = pcs_read(MDIO_REG_MSR);
msr = pcs_read(MDIO_REG_MSR); /* Read this flag twice to make sure the status is updated */
msr = pcs_read(MDIO_REG_MSR);
msr = pcs_read(MDIO_REG_MSR); /* Read this flag twice to make sure the status is updated */
if(lpa) *lpa = pcs_read(MDIO_REG_LPA);
if (lpa)
*lpa = pcs_read(MDIO_REG_LPA);
return (msr & flags) == flags ? 1 : 0;
return (msr & flags) == flags ? 1 : 0;
}
/* Returns the TX/RX latencies. They are valid only when the link is up. */
int ep_get_deltas(uint32_t *delta_tx, uint32_t *delta_rx)
int ep_get_deltas(uint32_t * delta_tx, uint32_t * delta_rx)
{
/* fixme: these values should be stored in calibration block in the EEPROM on the FMC. Also, the TX/RX delays of a particular SFP
should be added here */
*delta_tx = sfp_deltaTx;
*delta_rx = sfp_deltaRx + PICOS_PER_SERIAL_BIT * MDIO_WR_SPEC_BSLIDE_R(pcs_read(MDIO_REG_WR_SPEC));
/* fixme: these values should be stored in calibration block in the EEPROM on the FMC. Also, the TX/RX delays of a particular SFP
should be added here */
*delta_tx = sfp_deltaTx;
*delta_rx =
sfp_deltaRx +
PICOS_PER_SERIAL_BIT *
MDIO_WR_SPEC_BSLIDE_R(pcs_read(MDIO_REG_WR_SPEC));
return 0;
}
int ep_cal_pattern_enable()
{
uint32_t val;
val = pcs_read(MDIO_REG_WR_SPEC);
val |= MDIO_WR_SPEC_TX_CAL;
pcs_write(MDIO_REG_WR_SPEC, val);
uint32_t val;
val = pcs_read(MDIO_REG_WR_SPEC);
val |= MDIO_WR_SPEC_TX_CAL;
pcs_write(MDIO_REG_WR_SPEC, val);
return 0;
return 0;
}
int ep_cal_pattern_disable()
{
uint32_t val;
val = pcs_read(MDIO_REG_WR_SPEC);
val &= (~MDIO_WR_SPEC_TX_CAL);
pcs_write(MDIO_REG_WR_SPEC, val);
uint32_t val;
val = pcs_read(MDIO_REG_WR_SPEC);
val &= (~MDIO_WR_SPEC_TX_CAL);
pcs_write(MDIO_REG_WR_SPEC, val);
return 0;
return 0;
}
This diff is collapsed.
......@@ -6,8 +6,9 @@
void mi2c_delay()
{
int i;
for(i=0;i<I2C_DELAY;i++) asm volatile ("nop");
int i;
for (i = 0; i < I2C_DELAY; i++)
asm volatile ("nop");
}
#define M_SDA_OUT(i, x) { gpio_out(i2c_if[i].sda, x); mi2c_delay(); }
......@@ -16,109 +17,105 @@ void mi2c_delay()
void mi2c_start(uint8_t i2cif)
{
M_SDA_OUT(i2cif, 0);
M_SCL_OUT(i2cif, 0);
M_SDA_OUT(i2cif, 0);
M_SCL_OUT(i2cif, 0);
}
void mi2c_repeat_start(uint8_t i2cif)
{
M_SDA_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 0);
M_SCL_OUT(i2cif, 0);
M_SDA_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 0);
M_SCL_OUT(i2cif, 0);
}
void mi2c_stop(uint8_t i2cif)
{
M_SDA_OUT(i2cif, 0);
M_SCL_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 0);
M_SCL_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 1);
}
unsigned char mi2c_put_byte(uint8_t i2cif, unsigned char data)
{
char i;
unsigned char ack;
char i;
unsigned char ack;
for (i=0;i<8;i++, data<<=1)
{
M_SDA_OUT(i2cif, data&0x80);
M_SCL_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 0);
}
for (i = 0; i < 8; i++, data <<= 1) {
M_SDA_OUT(i2cif, data & 0x80);
M_SCL_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 0);
}
M_SDA_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 1);
ack = M_SDA_IN(i2cif); /* ack: sda is pulled low ->success. */
ack = M_SDA_IN(i2cif); /* ack: sda is pulled low ->success. */
M_SCL_OUT(i2cif, 0);
M_SDA_OUT(i2cif, 0);
M_SCL_OUT(i2cif, 0);
M_SDA_OUT(i2cif, 0);
return ack!=0;
return ack != 0;
}
void mi2c_get_byte(uint8_t i2cif, unsigned char *data, uint8_t last)
{
int i;
unsigned char indata = 0;
M_SDA_OUT(i2cif, 1);
/* assert: scl is low */
M_SCL_OUT(i2cif, 0);
for (i=0;i<8;i++)
{
M_SCL_OUT(i2cif, 1);
indata <<= 1;
if ( M_SDA_IN(i2cif) ) indata |= 0x01;
M_SCL_OUT(i2cif, 0);
}
if(last)
{
M_SDA_OUT(i2cif, 1); //noack
M_SCL_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 0);
}
else
{
M_SDA_OUT(i2cif, 0); //ack
M_SCL_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 0);
}
*data= indata;
int i;
unsigned char indata = 0;
M_SDA_OUT(i2cif, 1);
/* assert: scl is low */
M_SCL_OUT(i2cif, 0);
for (i = 0; i < 8; i++) {
M_SCL_OUT(i2cif, 1);
indata <<= 1;
if (M_SDA_IN(i2cif))
indata |= 0x01;
M_SCL_OUT(i2cif, 0);
}
if (last) {
M_SDA_OUT(i2cif, 1); //noack
M_SCL_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 0);
} else {
M_SDA_OUT(i2cif, 0); //ack
M_SCL_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 0);
}
*data = indata;
}
void mi2c_init(uint8_t i2cif)
{
M_SCL_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 1);
M_SCL_OUT(i2cif, 1);
M_SDA_OUT(i2cif, 1);
}
uint8_t mi2c_devprobe(uint8_t i2cif, uint8_t i2c_addr)
{
uint8_t ret;
mi2c_start(i2cif);
ret = !mi2c_put_byte(i2cif, i2c_addr<<1);
mi2c_stop(i2cif);
uint8_t ret;
mi2c_start(i2cif);
ret = !mi2c_put_byte(i2cif, i2c_addr << 1);
mi2c_stop(i2cif);
return ret;
return ret;
}
//void mi2c_scan(uint8_t i2cif)
//{
// int i;
//
//
// //for(i=0;i<0x80;i++)
// for(i=0x50;i<0x51;i++)
// {
// mi2c_start(i2cif);
// if(!mi2c_put_byte(i2cif, i<<1)) mprintf("found : %x\n", i);
// mi2c_stop(i2cif);
//
// }
//
// }
// mprintf("Nothing more found...\n");
//}
This diff is collapsed.
......@@ -10,106 +10,115 @@ uint8_t found_msk;
void own_scanbus(uint8_t portnum)
{
// Find the device(s)
found_msk = 0;
devsnum = 0;
devsnum += FindDevices(portnum, &FamilySN[devsnum], 0x28, MAX_DEV1WIRE - devsnum); /* Temperature 28 sensor (SPEC) */
if(devsnum>0) found_msk |= FOUND_DS18B20;
devsnum += FindDevices(portnum, &FamilySN[devsnum], 0x42, MAX_DEV1WIRE - devsnum); /* Temperature 42 sensor (SCU) */
devsnum += FindDevices(portnum, &FamilySN[devsnum], 0x43, MAX_DEV1WIRE - devsnum); /* EEPROM */
// Find the device(s)
found_msk = 0;
devsnum = 0;
devsnum += FindDevices(portnum, &FamilySN[devsnum], 0x28, MAX_DEV1WIRE - devsnum); /* Temperature 28 sensor (SPEC) */
if (devsnum > 0)
found_msk |= FOUND_DS18B20;
devsnum += FindDevices(portnum, &FamilySN[devsnum], 0x42, MAX_DEV1WIRE - devsnum); /* Temperature 42 sensor (SCU) */
devsnum += FindDevices(portnum, &FamilySN[devsnum], 0x43, MAX_DEV1WIRE - devsnum); /* EEPROM */
#if DEBUG_PMAC
mprintf("Found %d onewire devices\n", devsnum);
mprintf("Found %d onewire devices\n", devsnum);
#endif
}
int16_t own_readtemp(uint8_t portnum, int16_t *temp, int16_t *t_frac)
int16_t own_readtemp(uint8_t portnum, int16_t * temp, int16_t * t_frac)
{
if(!(found_msk & FOUND_DS18B20))
return -1;
if(ReadTemperature28(portnum, FamilySN[0], temp))
{
*t_frac = 5000*(!!(*temp & 0x08)) + 2500*(!!(*temp & 0x04)) + 1250*(!!(*temp & 0x02)) +
625*(!!(*temp & 0x01));
*t_frac = *t_frac/100 + (*t_frac%100)/50;
*temp >>= 4;
return 0;
}
return -1;
if (!(found_msk & FOUND_DS18B20))
return -1;
if (ReadTemperature28(portnum, FamilySN[0], temp)) {
*t_frac =
5000 * (! !(*temp & 0x08)) + 2500 * (! !(*temp & 0x04)) +
1250 * (! !(*temp & 0x02)) + 625 * (! !(*temp & 0x01));
*t_frac = *t_frac / 100 + (*t_frac % 100) / 50;
*temp >>= 4;
return 0;
}
return -1;
}
/* 0 = success, -1 = error */
int8_t get_persistent_mac(uint8_t portnum, uint8_t* mac)
int8_t get_persistent_mac(uint8_t portnum, uint8_t * mac)
{
uint8_t read_buffer[32];
uint8_t i;
int8_t out;
out = -1;
if(devsnum == 0) return out;
for (i = 0; i < devsnum; ++i) {
uint8_t read_buffer[32];
uint8_t i;
int8_t out;
out = -1;
if (devsnum == 0)
return out;
for (i = 0; i < devsnum; ++i) {
//#if DEBUG_PMAC
mprintf("Found device: %x:%x:%x:%x:%x:%x:%x:%x\n",
FamilySN[i][7], FamilySN[i][6], FamilySN[i][5], FamilySN[i][4],
FamilySN[i][3], FamilySN[i][2], FamilySN[i][1], FamilySN[i][0]);
mprintf("Found device: %x:%x:%x:%x:%x:%x:%x:%x\n",
FamilySN[i][7], FamilySN[i][6], FamilySN[i][5], FamilySN[i][4],
FamilySN[i][3], FamilySN[i][2], FamilySN[i][1], FamilySN[i][0]);
//#endif
/* If there is a temperature sensor, use it for the low three MAC values */
if (FamilySN[i][0] == 0x28 || FamilySN[i][0] == 0x42) {
mac[3] = FamilySN[i][3];
mac[4] = FamilySN[i][2];
mac[5] = FamilySN[i][1];
out = 0;
/* If there is a temperature sensor, use it for the low three MAC values */
if (FamilySN[i][0] == 0x28 || FamilySN[i][0] == 0x42) {
mac[3] = FamilySN[i][3];
mac[4] = FamilySN[i][2];
mac[5] = FamilySN[i][1];
out = 0;
#if DEBUG_PMAC
mprintf("Using temperature ID for MAC\n");
mprintf("Using temperature ID for MAC\n");
#endif
}
/* If there is an EEPROM, read page 0 for the MAC */
if (FamilySN[i][0] == 0x43) {
owLevel(portnum, MODE_NORMAL);
if (ReadMem43(portnum, FamilySN[i], EEPROM_MAC_PAGE, &read_buffer) == TRUE) {
if (read_buffer[0] == 0 && read_buffer[1] == 0 && read_buffer[2] == 0) {
/* Skip the EEPROM since it has not been programmed! */
}
/* If there is an EEPROM, read page 0 for the MAC */
if (FamilySN[i][0] == 0x43) {
owLevel(portnum, MODE_NORMAL);
if (ReadMem43(portnum, FamilySN[i], EEPROM_MAC_PAGE,
&read_buffer) == TRUE) {
if (read_buffer[0] == 0 && read_buffer[1] == 0
&& read_buffer[2] == 0) {
/* Skip the EEPROM since it has not been programmed! */
#if DEBUG_PMAC
mprintf("EEPROM has not been programmed with a MAC\n");
mprintf("EEPROM has not been "
"programmed with a MAC\n");
#endif
} else {
memcpy(mac, read_buffer, 6);
out = 0;
} else {
memcpy(mac, read_buffer, 6);
out = 0;
#if DEBUG_PMAC
mprintf("Using EEPROM page: %x:%x:%x:%x:%x:%x\n",
mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
mprintf("Using EEPROM page: "
"%x:%x:%x:%x:%x:%x\n",
mac[0], mac[1], mac[2], mac[3],
mac[4], mac[5]);
#endif
}
}
}
}
return out;
}
}
}
}
return out;
}
/* 0 = success, -1 = error */
int8_t set_persistent_mac(uint8_t portnum, uint8_t* mac)
int8_t set_persistent_mac(uint8_t portnum, uint8_t * mac)
{
uint8_t FamilySN[1][8];
uint8_t write_buffer[32];
// Find the device (only the first one, we won't write MAC to all EEPROMs out there, right?)
if( FindDevices(portnum, &FamilySN[0], 0x43, 1) == 0) return -1;
memset(write_buffer, 0, sizeof(write_buffer));
memcpy(write_buffer, mac, 6);
uint8_t FamilySN[1][8];
uint8_t write_buffer[32];
// Find the device (only the first one, we won't write MAC to all EEPROMs out there, right?)
if (FindDevices(portnum, &FamilySN[0], 0x43, 1) == 0)
return -1;
memset(write_buffer, 0, sizeof(write_buffer));
memcpy(write_buffer, mac, 6);
#if DEBUG_PMAC
mprintf("Writing to EEPROM\n");
mprintf("Writing to EEPROM\n");
#endif
/* Write the last EEPROM with the MAC */
owLevel(portnum, MODE_NORMAL);
if (Write43(portnum, FamilySN[0], EEPROM_MAC_PAGE, &write_buffer) == TRUE)
return 0;
return -1;
/* Write the last EEPROM with the MAC */
owLevel(portnum, MODE_NORMAL);
if (Write43(portnum, FamilySN[0], EEPROM_MAC_PAGE, &write_buffer) ==
TRUE)
return 0;
return -1;
}
......@@ -24,50 +24,54 @@ int pps_gen_init()
cr = PPSG_CR_CNT_EN | PPSG_CR_PWIDTH_W(PPS_WIDTH);
ppsg_write(CR, cr);
ppsg_write(CR, cr);
ppsg_write(ADJ_UTCLO, 0);
ppsg_write(ADJ_UTCHI, 0);
ppsg_write(ADJ_NSEC, 0);
ppsg_write(ADJ_UTCLO, 0);
ppsg_write(ADJ_UTCHI, 0);
ppsg_write(ADJ_NSEC, 0);
ppsg_write(CR, cr | PPSG_CR_CNT_SET);
ppsg_write(CR, cr);
ppsg_write(ESCR, 0x6); /* enable PPS output */
ppsg_write(CR, cr | PPSG_CR_CNT_SET);
ppsg_write(CR, cr);
ppsg_write(ESCR, 0x6); /* enable PPS output */
}
/* Adjusts the nanosecond (refclk cycle) counter by atomically adding (how_much) cycles. */
int pps_gen_adjust(int counter, int64_t how_much)
{
uint32_t cr;
uint32_t cr;
TRACE_DEV("Adjust: counter = %s [%c%d]\n",
counter == PPSG_ADJUST_SEC ? "seconds" : "nanoseconds", how_much<0?'-':'+', (int32_t)abs(how_much));
TRACE_DEV("Adjust: counter = %s [%c%d]\n",
counter == PPSG_ADJUST_SEC ? "seconds" : "nanoseconds",
how_much < 0 ? '-' : '+', (int32_t) abs(how_much));
if(counter == PPSG_ADJUST_NSEC)
{
ppsg_write(ADJ_UTCLO, 0);
ppsg_write(ADJ_UTCHI, 0);
ppsg_write(ADJ_NSEC, (int32_t) ((int64_t) how_much * 1000LL / (int64_t)REF_CLOCK_PERIOD_PS));
if (counter == PPSG_ADJUST_NSEC) {
ppsg_write(ADJ_UTCLO, 0);
ppsg_write(ADJ_UTCHI, 0);
ppsg_write(ADJ_NSEC,
(int32_t) ((int64_t) how_much * 1000LL /
(int64_t) REF_CLOCK_PERIOD_PS));
} else {
ppsg_write(ADJ_UTCLO, (uint32_t ) (how_much & 0xffffffffLL));
ppsg_write(ADJ_UTCHI, (uint32_t ) (how_much >> 32) & 0xff);
ppsg_write(ADJ_UTCLO, (uint32_t) (how_much & 0xffffffffLL));
ppsg_write(ADJ_UTCHI, (uint32_t) (how_much >> 32) & 0xff);
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;
}
/* Sets the current time */
int pps_gen_set_time(uint64_t seconds, uint32_t nanoseconds)
{
uint32_t cr;
uint32_t cr;
ppsg_write(ADJ_UTCLO, (uint32_t ) (seconds & 0xffffffffLL));
ppsg_write(ADJ_UTCHI, (uint32_t ) (seconds >> 32) & 0xff);
ppsg_write(ADJ_NSEC, (int32_t) ((int64_t) nanoseconds * 1000LL / (int64_t)REF_CLOCK_PERIOD_PS));
ppsg_write(ADJ_UTCLO, (uint32_t) (seconds & 0xffffffffLL));
ppsg_write(ADJ_UTCHI, (uint32_t) (seconds >> 32) & 0xff);
ppsg_write(ADJ_NSEC,
(int32_t) ((int64_t) nanoseconds * 1000LL /
(int64_t) REF_CLOCK_PERIOD_PS));
ppsg_write(CR, (ppsg_read(CR) & 0xfffffffb) | PPSG_CR_CNT_SET);
ppsg_write(CR, (ppsg_read(CR) & 0xfffffffb) | PPSG_CR_CNT_SET);
return 0;
}
......@@ -75,46 +79,52 @@ uint64_t pps_get_utc(void)
{
uint64_t out;
uint32_t low, high;
low = ppsg_read(CNTR_UTCLO);
low = ppsg_read(CNTR_UTCLO);
high = ppsg_read(CNTR_UTCHI);
high &= 0xFF; /* CNTR_UTCHI has only 8 bits defined -- rest are HDL don't care */
out = (uint64_t)low | (uint64_t)high << 32;
high &= 0xFF; /* CNTR_UTCHI has only 8 bits defined -- rest are HDL don't care */
out = (uint64_t) low | (uint64_t) high << 32;
return out;
}
void pps_gen_get_time(uint64_t *seconds, uint32_t *nanoseconds)
void pps_gen_get_time(uint64_t * seconds, uint32_t * nanoseconds)
{
uint32_t ns_cnt;
uint64_t sec1, sec2;
do {
sec1 = pps_get_utc();
ns_cnt = ppsg_read(CNTR_NSEC) & 0xFFFFFFFUL; /* 28-bit wide register */
ns_cnt = ppsg_read(CNTR_NSEC) & 0xFFFFFFFUL; /* 28-bit wide register */
sec2 = pps_get_utc();
} while(sec2 != sec1);
if(seconds) *seconds = sec2;
if(nanoseconds) *nanoseconds = (uint32_t) ((int64_t)ns_cnt * (int64_t) REF_CLOCK_PERIOD_PS / 1000LL);
} while (sec2 != sec1);
if (seconds)
*seconds = sec2;
if (nanoseconds)
*nanoseconds =
(uint32_t) ((int64_t) ns_cnt *
(int64_t) REF_CLOCK_PERIOD_PS / 1000LL);
}
/* Returns 1 when the adjustment operation is not yet finished */
int pps_gen_busy()
{
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 */
int pps_gen_enable_output(int enable)
{
uint32_t escr = ppsg_read(ESCR);
if(enable)
ppsg_write(ESCR, escr | PPSG_ESCR_PPS_VALID | PPSG_ESCR_TM_VALID);
else
ppsg_write(ESCR, escr & ~(PPSG_ESCR_PPS_VALID | PPSG_ESCR_TM_VALID));
uint32_t escr = ppsg_read(ESCR);
if (enable)
ppsg_write(ESCR,
escr | PPSG_ESCR_PPS_VALID | PPSG_ESCR_TM_VALID);
else
ppsg_write(ESCR,
escr & ~(PPSG_ESCR_PPS_VALID | PPSG_ESCR_TM_VALID));
return 0;
return 0;
}
......@@ -6,123 +6,135 @@
#define SDB_EMPTY 0xFF
typedef struct pair64 {
uint32_t high;
uint32_t low;
uint32_t high;
uint32_t low;
} pair64_t;
struct sdb_empty {
int8_t reserved[63];
uint8_t record_type;
int8_t reserved[63];
uint8_t record_type;
};
struct sdb_product {
pair64_t vendor_id;
uint32_t device_id;
uint32_t version;
uint32_t date;
int8_t name[19];
uint8_t record_type;
pair64_t vendor_id;
uint32_t device_id;
uint32_t version;
uint32_t date;
int8_t name[19];
uint8_t record_type;
};
struct sdb_component {
pair64_t addr_first;
pair64_t addr_last;
struct sdb_product product;
pair64_t addr_first;
pair64_t addr_last;
struct sdb_product product;
};
struct sdb_device {
uint16_t abi_class;
uint8_t abi_ver_major;
uint8_t abi_ver_minor;
uint32_t bus_specific;
struct sdb_component sdb_component;
uint16_t abi_class;
uint8_t abi_ver_major;
uint8_t abi_ver_minor;
uint32_t bus_specific;
struct sdb_component sdb_component;
};
struct sdb_bridge {
pair64_t sdb_child;
struct sdb_component sdb_component;
pair64_t sdb_child;
struct sdb_component sdb_component;
};
struct sdb_interconnect {
uint32_t sdb_magic;
uint16_t sdb_records;
uint8_t sdb_version;
uint8_t sdb_bus_type;
struct sdb_component sdb_component;
uint32_t sdb_magic;
uint16_t sdb_records;
uint8_t sdb_version;
uint8_t sdb_bus_type;
struct sdb_component sdb_component;
};
typedef union sdb_record {
struct sdb_empty empty;
struct sdb_device device;
struct sdb_bridge bridge;
struct sdb_interconnect interconnect;
struct sdb_empty empty;
struct sdb_device device;
struct sdb_bridge bridge;
struct sdb_interconnect interconnect;
} sdb_record_t;
static unsigned char* find_device_deep(unsigned int base, unsigned int sdb, unsigned int devid) {
sdb_record_t* record = (sdb_record_t*)sdb;
int records = record->interconnect.sdb_records;
int i;
for (i = 0; i < records; ++i, ++record) {
if (record->empty.record_type == SDB_BRIDGE) {
unsigned char* out =
find_device_deep(
base + record->bridge.sdb_component.addr_first.low,
record->bridge.sdb_child.low,
devid);
if (out) return out;
}
if (record->empty.record_type == SDB_DEVICE &&
record->device.sdb_component.product.device_id == devid) {
break;
}
}
if (i == records) return 0;
return (unsigned char*)(base + record->device.sdb_component.addr_first.low);
static unsigned char *find_device_deep(unsigned int base, unsigned int sdb,
unsigned int devid)
{
sdb_record_t *record = (sdb_record_t *) sdb;
int records = record->interconnect.sdb_records;
int i;
for (i = 0; i < records; ++i, ++record) {
if (record->empty.record_type == SDB_BRIDGE) {
unsigned char *out =
find_device_deep(base +
record->bridge.sdb_component.
addr_first.low,
record->bridge.sdb_child.low,
devid);
if (out)
return out;
}
if (record->empty.record_type == SDB_DEVICE &&
record->device.sdb_component.product.device_id == devid) {
break;
}
}
if (i == records)
return 0;
return (unsigned char *)(base +
record->device.sdb_component.addr_first.low);
}
static void print_devices_deep(unsigned int base, unsigned int sdb) {
sdb_record_t* record = (sdb_record_t*)sdb;
int records = record->interconnect.sdb_records;
int i;
char buf[20];
for (i = 0; i < records; ++i, ++record) {
if (record->empty.record_type == SDB_BRIDGE)
print_devices_deep(
base + record->bridge.sdb_component.addr_first.low,
record->bridge.sdb_child.low);
if (record->empty.record_type != SDB_DEVICE) continue;
memcpy(buf, record->device.sdb_component.product.name, 19);
buf[19] = 0;
mprintf("%8x:%8x 0x%8x %s\n",
record->device.sdb_component.product.vendor_id.low,
record->device.sdb_component.product.device_id,
base + record->device.sdb_component.addr_first.low,
buf);
}
static void print_devices_deep(unsigned int base, unsigned int sdb)
{
sdb_record_t *record = (sdb_record_t *) sdb;
int records = record->interconnect.sdb_records;
int i;
char buf[20];
for (i = 0; i < records; ++i, ++record) {
if (record->empty.record_type == SDB_BRIDGE)
print_devices_deep(base +
record->bridge.sdb_component.
addr_first.low,
record->bridge.sdb_child.low);
if (record->empty.record_type != SDB_DEVICE)
continue;
memcpy(buf, record->device.sdb_component.product.name, 19);
buf[19] = 0;
mprintf("%8x:%8x 0x%8x %s\n",
record->device.sdb_component.product.vendor_id.low,
record->device.sdb_component.product.device_id,
base + record->device.sdb_component.addr_first.low,
buf);
}
}
static unsigned char* find_device(unsigned int devid) {
find_device_deep(0, SDB_ADDRESS, devid);
static unsigned char *find_device(unsigned int devid)
{
find_device_deep(0, SDB_ADDRESS, devid);
}
void sdb_print_devices(void) {
mprintf("SDB memory map:\n");
print_devices_deep(0, SDB_ADDRESS);
mprintf("---\n");
void sdb_print_devices(void)
{
mprintf("SDB memory map:\n");
print_devices_deep(0, SDB_ADDRESS);
mprintf("---\n");
}
void sdb_find_devices(void) {
BASE_MINIC = find_device(0xab28633a);
BASE_EP = find_device(0x650c2d4f);
BASE_SOFTPLL = find_device(0x65158dc0);
BASE_PPS_GEN = find_device(0xde0d8ced);
BASE_SYSCON = find_device(0xff07fc47);
BASE_UART = find_device(0xe2d13d04);
BASE_ONEWIRE = find_device(0x779c5443);
BASE_ETHERBONE_CFG = find_device(0x68202b22);
void sdb_find_devices(void)
{
BASE_MINIC = find_device(0xab28633a);
BASE_EP = find_device(0x650c2d4f);
BASE_SOFTPLL = find_device(0x65158dc0);
BASE_PPS_GEN = find_device(0xde0d8ced);
BASE_SYSCON = find_device(0xff07fc47);
BASE_UART = find_device(0xe2d13d04);
BASE_ONEWIRE = find_device(0x779c5443);
BASE_ETHERBONE_CFG = find_device(0x68202b22);
}
......@@ -16,32 +16,31 @@ int sfp_read_part_id(char *part_id)
{
int i;
uint8_t data, sum;
mi2c_init(WRPC_SFP_I2C);
mi2c_start(WRPC_SFP_I2C);
mi2c_put_byte(WRPC_SFP_I2C, 0xA0);
mi2c_put_byte(WRPC_SFP_I2C, 0x00);
mi2c_repeat_start(WRPC_SFP_I2C);
mi2c_put_byte(WRPC_SFP_I2C, 0xA1);
mi2c_get_byte(WRPC_SFP_I2C, &data, 1);
mi2c_stop(WRPC_SFP_I2C);
sum = data;
mi2c_start(WRPC_SFP_I2C);
mi2c_put_byte(WRPC_SFP_I2C, 0xA1);
for(i=1; i<63; ++i)
{
mi2c_get_byte(WRPC_SFP_I2C, &data, 0);
sum = (uint8_t) ((uint16_t)sum + data) & 0xff;
if(i>=40 && i<=55) //Part Number
part_id[i-40] = data;
}
mi2c_get_byte(WRPC_SFP_I2C, &data, 1); //final word, checksum
mi2c_stop(WRPC_SFP_I2C);
if(sum == data)
return 0;
return -1;
mi2c_init(WRPC_SFP_I2C);
mi2c_start(WRPC_SFP_I2C);
mi2c_put_byte(WRPC_SFP_I2C, 0xA0);
mi2c_put_byte(WRPC_SFP_I2C, 0x00);
mi2c_repeat_start(WRPC_SFP_I2C);
mi2c_put_byte(WRPC_SFP_I2C, 0xA1);
mi2c_get_byte(WRPC_SFP_I2C, &data, 1);
mi2c_stop(WRPC_SFP_I2C);
sum = data;
mi2c_start(WRPC_SFP_I2C);
mi2c_put_byte(WRPC_SFP_I2C, 0xA1);
for (i = 1; i < 63; ++i) {
mi2c_get_byte(WRPC_SFP_I2C, &data, 0);
sum = (uint8_t) ((uint16_t) sum + data) & 0xff;
if (i >= 40 && i <= 55) //Part Number
part_id[i - 40] = data;
}
mi2c_get_byte(WRPC_SFP_I2C, &data, 1); //final word, checksum
mi2c_stop(WRPC_SFP_I2C);
if (sum == data)
return 0;
return -1;
}
#include "syscon.h"
struct s_i2c_if i2c_if[2] = { {SYSC_GPSR_FMC_SCL, SYSC_GPSR_FMC_SDA},
{SYSC_GPSR_SFP_SCL, SYSC_GPSR_SFP_SDA} };
struct s_i2c_if i2c_if[2] = {
{SYSC_GPSR_FMC_SCL, SYSC_GPSR_FMC_SDA},
{SYSC_GPSR_SFP_SCL, SYSC_GPSR_SFP_SDA}
};
volatile struct SYSCON_WB *syscon;
......@@ -10,28 +12,27 @@ volatile struct SYSCON_WB *syscon;
***************************/
void timer_init(uint32_t enable)
{
syscon = (volatile struct SYSCON_WB *) BASE_SYSCON;
if(enable)
syscon->TCR |= SYSC_TCR_ENABLE;
else
syscon->TCR &= ~SYSC_TCR_ENABLE;
syscon = (volatile struct SYSCON_WB *)BASE_SYSCON;
if (enable)
syscon->TCR |= SYSC_TCR_ENABLE;
else
syscon->TCR &= ~SYSC_TCR_ENABLE;
}
uint32_t timer_get_tics()
{
return syscon->TVR;
return syscon->TVR;
}
void timer_delay(uint32_t how_long)
{
uint32_t t_start;
uint32_t t_start;
// timer_init(1);
do
{
t_start = timer_get_tics();
} while(t_start > UINT32_MAX - how_long); //in case of overflow
do {
t_start = timer_get_tics();
} while (t_start > UINT32_MAX - how_long); //in case of overflow
while(t_start + how_long > timer_get_tics());
while (t_start + how_long > timer_get_tics()) ;
}
......@@ -4,14 +4,14 @@
uint32_t timer_get_tics()
{
return *(volatile uint32_t *) (BASE_TIMER);
return *(volatile uint32_t *)(BASE_TIMER);
}
void timer_delay(uint32_t how_long)
{
uint32_t t_start;
uint32_t t_start;
t_start = timer_get_tics();
t_start = timer_get_tics();
while(t_start + how_long > timer_get_tics());
while (t_start + how_long > timer_get_tics()) ;
}
......@@ -13,16 +13,15 @@ volatile struct UART_WB *uart;
void uart_init()
{
uart = (volatile struct UART_WB *) BASE_UART;
uart = (volatile struct UART_WB *)BASE_UART;
uart->BCR = CALC_BAUD(UART_BAUDRATE);
}
void uart_write_byte(int b)
{
if(b == '\n')
if (b == '\n')
uart_write_byte('\r');
while(uart->SR & UART_SR_TX_BUSY)
;
while (uart->SR & UART_SR_TX_BUSY) ;
uart->TDR = b;
}
......@@ -34,13 +33,13 @@ void uart_write_string(char *s)
int uart_poll()
{
return uart->SR & UART_SR_RX_RDY;
return uart->SR & UART_SR_RX_RDY;
}
int uart_read_byte()
{
if(!uart_poll())
if (!uart_poll())
return -1;
return uart->RDR & 0xff;
}
\ No newline at end of file
return uart->RDR & 0xff;
}
......@@ -7,7 +7,7 @@
*.info
*.ky
*.log
fine-delay.pdf
wrpc.pdf
*.pg
*.texi
*.toc
......
This diff is collapsed.
......@@ -19,28 +19,32 @@ extern int32_t sfp_deltaRx;
extern uint32_t cal_phase_transition;
extern uint8_t has_eeprom;
struct s_sfpinfo
{
char pn[SFP_PN_LEN];
int32_t alpha;
int32_t dTx;
int32_t dRx;
uint8_t chksum;
} __attribute__((__packed__));
struct s_sfpinfo {
char pn[SFP_PN_LEN];
int32_t alpha;
int32_t dTx;
int32_t dRx;
uint8_t chksum;
} __attribute__ ((__packed__));
uint8_t eeprom_present(uint8_t i2cif, uint8_t i2c_addr);
int eeprom_read(uint8_t i2cif, uint8_t i2c_addr, uint32_t offset, uint8_t *buf, size_t size);
int eeprom_write(uint8_t i2cif, uint8_t i2c_addr, uint32_t offset, uint8_t *buf, size_t size);
int eeprom_read(uint8_t i2cif, uint8_t i2c_addr, uint32_t offset, uint8_t * buf,
size_t size);
int eeprom_write(uint8_t i2cif, uint8_t i2c_addr, uint32_t offset,
uint8_t * buf, size_t size);
int32_t eeprom_sfpdb_erase(uint8_t i2cif, uint8_t i2c_addr);
int32_t eeprom_sfp_section(uint8_t i2cif, uint8_t i2c_addr, size_t size, uint16_t *section_sz);
int8_t eeprom_match_sfp(uint8_t i2cif, uint8_t i2c_addr, struct s_sfpinfo* sfp);
int32_t eeprom_sfp_section(uint8_t i2cif, uint8_t i2c_addr, size_t size,
uint16_t * section_sz);
int8_t eeprom_match_sfp(uint8_t i2cif, uint8_t i2c_addr, struct s_sfpinfo *sfp);
int8_t eeprom_phtrans(uint8_t i2cif, uint8_t i2c_addr, uint32_t *val, uint8_t write);
int8_t eeprom_phtrans(uint8_t i2cif, uint8_t i2c_addr, uint32_t * val,
uint8_t write);
int8_t eeprom_init_erase(uint8_t i2cif, uint8_t i2c_addr);
int8_t eeprom_init_add(uint8_t i2cif, uint8_t i2c_addr, const char *args[]);
int32_t eeprom_init_show(uint8_t i2cif, uint8_t i2c_addr);
int8_t eeprom_init_readcmd(uint8_t i2cif, uint8_t i2c_addr, char* buf, uint8_t bufsize, uint8_t next);
int8_t eeprom_init_readcmd(uint8_t i2cif, uint8_t i2c_addr, char *buf,
uint8_t bufsize, uint8_t next);
#endif
......@@ -7,23 +7,23 @@
#include <stdint.h>
typedef enum {
AND=0,
NAND=4,
OR=1,
NOR=5,
XOR=2,
XNOR=6,
MOV=3,
NOT=7
AND = 0,
NAND = 4,
OR = 1,
NOR = 5,
XOR = 2,
XNOR = 6,
MOV = 3,
NOT = 7
} pfilter_op_t;
void ep_init(uint8_t mac_addr[]);
void get_mac_addr(uint8_t dev_addr[]);
void set_mac_addr(uint8_t dev_addr[]);
int ep_enable(int enabled, int autoneg);
int ep_link_up(uint16_t *lpa);
int ep_get_deltas(uint32_t *delta_tx, uint32_t *delta_rx);
int ep_get_psval(int32_t *psval);
int ep_link_up(uint16_t * lpa);
int ep_get_deltas(uint32_t * delta_tx, uint32_t * delta_rx);
int ep_get_psval(int32_t * psval);
int ep_cal_pattern_enable();
int ep_cal_pattern_disable();
......@@ -32,7 +32,8 @@ void pfilter_cmp(int offset, int value, int mask, pfilter_op_t op, int rd);
void pfilter_btst(int offset, int bit_index, pfilter_op_t op, int rd);
void pfilter_nop();
void pfilter_logic2(int rd, int ra, pfilter_op_t op, int rb);
static void pfilter_logic3(int rd, int ra, pfilter_op_t op, int rb, pfilter_op_t op2, int rc);
static void pfilter_logic3(int rd, int ra, pfilter_op_t op, int rb,
pfilter_op_t op2, int rc);
void pfilter_load();
void pfilter_init_default();
......
......@@ -30,7 +30,6 @@
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: MDIO Control Register */
/* definitions for field: Reserved in reg: MDIO Control Register */
......
......@@ -3,18 +3,18 @@
#define SDB_ADDRESS 0x30000
unsigned char* BASE_MINIC;
unsigned char* BASE_EP;
unsigned char* BASE_SOFTPLL;
unsigned char* BASE_PPS_GEN;
unsigned char* BASE_SYSCON;
unsigned char* BASE_UART;
unsigned char* BASE_ONEWIRE;
unsigned char* BASE_ETHERBONE_CFG;
unsigned char *BASE_MINIC;
unsigned char *BASE_EP;
unsigned char *BASE_SOFTPLL;
unsigned char *BASE_PPS_GEN;
unsigned char *BASE_SYSCON;
unsigned char *BASE_UART;
unsigned char *BASE_ONEWIRE;
unsigned char *BASE_ETHERBONE_CFG;
#define FMC_EEPROM_ADR 0x50
void sdb_find_devices(void);
void sdb_print_devices(void);
#endif
......@@ -30,7 +30,6 @@
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Status Register */
/* definitions for field: TX busy in reg: Status Register */
......@@ -66,14 +65,14 @@
#define UART_REG_RDR 0x0000000c
PACKED struct UART_WB {
/* [0x0]: REG Status Register */
uint32_t SR;
/* [0x4]: REG Baudrate control register */
uint32_t BCR;
/* [0x8]: REG Transmit data regsiter */
uint32_t TDR;
/* [0xc]: REG Receive data regsiter */
uint32_t RDR;
/* [0x0]: REG Status Register */
uint32_t SR;
/* [0x4]: REG Baudrate control register */
uint32_t BCR;
/* [0x8]: REG Transmit data regsiter */
uint32_t TDR;
/* [0xc]: REG Receive data regsiter */
uint32_t RDR;
};
#endif
......@@ -30,7 +30,6 @@
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Status Register */
/* definitions for field: TX busy in reg: Status Register */
......@@ -80,18 +79,18 @@
#define UART_DEBUG_CSR_USEDW_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
PACKED struct UART_WB {
/* [0x0]: REG Status Register */
uint32_t SR;
/* [0x4]: REG Baudrate control register */
uint32_t BCR;
/* [0x8]: REG Transmit data regsiter */
uint32_t TDR;
/* [0xc]: REG Receive data regsiter */
uint32_t RDR;
/* [0x10]: REG FIFO 'UART TX FIFO' data output register 0 */
uint32_t DEBUG_R0;
/* [0x14]: REG FIFO 'UART TX FIFO' control/status register */
uint32_t DEBUG_CSR;
/* [0x0]: REG Status Register */
uint32_t SR;
/* [0x4]: REG Baudrate control register */
uint32_t BCR;
/* [0x8]: REG Transmit data regsiter */
uint32_t TDR;
/* [0xc]: REG Receive data regsiter */
uint32_t RDR;
/* [0x10]: REG FIFO 'UART TX FIFO' data output register 0 */
uint32_t DEBUG_R0;
/* [0x14]: REG FIFO 'UART TX FIFO' control/status register */
uint32_t DEBUG_CSR;
};
#endif
#ifndef __I2C_H
#define __I2C_H
uint8_t mi2c_devprobe(uint8_t i2cif, uint8_t i2c_addr);
void mi2c_init(uint8_t i2cif);
void mi2c_start(uint8_t i2cif);
......
......@@ -3,8 +3,8 @@
static inline void clear_irq()
{
unsigned int val = 1;
asm volatile ("wcsr ip, %0"::"r"(val));
unsigned int val = 1;
asm volatile ("wcsr ip, %0"::"r" (val));
}
void disable_irq();
......
......@@ -11,9 +11,9 @@ void minic_disable();
int minic_poll_rx();
void minic_get_stats(int *tx_frames, int *rx_frames);
int minic_rx_frame(uint8_t *hdr, uint8_t *payload, uint32_t buf_size, struct hw_timestamp *hwts);
int minic_tx_frame(uint8_t *hdr, uint8_t *payload, uint32_t size, struct hw_timestamp *hwts);
int minic_rx_frame(uint8_t * hdr, uint8_t * payload, uint32_t buf_size,
struct hw_timestamp *hwts);
int minic_tx_frame(uint8_t * hdr, uint8_t * payload, uint32_t size,
struct hw_timestamp *hwts);
#endif
......@@ -8,9 +8,9 @@
#define FOUND_DS18B20 0x01
void own_scanbus(uint8_t portnum);
int16_t own_readtemp(uint8_t portnum, int16_t *temp, int16_t *t_frac);
int16_t own_readtemp(uint8_t portnum, int16_t * temp, int16_t * t_frac);
/* 0 = success, -1 = error */
int8_t get_persistent_mac(uint8_t portnum, uint8_t* mac);
int8_t set_persistent_mac(uint8_t portnum, uint8_t* mac);
int8_t get_persistent_mac(uint8_t portnum, uint8_t * mac);
int8_t set_persistent_mac(uint8_t portnum, uint8_t * mac);
#endif
......@@ -19,10 +19,9 @@ int shw_pps_gen_busy();
int shw_pps_gen_enable_output(int enable);
/* Reads the current time and stores at <seconds,nanoseconds>. */
void shw_pps_gen_get_time(uint64_t *seconds, uint32_t *nanoseconds);
void shw_pps_gen_get_time(uint64_t * seconds, uint32_t * nanoseconds);
/* Sets the time to <seconds,nanoseconds>. */
void shw_pps_gen_set_time(uint64_t seconds, uint32_t nanoseconds);
#endif
......@@ -12,4 +12,3 @@ int sfp_present();
int sfp_read_part_id(char *part_id);
#endif
......@@ -7,8 +7,8 @@
extern int wrc_ui_mode;
const char* fromhex(const char* hex, int* v);
const char* fromdec(const char* dec, int* v);
const char *fromhex(const char *hex, int *v);
const char *fromdec(const char *dec, int *v);
int cmd_gui(const char *args[]);
int cmd_pll(const char *args[]);
......@@ -25,7 +25,6 @@ int cmd_sdb(const char *args[]);
int cmd_mac(const char *args[]);
int cmd_init(const char *args[]);
int cmd_env(const char *args[]);
int cmd_saveenv(const char *args[]);
int cmd_set(const char *args[]);
......@@ -40,4 +39,3 @@ void shell_interactive();
int shell_boot_script(void);
#endif
......@@ -6,7 +6,6 @@ WARNING: These parameters must be in sync with the generics of the HDL instantia
*/
#include <stdio.h>
/* Reference clock frequency, in [Hz] */
......@@ -16,11 +15,11 @@ WARNING: These parameters must be in sync with the generics of the HDL instantia
#define CLOCK_PERIOD_PICOSECONDS 8000
/* optional DMTD clock division to improve FPGA timing closure by avoiding
clock nets directly driving FD inputs. Must be consistent with the
clock nets directly driving FD inputs. Must be consistent with the
g_divide_inputs_by_2 generic. */
#define DIVIDE_DMTD_CLOCKS_BY_2 1
/* Number of bits in phase tags generated by the DMTDs. Used to sign-extend the tags.
/* Number of bits in phase tags generated by the DMTDs. Used to sign-extend the tags.
Corresponding VHDL generic: g_tag_bits. */
#define TAG_BITS 22
......
......@@ -6,14 +6,13 @@
#include "board.h"
#include <hw/wrc_syscon_regs.h>
struct SYSCON_WB
{
uint32_t RSTR; /*Syscon Reset Register*/
uint32_t GPSR; /*GPIO Set/Readback Register*/
uint32_t GPCR; /*GPIO Clear Register*/
uint32_t HWFR; /*Hardware Feature Register*/
uint32_t TCR; /*Timer Control Register*/
uint32_t TVR; /*Timer Counter Value Register*/
struct SYSCON_WB {
uint32_t RSTR; /*Syscon Reset Register */
uint32_t GPSR; /*GPIO Set/Readback Register */
uint32_t GPCR; /*GPIO Clear Register */
uint32_t HWFR; /*Hardware Feature Register */
uint32_t TCR; /*Timer Control Register */
uint32_t TVR; /*Timer Counter Value Register */
};
/*GPIO pins*/
......@@ -26,10 +25,9 @@ struct SYSCON_WB
#define WRPC_FMC_I2C 0
#define WRPC_SFP_I2C 1
struct s_i2c_if
{
uint32_t scl;
uint32_t sda;
struct s_i2c_if {
uint32_t scl;
uint32_t sda;
};
extern struct s_i2c_if i2c_if[2];
......@@ -45,21 +43,20 @@ extern volatile struct SYSCON_WB *syscon;
***************************/
static inline void gpio_out(int pin, int val)
{
if(val)
syscon->GPSR = pin;
else
syscon->GPCR = pin;
if (val)
syscon->GPSR = pin;
else
syscon->GPCR = pin;
}
static inline int gpio_in(int pin)
{
return syscon->GPSR & pin ? 1: 0;
return syscon->GPSR & pin ? 1 : 0;
}
static inline int sysc_get_memsize()
{
return (SYSC_HWFR_MEMSIZE_R(syscon->HWFR) + 1) * 16;
}
#endif
#ifndef __TYPES_H
#define __TYPES_H
#include <inttypes.h>
#include <inttypes.h>
struct hw_timestamp {
uint8_t valid;
int ahead;
uint64_t sec;
uint32_t nsec;
uint32_t phase;
uint8_t valid;
int ahead;
uint64_t sec;
uint32_t nsec;
uint32_t phase;
};
#endif
......@@ -4,10 +4,10 @@
/* Color codes for cprintf()/pcprintf() */
#define C_DIM 0x80
#define C_WHITE 7
#define C_GREY (C_WHITE | C_DIM)
#define C_GREY (C_WHITE | C_DIM)
#define C_RED 1
#define C_GREEN 2
#define C_BLUE 4
#define C_GREEN 2
#define C_BLUE 4
/* Return TAI date/time in human-readable form. Non-reentrant. */
char *format_time(uint64_t sec);
......@@ -19,6 +19,6 @@ void cprintf(int color, const char *fmt, ...);
void pcprintf(int row, int col, int color, const char *fmt, ...);
/* Clears the terminal scree. */
void term_clear();
void term_clear();
#endif
......@@ -3,7 +3,7 @@
#include "ipv4.h"
#include "ptpd_netif.h"
static wr_socket_t* arp_socket;
static wr_socket_t *arp_socket;
#define ARP_HTYPE 0
#define ARP_PTYPE (ARP_HTYPE+2)
......@@ -16,67 +16,73 @@ static wr_socket_t* arp_socket;
#define ARP_TPA (ARP_THA+6)
#define ARP_END (ARP_TPA+4)
void arp_init(const char* if_name) {
wr_sockaddr_t saddr;
/* Configure socket filter */
memset(&saddr, 0, sizeof(saddr));
strcpy(saddr.if_name, if_name);
memset(&saddr.mac, 0xFF, 6); /* Broadcast */
saddr.ethertype = htons(0x0806); /* ARP */
saddr.family = PTPD_SOCK_RAW_ETHERNET;
arp_socket = ptpd_netif_create_socket(PTPD_SOCK_RAW_ETHERNET, 0, &saddr);
void arp_init(const char *if_name)
{
wr_sockaddr_t saddr;
/* Configure socket filter */
memset(&saddr, 0, sizeof(saddr));
strcpy(saddr.if_name, if_name);
memset(&saddr.mac, 0xFF, 6); /* Broadcast */
saddr.ethertype = htons(0x0806); /* ARP */
saddr.family = PTPD_SOCK_RAW_ETHERNET;
arp_socket = ptpd_netif_create_socket(PTPD_SOCK_RAW_ETHERNET,
0, &saddr);
}
static int process_arp(uint8_t* buf, int len) {
uint8_t hisMAC[6];
uint8_t hisIP[4];
uint8_t myIP[4];
if (len < ARP_END) return 0;
/* Is it ARP request targetting our IP? */
getIP(myIP);
if (buf[ARP_OPER+0] != 0 ||
buf[ARP_OPER+1] != 1 ||
memcmp(buf+ARP_TPA, myIP, 4))
return 0;
static int process_arp(uint8_t * buf, int len)
{
uint8_t hisMAC[6];
uint8_t hisIP[4];
uint8_t myIP[4];
if (len < ARP_END)
return 0;
/* Is it ARP request targetting our IP? */
getIP(myIP);
if (buf[ARP_OPER + 0] != 0 ||
buf[ARP_OPER + 1] != 1 || memcmp(buf + ARP_TPA, myIP, 4))
return 0;
memcpy(hisMAC, buf+ARP_SHA, 6);
memcpy(hisIP, buf+ARP_SPA, 4);
memcpy(hisMAC, buf + ARP_SHA, 6);
memcpy(hisIP, buf + ARP_SPA, 4);
// ------------- ARP ------------
// HW ethernet
buf[ARP_HTYPE+0] = 0;
buf[ARP_HTYPE+1] = 1;
// proto IP
buf[ARP_PTYPE+0] = 8;
buf[ARP_PTYPE+1] = 0;
// lengths
buf[ARP_HLEN] = 6;
buf[ARP_PLEN] = 4;
// Response
buf[ARP_OPER+0] = 0;
buf[ARP_OPER+1] = 2;
// my MAC+IP
get_mac_addr(buf+ARP_SHA);
memcpy(buf+ARP_SPA, myIP, 4);
// his MAC+IP
memcpy(buf+ARP_THA, hisMAC, 6);
memcpy(buf+ARP_TPA, hisIP, 4);
return ARP_END;
// ------------- ARP ------------
// HW ethernet
buf[ARP_HTYPE + 0] = 0;
buf[ARP_HTYPE + 1] = 1;
// proto IP
buf[ARP_PTYPE + 0] = 8;
buf[ARP_PTYPE + 1] = 0;
// lengths
buf[ARP_HLEN] = 6;
buf[ARP_PLEN] = 4;
// Response
buf[ARP_OPER + 0] = 0;
buf[ARP_OPER + 1] = 2;
// my MAC+IP
get_mac_addr(buf + ARP_SHA);
memcpy(buf + ARP_SPA, myIP, 4);
// his MAC+IP
memcpy(buf + ARP_THA, hisMAC, 6);
memcpy(buf + ARP_TPA, hisIP, 4);
return ARP_END;
}
void arp_poll(void) {
uint8_t buf[ARP_END+100];
wr_sockaddr_t addr;
int len;
if (needIP) return; /* can't do ARP w/o an address... */
if ((len = ptpd_netif_recvfrom(arp_socket, &addr, buf, sizeof(buf), 0)) > 0)
if ((len = process_arp(buf, len)) > 0)
ptpd_netif_sendto(arp_socket, &addr, buf, len, 0);
void arp_poll(void)
{
uint8_t buf[ARP_END + 100];
wr_sockaddr_t addr;
int len;
if (needIP)
return; /* can't do ARP w/o an address... */
if ((len = ptpd_netif_recvfrom(arp_socket,
&addr, buf, sizeof(buf), 0)) > 0)
if ((len = process_arp(buf, len)) > 0)
ptpd_netif_sendto(arp_socket, &addr, buf, len, 0);
}
......@@ -2,6 +2,6 @@
#define ARP_H
void arp_poll();
void arp_init(const char* if_name, uint32_t ip);
void arp_init(const char *if_name, uint32_t ip);
#endif
......@@ -43,103 +43,113 @@
#define BOOTP_VEND (BOOTP_FILE+128)
#define BOOTP_END (BOOTP_VEND+64)
int send_bootp(uint8_t* buf, int retry) {
unsigned short sum;
// ----------- BOOTP ------------
buf[BOOTP_OP] = 1; /* bootrequest */
buf[BOOTP_HTYPE] = 1; /* ethernet */
buf[BOOTP_HLEN] = 6; /* MAC length */
buf[BOOTP_HOPS] = 0;
/* A unique identifier for the request !!! FIXME */
get_mac_addr(buf+BOOTP_XID);
buf[BOOTP_XID+0] ^= buf[BOOTP_XID+4];
buf[BOOTP_XID+1] ^= buf[BOOTP_XID+5];
buf[BOOTP_XID+2] ^= (retry >> 8) & 0xFF;
buf[BOOTP_XID+3] ^= retry & 0xFF;
buf[BOOTP_SECS] = (retry >> 8) & 0xFF;
buf[BOOTP_SECS+1] = retry & 0xFF;
memset(buf+BOOTP_UNUSED, 0, 2);
memset(buf+BOOTP_CIADDR, 0, 4); /* own IP if known */
memset(buf+BOOTP_YIADDR, 0, 4);
memset(buf+BOOTP_SIADDR, 0, 4);
memset(buf+BOOTP_GIADDR, 0, 4);
memset(buf+BOOTP_CHADDR, 0, 16);
get_mac_addr(buf+BOOTP_CHADDR); /* own MAC address */
memset(buf+BOOTP_SNAME, 0, 64); /* desired BOOTP server */
memset(buf+BOOTP_FILE, 0, 128); /* desired BOOTP file */
memset(buf+BOOTP_VEND, 0, 64); /* vendor extensions */
// ------------ UDP -------------
memset(buf+UDP_VIRT_SADDR, 0, 4);
memset(buf+UDP_VIRT_DADDR, 0xFF, 4);
buf[UDP_VIRT_ZEROS] = 0;
buf[UDP_VIRT_PROTO] = 0x11; /* UDP */
buf[UDP_VIRT_LENGTH] = (BOOTP_END-IP_END) >> 8;
buf[UDP_VIRT_LENGTH+1] = (BOOTP_END-IP_END) & 0xff;
buf[UDP_SPORT] = 0;
buf[UDP_SPORT+1] = 68; /* BOOTP client */
buf[UDP_DPORT] = 0;
buf[UDP_DPORT+1] = 67; /* BOOTP server */
buf[UDP_LENGTH] = (BOOTP_END-IP_END) >> 8;
buf[UDP_LENGTH+1] = (BOOTP_END-IP_END) & 0xff;
buf[UDP_CHECKSUM] = 0;
buf[UDP_CHECKSUM+1] = 0;
sum = ipv4_checksum((unsigned short*)(buf+UDP_VIRT_SADDR), (BOOTP_END-UDP_VIRT_SADDR)/2);
if (sum == 0) sum = 0xFFFF;
buf[UDP_CHECKSUM+0] = (sum >> 8);
buf[UDP_CHECKSUM+1] = sum & 0xff;
// ------------ IP --------------
buf[IP_VERSION] = 0x45;
buf[IP_TOS] = 0;
buf[IP_LEN+0] = (BOOTP_END) >> 8;
buf[IP_LEN+1] = (BOOTP_END) & 0xff;
buf[IP_ID+0] = 0;
buf[IP_ID+1] = 0;
buf[IP_FLAGS+0] = 0;
buf[IP_FLAGS+1] = 0;
buf[IP_TTL] = 63;
buf[IP_PROTOCOL] = 17; /* UDP */
buf[IP_CHECKSUM+0] = 0;
buf[IP_CHECKSUM+1] = 0;
memset(buf+IP_SOURCE, 0, 4);
memset(buf+IP_DEST, 0xFF, 4);
sum = ipv4_checksum((unsigned short*)(buf+IP_VERSION), (IP_END-IP_VERSION)/2);
buf[IP_CHECKSUM+0] = sum >> 8;
buf[IP_CHECKSUM+1] = sum & 0xff;
mprintf("Sending BOOTP request...\n");
return BOOTP_END;
int send_bootp(uint8_t * buf, int retry)
{
unsigned short sum;
// ----------- BOOTP ------------
buf[BOOTP_OP] = 1; /* bootrequest */
buf[BOOTP_HTYPE] = 1; /* ethernet */
buf[BOOTP_HLEN] = 6; /* MAC length */
buf[BOOTP_HOPS] = 0;
/* A unique identifier for the request !!! FIXME */
get_mac_addr(buf + BOOTP_XID);
buf[BOOTP_XID + 0] ^= buf[BOOTP_XID + 4];
buf[BOOTP_XID + 1] ^= buf[BOOTP_XID + 5];
buf[BOOTP_XID + 2] ^= (retry >> 8) & 0xFF;
buf[BOOTP_XID + 3] ^= retry & 0xFF;
buf[BOOTP_SECS] = (retry >> 8) & 0xFF;
buf[BOOTP_SECS + 1] = retry & 0xFF;
memset(buf + BOOTP_UNUSED, 0, 2);
memset(buf + BOOTP_CIADDR, 0, 4); /* own IP if known */
memset(buf + BOOTP_YIADDR, 0, 4);
memset(buf + BOOTP_SIADDR, 0, 4);
memset(buf + BOOTP_GIADDR, 0, 4);
memset(buf + BOOTP_CHADDR, 0, 16);
get_mac_addr(buf + BOOTP_CHADDR); /* own MAC address */
memset(buf + BOOTP_SNAME, 0, 64); /* desired BOOTP server */
memset(buf + BOOTP_FILE, 0, 128); /* desired BOOTP file */
memset(buf + BOOTP_VEND, 0, 64); /* vendor extensions */
// ------------ UDP -------------
memset(buf + UDP_VIRT_SADDR, 0, 4);
memset(buf + UDP_VIRT_DADDR, 0xFF, 4);
buf[UDP_VIRT_ZEROS] = 0;
buf[UDP_VIRT_PROTO] = 0x11; /* UDP */
buf[UDP_VIRT_LENGTH] = (BOOTP_END - IP_END) >> 8;
buf[UDP_VIRT_LENGTH + 1] = (BOOTP_END - IP_END) & 0xff;
buf[UDP_SPORT] = 0;
buf[UDP_SPORT + 1] = 68; /* BOOTP client */
buf[UDP_DPORT] = 0;
buf[UDP_DPORT + 1] = 67; /* BOOTP server */
buf[UDP_LENGTH] = (BOOTP_END - IP_END) >> 8;
buf[UDP_LENGTH + 1] = (BOOTP_END - IP_END) & 0xff;
buf[UDP_CHECKSUM] = 0;
buf[UDP_CHECKSUM + 1] = 0;
sum =
ipv4_checksum((unsigned short *)(buf + UDP_VIRT_SADDR),
(BOOTP_END - UDP_VIRT_SADDR) / 2);
if (sum == 0)
sum = 0xFFFF;
buf[UDP_CHECKSUM + 0] = (sum >> 8);
buf[UDP_CHECKSUM + 1] = sum & 0xff;
// ------------ IP --------------
buf[IP_VERSION] = 0x45;
buf[IP_TOS] = 0;
buf[IP_LEN + 0] = (BOOTP_END) >> 8;
buf[IP_LEN + 1] = (BOOTP_END) & 0xff;
buf[IP_ID + 0] = 0;
buf[IP_ID + 1] = 0;
buf[IP_FLAGS + 0] = 0;
buf[IP_FLAGS + 1] = 0;
buf[IP_TTL] = 63;
buf[IP_PROTOCOL] = 17; /* UDP */
buf[IP_CHECKSUM + 0] = 0;
buf[IP_CHECKSUM + 1] = 0;
memset(buf + IP_SOURCE, 0, 4);
memset(buf + IP_DEST, 0xFF, 4);
sum =
ipv4_checksum((unsigned short *)(buf + IP_VERSION),
(IP_END - IP_VERSION) / 2);
buf[IP_CHECKSUM + 0] = sum >> 8;
buf[IP_CHECKSUM + 1] = sum & 0xff;
mprintf("Sending BOOTP request...\n");
return BOOTP_END;
}
int process_bootp(uint8_t* buf, int len)
int process_bootp(uint8_t * buf, int len)
{
uint8_t mac[6];
get_mac_addr(mac);
if (len != BOOTP_END) return 0;
if (buf[IP_VERSION] != 0x45) return 0;
if (buf[IP_PROTOCOL] != 17 ||
buf[UDP_DPORT] != 0 || buf[UDP_DPORT+1] != 68 ||
buf[UDP_SPORT] != 0 || buf[UDP_SPORT+1] != 67) return 0;
if (memcmp(buf+BOOTP_CHADDR, mac, 6)) return 0;
mprintf("Discovered IP address!\n");
setIP(buf+BOOTP_YIADDR);
return 1;
uint8_t mac[6];
get_mac_addr(mac);
if (len != BOOTP_END)
return 0;
if (buf[IP_VERSION] != 0x45)
return 0;
if (buf[IP_PROTOCOL] != 17 ||
buf[UDP_DPORT] != 0 || buf[UDP_DPORT + 1] != 68 ||
buf[UDP_SPORT] != 0 || buf[UDP_SPORT + 1] != 67)
return 0;
if (memcmp(buf + BOOTP_CHADDR, mac, 6))
return 0;
mprintf("Discovered IP address!\n");
setIP(buf + BOOTP_YIADDR);
return 1;
}
......@@ -20,59 +20,62 @@
#define ICMP_CHECKSUM (ICMP_CODE+1)
#define ICMP_END (ICMP_CHECKSUM+2)
int process_icmp(uint8_t* buf, int len) {
int iplen, hisBodyLen;
uint8_t hisIP[4];
uint8_t myIP[4];
uint16_t sum;
/* Is it IP targetting us? */
getIP(myIP);
if (buf[IP_VERSION] != 0x45 ||
memcmp(buf+IP_DEST, myIP, 4))
return 0;
iplen = (buf[IP_LEN+0] << 8 | buf[IP_LEN+1]);
/* An ICMP ECHO request? */
if (buf[IP_PROTOCOL] != 0x01 || buf[ICMP_TYPE] != 0x08)
return 0;
int process_icmp(uint8_t * buf, int len)
{
int iplen, hisBodyLen;
uint8_t hisIP[4];
uint8_t myIP[4];
uint16_t sum;
hisBodyLen = iplen - 24;
if (hisBodyLen > 64) hisBodyLen = 64;
memcpy(hisIP, buf+IP_SOURCE, 4);
/* Is it IP targetting us? */
getIP(myIP);
if (buf[IP_VERSION] != 0x45 || memcmp(buf + IP_DEST, myIP, 4))
return 0;
// ------------ IP --------------
buf[IP_VERSION] = 0x45;
buf[IP_TOS] = 0;
buf[IP_LEN+0] = (hisBodyLen+24) >> 8;
buf[IP_LEN+1] = (hisBodyLen+24) & 0xff;
buf[IP_ID+0] = 0;
buf[IP_ID+1] = 0;
buf[IP_FLAGS+0] = 0;
buf[IP_FLAGS+1] = 0;
buf[IP_TTL] = 63;
buf[IP_PROTOCOL] = 1; /* ICMP */
buf[IP_CHECKSUM+0] = 0;
buf[IP_CHECKSUM+1] = 0;
memcpy(buf+IP_SOURCE, myIP, 4);
memcpy(buf+IP_DEST, hisIP, 4);
// ------------ ICMP ---------
buf[ICMP_TYPE] = 0x0; // echo reply
buf[ICMP_CODE] = 0;
buf[ICMP_CHECKSUM+0] = 0;
buf[ICMP_CHECKSUM+1] = 0;
// No need to copy payload; we modified things in-place
sum = ipv4_checksum((unsigned short*)(buf+ICMP_TYPE), (hisBodyLen+4+1)/2);
buf[ICMP_CHECKSUM+0] = sum >> 8;
buf[ICMP_CHECKSUM+1] = sum & 0xff;
sum = ipv4_checksum((unsigned short*)(buf+IP_VERSION), 10);
buf[IP_CHECKSUM+0] = sum >> 8;
buf[IP_CHECKSUM+1] = sum & 0xff;
return 24+hisBodyLen;
iplen = (buf[IP_LEN + 0] << 8 | buf[IP_LEN + 1]);
/* An ICMP ECHO request? */
if (buf[IP_PROTOCOL] != 0x01 || buf[ICMP_TYPE] != 0x08)
return 0;
hisBodyLen = iplen - 24;
if (hisBodyLen > 64)
hisBodyLen = 64;
memcpy(hisIP, buf + IP_SOURCE, 4);
// ------------ IP --------------
buf[IP_VERSION] = 0x45;
buf[IP_TOS] = 0;
buf[IP_LEN + 0] = (hisBodyLen + 24) >> 8;
buf[IP_LEN + 1] = (hisBodyLen + 24) & 0xff;
buf[IP_ID + 0] = 0;
buf[IP_ID + 1] = 0;
buf[IP_FLAGS + 0] = 0;
buf[IP_FLAGS + 1] = 0;
buf[IP_TTL] = 63;
buf[IP_PROTOCOL] = 1; /* ICMP */
buf[IP_CHECKSUM + 0] = 0;
buf[IP_CHECKSUM + 1] = 0;
memcpy(buf + IP_SOURCE, myIP, 4);
memcpy(buf + IP_DEST, hisIP, 4);
// ------------ ICMP ---------
buf[ICMP_TYPE] = 0x0; // echo reply
buf[ICMP_CODE] = 0;
buf[ICMP_CHECKSUM + 0] = 0;
buf[ICMP_CHECKSUM + 1] = 0;
// No need to copy payload; we modified things in-place
sum =
ipv4_checksum((unsigned short *)(buf + ICMP_TYPE),
(hisBodyLen + 4 + 1) / 2);
buf[ICMP_CHECKSUM + 0] = sum >> 8;
buf[ICMP_CHECKSUM + 1] = sum & 0xff;
sum = ipv4_checksum((unsigned short *)(buf + IP_VERSION), 10);
buf[IP_CHECKSUM + 0] = sum >> 8;
buf[IP_CHECKSUM + 1] = sum & 0xff;
return 24 + hisBodyLen;
}
......@@ -8,81 +8,88 @@
int needIP = 1;
static uint8_t myIP[4];
static wr_socket_t* ipv4_socket;
unsigned int ipv4_checksum(unsigned short* buf, int shorts) {
int i;
unsigned int sum;
sum = 0;
for (i = 0; i < shorts; ++i)
sum += buf[i];
sum = (sum >> 16) + (sum & 0xffff);
sum += (sum >> 16);
return (~sum & 0xffff);
static wr_socket_t *ipv4_socket;
unsigned int ipv4_checksum(unsigned short *buf, int shorts)
{
int i;
unsigned int sum;
sum = 0;
for (i = 0; i < shorts; ++i)
sum += buf[i];
sum = (sum >> 16) + (sum & 0xffff);
sum += (sum >> 16);
return (~sum & 0xffff);
}
void ipv4_init(const char* if_name) {
wr_sockaddr_t saddr;
/* Configure socket filter */
memset(&saddr, 0, sizeof(saddr));
strcpy(saddr.if_name, if_name);
get_mac_addr(&saddr.mac[0]); /* Unicast */
saddr.ethertype = htons(0x0800); /* IPv4 */
saddr.family = PTPD_SOCK_RAW_ETHERNET;
ipv4_socket = ptpd_netif_create_socket(PTPD_SOCK_RAW_ETHERNET, 0, &saddr);
void ipv4_init(const char *if_name)
{
wr_sockaddr_t saddr;
/* Configure socket filter */
memset(&saddr, 0, sizeof(saddr));
strcpy(saddr.if_name, if_name);
get_mac_addr(&saddr.mac[0]); /* Unicast */
saddr.ethertype = htons(0x0800); /* IPv4 */
saddr.family = PTPD_SOCK_RAW_ETHERNET;
ipv4_socket = ptpd_netif_create_socket(PTPD_SOCK_RAW_ETHERNET,
0, &saddr);
}
static int bootp_retry = 0;
static int bootp_timer = 0;
void ipv4_poll(void) {
uint8_t buf[400];
wr_sockaddr_t addr;
int len;
if ((len = ptpd_netif_recvfrom(ipv4_socket, &addr, buf, sizeof(buf), 0)) > 0) {
if (needIP)
process_bootp(buf, len-14);
if (!needIP && (len = process_icmp(buf, len-14)) > 0)
ptpd_netif_sendto(ipv4_socket, &addr, buf, len, 0);
}
if (needIP && bootp_timer == 0) {
len = send_bootp(buf, ++bootp_retry);
memset(addr.mac, 0xFF, 6);
addr.ethertype = htons(0x0800); /* IPv4 */
ptpd_netif_sendto(ipv4_socket, &addr, buf, len, 0);
}
if (needIP && ++bootp_timer == 100000) bootp_timer = 0;
void ipv4_poll(void)
{
uint8_t buf[400];
wr_sockaddr_t addr;
int len;
if ((len = ptpd_netif_recvfrom(ipv4_socket, &addr,
buf, sizeof(buf), 0)) > 0) {
if (needIP)
process_bootp(buf, len - 14);
if (!needIP && (len = process_icmp(buf, len - 14)) > 0)
ptpd_netif_sendto(ipv4_socket, &addr, buf, len, 0);
}
if (needIP && bootp_timer == 0) {
len = send_bootp(buf, ++bootp_retry);
memset(addr.mac, 0xFF, 6);
addr.ethertype = htons(0x0800); /* IPv4 */
ptpd_netif_sendto(ipv4_socket, &addr, buf, len, 0);
}
if (needIP && ++bootp_timer == 100000)
bootp_timer = 0;
}
void getIP(unsigned char* IP) {
memcpy(IP, myIP, 4);
void getIP(unsigned char *IP)
{
memcpy(IP, myIP, 4);
}
void setIP(unsigned char* IP) {
volatile unsigned int *eb_ip =
(unsigned int*)(BASE_ETHERBONE_CFG + EB_IPV4);
unsigned int ip;
memcpy(myIP, IP, 4);
ip =
(myIP[0] << 24) | (myIP[1] << 16) |
(myIP[2] << 8) | (myIP[3]);
while (*eb_ip != ip) *eb_ip = ip;
needIP = (ip == 0);
if (!needIP) {
bootp_retry = 0;
bootp_timer = 0;
}
void setIP(unsigned char *IP)
{
volatile unsigned int *eb_ip =
(unsigned int *)(BASE_ETHERBONE_CFG + EB_IPV4);
unsigned int ip;
memcpy(myIP, IP, 4);
ip = (myIP[0] << 24) | (myIP[1] << 16) | (myIP[2] << 8) | (myIP[3]);
while (*eb_ip != ip)
*eb_ip = ip;
needIP = (ip == 0);
if (!needIP) {
bootp_retry = 0;
bootp_timer = 0;
}
}
#ifndef IPV4_H
#define IPV4_H
void ipv4_init(const char* if_name);
void ipv4_init(const char *if_name);
void ipv4_poll(void);
/* Internal to IP stack: */
unsigned int ipv4_checksum(unsigned short* buf, int shorts);
unsigned int ipv4_checksum(unsigned short *buf, int shorts);
void arp_init(const char* if_name);
void arp_init(const char *if_name);
void arp_poll(void);
extern int needIP;
void setIP(unsigned char* IP);
void getIP(unsigned char* IP);
void setIP(unsigned char *IP);
void getIP(unsigned char *IP);
int process_icmp(uint8_t* buf, int len);
int process_bootp(uint8_t* buf, int len); /* non-zero if IP was set */
int send_bootp(uint8_t* buf, int retry);
int process_icmp(uint8_t * buf, int len);
int process_bootp(uint8_t * buf, int len); /* non-zero if IP was set */
int send_bootp(uint8_t * buf, int retry);
#endif
OBJS_LIB= lib/mprintf.o \
lib/util.o
ifneq ($(WITH_ETHERBONE), 0)
OBJS_LIB += lib/arp.o lib/icmp.o lib/ipv4.o lib/bootp.o
......
......@@ -5,247 +5,226 @@
#include "uart.h"
#include "util.h"
int vprintf(char const *format,va_list ap)
int vprintf(char const *format, va_list ap)
{
unsigned char scratch[16];
unsigned char format_flag;
unsigned int u_val=0;
unsigned char base;
unsigned char *ptr;
unsigned char width = 0;
unsigned char fill;
while(1)
{
width = 0;
fill = ' ';
while ((format_flag = *format++) != '%')
{
if (!format_flag)
{
va_end (ap);
return (0);
}
uart_write_byte(format_flag);
}
// check for zero pad
format_flag = *format - '0';
if (format_flag == 0) // zero pad
{
fill = '0';
format++;
}
// check for width spec
format_flag = *format - '0';
if (format_flag > 0 && format_flag <= 9) // width set
{
width = format_flag;
format++;
}
switch (format_flag = *format++)
{
unsigned char scratch[16];
unsigned char format_flag;
unsigned int u_val = 0;
unsigned char base;
unsigned char *ptr;
unsigned char width = 0;
unsigned char fill;
while (1) {
width = 0;
fill = ' ';
while ((format_flag = *format++) != '%') {
if (!format_flag) {
va_end(ap);
return (0);
}
uart_write_byte(format_flag);
}
// check for zero pad
format_flag = *format - '0';
if (format_flag == 0) // zero pad
{
fill = '0';
format++;
}
// check for width spec
format_flag = *format - '0';
if (format_flag > 0 && format_flag <= 9) // width set
{
width = format_flag;
format++;
}
switch (format_flag = *format++) {
case 'c':
format_flag = va_arg(ap,int);
format_flag = va_arg(ap, int);
//fall through
//fall through
default:
uart_write_byte(format_flag);
uart_write_byte(format_flag);
continue;
continue;
case 'S':
case 's':
ptr = (unsigned char *)va_arg(ap, char *);
while (*ptr)
uart_write_byte(*ptr++);
continue;
ptr = (unsigned char *)va_arg(ap, char *);
while (*ptr)
uart_write_byte(*ptr++);
continue;
case 'd':
base = 10;
goto CONVERSION_LOOP;
base = 10;
goto CONVERSION_LOOP;
case 'u':
base = 10;
goto CONVERSION_LOOP;
base = 10;
goto CONVERSION_LOOP;
case 'x':
base = 16;
base = 16;
CONVERSION_LOOP:
u_val = va_arg(ap,unsigned int);
if((format_flag=='d') && (u_val&0x80000000))
{
uart_write_byte('-');
u_val=-u_val;
}
u_val = va_arg(ap, unsigned int);
if ((format_flag == 'd') && (u_val & 0x80000000)) {
uart_write_byte('-');
u_val = -u_val;
}
ptr = scratch + 16;
ptr = scratch + 16;
*--ptr = 0;
*--ptr = 0;
do
{
char ch = (u_val % base) + '0';
if (ch > '9')
ch += 'a' - '9' - 1;
do {
char ch = (u_val % base) + '0';
if (ch > '9')
ch += 'a' - '9' - 1;
*--ptr = ch;
*--ptr = ch;
u_val /= base;
u_val /= base;
if (width)
width--;
} while (u_val>0);
if (width)
width--;
while (width--)
*--ptr = fill;
while (*ptr)
uart_write_byte(*ptr++);
} while (u_val > 0);
}
}
return 0;
}
while (width--)
*--ptr = fill;
while (*ptr)
uart_write_byte(*ptr++);
static int _p_vsprintf(char const *format,va_list ap, char*dst)
{
unsigned char scratch[16];
unsigned char format_flag;
unsigned int u_val=0;
unsigned char base;
unsigned char *ptr;
unsigned char width = 0;
unsigned char fill;
while(1)
{
width = 0;
fill = ' ';
while ((format_flag = *format++) != '%')
{
if (!format_flag)
{
va_end (ap);
*dst++=0;
return (0);
}
*dst++=format_flag;
}
// check for zero pad
format_flag = *format - '0';
if (format_flag == 0) // zero pad
{
fill = '0';
format++;
}
// check for width spec
format_flag = *format - '0';
if (format_flag > 0 && format_flag <= 9) // width set
{
width = format_flag;
format++;
}
}
switch (format_flag = *format++)
{
return 0;
}
static int _p_vsprintf(char const *format, va_list ap, char *dst)
{
unsigned char scratch[16];
unsigned char format_flag;
unsigned int u_val = 0;
unsigned char base;
unsigned char *ptr;
unsigned char width = 0;
unsigned char fill;
while (1) {
width = 0;
fill = ' ';
while ((format_flag = *format++) != '%') {
if (!format_flag) {
va_end(ap);
*dst++ = 0;
return (0);
}
*dst++ = format_flag;
}
// check for zero pad
format_flag = *format - '0';
if (format_flag == 0) // zero pad
{
fill = '0';
format++;
}
// check for width spec
format_flag = *format - '0';
if (format_flag > 0 && format_flag <= 9) // width set
{
width = format_flag;
format++;
}
switch (format_flag = *format++) {
case 'c':
format_flag = va_arg(ap,int);
format_flag = va_arg(ap, int);
//fall through
//fall through
default:
*dst++=format_flag;
*dst++ = format_flag;
continue;
continue;
case 'S':
case 's':
ptr = (unsigned char *)va_arg(ap, char *);
while (*ptr)
*dst++=*ptr++;
continue;
ptr = (unsigned char *)va_arg(ap, char *);
while (*ptr)
*dst++ = *ptr++;
continue;
case 'd':
case 'u':
base = 10;
goto CONVERSION_LOOP;
base = 10;
goto CONVERSION_LOOP;
case 'x':
base = 16;
base = 16;
CONVERSION_LOOP:
u_val = va_arg(ap,unsigned int);
ptr = scratch + 16;
u_val = va_arg(ap, unsigned int);
ptr = scratch + 16;
*--ptr = 0;
*--ptr = 0;
do {
char ch = (u_val % base) + '0';
if (ch > '9')
ch += 'a' - '9' - 1;
do
{
char ch = (u_val % base) + '0';
if (ch > '9')
ch += 'a' - '9' - 1;
*--ptr = ch;
*--ptr = ch;
u_val /= base;
u_val /= base;
if (width)
width--;
if (width)
width--;
} while (u_val>0);
} while (u_val > 0);
// while (width--)
// *--ptr = fill;
while (*ptr)
*dst++=*ptr++;
// while (width--)
// *--ptr = fill;
}
}
*dst++=0;
return 0;
while (*ptr)
*dst++ = *ptr++;
}
}
*dst++ = 0;
return 0;
}
int mprintf(char const *format, ...)
{
int rval;
va_list ap;
va_start (ap, format);
rval = vprintf(format,ap);
va_end(ap);
return rval;
va_list ap;
va_start(ap, format);
rval = vprintf(format, ap);
va_end(ap);
return rval;
}
int sprintf(char *dst, char const *format, ...)
{
va_list ap;
va_start (ap, format);
int r= _p_vsprintf(format,ap,dst);
return r;
va_list ap;
va_start(ap, format);
int r = _p_vsprintf(format, ap, dst);
return r;
}
......@@ -18,77 +18,77 @@
#define ABB_LEN 3
static const char *_days[] = {
"Sun", "Mon", "Tue", "Wed",
"Thu", "Fri", "Sat"
"Sun", "Mon", "Tue", "Wed",
"Thu", "Fri", "Sat"
};
static const char *_months[] = {
"Jan", "Feb", "Mar",
"Apr", "May", "Jun",
"Jul", "Aug", "Sep",
"Oct", "Nov", "Dec"
"Jan", "Feb", "Mar",
"Apr", "May", "Jun",
"Jul", "Aug", "Sep",
"Oct", "Nov", "Dec"
};
static const int _ytab[2][12] = {
{ 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 },
{ 31, 29, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }
{31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31},
{31, 29, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31}
};
char *format_time(uint64_t sec)
{
struct tm t;
static char buf[64];
unsigned long dayclock, dayno;
int year = EPOCH_YR;
dayclock = (unsigned long)sec % SECS_DAY;
dayno = (unsigned long)sec / SECS_DAY;
t.tm_sec = dayclock % 60;
t.tm_min = (dayclock % 3600) / 60;
t.tm_hour = dayclock / 3600;
t.tm_wday = (dayno + 4) % 7; /* day 0 was a thursday */
while (dayno >= YEARSIZE(year)) {
dayno -= YEARSIZE(year);
year++;
}
t.tm_year = year - YEAR0;
t.tm_yday = dayno;
t.tm_mon = 0;
while (dayno >= _ytab[LEAPYEAR(year)][t.tm_mon]) {
dayno -= _ytab[LEAPYEAR(year)][t.tm_mon];
t.tm_mon++;
}
t.tm_mday = dayno + 1;
t.tm_isdst = 0;
struct tm t;
static char buf[64];
unsigned long dayclock, dayno;
int year = EPOCH_YR;
sprintf(buf, "%s, %s %d, %d, %2d:%2d:%2d", _days[t.tm_wday], _months[t.tm_mon],
t.tm_mday, t.tm_year + YEAR0, t.tm_hour, t.tm_min, t.tm_sec);
dayclock = (unsigned long)sec % SECS_DAY;
dayno = (unsigned long)sec / SECS_DAY;
return buf;
t.tm_sec = dayclock % 60;
t.tm_min = (dayclock % 3600) / 60;
t.tm_hour = dayclock / 3600;
t.tm_wday = (dayno + 4) % 7; /* day 0 was a thursday */
while (dayno >= YEARSIZE(year)) {
dayno -= YEARSIZE(year);
year++;
}
t.tm_year = year - YEAR0;
t.tm_yday = dayno;
t.tm_mon = 0;
while (dayno >= _ytab[LEAPYEAR(year)][t.tm_mon]) {
dayno -= _ytab[LEAPYEAR(year)][t.tm_mon];
t.tm_mon++;
}
t.tm_mday = dayno + 1;
t.tm_isdst = 0;
sprintf(buf, "%s, %s %d, %d, %2d:%2d:%2d", _days[t.tm_wday],
_months[t.tm_mon], t.tm_mday, t.tm_year + YEAR0, t.tm_hour,
t.tm_min, t.tm_sec);
return buf;
}
void cprintf(int color, const char *fmt, ...)
void cprintf(int color, const char *fmt, ...)
{
va_list ap;
mprintf("\033[0%d;3%dm",color & C_DIM ? 2:1, color&0x7f);
va_start(ap, fmt);
vprintf(fmt, ap);
va_end(ap);
va_list ap;
mprintf("\033[0%d;3%dm", color & C_DIM ? 2 : 1, color & 0x7f);
va_start(ap, fmt);
vprintf(fmt, ap);
va_end(ap);
}
void pcprintf(int row, int col, int color, const char *fmt, ...)
void pcprintf(int row, int col, int color, const char *fmt, ...)
{
va_list ap;
mprintf("\033[%d;%df", row, col);
mprintf("\033[0%d;3%dm",color & C_DIM ? 2:1, color&0x7f);
va_start(ap, fmt);
vprintf(fmt, ap);
va_end(ap);
va_list ap;
mprintf("\033[%d;%df", row, col);
mprintf("\033[0%d;3%dm", color & C_DIM ? 2 : 1, color & 0x7f);
va_start(ap, fmt);
vprintf(fmt, ap);
va_end(ap);
}
void term_clear()
void term_clear()
{
mprintf("\033[2J\033[1;1H");
mprintf("\033[2J\033[1;1H");
}
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
/* Command: gui
/* Command: gui
Arguments: none
Description: launches the WR Core monitor GUI */
#include "shell.h"
int cmd_gui(const char *args[])
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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