Commit 1d24ecfb authored by Alessandro Rubini's avatar Alessandro Rubini

Remove all spaces at end-of-line

If you find this patch with "git blame" please use "git blame -w"
to have all white-space ignored while associating lines to commits.

This commit has no practical effect but cleanup. I made it
with sed like this:

  git grep -l '[ \t]$' | xargs sed -i 's/[ \t]*$//'

However, I had to manually restore doc/wrpc_mon.png after the fact.
Similarly, I restored the include/hw/*regs.h files, as they
are (most likely) auto-generated.
parent 11c623d7
# 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
......
......@@ -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,7 +10,7 @@ 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);
......@@ -19,7 +19,7 @@ void dna_read(uint32_t *lo, uint32_t *hi)
delay(10);
gpio_out(DNA_SHIFT, 0);
delay(10);
delay(10);
gpio_out(DNA_CLK, 1);
delay(10);
......@@ -31,7 +31,7 @@ void dna_read(uint32_t *lo, uint32_t *hi)
gpio_out(DNA_SHIFT, 1);
delay(10);
for(i=0;i<57;i++)
{
dna <<= 1;
......@@ -44,7 +44,7 @@ void dna_read(uint32_t *lo, uint32_t *hi)
gpio_out(DNA_CLK, 0);
delay(10);
}
*hi = (uint32_t) (dna >> 32);
*lo = (uint32_t) dna;
}
......@@ -5,8 +5,8 @@
#include "syscon.h"
/*
* The SFP section is placed somewhere inside FMC EEPROM and it really does not
* matter where (can be a binary data inside the Board Info section but can be
* The SFP section is placed somewhere inside FMC EEPROM and it really does not
* matter where (can be a binary data inside the Board Info section but can be
* placed also outside the FMC standardized EEPROM structure. The only requirement
* is that it starts with 0xdeadbeef pattern. The structure of SFP section is:
*
......@@ -23,10 +23,10 @@
* --------------------------------------------------------------------------------------------
*
* Fields description:
* cal_ph_trans - t2/t4 phase transition value (got from measure_t24p() ), contains
* cal_ph_trans - t2/t4 phase transition value (got from measure_t24p() ), contains
* _valid_ bit (MSB) and 31 bits of cal_phase_transition value
* count - how many SFPs are described in the list (binary)
* SFP(n) part number - SFP PN as read from SFP's EEPROM (e.g. AXGE-1254-0531)
* SFP(n) part number - SFP PN as read from SFP's EEPROM (e.g. AXGE-1254-0531)
* (16 ascii chars)
* checksum - low order 8 bits of the sum of all bytes for the SFP(PN,alpha,dTx,dRx)
*
......@@ -49,7 +49,7 @@ uint8_t has_eeprom = 0;
uint8_t eeprom_present(uint8_t i2cif, uint8_t i2c_addr)
{
has_eeprom = 1;
has_eeprom = 1;
if( !mi2c_devprobe(i2cif, i2c_addr) )
if( !mi2c_devprobe(i2cif, i2c_addr) )
has_eeprom = 0;
......@@ -151,7 +151,7 @@ int32_t eeprom_get_sfp(uint8_t i2cif, uint8_t i2c_addr, struct s_sfpinfo* sfp, u
if(!add)
{
if( eeprom_read(i2cif, i2c_addr, EE_BASE_SFP + sizeof(sfpcount) + pos*sizeof(struct s_sfpinfo), (uint8_t*)sfp,
if( eeprom_read(i2cif, i2c_addr, EE_BASE_SFP + sizeof(sfpcount) + pos*sizeof(struct s_sfpinfo), (uint8_t*)sfp,
sizeof(struct s_sfpinfo)) != sizeof(struct s_sfpinfo) )
return EE_RET_I2CERR;
......@@ -184,16 +184,16 @@ int8_t eeprom_match_sfp(uint8_t i2cif, uint8_t i2c_addr, struct s_sfpinfo* sfp)
struct s_sfpinfo dbsfp;
for(i=0; i<sfpcount; ++i)
{
temp = eeprom_get_sfp(WRPC_FMC_I2C, FMC_EEPROM_ADR, &dbsfp, 0, i);
if(!i)
{
{
temp = eeprom_get_sfp(WRPC_FMC_I2C, FMC_EEPROM_ADR, &dbsfp, 0, i);
if(!i)
{
sfpcount=temp; //only in first round valid sfpcount is returned from eeprom_get_sfp
if(sfpcount == 0 || sfpcount == 0xFF)
return 0;
else if(sfpcount<0)
else if(sfpcount<0)
return sfpcount;
}
}
if( !strncmp(dbsfp.pn, sfp->pn, 16) )
{
sfp->dTx = dbsfp.dTx;
......@@ -201,7 +201,7 @@ int8_t eeprom_match_sfp(uint8_t i2cif, uint8_t i2c_addr, struct s_sfpinfo* sfp)
sfp->alpha = dbsfp.alpha;
return 1;
}
}
}
return 0;
}
......@@ -256,7 +256,7 @@ int8_t eeprom_init_purge(uint8_t i2cif, uint8_t i2c_addr)
return used;
}
/*
/*
* Appends a new shell command at the end of boot script
*/
int8_t eeprom_init_add(uint8_t i2cif, uint8_t i2c_addr, const char *args[])
......@@ -302,7 +302,7 @@ int32_t eeprom_init_show(uint8_t i2cif, uint8_t i2c_addr)
if( eeprom_read(i2cif, i2c_addr, EE_BASE_INIT, (uint8_t*)&used, sizeof(used)) != sizeof(used) )
return EE_RET_I2CERR;
if(used==0 || used==0xffff)
if(used==0 || used==0xffff)
{
used = 0; //this means the memory is blank
mprintf("Empty init script...\n");
......@@ -325,7 +325,7 @@ int8_t eeprom_init_readcmd(uint8_t i2cif, uint8_t i2c_addr, char* buf, uint8_t b
static uint16_t used = 0;
uint8_t i=0;
if(next == 0)
if(next == 0)
{
if( eeprom_read(i2cif, i2c_addr, EE_BASE_INIT, (uint8_t*)&used, sizeof(used)) != sizeof(used) )
return EE_RET_I2CERR;
......
/*
WR Endpoint (WR-compatible Ethernet MAC driver
WR Endpoint (WR-compatible Ethernet MAC driver
Tomasz Wlostowski/CERN 2011
......@@ -63,8 +63,8 @@ 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[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;
}
......@@ -85,7 +85,7 @@ void ep_init(uint8_t mac_addr[])
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,
......@@ -153,9 +153,9 @@ int ep_link_up(uint16_t *lpa)
/* 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)
{
/* fixme: these values should be stored in calibration block in the EEPROM on the FMC. Also, the TX/RX delays of a particular SFP
/* 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_tx = sfp_deltaTx;
*delta_rx = sfp_deltaRx + PICOS_PER_SERIAL_BIT * MDIO_WR_SPEC_BSLIDE_R(pcs_read(MDIO_REG_WR_SPEC));
return 0;
}
......@@ -164,7 +164,7 @@ int ep_get_deltas(uint32_t *delta_tx, uint32_t *delta_rx)
int ep_cal_pattern_enable()
{
uint32_t val;
val = pcs_read(MDIO_REG_WR_SPEC);
val = pcs_read(MDIO_REG_WR_SPEC);
val |= MDIO_WR_SPEC_TX_CAL;
pcs_write(MDIO_REG_WR_SPEC, val);
......
/* Endpoint Packet Filter/Classifier driver
/* Endpoint Packet Filter/Classifier driver
A little explanation: The WR core needs to classify the incoming packets into
two (or more categories):
......@@ -6,11 +6,11 @@
- Other packets matching user's provided pattern, which shall go to the external fabric
port - for example to Etherbone, host network controller, etc.
- packets to be dropped (used neither by the WR Core or the user application)
WR Endpoint (WR MAC) inside the WR Core therefore contains a simple microprogrammable
packet filter/classifier. The classifier processes the incoming packet, and assigns it
to one of 8 classes (an 8-bit word, where each bit corresponds to a particular class) or
eventually drops it. Hardware implementation of the unit is a simple VLIW processor with
to one of 8 classes (an 8-bit word, where each bit corresponds to a particular class) or
eventually drops it. Hardware implementation of the unit is a simple VLIW processor with
32 single-bit registers (0 - 31). The registers are organized as follows:
- 0: don't touch (always 0)
- 1 - 22: general purpose registers
......@@ -22,54 +22,54 @@
1. CMP offset, value, mask, oper, Rd:
------------------------------------------
* Rd = Rd oper ((((uint16_t *)packet) [offset] & mask) == value)
Examples:
* CMP 3, 0xcafe, 0xffff, MOV, Rd
* CMP 3, 0xcafe, 0xffff, MOV, Rd
will compare the 3rd word of the packet (bytes 6, 7) against 0xcafe and if the words are equal,
1 will be written to Rd register.
* CMP 4, 0xbabe, 0xffff, AND, Rd
will do the same with the 4th word and write to Rd its previous value ANDed with the result
of the comparison. Effectively, Rd now will be 1 only if bytes [6..9] of the payload contain word
0xcafebabe.
Note that the mask value is nibble-granular. That means you can choose a particular
0xcafebabe.
Note that the mask value is nibble-granular. That means you can choose a particular
set of nibbles within a word to be compared, but not an arbitrary set of bits (e.g. 0xf00f, 0xff00
and 0xf0f0 masks are ok, but 0x8001 is wrong.
2. BTST offset, bit_number, oper, Rd
------------------------------------------
* Rd = Rd oper (((uint16_t *)packet) [offset] & (1<<bit_number) ? 1 : 0)
Examples:
* BTST 3, 10, MOV, 11
will write 1 to reg 11 if the 10th bit in the 3rd word of the packet is set (and 0 if it's clear)
3. Logic opearations:
-----------------------------------------
* LOGIC2 Rd, Ra, OPER Rb - 2 argument logic (Rd = Ra OPER Rb). If the operation is MOV or NOT, Ra is
taken as the source register.
* LOGIC3 Rd, Ra, OPER Rb, OPER2, Rc - 3 argument logic Rd = (Ra OPER Rb) OPER2 Rc.
4. Misc
-----------------------------------------
FIN instruction terminates the program.
NOP executes a dummy instruction (LOGIC2 0, 0, AND, 0)
IMPORTANT:
- the program counter is advanved each time a 16-bit words of the packet arrives.
- the program counter is advanved each time a 16-bit words of the packet arrives.
- the CPU doesn't have any interlocks to simplify the HW, so you can't compare the
10th word when PC = 2. Max comparison offset is always equal to the address of the instruction.
- Code may contain up to 64 operations, but it must classify shorter packets faster than in
32 instructions (there's no flow throttling)
*/
#include <stdio.h>
......@@ -79,7 +79,7 @@
#define PFILTER_MAX_CODE_SIZE 32
#define pfilter_dbg
#define pfilter_dbg
extern volatile struct EP_WB *EP;
......@@ -111,19 +111,19 @@ static void check_reg_range(int val, int minval, int maxval, char *name)
pfilter_dbg("microcode: %s register out of range (%d to %d)", name, minval,maxval);
}
}
void pfilter_cmp(int offset, int value, int mask, pfilter_op_t op, int rd)
{
uint64_t ir;
check_size();
if(offset > code_pos)
pfilter_dbg("microcode: comparison offset is bigger than current PC. Insert some nops before comparing");
check_reg_range(rd, 1, 15, "ra/rd");
ir = (PF_MODE_CMP | ((uint64_t)offset << 7)
| ((mask & 0x1) ? (1ULL<<29) : 0)
| ((mask & 0x10) ? (1ULL<<30) : 0)
......@@ -142,19 +142,19 @@ void pfilter_btst(int offset, int bit_index, pfilter_op_t op, int rd)
uint64_t ir;
check_size();
if(offset > code_pos)
pfilter_dbg("microcode: comparison offset is bigger than current PC. Insert some nops before comparing");
check_reg_range(rd, 1, 15, "ra/rd");
check_reg_range(bit_index, 0, 15, "bit index");
ir = ((1ULL<<33) | PF_MODE_CMP | ((uint64_t)offset << 7) | ((uint64_t)bit_index << 29) | (uint64_t)op | ((uint64_t)rd << 3));
code_buf[code_pos++] = ir;
}
void pfilter_nop()
void pfilter_nop()
{
uint64_t ir;
check_size();
......@@ -191,7 +191,7 @@ static void pfilter_logic3(int rd, int ra, pfilter_op_t op, int rb, pfilter_op_t
code_buf[code_pos++] = ir;
}
/* Terminates the microcode, loads it to the endpoint and enables the pfilter */
/* Terminates the microcode, loads it to the endpoint and enables the pfilter */
void pfilter_load()
{
int i;
......@@ -204,11 +204,11 @@ void pfilter_load()
uint32_t cr0, cr1;
cr1 = EP_PFCR1_MM_DATA_LSB_W(code_buf[i] & 0xfff);
cr0 = EP_PFCR0_MM_ADDR_W(i) | EP_PFCR0_MM_DATA_MSB_W(code_buf[i]>>12) | EP_PFCR0_MM_WRITE_MASK;
EP->PFCR1 = cr1;
EP->PFCR0 = cr0;
}
EP->PFCR0 = EP_PFCR0_ENABLE;
}
......@@ -228,34 +228,34 @@ void pfilter_init_default()
pfilter_cmp(0, 0xffff, 0xffff, MOV, 1);
pfilter_cmp(1, 0xffff, 0xffff, AND, 1);
pfilter_cmp(2, 0xffff, 0xffff, AND, 1); /* r1 = 1 when dst mac is broadcast */
pfilter_cmp(0, 0x011b, 0xffff, MOV, 2);
pfilter_cmp(0, 0x011b, 0xffff, MOV, 2);
pfilter_cmp(1, 0x1900, 0xffff, AND, 2);
pfilter_cmp(2, 0x0000, 0xffff, AND, 2); /* r2 = 1 when dst mac is PTP multicast (01:1b:19:00:00:00) */
pfilter_cmp(0, EP->MACH & 0xffff, 0xffff, MOV, 3);
pfilter_cmp(0, EP->MACH & 0xffff, 0xffff, MOV, 3);
pfilter_cmp(1, EP->MACL >> 16, 0xffff, AND, 3);
pfilter_cmp(2, EP->MACL & 0xffff, 0xffff, AND, 3); /* r3 = 1 when the packet is unicast to our own MAC */
pfilter_cmp(6, 0x0800, 0xffff, MOV, 4); /* r4 = 1 when ethertype = IPv4 */
pfilter_cmp(6, 0x0800, 0xffff, MOV, 4); /* r4 = 1 when ethertype = IPv4 */
pfilter_cmp(6, 0x88f7, 0xffff, MOV, 5); /* r5 = 1 when ethertype = PTPv2 */
pfilter_cmp(6, 0x0806, 0xffff, MOV, 6); /* r6 = 1 when ethertype = ARP */
/* Ethernet = 14 bytes, Offset to type in IP: 8 bytes = 22/2 = 11 */
pfilter_cmp(11,0x0001, 0x00ff, MOV, 7); /* r7 = 1 when IP type = ICMP */
pfilter_cmp(11,0x0011, 0x00ff, MOV, 8); /* r8 = 1 when IP type = UDP */
pfilter_logic3(10, 3, OR, 0, AND, 4); /* r10 = IP(unicast) */
pfilter_logic3(11, 1, OR, 3, AND, 4); /* r11 = IP(unicast+broadcast) */
pfilter_logic3(14, 1, AND, 6, OR, 5); /* r14 = ARP(broadcast) or PTPv2 */
pfilter_logic3(15, 10, AND, 7, OR, 14); /* r15 = ICMP/IP(unicast) or ARP(broadcast) or PTPv2 */
/* Ethernet = 14 bytes, IPv4 = 20 bytes, offset to dport: 2 = 36/2 = 18 */
pfilter_cmp(18, 0x0044, 0xffff, MOV, 14); /* r14 = 1 when dport = BOOTPC */
pfilter_logic3(14, 14, AND, 8, AND, 11); /* r14 = BOOTP/UDP/IP(unicast|broadcast) */
pfilter_logic2(15, 14, OR, 15); /* r15 = BOOTP/UDP/IP(unicast|broadcast) or ICMP/IP(unicast) or ARP(broadcast) or PTPv2 */
pfilter_logic3(20, 11, AND, 8, OR, 15); /* r16 = Something we accept */
pfilter_logic2(R_DROP, 20, NOT, 0); /* None match? drop */
pfilter_logic2(R_CLASS(7), 11, AND, 8); /* class 7: UDP/IP(unicast|broadcast) => external fabric */
pfilter_logic2(R_CLASS(0), 15, MOV, 0); /* class 0: ICMP/IP(unicast) or ARP(broadcast) or PTPv2 => PTP LM32 core */
......@@ -278,5 +278,5 @@ void pfilter_init_default()
pfilter_logic2(R_CLASS(0), 6, MOV, 0); /* class 0: PTPv2 => PTP LM32 core */
pfilter_load();
#endif
}
\ No newline at end of file
......@@ -111,14 +111,14 @@ uint8_t mi2c_devprobe(uint8_t i2cif, uint8_t i2c_addr)
//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");
//}
......@@ -42,11 +42,11 @@ static volatile uint32_t dma_tx_buf[MINIC_DMA_TX_BUF_SIZE / 4];
static volatile uint32_t dma_rx_buf[MINIC_DMA_RX_BUF_SIZE / 4];
struct wr_minic {
volatile uint32_t *rx_head, *rx_base;
volatile uint32_t *rx_head, *rx_base;
uint32_t rx_avail, rx_size;
volatile uint32_t *tx_head, *tx_base;
uint32_t tx_avail, tx_size;
int tx_count, rx_count;
};
......@@ -127,14 +127,14 @@ static void minic_new_tx_buffer()
minic.tx_head = minic.tx_base;
minic.tx_avail = minic.tx_size;
minic_writel(MINIC_REG_TX_ADDR, (uint32_t) minic.tx_base);
}
void minic_init()
{
uint32_t lo , hi;
minic_writel(MINIC_REG_EIC_IDR, MINIC_EIC_IDR_RX);
minic_writel(MINIC_REG_EIC_ISR, MINIC_EIC_ISR_RX);
minic.rx_base = dma_rx_buf;
......@@ -143,7 +143,7 @@ void minic_init()
/* FIXME: now we have a temporary HW protection against accidentally overwriting the memory - there's some
very well hidden bug in Minic's RX logic which sometimes causes an overwrite of the memory outside
the buffer. */
lo = (uint32_t)minic.rx_base >> 2;
hi = ((uint32_t)minic.rx_base >> 2) + (sizeof(dma_rx_buf)>>2) - 1;
......@@ -196,16 +196,16 @@ int minic_rx_frame(uint8_t *hdr, uint8_t *payload, uint32_t buf_size, struct hw_
//otherwise, weird !!
mprintf("invalid descriptor @%x = %x\n", (uint32_t)minic.rx_head, desc_hdr);
minic_new_rx_buffer();
}
}
return 0;
}
payload_size = RX_DESC_SIZE(desc_hdr);
num_words = ((payload_size + 3) >> 2) + 1;
/* valid packet */
/* valid packet */
if(!RX_DESC_ERROR(desc_hdr))
{
{
if(RX_DESC_HAS_OOB(desc_hdr) && hwts != NULL)
{
......@@ -223,7 +223,7 @@ int minic_rx_frame(uint8_t *hdr, uint8_t *payload, uint32_t buf_size, struct hw_
pps_gen_get_time(&sec, &counter_ppsg);
if(counter_r > 3*REF_CLOCK_FREQ_HZ/4 && counter_ppsg < 250000000)
sec--;
sec--;
hwts->sec = sec & 0x7fffffff ;
......@@ -243,8 +243,8 @@ int minic_rx_frame(uint8_t *hdr, uint8_t *payload, uint32_t buf_size, struct hw_
minic_rx_memcpy(hdr, (void*)minic.rx_head + 4, ETH_HEADER_SIZE);
minic_rx_memcpy(payload, (void*)minic.rx_head + 4 + ETH_HEADER_SIZE, n_recvd - ETH_HEADER_SIZE);
}
else {
}
else {
n_recvd = -1;
}
minic_rxbuf_free(num_words);
......@@ -288,7 +288,7 @@ int minic_tx_frame(uint8_t *hdr, uint8_t *payload, uint32_t size, struct hw_time
d_hdr = TX_DESC_WITH_OOB | (WRPC_FID<<12);
d_hdr |= TX_DESC_VALID | nwords;
*(volatile uint32_t *)(minic.tx_head) = d_hdr;
*(volatile uint32_t *)(minic.tx_head + nwords) = 0;
......
......@@ -43,14 +43,14 @@ 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) {
//#if DEBUG_PMAC
mprintf("Found device: %x:%x:%x:%x:%x:%x:%x:%x\n",
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
......@@ -65,7 +65,7 @@ int8_t get_persistent_mac(uint8_t portnum, uint8_t* mac)
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);
......@@ -79,14 +79,14 @@ int8_t get_persistent_mac(uint8_t portnum, uint8_t* mac)
memcpy(mac, read_buffer, 6);
out = 0;
#if DEBUG_PMAC
mprintf("Using EEPROM page: %x:%x:%x:%x:%x:%x\n",
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;
}
......@@ -98,18 +98,18 @@ int8_t set_persistent_mac(uint8_t portnum, uint8_t* mac)
// 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");
#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;
}
......@@ -40,7 +40,7 @@ int pps_gen_adjust(int counter, int64_t how_much)
{
uint32_t cr;
TRACE_DEV("Adjust: counter = %s [%c%d]\n",
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)
......@@ -75,12 +75,12 @@ uint64_t pps_get_utc(void)
{
uint64_t out;
uint32_t low, high;
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;
return out;
}
......@@ -89,7 +89,7 @@ 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 */
......
......@@ -62,22 +62,22 @@ static unsigned char* find_device_deep(unsigned int base, unsigned int sdb, unsi
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 =
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 &&
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);
}
......@@ -87,20 +87,20 @@ static void print_devices_deep(unsigned int base, unsigned int 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",
mprintf("%8x:%8x 0x%8x %s\n",
record->device.sdb_component.product.vendor_id.low,
record->device.sdb_component.product.device_id,
record->device.sdb_component.product.device_id,
base + record->device.sdb_component.addr_first.low,
buf);
}
......
......@@ -21,7 +21,7 @@ int sfp_read_part_id(char *part_id)
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_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);
......@@ -40,8 +40,8 @@ int sfp_read_part_id(char *part_id)
mi2c_get_byte(WRPC_SFP_I2C, &data, 1); //final word, checksum
mi2c_stop(WRPC_SFP_I2C);
if(sum == data)
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},
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;
......@@ -11,9 +11,9 @@ 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;
syscon->TCR |= SYSC_TCR_ENABLE;
else
syscon->TCR &= ~SYSC_TCR_ENABLE;
}
......
......@@ -41,6 +41,6 @@ int uart_read_byte()
{
if(!uart_poll())
return -1;
return uart->RDR & 0xff;
}
\ No newline at end of file
This diff is collapsed.
......@@ -16,5 +16,5 @@ unsigned char* BASE_ETHERBONE_CFG;
void sdb_find_devices(void);
void sdb_print_devices(void);
#endif
......@@ -16,11 +16,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
......
......@@ -8,7 +8,7 @@
struct SYSCON_WB
{
uint32_t RSTR; /*Syscon Reset Register*/
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*/
......@@ -29,7 +29,7 @@ struct SYSCON_WB
struct s_i2c_if
{
uint32_t scl;
uint32_t sda;
uint32_t sda;
};
extern struct s_i2c_if i2c_if[2];
......@@ -60,6 +60,6 @@ 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;
......
......@@ -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
......@@ -18,14 +18,14 @@ static wr_socket_t* arp_socket;
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);
}
......@@ -33,9 +33,9 @@ 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 ||
......@@ -46,7 +46,7 @@ static int process_arp(uint8_t* buf, int len) {
memcpy(hisMAC, buf+ARP_SHA, 6);
memcpy(hisIP, buf+ARP_SPA, 4);
// ------------- ARP ------------
// ------------- ARP ------------
// HW ethernet
buf[ARP_HTYPE+0] = 0;
buf[ARP_HTYPE+1] = 1;
......@@ -65,7 +65,7 @@ static int process_arp(uint8_t* buf, int len) {
// his MAC+IP
memcpy(buf+ARP_THA, hisMAC, 6);
memcpy(buf+ARP_TPA, hisIP, 4);
return ARP_END;
}
......@@ -73,9 +73,9 @@ 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);
......
......@@ -45,36 +45,36 @@
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);
......@@ -82,7 +82,7 @@ int send_bootp(uint8_t* buf, int retry) {
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;
......@@ -91,10 +91,10 @@ int send_bootp(uint8_t* buf, int retry) {
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;
......@@ -113,33 +113,33 @@ int send_bootp(uint8_t* buf, int retry) {
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 ||
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;
}
......@@ -25,22 +25,22 @@ int process_icmp(uint8_t* buf, int len) {
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;
hisBodyLen = iplen - 24;
if (hisBodyLen > 64) hisBodyLen = 64;
memcpy(hisIP, buf+IP_SOURCE, 4);
// ------------ IP --------------
......@@ -58,21 +58,21 @@ int process_icmp(uint8_t* buf, int len) {
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;
}
......@@ -13,54 +13,54 @@ 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);
}
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;
}
......@@ -69,13 +69,13 @@ void getIP(unsigned char* IP) {
}
void setIP(unsigned char* IP) {
volatile unsigned int *eb_ip =
volatile unsigned int *eb_ip =
(unsigned int*)(BASE_ETHERBONE_CFG + EB_IPV4);
unsigned int ip;
memcpy(myIP, IP, 4);
ip =
ip =
(myIP[0] << 24) | (myIP[1] << 16) |
(myIP[2] << 8) | (myIP[3]);
while (*eb_ip != ip) *eb_ip = ip;
......
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
......
......@@ -17,49 +17,49 @@ int vprintf(char const *format,va_list ap)
while(1)
{
width = 0;
fill = ' ';
while ((format_flag = *format++) != '%')
{
{
if (!format_flag)
{
va_end (ap);
va_end (ap);
return (0);
}
uart_write_byte(format_flag);
}
// check for zero pad
format_flag = *format - '0';
format_flag = *format - '0';
if (format_flag == 0) // zero pad
{
fill = '0';
format++;
}
// check for width spec
format_flag = *format - '0';
format_flag = *format - '0';
if (format_flag > 0 && format_flag <= 9) // width set
{
width = format_flag;
format++;
format++;
}
switch (format_flag = *format++)
{
case 'c':
format_flag = va_arg(ap,int);
//fall through
default:
uart_write_byte(format_flag);
continue;
case 'S':
case 's':
ptr = (unsigned char *)va_arg(ap, char *);
......@@ -77,7 +77,7 @@ int vprintf(char const *format,va_list ap)
case 'u':
base = 10;
goto CONVERSION_LOOP;
case 'x':
base = 16;
......@@ -90,7 +90,7 @@ CONVERSION_LOOP:
u_val=-u_val;
}
ptr = scratch + 16;
*--ptr = 0;
......@@ -107,12 +107,12 @@ CONVERSION_LOOP:
if (width)
width--;
} while (u_val>0);
while (width--)
*--ptr = fill;
*--ptr = fill;
while (*ptr)
uart_write_byte(*ptr++);
......@@ -134,50 +134,50 @@ static int _p_vsprintf(char const *format,va_list ap, char*dst)
while(1)
{
width = 0;
fill = ' ';
while ((format_flag = *format++) != '%')
{
{
if (!format_flag)
{
va_end (ap);
va_end (ap);
*dst++=0;
return (0);
}
*dst++=format_flag;
}
// check for zero pad
format_flag = *format - '0';
format_flag = *format - '0';
if (format_flag == 0) // zero pad
{
fill = '0';
format++;
}
// check for width spec
format_flag = *format - '0';
format_flag = *format - '0';
if (format_flag > 0 && format_flag <= 9) // width set
{
width = format_flag;
format++;
format++;
}
switch (format_flag = *format++)
{
case 'c':
format_flag = va_arg(ap,int);
//fall through
default:
*dst++=format_flag;
continue;
case 'S':
case 's':
ptr = (unsigned char *)va_arg(ap, char *);
......@@ -191,14 +191,14 @@ static int _p_vsprintf(char const *format,va_list ap, char*dst)
case 'u':
base = 10;
goto CONVERSION_LOOP;
case 'x':
base = 16;
CONVERSION_LOOP:
u_val = va_arg(ap,unsigned int);
ptr = scratch + 16;
*--ptr = 0;
......@@ -215,12 +215,12 @@ CONVERSION_LOOP:
if (width)
width--;
} while (u_val>0);
// while (width--)
// *--ptr = fill;
// *--ptr = fill;
while (*ptr)
*dst++=*ptr++;
......@@ -238,7 +238,7 @@ int mprintf(char const *format, ...)
rval = vprintf(format,ap);
va_end(ap);
return rval;
}
int sprintf(char *dst, char const *format, ...)
......@@ -247,5 +247,5 @@ int sprintf(char *dst, char const *format, ...)
va_start (ap, format);
int r= _p_vsprintf(format,ap,dst);
return r;
}
......@@ -40,10 +40,10 @@ char *format_time(uint64_t sec)
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;
......@@ -68,27 +68,27 @@ char *format_time(uint64_t 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_list ap;
mprintf("\033[0%d;3%dm",color & C_DIM ? 2:1, color&0x7f);
va_start(ap, fmt);
vprintf(fmt, ap);
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;
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);
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");
}
......@@ -24,7 +24,7 @@ int wrc_mon_gui(void)
int aux_stat;
uint64_t sec;
uint32_t nsec;
if(timer_get_tics() - last < UI_REFRESH_PERIOD)
return 0;
......@@ -53,18 +53,18 @@ int wrc_mon_gui(void)
cprintf(C_GREY, "(RX: %d, TX: %d), mode: ", rx, tx);
switch(ps.mode)
{
{
case HEXP_PORT_MODE_WR_MASTER:cprintf(C_WHITE, "WR Master ");break;
case HEXP_PORT_MODE_WR_SLAVE:cprintf(C_WHITE, "WR Slave ");break;
}
}
if(ps.is_locked) cprintf(C_GREEN, "Locked "); else cprintf(C_RED, "NoLock ");
if(ps.rx_calibrated && ps.tx_calibrated) cprintf(C_GREEN, "Calibrated "); else cprintf(C_RED, "Uncalibrated ");
/* show_servo */
cprintf(C_BLUE, "\n\nSynchronization status:\n\n");
......@@ -72,13 +72,13 @@ int wrc_mon_gui(void)
{
cprintf(C_RED, "Master mode or sync info not valid\n\n");
return;
}
}
cprintf(C_GREY, "Servo state: "); cprintf(C_WHITE, "%s\n", cur_servo_state.slave_servo_state);
cprintf(C_GREY, "Phase tracking: "); if(cur_servo_state.tracking_enabled) cprintf(C_GREEN, "ON\n"); else cprintf(C_RED,"OFF\n");
cprintf(C_GREY, "Synchronization source: "); cprintf(C_WHITE, "%s\n", cur_servo_state.sync_source);
cprintf(C_GREY, "Aux clock status: ");
cprintf(C_GREY, "Aux clock status: ");
aux_stat = spll_get_aux_status(0);
......@@ -96,8 +96,8 @@ int wrc_mon_gui(void)
cprintf(C_GREY, "Master PHY delays: "); cprintf(C_WHITE, "TX: %d ps, RX: %d ps\n", (int32_t)cur_servo_state.delta_tx_m, (int32_t)cur_servo_state.delta_rx_m);
cprintf(C_GREY, "Slave PHY delays: "); cprintf(C_WHITE, "TX: %d ps, RX: %d ps\n", (int32_t)cur_servo_state.delta_tx_s, (int32_t)cur_servo_state.delta_rx_s);
cprintf(C_GREY, "Total link asymmetry: "); cprintf(C_WHITE, "%d ps\n", (int32_t)(cur_servo_state.total_asymmetry));
cprintf(C_GREY, "Cable rtt delay: "); cprintf(C_WHITE, "%d ps\n",
(int32_t)(cur_servo_state.mu) - (int32_t)cur_servo_state.delta_tx_m - (int32_t)cur_servo_state.delta_rx_m -
cprintf(C_GREY, "Cable rtt delay: "); cprintf(C_WHITE, "%d ps\n",
(int32_t)(cur_servo_state.mu) - (int32_t)cur_servo_state.delta_tx_m - (int32_t)cur_servo_state.delta_rx_m -
(int32_t)cur_servo_state.delta_tx_s - (int32_t)cur_servo_state.delta_rx_s);
cprintf(C_GREY, "Clock offset: "); cprintf(C_WHITE, "%d ps\n", (int32_t)(cur_servo_state.cur_offset));
cprintf(C_GREY, "Phase setpoint: "); cprintf(C_WHITE, "%d ps\n", (int32_t)(cur_servo_state.cur_setpoint));
......@@ -125,7 +125,7 @@ int wrc_log_stats(uint8_t onetime)
uint32_t nsec;
int16_t brd_temp = 0;
int16_t brd_temp_frac = 0;
if(!onetime && timer_get_tics() - last < UI_REFRESH_PERIOD)
return 0;
......@@ -146,8 +146,8 @@ int wrc_log_stats(uint8_t onetime)
mprintf("dtxm:%d drxm:%d ", (int32_t)cur_servo_state.delta_tx_m, (int32_t)cur_servo_state.delta_rx_m);
mprintf("dtxs:%d drxs:%d ", (int32_t)cur_servo_state.delta_tx_s, (int32_t)cur_servo_state.delta_rx_s);
mprintf("asym:%d ", (int32_t)(cur_servo_state.total_asymmetry));
mprintf("crtt:%d ",
(int32_t)(cur_servo_state.mu) - (int32_t)cur_servo_state.delta_tx_m - (int32_t)cur_servo_state.delta_rx_m -
mprintf("crtt:%d ",
(int32_t)(cur_servo_state.mu) - (int32_t)cur_servo_state.delta_tx_m - (int32_t)cur_servo_state.delta_rx_m -
(int32_t)cur_servo_state.delta_tx_s - (int32_t)cur_servo_state.delta_rx_s);
mprintf("cko:%d ", (int32_t)(cur_servo_state.cur_offset));
mprintf("setp:%d ", (int32_t)(cur_servo_state.cur_setpoint));
......
/* Command: gui
/* Command: gui
Arguments: none
Description: launches the WR Core monitor GUI */
#include "shell.h"
#include "eeprom.h"
#include "syscon.h"
......
/* Command: gui
/* Command: gui
Arguments: none
Description: launches the WR Core monitor GUI */
#include "shell.h"
int cmd_gui(const char *args[])
......
......@@ -8,7 +8,7 @@
static decode_ip(const char *str, unsigned char* ip) {
int i, x;
/* Don't try to detect bad input; need small code */
for (i = 0; i < 4; ++i) {
str = fromdec(str, &x);
......@@ -20,7 +20,7 @@ static decode_ip(const char *str, unsigned char* ip) {
int cmd_ip(const char *args[])
{
unsigned char ip[4];
if (!args[0] || !strcasecmp(args[0], "get")) {
getIP(ip);
} else if (!strcasecmp(args[0], "set") && args[1]) {
......@@ -29,11 +29,11 @@ int cmd_ip(const char *args[])
} else {
return -EINVAL;
}
if (needIP) {
mprintf("IP-address: in training\n");
} else {
mprintf("IP-address: %d.%d.%d.%d\n",
mprintf("IP-address: %d.%d.%d.%d\n",
ip[0], ip[1], ip[2], ip[3]);
}
}
......@@ -9,7 +9,7 @@
static decode_mac(const char *str, unsigned char* mac) {
int i, x;
/* Don't try to detect bad input; need small code */
for (i = 0; i < 6; ++i) {
str = fromhex(str, &x);
......@@ -21,7 +21,7 @@ static decode_mac(const char *str, unsigned char* mac) {
int cmd_mac(const char *args[])
{
unsigned char mac[6];
if (!args[0] || !strcasecmp(args[0], "get")) {
/* get current MAC */
get_mac_addr(mac);
......@@ -39,7 +39,7 @@ int cmd_mac(const char *args[])
} else {
return -EINVAL;
}
mprintf("MAC-address: %x:%x:%x:%x:%x:%x\n",
mprintf("MAC-address: %x:%x:%x:%x:%x:%x\n",
mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
}
/* Command: mode
Arguments: PTP mode: gm = grandmaster, master = free-running master, slave = slave
Description: (re)starts/stops the PTP session. */
#include <errno.h>
......@@ -13,7 +13,7 @@ int cmd_mode(const char *args[])
{
int mode;
static const char *modes[]={"unknown","grandmaster","master","slave"};
if(!strcasecmp(args[0], "gm"))
mode = WRC_MODE_GM;
else if(!strcasecmp(args[0], "master"))
......
......@@ -8,50 +8,50 @@
int cmd_pll(const char *args[])
{
int cur, tgt;
if(!strcasecmp(args[0], "init"))
{
if(!args[3])
if(!args[3])
return -EINVAL;
spll_init(atoi(args[1]), atoi(args[2]), atoi(args[3]));
} else if (!strcasecmp(args[0], "cl"))
{
if(!args[1])
if(!args[1])
return -EINVAL;
mprintf("%d\n", spll_check_lock(atoi(args[1])));
} else if (!strcasecmp(args[0], "sps"))
{
if(!args[2])
if(!args[2])
return -EINVAL;
spll_set_phase_shift(atoi(args[1]), atoi(args[2]));
} else if (!strcasecmp(args[0], "gps"))
{
if(!args[1])
if(!args[1])
return -EINVAL;
spll_get_phase_shift(atoi(args[1]), &cur, &tgt);
printf("%d %d\n", cur, tgt);
} else if (!strcasecmp(args[0], "start"))
{
if(!args[1])
if(!args[1])
return -EINVAL;
spll_start_channel(atoi(args[1]));
} else if (!strcasecmp(args[0], "stop"))
{
if(!args[1])
if(!args[1])
return -EINVAL;
spll_stop_channel(atoi(args[1]));
} else if (!strcasecmp(args[0], "sdac"))
{
if(!args[2])
if(!args[2])
return -EINVAL;
spll_set_dac(atoi(args[1]), atoi(args[2]));
} else if (!strcasecmp(args[0], "gdac"))
{
if(!args[1])
if(!args[1])
return -EINVAL;
mprintf("%d\n", spll_get_dac(atoi(args[1])));
} else return -EINVAL;
return 0;
}
/* Command: ptp
Arguments: one [start/stop]
Description: (re)starts/stops the PTP session. */
#include <errno.h>
......
/* Command: sfp
Arguments: subcommand [subcommand-specific args]
Description: SFP detection/database manipulation.
Subcommands:
add vendor_type delta_tx delta_rx alpha - adds an SFP to the database, with given alpha/delta_rx/delta_rx values
show - shows the SFP database
match - tries to get calibration parameters from DB for a detected SFP
erase - cleans the SFP database
detect - detects the transceiver type
detect - detects the transceiver type
*/
#include "shell.h"
......@@ -32,7 +32,7 @@ int cmd_sfp(const char *args[])
pn[16]=0;
mprintf("%s\n",pn);
return 0;
}
}
// else if (!strcasecmp(args[0], "i2cscan"))
// {
// mi2c_scan(WRPC_FMC_I2C);
......@@ -53,7 +53,7 @@ int cmd_sfp(const char *args[])
sfp.dTx = atoi(args[2]);
sfp.dRx = atoi(args[3]);
sfp.alpha = atoi(args[4]);
temp = eeprom_get_sfp(WRPC_FMC_I2C, FMC_EEPROM_ADR, &sfp, 1, 0);
temp = eeprom_get_sfp(WRPC_FMC_I2C, FMC_EEPROM_ADR, &sfp, 1, 0);
if(temp == EE_RET_DBFULL)
mprintf("SFP DB is full\n");
else if(temp == EE_RET_I2CERR)
......@@ -66,7 +66,7 @@ int cmd_sfp(const char *args[])
for(i=0; i<sfpcount; ++i)
{
temp = eeprom_get_sfp(WRPC_FMC_I2C, FMC_EEPROM_ADR, &sfp, 0, i);
if(!i)
if(!i)
{
sfpcount=temp; //only in first round valid sfpcount is returned from eeprom_get_sfp
if(sfpcount == 0 || sfpcount == 0xFF)
......@@ -105,6 +105,6 @@ int cmd_sfp(const char *args[])
mprintf("Could not match to DB\n");
return 0;
}
return 0;
}
/* Command: time
Arguments:
Arguments:
set UTC NSEC - sets time
raw - dumps raw time
<none> - dumps pretty time
Description: (re)starts/stops the PTP session. */
#include <errno.h>
......@@ -21,7 +21,7 @@ int cmd_time(const char *args[])
uint32_t nsec;
pps_gen_get_time(&sec, &nsec);
if(args[2] && !strcasecmp(args[0], "set")) {
if(wrc_ptp_get_mode() != WRC_MODE_SLAVE)
{
......@@ -36,6 +36,6 @@ int cmd_time(const char *args[])
}
mprintf("%s +%d nanoseconds.\n", format_time(sec), nsec); /* fixme: clock freq is not always 125 MHz */
return 0;
return 0;
}
......@@ -25,16 +25,16 @@ static char *_env_get(const char *var)
i++;
}
return NULL;
}
char *env_get(const char *var)
{
char *p = _env_get(var);
if(!p) return NULL;
return p+2+strlen(p+1);
}
......@@ -55,22 +55,22 @@ int env_set(const char *var, const char *value)
{
p=vstart+1;
while(*p != 0xaa && *p != 0xff) p++;
memmove(vstart, p, SH_ENVIRON_SIZE - (p - env_buf));
}
end = _env_end();
if ((end + strlen(var) + strlen(value) + 3) >= SH_ENVIRON_SIZE)
return -ENOMEM;
p = &env_buf[end];
*p++ = 0xaa;
memcpy(p, var, strlen(var) + 1); p += strlen(var) + 1;
memcpy(p, value, strlen(value) + 1); p += strlen(value) + 1;
*p++ = 0xff;
p = env_buf;
return 0;
......@@ -79,14 +79,14 @@ int env_set(const char *var, const char *value)
int cmd_env(const char *args[])
{
unsigned char *p = env_buf;
while(*p != 0xff)
{
if(*p==0xaa)
mprintf("%s=%s\n", p+1, p+strlen(p+1)+2);
p++;
}
return 0;
}
......@@ -100,7 +100,7 @@ int cmd_set(const char *args[])
{
if(!args[1])
return -EINVAL;
return env_set(args[0], args[1]);
}
......@@ -8,7 +8,7 @@
#include "shell.h"
#include "eeprom.h"
#define SH_MAX_LINE_LEN 80
#define SH_MAX_LINE_LEN 80
#define SH_MAX_ARGS 8
#define SH_ENVIRON_SIZE 256
......@@ -53,7 +53,7 @@ static const struct shell_cmd cmds_list[] = {
#endif
{ "mac", cmd_mac },
{ "sdb", cmd_sdb },
{ NULL, NULL }
};
......@@ -94,7 +94,7 @@ static int _shell_exec()
int n = 0, i = 0;
memset(tokptr, 0, sizeof(tokptr));
while(1)
{
if(n >= SH_MAX_ARGS)
......@@ -102,13 +102,13 @@ static int _shell_exec()
while(cmd_buf[i] == ' ' && cmd_buf[i]) cmd_buf[i++] = 0;
if(!cmd_buf[i])
if(!cmd_buf[i])
break;
tokptr [n++] = &cmd_buf[i];
while(cmd_buf[i] != ' ' && cmd_buf[i]) i++;
if(!cmd_buf[i])
if(!cmd_buf[i])
break;
}
......@@ -122,7 +122,7 @@ static int _shell_exec()
if(!strcasecmp(cmds_list[i].name, tokptr[0]))
{
int rv = cmds_list[i].exec((const char **)tokptr+1);
if(rv<0)
if(rv<0)
mprintf("Err %d\n", rv);
return rv;
}
......@@ -160,18 +160,18 @@ void shell_interactive()
case SH_INPUT:
c = uart_read_byte();
if(c < 0)
return;
if(c == 27 || ((current_key & ESCAPE_FLAG) && c == 91))
current_key = ESCAPE_FLAG;
else
else
current_key |= c;
if(current_key & 0xff)
{
{
switch(current_key)
{
case KEY_LEFT:
......@@ -188,12 +188,12 @@ void shell_interactive()
esc('C');
}
break;
case KEY_ENTER:
mprintf("\n");
state = SH_EXEC;
break;
case KEY_DELETE:
if(cmd_pos != cmd_len)
{
......@@ -201,7 +201,7 @@ void shell_interactive()
esc('P');
}
break;
case KEY_BACKSPACE:
if(cmd_pos > 0)
{
......@@ -211,10 +211,10 @@ void shell_interactive()
cmd_pos--;
}
break;
case '\t':
break;
default:
if(!(current_key & ESCAPE_FLAG) && insert(current_key))
{
......@@ -222,12 +222,12 @@ void shell_interactive()
mprintf("%c", current_key);
}
break;
}
current_key = 0;
}
break;
case SH_EXEC:
cmd_buf[cmd_len] = 0;
_shell_exec();
......@@ -238,7 +238,7 @@ void shell_interactive()
const char* fromhex(const char* hex, int* v) {
int o = 0;
for (; *hex; ++hex) {
if (*hex >= '0' && *hex <= '9') {
o = (o << 4) + (*hex - '0');
......@@ -250,14 +250,14 @@ const char* fromhex(const char* hex, int* v) {
break;
}
}
*v = o;
return hex;
}
const char* fromdec(const char* dec, int* v) {
int o = 0;
for (; *dec; ++dec) {
if (*dec >= '0' && *dec <= '9') {
o = (o * 10) + (*dec - '0');
......@@ -265,7 +265,7 @@ const char* fromdec(const char* dec, int* v) {
break;
}
}
*v = o;
return dec;
}
......@@ -282,12 +282,12 @@ int shell_boot_script(void)
{
cmd_len = eeprom_init_readcmd(WRPC_FMC_I2C, FMC_EEPROM_ADR, cmd_buf, SH_MAX_LINE_LEN, next);
if(cmd_len <= 0)
{
{
if(next==0) mprintf("Empty init script...\n");
break;
}
cmd_buf[cmd_len-1] = 0;
mprintf("executing: %s\n", cmd_buf);
_shell_exec();
next = 1;
......
......@@ -21,11 +21,11 @@ int Write43(int portnum, uchar *SerialNum, int page, uchar *page_buffer)
#if DEBUG_EEP43
mprintf(" Writing Scratchpad...\n");
#endif
if (!owWriteBytePower(portnum, WRITE_SCRATCH_CMD))
if (!owWriteBytePower(portnum, WRITE_SCRATCH_CMD))
return FALSE;
setcrc16(portnum, 0);
docrc16(portnum,(ushort)WRITE_SCRATCH_CMD);
owLevel(portnum, MODE_NORMAL);
owWriteBytePower(portnum, 0x00); //write LSB of target addr
docrc16(portnum,(ushort)0x00);
......@@ -34,8 +34,8 @@ int Write43(int portnum, uchar *SerialNum, int page, uchar *page_buffer)
docrc16(portnum,(ushort)0x00);
for(i = 0; i < 32; i++) //write 32 data bytes to scratchpad
{
for(i = 0; i < 32; i++) //write 32 data bytes to scratchpad
{
owLevel(portnum,MODE_NORMAL);
owWriteBytePower(portnum, page_buffer[i]);
lastcrc16 = docrc16(portnum, page_buffer[i]);
......@@ -56,7 +56,7 @@ int Write43(int portnum, uchar *SerialNum, int page, uchar *page_buffer)
owLevel(portnum, MODE_NORMAL);
if(Copy2Mem43(portnum, SerialNum))
rt=TRUE;
}
}
......@@ -67,15 +67,15 @@ int Write43(int portnum, uchar *SerialNum, int page, uchar *page_buffer)
int Copy2Mem43(int portnum, uchar *SerialNum)
{
uchar rt=FALSE;
ushort lastcrc16;
ushort lastcrc16;
int i;
uchar read_data;
owSerialNum(portnum, SerialNum, FALSE);
if(owAccess(portnum))
{
if (!owWriteBytePower(portnum, COPY_SCRATCH_CMD))
{
if (!owWriteBytePower(portnum, COPY_SCRATCH_CMD))
return FALSE;
owLevel(portnum, MODE_NORMAL);
owWriteBytePower(portnum, 0x00); //write LSB of target addr
......@@ -85,12 +85,12 @@ int Copy2Mem43(int portnum, uchar *SerialNum)
owWriteBytePower(portnum, 0x1f); //write E/S
usleep(500000);
owLevel(portnum,MODE_NORMAL);
owLevel(portnum,MODE_NORMAL);
read_data = owReadBytePower(portnum);
if (read_data == 0xaa)
if (read_data == 0xaa)
rt=TRUE;
}
......@@ -98,7 +98,7 @@ int Copy2Mem43(int portnum, uchar *SerialNum)
return rt;
}
// routine for reading the scratchpad of a DS28EC20P EEPROM
// 80 pages of 32byte
// 32byte scratchpad
......@@ -106,45 +106,45 @@ int Copy2Mem43(int portnum, uchar *SerialNum)
int ReadScratch43(int portnum, uchar *SerialNum, uchar *page_buffer)
{
uchar rt=FALSE;
ushort lastcrc16;
ushort lastcrc16;
int i;
ushort target_addr = 0;
uchar read_data;
owSerialNum(portnum, SerialNum, FALSE);
if(owAccess(portnum))
{
{
#if DEBUG_EEP43
mprintf(" Reading Scratchpad...\n");
#endif
if (!owWriteBytePower(portnum, READ_SCRATCH_CMD))
if (!owWriteBytePower(portnum, READ_SCRATCH_CMD))
return FALSE;
setcrc16(portnum, 0); //init crc
docrc16(portnum,(ushort)READ_SCRATCH_CMD);
owLevel(portnum,MODE_NORMAL); //read 2 byte address and 1 byte status
read_data = owReadBytePower(portnum);
lastcrc16 = docrc16(portnum, read_data);
target_addr = read_data;
owLevel(portnum,MODE_NORMAL);
owLevel(portnum,MODE_NORMAL);
read_data = owReadBytePower(portnum);
lastcrc16 = docrc16(portnum, read_data);
target_addr |= read_data << 8;
owLevel(portnum,MODE_NORMAL);
owLevel(portnum,MODE_NORMAL);
read_data = owReadBytePower(portnum);
lastcrc16 = docrc16(portnum, read_data);
#if DEBUG_EEP43
mprintf("E/S: 0x%x\n", read_data);
#endif
for(i = 0; i < 32; i++)
{
for(i = 0; i < 32; i++)
{
owLevel(portnum,MODE_NORMAL);
page_buffer[i] = owReadBytePower(portnum);
lastcrc16 = docrc16(portnum, page_buffer[i]);
......@@ -152,14 +152,14 @@ int ReadScratch43(int portnum, uchar *SerialNum, uchar *page_buffer)
// mprintf(" CRC16: %x", lastcrc16);
// mprintf(" CRC16i: %x\n", ~lastcrc16);
}
for(i = 0; i < 2; i++)
{
owLevel(portnum,MODE_NORMAL);
owLevel(portnum,MODE_NORMAL);
read_data = owReadBytePower(portnum);
lastcrc16 = docrc16(portnum, read_data);
}
if (lastcrc16 == 0xb001)
}
if (lastcrc16 == 0xb001)
rt=TRUE;
}
......@@ -173,30 +173,30 @@ int ReadScratch43(int portnum, uchar *SerialNum, uchar *page_buffer)
int ReadMem43(int portnum, uchar *SerialNum, int page, uchar *page_buffer)
{
uchar rt=FALSE;
ushort lastcrc16;
ushort lastcrc16;
int i;
ushort target_addr = 0;
uchar read_data;
owSerialNum(portnum, SerialNum, FALSE);
if(owAccess(portnum))
{
if (!owWriteBytePower(portnum, E_READ_MEM_CMD))
{
if (!owWriteBytePower(portnum, E_READ_MEM_CMD))
return FALSE;
setcrc16(portnum, 0); //init crc
docrc16(portnum,(ushort)E_READ_MEM_CMD);
owLevel(portnum, MODE_NORMAL);
owWriteBytePower(portnum, 0x00); //write LSB of target addr
docrc16(portnum,(ushort)0x00);
owLevel(portnum, MODE_NORMAL);
owWriteBytePower(portnum, 0x00); //write MSB of target addr
docrc16(portnum,(ushort)0x00);
for(i = 0; i < 32; i++)
{
for(i = 0; i < 32; i++)
{
owLevel(portnum,MODE_NORMAL);
page_buffer[i] = owReadBytePower(portnum);
lastcrc16 = docrc16(portnum, page_buffer[i]);
......@@ -204,14 +204,14 @@ int ReadMem43(int portnum, uchar *SerialNum, int page, uchar *page_buffer)
// mprintf(" CRC16: %x", lastcrc16);
// mprintf(" CRC16i: %x\n", ~lastcrc16);
}
for(i = 0; i < 2; i++)
{
owLevel(portnum,MODE_NORMAL);
owLevel(portnum,MODE_NORMAL);
read_data = owReadBytePower(portnum);
lastcrc16 = docrc16(portnum, read_data);
}
if (lastcrc16 == 0xb001)
}
if (lastcrc16 == 0xb001)
rt=TRUE;
}
......
......@@ -64,7 +64,7 @@ SMALLINT FindDevices(int portnum, uchar FamilySN[][8], SMALLINT family_code, int
// perform the search
if (!owNext(portnum,TRUE, FALSE))
break;
owSerialNum(portnum,FamilySN[NumDevices], TRUE);
if ((FamilySN[NumDevices][0] & 0x7F) == (family_code & 0x7F))
{
......
......@@ -41,8 +41,8 @@
#include "board.h"
//#define S_OVD 1
//#define S_PWR 0
//#define S_OVD 1
//#define S_PWR 0
#define S_IEN 0
#define S_OVD_E 1
#define CLK_DIV_NOR (CPU_CLOCK/200000-1) //clock divider for normal mode
......@@ -74,7 +74,7 @@ int S_PWR = 0;
// init clock divider for SCU board
SMALLINT owInit(void)
{
IOWR_SOCKIT_OWM_CDR(BASE_ONEWIRE, ((CLK_DIV_NOR & SOCKIT_OWM_CDR_N_MSK) | ((CLK_DIV_OVD << SOCKIT_OWM_CDR_O_OFST) & SOCKIT_OWM_CDR_O_MSK)));
IOWR_SOCKIT_OWM_CDR(BASE_ONEWIRE, ((CLK_DIV_NOR & SOCKIT_OWM_CDR_N_MSK) | ((CLK_DIV_OVD << SOCKIT_OWM_CDR_O_OFST) & SOCKIT_OWM_CDR_O_MSK)));
return 0;
}
......
......@@ -67,7 +67,7 @@ uint8_t ReadTemperature28(uint8_t portnum, uint8_t *SerialNum, int16_t *Temp)
}
}
if(toggle)
if(toggle)
{
if( owAccess(portnum))
{
......
......@@ -31,7 +31,7 @@
//
#include "ownet.h"
#include "temp42.h"
//----------------------------------------------------------------------
// Read the temperature of a DS28EA00 (family code 0x42)
//
......@@ -54,10 +54,10 @@ int ReadTemperature42(int portnum, uchar *SerialNum, int *Temp, int *frac )
int val_int=0;
int is_neg=FALSE;
// set the device serial number to the counter device
owSerialNum(portnum,SerialNum,FALSE);
for (loop = 0; loop < 2; loop ++)
{
// check if the chip is connected to VDD
......@@ -65,13 +65,13 @@ int ReadTemperature42(int portnum, uchar *SerialNum, int *Temp, int *frac )
{
owWriteByte(portnum,0xB4);
power = owReadByte(portnum);
}
}
// access the device
if (owOverdriveAccess(portnum))
{
// send the convert command and if nesessary start power delivery
// if (power) {
// if (power) {
// if (!owWriteBytePower(portnum,0x44))
// return FALSE;
// } else {
......@@ -81,11 +81,11 @@ int ReadTemperature42(int portnum, uchar *SerialNum, int *Temp, int *frac )
// sleep for 1 second
msDelay(1000);
// turn off the 1-Wire Net strong pull-up
if (power) {
if (power) {
if (owLevel(portnum,MODE_NORMAL) != MODE_NORMAL)
return FALSE;
}
// access the device
if (owOverdriveAccess(portnum))
{
......@@ -96,7 +96,7 @@ int ReadTemperature42(int portnum, uchar *SerialNum, int *Temp, int *frac )
// now add the read bytes for data bytes and crc8
for (i = 0; i < 9; i++)
send_block[send_cnt++] = 0xFF;
// now send the block
if (owBlock(portnum,FALSE,send_block,send_cnt))
{
......@@ -105,20 +105,20 @@ int ReadTemperature42(int portnum, uchar *SerialNum, int *Temp, int *frac )
// perform the CRC8 on the last 8 bytes of packet
for (i = send_cnt - 9; i < send_cnt; i++)
lastcrc8 = docrc8(portnum,send_block[i]);
// verify CRC8 is correct
if (lastcrc8 == 0x00)
{
// calculate the high-res temperature
// from twos complement representation
val_int = send_block[1]; // low byte
val_int |= send_block[2] << 8; // high byte
if (val_int & 0x00001000) { // check sign for negative
val_int = ~val_int + 1;
is_neg = TRUE;
}
is_neg = TRUE;
}
*Temp = val_int >> 4; // only integer part
*frac = val_int & 0x08; // only 1/2 bit
// success
......
......@@ -9,15 +9,15 @@ OBJS_TEST = testtool.o
INCLUDE_DIR = -I../include -I../ptp-noposix/PTPWRd
CROSS_COMPILE ?= lm32-elf-
CFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled
LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -nostdlib -T ../target/lm32/ram.ld
CFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled
LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -nostdlib -T ../target/lm32/ram.ld
OBJS_PLATFORM=../target/lm32/crt0.o ../target/lm32/irq.o
CC=$(CROSS_COMPILE)gcc
OBJCOPY=$(CROSS_COMPILE)objcopy
OBJDUMP=$(CROSS_COMPILE)objdump
CFLAGS= $(CFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -include ../include/trace.h -I../include/ -I../ptp-noposix/libptpnetif -I../ptp-noposix/PTPWRd
LDFLAGS= $(LDFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os
LDFLAGS= $(LDFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os
SIZE = $(CROSS_COMPILE)size
OBJS=$(OBJS_PLATFORM) $(OBJS_COMMON) $(OBJS_TEST)
......@@ -26,11 +26,11 @@ OUTPUT = testtool
all: $(OBJS)
$(SIZE) -t $(OBJS)
${CC} -o $(OUTPUT).elf $(OBJS) $(LDFLAGS)
${CC} -o $(OUTPUT).elf $(OBJS) $(LDFLAGS)
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
clean:
rm -f $(OBJS) $(OUTPUT).elf $(OUTPUT).bin
rm -f $(OBJS) $(OUTPUT).elf $(OUTPUT).bin
%.o: %.c
${CC} $(CFLAGS) -c $^ -o $@
......
......@@ -47,7 +47,7 @@ static int meas_phase_range(wr_socket_t *sock, int phase_min, int phase_max, int
spll_set_phase_shift(SPLL_ALL_CHANNELS, phase_min);
while(spll_shifter_busy(0));
purge_socket(sock);
i=0;
......@@ -58,9 +58,9 @@ static int meas_phase_range(wr_socket_t *sock, int phase_min, int phase_max, int
update_rx_queues();
int n = ptpd_netif_recvfrom(sock, &from, buf, 128, &ts_rx);
if(n>0)
{
{
msgUnpackHeader(buf, &mhdr);
if(mhdr.messageType == 0)
ts_sync = ts_rx;
......@@ -68,14 +68,14 @@ static int meas_phase_range(wr_socket_t *sock, int phase_min, int phase_max, int
{
MsgFollowUp fup;
msgUnpackFollowUp(buf, &fup);
mprintf("Shift: %d/%dps [step %dps] \r", setpoint,phase_max,phase_step);
results[i].phase = phase;
results[i].phase_sync = ts_sync.phase;
results[i].ahead = ts_sync.raw_ahead;
results[i].delta_ns = fup.preciseOriginTimestamp.nanosecondsField - ts_sync.nsec;
results[i].delta_ns += (fup.preciseOriginTimestamp.secondsField.lsb - ts_sync.sec) * 1000000000;
setpoint += phase_step;
spll_set_phase_shift(0, setpoint);
while(spll_shifter_busy(0));
......@@ -107,7 +107,7 @@ int measure_t24p(int *value)
wr_sockaddr_t sock_addr;
int i, nr;
struct meas_entry results[128];
spll_enable_ptracker(0, 1);
sock_addr.family = PTPD_SOCK_RAW_ETHERNET; // socket type
......@@ -134,7 +134,7 @@ int measure_t24p(int *value)
if(ptpd_netif_init() != 0)
return -1;
sock = ptpd_netif_create_socket(PTPD_SOCK_RAW_ETHERNET, 0, &sock_addr);
nr=meas_phase_range(sock, 0, 8000, 1000, results);
int tplus = find_transition(results, nr, 1);
......@@ -142,31 +142,31 @@ int measure_t24p(int *value)
int approx_plus = results[tplus].phase;
int approx_minus = results[tminus].phase;
nr=meas_phase_range(sock, approx_plus-1000, approx_plus+1000, 100, results);
tplus = find_transition(results, nr, 1);
int phase_plus = results[tplus].phase;
nr=meas_phase_range(sock, approx_minus-1000, approx_minus+1000, 100, results);
tminus = find_transition(results, nr, 0);
int phase_minus = results[tminus].phase;
mprintf("Transitions found: positive @ %d ps, negative @ %d ps.\n", phase_plus, phase_minus);
int ttrans = phase_minus-1000;
if(ttrans < 0) ttrans+=8000;
mprintf("(t2/t4)_phase_transition = %dps\n", ttrans);
ptpd_netif_set_phase_transition(sock, ttrans);
mprintf("Verification... \n");
nr =meas_phase_range(sock, 0, 16000, 500, results);
for(i=0;i<nr;i++) mprintf("phase_dmtd: %d delta_ns: %d, phase_sync: %d\n", results[i].phase, results[i].delta_ns, results[i].phase_sync);
if(value) *value = ttrans;
return 0;
return 0;
}
......@@ -22,4 +22,4 @@ genramvhd: genramvhd.o
${CC} -c $^ $(CFLAGS) -O0
clean:
rm -f $(ALL) *.o
rm -f $(ALL) *.o
......@@ -3,9 +3,9 @@
main(int argc, char *argv[])
{
if(argc < 3) return -1;
if(argc < 3) return -1;
FILE *f = fopen(argv[1],"rb");
if(!f) return -1;
if(!f) return -1;
unsigned char x[4];
int i=0;
int n = atoi(argv[2]);
......@@ -18,7 +18,7 @@ main(int argc, char *argv[])
for(;i<n;)
{
printf("write %x %02X%02X%02X%02X\n", i++, 0,0,0,0);
printf("write %x %02X%02X%02X%02X\n", i++, 0,0,0,0);
}
fclose(f);
return 0;
......
......@@ -43,7 +43,7 @@ int main(int argc, char **argv) {
unsigned char x[16]; /* Up to 128 bit */
char buf[100];
FILE* f;
/* Default values */
program = argv[0];
package = 0; /* auto-detect */
......@@ -51,7 +51,7 @@ int main(int argc, char **argv) {
bigendian = 1;
verbose = 0;
size = -1; /* file size */
/* Process the command-line */
while ((opt = getopt(argc, argv, "w:p:s:blvh")) != -1) {
switch (opt) {
......@@ -96,56 +96,56 @@ int main(int argc, char **argv) {
return 1;
}
}
if (optind + 1 != argc) {
fprintf(stderr, "%s: expecting one non-optional argument: <filename>\n", program);
return 1;
}
filename = argv[optind];
/* Confirm the filename exists */
if ((f = fopen(filename, "r")) == 0) {
fprintf(stderr, "%s: %s while opening '%s'\n", program, strerror(errno), filename);
return 1;
}
/* Deduce if it's aligned */
fseek(f, 0, SEEK_END);
elements = ftell(f);
rewind(f);
if (size == -1) {
size = elements;
}
if (size < elements) {
fprintf(stderr, "%s: length of initialization file '%s' (%ld) exceeds specified size (%ld)\n", program, filename, elements, size);
return 1;
}
if (elements % width != 0) {
fprintf(stderr, "%s: initialization file '%s' is not a multiple of %ld bytes\n", program, filename, width);
return 1;
}
elements /= width;
if (size % width != 0) {
fprintf(stderr, "%s: specified size '%ld' is not a multiple of %ld bytes\n", program, size, width);
return 1;
}
size /= width;
/* Find a suitable package name */
if (package == 0) {
if (strlen(filename) >= sizeof(buf)-5) {
fprintf(stderr, "%s: filename too long to deduce package name -- '%s'\n", program, filename);
return 1;
}
/* Find the first alpha character */
while (*filename && !my_isalpha(*filename)) ++filename;
/* Start copying the filename to the package */
for (i = 0; filename[i]; ++i) {
if (my_isok(filename[i]))
......@@ -154,12 +154,12 @@ int main(int argc, char **argv) {
buf[i] = '_';
}
buf[i] = 0;
if (i == 0) {
fprintf(stderr, "%s: no appropriate characters in filename to use for package name -- '%s'\n", program, filename);
return 1;
}
package = &buf[0];
} else {
/* Check for valid VHDL identifier */
......@@ -174,16 +174,16 @@ int main(int argc, char **argv) {
}
}
}
/* Find how many digits it takes to fit 'size' */
i_width = 1;
for (i = 10; i <= size; i *= 10)
++i_width;
/* How wide is an entry of the table? */
entry_width = i_width + 6 + width*2 + 3;
columns = 76 / entry_width;
printf("-- AUTOGENERATED FILE (from genramvhd.c run on %s) --\n", argv[1]);
printf("library IEEE;\n");
printf("use IEEE.std_logic_1164.all;\n");
......@@ -192,13 +192,13 @@ int main(int argc, char **argv) {
printf("library work;\n");
printf("use work.memory_loader_pkg.all;\n");
printf("\n");
printf("package %s_pkg is\n", package);
printf(" constant %s_init : t_meminit_array(%ld downto 0, %ld downto 0) := (\n", package, size-1, (width*8)-1);
for (i = 0; i < size; ++i) {
if (i % columns == 0) printf(" ");
if (i < elements) {
if (fread(x, 1, width, f) != width) {
perror("fread");
......@@ -207,7 +207,7 @@ int main(int argc, char **argv) {
} else {
memset(x, 0, sizeof(x));
}
printf("%*ld => x\"", i_width, i);
if (bigendian) {
for (j = 0; j < width; ++j)
......@@ -217,13 +217,13 @@ int main(int argc, char **argv) {
printf("%02x", x[j]);
}
printf("\"");
if ((i+1) == size) printf(");\n");
else if ((i+1) % columns == 0) printf(",\n");
else printf(", ");
}
fclose(f);
printf("end %s_pkg;\n", package);
return 0;
......
......@@ -33,25 +33,25 @@ void wrc_initialize()
int ret, i;
uint8_t mac_addr[6], ds18_id[8] = {0,0,0,0,0,0,0,0};
char sfp_pn[17];
sdb_find_devices();
uart_init();
mprintf("WR Core: starting up...\n");
timer_init(1);
owInit();
mac_addr[0] = 0x08; //
mac_addr[1] = 0x00; // CERN OUI
mac_addr[2] = 0x30; //
mac_addr[2] = 0x30; //
own_scanbus(ONEWIRE_PORT);
if (get_persistent_mac(ONEWIRE_PORT, mac_addr) == -1) {
mprintf("Unable to determine MAC address\n");
mac_addr[0] = 0x11; //
mac_addr[1] = 0x22; //
mac_addr[2] = 0x33; // fallback MAC if get_persistent_mac fails
mac_addr[1] = 0x22; //
mac_addr[2] = 0x33; // fallback MAC if get_persistent_mac fails
mac_addr[3] = 0x44; //
mac_addr[4] = 0x55; //
mac_addr[5] = 0x66; //
......@@ -65,7 +65,7 @@ void wrc_initialize()
minic_init();
pps_gen_init();
wrc_ptp_init();
#if WITH_ETHERBONE
ipv4_init("wru1");
arp_init("wru1");
......@@ -88,7 +88,7 @@ int wrc_check_link()
TRACE_DEV("Link up.\n");
gpio_out(GPIO_LED_LINK, 1);
rv = LINK_WENT_UP;
}
}
else if(prev_link_state && !link_state)
{
TRACE_DEV("Link down.\n");
......@@ -105,14 +105,14 @@ int wrc_extra_debug = 0;
void wrc_debug_printf(int subsys, const char *fmt, ...)
{
va_list ap;
if(wrc_ui_mode) return;
va_start(ap, fmt);
if(wrc_extra_debug || (!wrc_extra_debug && (subsys & TRACE_SERVO)))
vprintf(fmt, ap);
va_end(ap);
}
......@@ -130,7 +130,7 @@ static void ui_update()
{
shell_init();
wrc_ui_mode = UI_SHELL_MODE;
}
}
}
else if(wrc_ui_mode == UI_STAT_MODE)
{
......@@ -139,7 +139,7 @@ static void ui_update()
{
shell_init();
wrc_ui_mode = UI_SHELL_MODE;
}
}
}
else
shell_interactive();
......@@ -159,7 +159,7 @@ int main(void)
//try to read and execute init script from EEPROM
shell_boot_script();
for (;;)
{
int l_status = wrc_check_link();
......@@ -171,7 +171,7 @@ int main(void)
needIP = 1;
break;
#endif
case LINK_UP:
update_rx_queues();
#if WITH_ETHERBONE
......
......@@ -38,7 +38,7 @@ static RunTimeOpts rtOpts = {
.wrStateTimeout= WR_DEFAULT_STATE_TIMEOUT_MS,
.phyCalibrationRequired = FALSE,
.disableFallbackIfWRFails = TRUE,
.primarySource = FALSE,
.wrConfig = WR_S_ONLY,
.masterOnly = FALSE,
......@@ -53,7 +53,7 @@ static int ptp_enabled = 0, ptp_mode = WRC_MODE_UNKNOWN;
int wrc_ptp_init()
{
Integer16 ret;
netStartup();
ptpPortDS = ptpdStartup(0, NULL, &ret, &rtOpts, &ptpClockDS);
......@@ -65,7 +65,7 @@ int wrc_ptp_init()
PTPD_TRACE(TRACE_WRPC, NULL,"failed to initialize network\n");
return -1;
}
ptpPortDS->linkUP = FALSE;
ptp_enabled = 0;
return 0;
......@@ -79,12 +79,12 @@ int wrc_ptp_set_mode(int mode)
uint32_t start_tics, lock_timeout = 0;
ptp_mode = 0;
wrc_ptp_stop();
switch(mode)
{
case WRC_MODE_GM:
case WRC_MODE_GM:
rtOpts.primarySource = TRUE;
rtOpts.wrConfig = WR_M_ONLY;
rtOpts.masterOnly = TRUE;
......@@ -103,15 +103,15 @@ int wrc_ptp_set_mode(int mode)
case WRC_MODE_SLAVE:
rtOpts.primarySource = FALSE;
rtOpts.wrConfig = WR_S_ONLY;
rtOpts.masterOnly = FALSE;
rtOpts.masterOnly = FALSE;
spll_init(SPLL_MODE_SLAVE, 0, 1);
break;
}
initDataClock(&rtOpts, &ptpClockDS);
start_tics = timer_get_tics();
mprintf("Locking PLL");
pps_gen_enable_output(0);
......@@ -130,10 +130,10 @@ int wrc_ptp_set_mode(int mode)
return -EINTR;
}
}
if(mode == WRC_MODE_MASTER || mode == WRC_MODE_GM)
pps_gen_enable_output(1);
mprintf("\n");
ptp_mode = mode;
return 0;
......
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