Commit 39d6fb3b authored by Aurelio Colosimo's avatar Aurelio Colosimo

use arch-spec/dev sources from wrpc-sw

Removed any dependency from ppsi's internal copy of spec drivers, and the
drivers' source itself.

With this patch, now we ppsi is fully compatible with wrpc-sw drivers.

In order to compile ppsi main (which, in the future, will become obsolete)
you can now either:
- copy ppsi project inside the wrpc-sw dir (or, better, use the ppsi as
wrpc-sw submodule)
- go into arch-spec/Makefile and modify the WRPCSW_ROOT var
Signed-off-by: Aurelio Colosimo's avatarAurelio Colosimo <aurelio@aureliocolosimo.it>
parent 108fc4dc
......@@ -13,6 +13,9 @@ WRPCSW_ROOT = ..
# wrpc-sw
PTPNOPOSIX_ROOT = $(WRPCSW_ROOT)/ptp-noposix
CFLAGS += -I$(WRPCSW_ROOT)/include -I$(PTPNOPOSIX_ROOT)/softpll \
-I$(WRPCSW_ROOT)/boards/spec
# All files are under A (short for ARCH): I'm lazy
A := arch-$(ARCH)
......@@ -28,7 +31,7 @@ OBJ-libarch := $A/spec-startup.o \
$A/spec-halexp.o \
lib/div64.o
OBJ-specdev := $(WRPCSW_ROOT)/dev/uart.o \
specdev-objects := $(WRPCSW_ROOT)/dev/uart.o \
$(WRPCSW_ROOT)/dev/syscon.o \
$(WRPCSW_ROOT)/dev/ep_pfilter.o \
$(WRPCSW_ROOT)/dev/endpoint.o \
......@@ -48,7 +51,7 @@ all: $(TARGET) $(TARGET).bin
# were not selected yet (e.g., pp_open_instance() ).
$(TARGET): $(TARGET).o $A/crt0.o $(LIBARCH)
$(CC) -Wl,-Map,$(TARGET).map2 $(ARCH_LDFLAGS) -o $@ $A/crt0.o \
$(TARGET).o $(OBJ-specdev) -L$A -larch -L$W -lwr
$(TARGET).o $(specdev-objects) -L$A -larch $(LIBS)
$(TARGET).bin: $(TARGET)
$(OBJCOPY) -O binary $^ $@
#include "board.h"
#include "syscon.h"
#define DNA_DATA 1
#define DNA_CLK 4
#define DNA_SHIFT 3
#define DNA_READ 2
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);
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
Tomasz Wlostowski/CERN 2011
LGPL 2.1
*/
#include "../spec.h"
#include "syscon.h"
#include <endpoint.h>
#include "eeprom.h"
#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
/* Number of raw phase samples averaged by the DMTD detector in the Endpoint during single phase measurement.
The bigger, the better precision, but slower rate */
#define DMTD_AVG_SAMPLES 256
static int autoneg_enabled;
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;
}
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;
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->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;
}
/* 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);
*(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 */
/* Configure DMTD phase tracking */
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;
if(!enabled)
{
EP->ECR = 0;
return 0;
}
/* Disable the endpoint */
EP->ECR = 0;
mprintf("ID: %x\n", EP->IDCODE);
/* Load default packet classifier rules - see ep_pfilter.c for details */
pfilter_init_default();
/* Enable TX/RX paths, reset RMON counters */
EP->ECR = EP_ECR_TX_EN | EP_ECR_RX_EN | EP_ECR_RST_CNT;
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 */
/* Don't advertise anything - we don't want flow control */
pcs_write(MDIO_REG_ADVERTISE, 0);
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;
}
/* 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)
{
uint16_t flags = MDIO_MSR_LSTATUS;
volatile uint16_t msr;
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 */
if(lpa) *lpa = pcs_read(MDIO_REG_LPA);
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)
{
/* 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);
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);
return 0;
}
This diff is collapsed.
#include "irq.h"
void disable_irq()
{
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 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;
/* 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));
ie |= 0x1;
asm volatile ("wcsr ie, %0"::"r"(ie));
}
/*#include <stdio.h>*/
/*#include "types.h"*/
#include "../spec.h"
#include "pps_gen.h" /* for pps_gen_get_time() */
#include "minic.h"
#include <hw/minic_regs.h>
#define MINIC_DMA_TX_BUF_SIZE 1024
#define MINIC_DMA_RX_BUF_SIZE 2048
#define MINIC_MTU 256
#define F_COUNTER_BITS 4
#define F_COUNTER_MASK ((1<<F_COUNTER_BITS)-1)
#define RX_DESC_VALID(d) ((d) & (1<<31) ? 1 : 0)
#define RX_DESC_ERROR(d) ((d) & (1<<30) ? 1 : 0)
#define RX_DESC_HAS_OOB(d) ((d) & (1<<29) ? 1 : 0)
#define RX_DESC_SIZE(d) (((d) & (1<<0) ? -1 : 0) + (d & 0xffe))
#define RXOOB_TS_INCORRECT (1<<11)
#define TX_DESC_VALID (1<<31)
#define TX_DESC_WITH_OOB (1<<30)
#define TX_DESC_HAS_OWN_MAC (1<<28)
#define RX_OOB_SIZE 6
#define ETH_HEADER_SIZE 14
// extracts the values of TS rising and falling edge counters from the descriptor header
#define EXPLODE_WR_TIMESTAMP(raw, rc, fc) \
rc = (raw) & 0xfffffff; \
fc = (raw >> 28) & 0xf;
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;
uint32_t rx_avail, rx_size;
volatile uint32_t *tx_head, *tx_base;
uint32_t tx_avail, tx_size;
int tx_count, rx_count;
};
static struct wr_minic minic;
static inline void minic_writel(uint32_t reg,uint32_t data)
{
*(volatile uint32_t *) (BASE_MINIC + reg) = data;
}
static inline uint32_t minic_readl(uint32_t reg)
{
return *(volatile uint32_t *)(BASE_MINIC + reg);
}
/*
* uint32_t size - in bytes
*/
static uint8_t * minic_rx_memcpy( uint8_t *dst, uint8_t *src, uint32_t size)
{
uint32_t part;
//if src is outside the circular buffer, bring it back to the beginning
src = (uint8_t *) ((uint32_t)minic.rx_base + ((uint32_t)src - (uint32_t)minic.rx_base) % (minic.rx_size<<2));
if((uint32_t)src + size <= (uint32_t)minic.rx_base + (minic.rx_size<<2))
return memcpy(dst, src, size);
part = (uint32_t)minic.rx_base + (minic.rx_size<<2) - (uint32_t)src;
memcpy(dst, src, part);
memcpy((void*) (dst+part), (void*)minic.rx_base, size - part);
return dst;
}
/*
* uint32_t size - in bytes
*/
static uint8_t *minic_rx_memset( uint8_t *mem, uint8_t c, uint32_t size)
{
uint32_t part;
uint32_t *src;
//if src is outside the circular buffer, bring it back to the beginning
src = (uint32_t*)((uint32_t)minic.rx_base + ((uint32_t)mem - (uint32_t)minic.rx_base) % (minic.rx_size<<2));
if((uint32_t)src + size <= (uint32_t)minic.rx_base + (minic.rx_size<<2))
return memset((void*)src, c, size);
part = (uint32_t)minic.rx_base + (minic.rx_size<<2) - (uint32_t)src;
memset(src, c, part);
memset((void*)minic.rx_base, c, size - part);
return (uint8_t*)src;
}
static void minic_new_rx_buffer()
{
minic_writel(MINIC_REG_MCR, 0);
minic.rx_base = dma_rx_buf;
minic.rx_size = MINIC_DMA_RX_BUF_SIZE/4;
minic.rx_head = minic.rx_base;
minic_rx_memset((uint8_t*)minic.rx_base, 0x00, minic.rx_size<<2);
minic_writel(MINIC_REG_RX_ADDR, (uint32_t) minic.rx_base);
minic_writel(MINIC_REG_RX_SIZE, minic.rx_size);
//new buffer allocated, clear any old RX interrupts
minic_writel(MINIC_REG_EIC_ISR, MINIC_EIC_ISR_RX);
minic_writel(MINIC_REG_MCR, MINIC_MCR_RX_EN);
}
static void minic_rxbuf_free(uint32_t words)
{
minic_rx_memset((uint8_t*)minic.rx_head, 0x00, words<<2);
minic_writel(MINIC_REG_RX_AVAIL, words);
}
static void minic_new_tx_buffer()
{
minic.tx_base = dma_tx_buf;
minic.tx_size = MINIC_DMA_TX_BUF_SIZE>>2;
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;
minic.rx_size = sizeof(dma_rx_buf);
/* 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;
minic_writel(MINIC_REG_MPROT, MINIC_MPROT_LO_W(lo) | MINIC_MPROT_HI_W(hi));
minic.tx_base = dma_tx_buf;
minic.tx_size = MINIC_DMA_TX_BUF_SIZE>>2;
minic.tx_count = 0;
minic.rx_count = 0;
minic_new_rx_buffer();
minic_writel(MINIC_REG_EIC_IER, MINIC_EIC_IER_RX);
}
void minic_disable()
{
minic_writel(MINIC_REG_MCR, 0);
}
int minic_poll_rx()
{
uint32_t isr;
isr = minic_readl(MINIC_REG_EIC_ISR);
return (isr & MINIC_EIC_ISR_RX) ? 1 : 0;
}
int minic_rx_frame(uint8_t *hdr, uint8_t *payload, uint32_t buf_size, struct hw_timestamp *hwts)
{
uint32_t payload_size, num_words;
uint32_t desc_hdr;
uint32_t raw_ts;
uint32_t rx_addr_cur, cur_avail;
int n_recvd;
if(! (minic_readl(MINIC_REG_EIC_ISR) & MINIC_EIC_ISR_RX))
return 0;
desc_hdr = *minic.rx_head;
if(!RX_DESC_VALID(desc_hdr)) /* invalid descriptor? Weird, the RX_ADDR seems to be saying something different. Ignore the packet and purge the RX buffer. */
{
//invalid descriptor ? then probably the interrupt was generated by full rx buffer
if(minic_readl(MINIC_REG_MCR) & MINIC_MCR_RX_FULL)
minic_new_rx_buffer();
else
{
//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 */
if(!RX_DESC_ERROR(desc_hdr))
{
if(RX_DESC_HAS_OOB(desc_hdr) && hwts != NULL)
{
uint32_t counter_r, counter_f, counter_ppsg;
uint64_t sec;
int cntr_diff;
uint16_t dhdr;
payload_size -= RX_OOB_SIZE;
minic_rx_memcpy((uint8_t *)&raw_ts, (uint8_t *)minic.rx_head + payload_size + 6, 4); /* fixme: ugly way of doing unaligned read */
minic_rx_memcpy((uint8_t *)&dhdr, (uint8_t *)minic.rx_head + payload_size + 4, 2);
EXPLODE_WR_TIMESTAMP(raw_ts, counter_r, counter_f);
pps_gen_get_time(&sec, &counter_ppsg);
if(counter_r > 3*REF_CLOCK_FREQ_HZ/4 && counter_ppsg < 250000000)
sec--;
hwts->sec = sec & 0x7fffffff ;
cntr_diff = (counter_r & F_COUNTER_MASK) - counter_f;
if(cntr_diff == 1 || cntr_diff == (-F_COUNTER_MASK))
hwts->ahead = 1;
else
hwts->ahead = 0;
hwts->nsec = counter_r * (REF_CLOCK_PERIOD_PS/1000);
hwts->valid = (dhdr & RXOOB_TS_INCORRECT) ? 0 : 1;
if (!hwts->valid) {
int k;
PP_VPRINTF("Warning: rx timestamp invalid - dhdr: ");
for (k = 0; k < 2; k++) PP_VPRINTF("%02x ", ((char*)&dhdr)[k]);
PP_VPRINTF("\n");
}
}
n_recvd = (buf_size < payload_size ? buf_size : payload_size);
minic.rx_count++;
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 {
n_recvd = -1;
}
minic_rxbuf_free(num_words);
minic.rx_head = (uint32_t *)((uint32_t)minic.rx_base + ((uint32_t)minic.rx_head+(num_words<<2) - (uint32_t)minic.rx_base) % (minic.rx_size<<2));
cur_avail = minic_readl(MINIC_REG_RX_AVAIL) & 0xFFFFFF; /* 24-bit field */
/*empty buffer->no more received packets, or packet reception in progress but not done*/
if( !RX_DESC_VALID(*minic.rx_head))
{
if(minic_readl(MINIC_REG_MCR) & MINIC_MCR_RX_FULL)
minic_new_rx_buffer();
minic_writel(MINIC_REG_EIC_ISR, MINIC_EIC_ISR_RX);
}
return n_recvd;
}
int minic_tx_frame(uint8_t *hdr, uint8_t *payload, uint32_t size, struct hw_timestamp *hwts)
{
uint32_t d_hdr, mcr, nwords;
uint8_t ts_valid;
int i = 0;
minic_new_tx_buffer();
memset((void*)minic.tx_head, 0x0, size + 16);
memset((void*)minic.tx_head + 4, 0, size < 60 ? 60 : size);
memcpy((void*)minic.tx_head + 4, hdr, ETH_HEADER_SIZE);
memcpy((void*)minic.tx_head + 4 + ETH_HEADER_SIZE, payload, size - ETH_HEADER_SIZE);
if(size < 60)
size = 60;
nwords = ((size + 1) >> 1);
d_hdr = 0;
if(hwts)
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;
mcr = minic_readl(MINIC_REG_MCR);
minic_writel(MINIC_REG_MCR, mcr | MINIC_MCR_TX_START);
i = 0;
do {
mcr = minic_readl(MINIC_REG_MCR);
if (i > 0)
timer_delay(1000);
i++;
} while (((mcr & MINIC_MCR_TX_IDLE) == 0) && (i < 1000));
if (i == 1000)
pp_printf("Warning: tx not terminated infinite mcr=0x%x\n",mcr);
if(hwts) /* wait for the timestamp */
{
uint32_t raw_ts;
uint16_t fid;
uint32_t counter_r, counter_f;
uint64_t sec;
uint32_t nsec;
ts_valid = (uint8_t) (minic_readl(MINIC_REG_TSR0) & MINIC_TSR0_VALID);
raw_ts = minic_readl(MINIC_REG_TSR1);
fid = MINIC_TSR0_FID_R(minic_readl(MINIC_REG_TSR0));
if(fid != WRPC_FID)
{
TRACE_DEV("minic_tx_frame: unmatched fid %d vs %d\n", fid, WRPC_FID);
}
EXPLODE_WR_TIMESTAMP(raw_ts, counter_r, counter_f);
pps_gen_get_time(&sec, &nsec);
if(counter_r > 3*REF_CLOCK_FREQ_HZ/4 && nsec < 250000000)
sec--;
hwts->valid = ts_valid;
hwts->sec = sec;
hwts->ahead = 0;
hwts->nsec = counter_r * 8;
if (!ts_valid) {
PP_PRINTF("Warning: tx timestamp invalid\n");
}
// TRACE_DEV("minic_tx_frame [%d bytes] TS: %d.%d valid %d\n", size, hwts->utc, hwts->nsec, hwts->valid);
minic.tx_count++;
}
return size;
}
void minic_get_stats(int *tx_frames, int *rx_frames)
{
*tx_frames = minic.tx_count;
*rx_frames = minic.rx_count;
}
#include "onewire.h"
#include "../sockitowm/ownet.h"
#include "../sockitowm/findtype.h"
#define DEBUG_PMAC 0
uint8_t FamilySN[MAX_DEV1WIRE][8];
uint8_t devsnum;
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 */
#if DEBUG_PMAC
mprintf("Found %d onewire devices\n", devsnum);
#endif
}
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;
}
/* 0 = success, -1 = error */
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",
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 DEBUG_PMAC
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 DEBUG_PMAC
mprintf("EEPROM has not been programmed with a MAC\n");
#endif
} 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]);
#endif
}
}
}
}
return out;
}
/* 0 = success, -1 = error */
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);
#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;
}
#include "../spec.h"
#include <hw/pps_gen_regs.h>
#include <pps_gen.h>
/*#include <inttypes.h>*/
/* PPS Generator driver */
/* Warning: references to "UTC" in the registers DO NOT MEAN actual UTC time, it's just a plain second counter
It doesn't care about leap seconds. */
/* Default width (in 8ns units) of the pulses on the PPS output */
#define PPS_WIDTH 100000
#define ppsg_write(reg, val) \
*(volatile uint32_t *) (BASE_PPS_GEN + (offsetof(struct PPSG_WB, reg))) = (val)
#define ppsg_read(reg) \
*(volatile uint32_t *) (BASE_PPS_GEN + (offsetof(struct PPSG_WB, reg)))
int pps_gen_init()
{
uint32_t cr;
cr = PPSG_CR_CNT_EN | PPSG_CR_PWIDTH_W(PPS_WIDTH);
ppsg_write(CR, cr);
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 */
}
/* 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;
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_NSEC, 0);
}
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;
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);
return 0;
}
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;
}
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 */
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);
}
/* 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;
}
/* 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));
return 0;
}
#include "../spec.h"
#include "hw/memlayout.h"
#define SDB_INTERCONNET 0x00
#define SDB_DEVICE 0x01
#define SDB_BRIDGE 0x02
#define SDB_EMPTY 0xFF
typedef struct pair64 {
uint32_t high;
uint32_t low;
} pair64_t;
struct sdb_empty {
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;
};
struct sdb_component {
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;
};
struct sdb_bridge {
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;
};
typedef union sdb_record {
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 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);
}
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);
}
/* SFP Detection / managenent functions */
#include <stdio.h>
#include <inttypes.h>
#include "syscon.h"
#include "i2c.h"
#include "sfp.h"
int sfp_present()
{
return !gpio_in(GPIO_SFP_DET);
}
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;
}
This diff is collapsed.
#ifndef __SOFTPLL_NG_H
#define __SOFTPLL_NG_H
#include <stdio.h>
/* Modes */
#define SPLL_MODE_GRAND_MASTER 1
#define SPLL_MODE_FREE_RUNNING_MASTER 2
#define SPLL_MODE_SLAVE 3
#define SPLL_MODE_DISABLED 4
#define SPLL_ALL_CHANNELS 0xffff
#define SPLL_AUX_ENABLED (1<<0)
#define SPLL_AUX_LOCKED (1<<1)
void spll_init(int mode, int slave_ref_channel, int align_pps);
void spll_shutdown();
void spll_start_channel(int channel);
void spll_stop_channel(int channel);
int spll_check_lock(int channel);
void spll_set_phase_shift(int channel, int32_t value_picoseconds);
void spll_get_phase_shift(int channel, int32_t *current, int32_t *target);
void spll_enable_ptracker(int ref_channel, int enable);
int spll_read_ptracker(int channel, int32_t *phase_ps, int *enabled);
void spll_get_num_channels(int *n_ref, int *n_out);
int spll_shifter_busy(int channel);
int spll_get_delock_count();
int spll_update_aux_clocks();
int spll_get_aux_status(int channel);
void spll_set_dac(int index, int value);
int spll_get_dac(int index);
#endif
/*
White Rabbit Softcore PLL (SoftPLL) - common definitions
Copyright (c) 2010 - 2012 CERN / BE-CO-HT (Tomasz Włostowski)
Licensed under LGPL 2.1.
spll_common.h - common data structures and functions
*/
/* Number of reference/output channels. Currently we support only one SoftPLL instantiation per project,
so these can remain static. */
static int n_chan_ref, n_chan_out;
/* PI regulator state */
typedef struct {
int ki, kp; /* integral and proportional gains (1<<PI_FRACBITS == 1.0f) */
int integrator; /* current integrator value */
int bias; /* DC offset always added to the output */
int anti_windup; /* when non-zero, anti-windup is enabled */
int y_min; /* min/max output range, used by clapming and antiwindup algorithms */
int y_max;
int x, y; /* Current input (x) and output value (y) */
} spll_pi_t;
/* lock detector state */
typedef struct {
int lock_cnt; /* Lock sample counter */
int lock_samples; /* Number of samples below the (threshold) to assume that we are locked */
int delock_samples; /* Accumulated number of samples that causes the PLL go get out of lock.
delock_samples < lock_samples. */
int threshold; /* Error threshold */
int locked; /* Non-zero: we are locked */
} spll_lock_det_t;
/* simple, 1st-order lowpass filter */
typedef struct {
int alpha;
int y_d;
} spll_lowpass_t;
/* Processes a single sample (x) with PI control algorithm (pi). Returns the value (y) to
drive the actuator. */
static inline int pi_update(spll_pi_t *pi, int x)
{
int i_new, y;
pi->x = x;
i_new = pi->integrator + x;
y = ((i_new * pi->ki + x * pi->kp) >> PI_FRACBITS) + pi->bias;
/* clamping (output has to be in <y_min, y_max>) and anti-windup:
stop the integrator if the output is already out of range and the output
is going further away from y_min/y_max. */
if(y < pi->y_min)
{
y = pi->y_min;
if((pi->anti_windup && (i_new > pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new;
} else if (y > pi->y_max) {
y = pi->y_max;
if((pi->anti_windup && (i_new < pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new;
} else /* No antiwindup/clamping? */
pi->integrator = i_new;
pi->y = y;
return y;
}
/* initializes the PI controller state. Currently almost a stub. */
static inline void pi_init(spll_pi_t *pi)
{
pi->integrator = 0;
}
/* Lock detector state machine. Takes an error sample (y) and checks if it's withing an acceptable range
(i.e. <-ld.threshold, ld.threshold>. If it has been inside the range for (ld.lock_samples) cyckes, the
FSM assumes the PLL is locked.
Return value:
0: PLL not locked
1: PLL locked
-1: PLL just got out of lock
*/
static inline int ld_update(spll_lock_det_t *ld, int y)
{
if (abs(y) <= ld->threshold)
{
if(ld->lock_cnt < ld->lock_samples)
ld->lock_cnt++;
if(ld->lock_cnt == ld->lock_samples)
{
ld->locked = 1;
return 1;
}
} else {
if(ld->lock_cnt > ld->delock_samples)
ld->lock_cnt--;
if(ld->lock_cnt == ld->delock_samples)
{
ld->lock_cnt= 0;
ld->locked = 0;
return -1;
}
}
return ld->locked;
}
static void ld_init(spll_lock_det_t *ld)
{
ld->locked = 0;
ld->lock_cnt = 0;
}
static void lowpass_init(spll_lowpass_t *lp, int alpha)
{
lp->y_d = 0x80000000;
lp->alpha = alpha;
}
static int lowpass_update(spll_lowpass_t *lp, int x)
{
if(lp->y_d == 0x80000000)
{
lp->y_d = x;
return x;
} else {
int scaled = (lp->alpha * (x - lp->y_d)) >> 15;
lp->y_d = lp->y_d + (scaled >> 1) + (scaled & 1);
return lp->y_d;
}
}
/* Enables/disables DDMTD tag generation on a given (channel).
Channels (0 ... n_chan_ref - 1) are the reference channels (e.g. transceivers' RX clocks
or a local reference)
Channels (n_chan_ref ... n_chan_out + n_chan_ref-1) are the output channels (local voltage
controlled oscillators). One output (usually the first one) is always used to drive the
oscillator which produces the reference clock for the transceiver. Other outputs can be
used to discipline external oscillators (e.g. on FMCs).
*/
static void spll_enable_tagger(int channel, int enable)
{
if(channel >= n_chan_ref) /* Output channel? */
{
if(enable)
SPLL->OCER |= 1<< (channel - n_chan_ref);
else
SPLL->OCER &= ~ (1<< (channel - n_chan_ref));
} else { /* Reference channel */
if(enable)
SPLL->RCER |= 1<<channel;
else
SPLL->RCER &= ~ (1<<channel);
}
// TRACE("%s: ch %d, OCER 0x%x, RCER 0x%x\n", __FUNCTION__, channel, SPLL->OCER, SPLL->RCER);
}
static void spll_resync_dmtd_counter(int channel)
{
if(channel >= n_chan_ref) /* Output channel? */
SPLL->CRR_OUT = 1<< (channel - n_chan_ref);
else
SPLL->CRR_IN = 1<< channel;
}
static int spll_check_dmtd_resync(int channel)
{
if(channel >= n_chan_ref) /* Output channel? */
return (SPLL->CRR_OUT & (1<< (channel - n_chan_ref))) ? 1 : 0;
else
return (SPLL->CRR_IN & (1<< channel)) ? 1 :0;
}
\ No newline at end of file
/*
White Rabbit Softcore PLL (SoftPLL) - common definitions
Copyright (c) 2010 - 2012 CERN / BE-CO-HT (Tomasz Włostowski)
Licensed under LGPL 2.1.
spll_debug.h - debugging/diagnostic interface
The so-called debug inteface is a large, interrupt-driven FIFO which passes
various realtime parameters (e.g. error value, tags, DAC drive) to an external
application where they are further analyzed. It's very useful for optimizing PI coefficients
and/or lock thresholds.
The data is organized as a stream of samples, where each sample can store a number of parameters.
For example, a stream samples with Y and ERR parameters can be used to evaluate the impact of
integral/proportional gains on the response of the system.
*/
#define DBG_Y 0
#define DBG_ERR 1
#define DBG_TAG 2
#define DBG_REF 5
#define DBG_PERIOD 3
#define DBG_EVENT 4
#define DBG_SAMPLE_ID 6
#define DBG_HELPER 0x20 /* Sample source: Helper PLL */
#define DBG_EXT 0x40 /* Sample source: External Reference PLL */
#define DBG_MAIN 0x0 /* ... : Main PLL */
#define DBG_EVT_START 1 /* PLL has just started */
#define DBG_EVT_LOCKED 2 /* PLL has just become locked */
/* Writes a parameter to the debug FIFO.
value: value of the parameter.
what: type of the parameter and its' source. For example,
- DBG_ERR | DBG_HELPER means that (value) contains the phase error of the helper PLL.
- DBG_EVENT indicates an asynchronous event. (value) must contain the event type (DBG_EVT_xxx)
last: when non-zero, indicates the last parameter in a sample.
*/
static inline void spll_debug(int what, int value, int last)
{
SPLL->DFR_SPLL = (last ? 0x80000000 : 0) | (value & 0xffffff) | (what << 24);
}
/*
White Rabbit Softcore PLL (SoftPLL) - common definitions
WARNING: These parameters must be in sync with the generics of the HDL instantiation of wr_softpll_ng.
*/
#include <stdio.h>
/* Reference clock frequency, in [Hz] */
#define CLOCK_FREQ 125000000
/* Reference clock period, in picoseconds */
#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
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.
Corresponding VHDL generic: g_tag_bits. */
#define TAG_BITS 22
/* Helper PLL N divider (2**(-N) is the frequency offset). Must be big enough
to offer reasonable PLL bandwidth, and small enough so the offset frequency fits
within the tuning range of the helper oscillator. */
#define HPLL_N 14
/* Fractional bits in PI controller coefficients */
#define PI_FRACBITS 12
/* Max. allowed number of reference channels. Can be used to tweak memory usage. */
#define MAX_CHAN_REF 1
/* Max. allowed number of auxillary channels */
#define MAX_CHAN_AUX 1
/* Max. allowed number of phase trackers */
#define MAX_PTRACKERS 1
/* Number of bits of the DAC(s) driving the oscillator(s). Must be the same for
all the outputs. */
#define DAC_BITS 16
/* Number of samples in a single ptracker averaging bin */
#define PTRACKER_AVERAGE_SAMPLES 512
/* 1.0 / (Speed of the phase shifter) - the higher value, the slower phase shifting.
Used to prevent de-locking PLLs when shifting large offsets. */
#define PHASE_SHIFTER_SPEED 1
#include <timer.h>
/* Number of bits of the BB phase detector error counter. Bit [BB_ERROR_BITS] is the wrap-around bit */
#define BB_ERROR_BITS 16
/* Alignment FSM states */
/* 1st alignment stage, done before starting the ext channel PLL: alignment of the rising edge
of the external clock (10 MHz), with the rising edge of the local reference (62.5/125 MHz)
and the PPS signal. Because of non-integer ratio (6.25 or 12.5), the PLL must know which edges
shall be kept at phase==0. We align to the edge of the 10 MHz clock which comes right after the edge
of the PPS pulse (see drawing below):
PLL reference (62.5 MHz) ____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|
External clock (10 MHz) ^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|___
External PPS ___________|^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
*/
#define REALIGN_STAGE1 1
#define REALIGN_STAGE1_WAIT 2
/* 2nd alignment stage, done after the ext channel PLL has locked. We make sure that the switch's internal PPS signal
is produced exactly on the edge of PLL reference in-phase with 10 MHz clock edge, which has come right after the PPS input
PLL reference (62.5 MHz) ____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|
External clock (10 MHz) ^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|___
External PPS ___________|^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Internal PPS __________________________________|^^^^^^^^^|______________________________________________________________________
^ aligned clock edges and PPS
*/
#define REALIGN_STAGE2 3
#define REALIGN_STAGE2_WAIT 4
/* Error state - PPS signal missing or of bad frequency */
#define REALIGN_PPS_INVALID 5
/* Realignment is disabled (i.e. the switch inputs only the reference frequency, but not time) */
#define REALIGN_DISABLED 6
/* Realignment done */
#define REALIGN_DONE 7
struct spll_external_state {
int ref_src;
int sample_n;
int ph_err_offset, ph_err_cur, ph_err_d0, ph_raw_d0;
int realign_clocks;
int realign_state;
int realign_timer;
spll_pi_t pi;
spll_lowpass_t lp_short, lp_long;
spll_lock_det_t ld;
};
static void external_init(volatile struct spll_external_state *s, int ext_ref, int realign_clocks)
{
s->pi.y_min = 5;
s->pi.y_max = (1 << DAC_BITS) - 5;
s->pi.kp = (int)(300);
s->pi.ki = (int)(1);
s->pi.anti_windup = 1;
s->pi.bias = 32768;
/* Phase branch lock detection */
s->ld.threshold = 250;
s->ld.lock_samples = 10000;
s->ld.delock_samples = 9990;
s->ref_src = ext_ref;
s->ph_err_cur = 0;
s->ph_err_d0 = 0;
s->ph_raw_d0 = 0;
s->realign_clocks = realign_clocks;
s->realign_state = (realign_clocks ? REALIGN_STAGE1 : REALIGN_DISABLED);
pi_init((spll_pi_t *) &s->pi);
ld_init((spll_lock_det_t *) &s->ld);
lowpass_init((spll_lowpass_t *) &s->lp_short, 4000);
lowpass_init((spll_lowpass_t *) &s->lp_long, 300);
}
static inline void realign_fsm( struct spll_external_state *s)
{
uint32_t eccr;
switch(s->realign_state)
{
case REALIGN_STAGE1:
SPLL->ECCR |= SPLL_ECCR_ALIGN_EN;
s->realign_state = REALIGN_STAGE1_WAIT;
s->realign_timer = timer_get_tics();
break;
case REALIGN_STAGE1_WAIT:
if(SPLL->ECCR & SPLL_ECCR_ALIGN_DONE)
s->realign_state = REALIGN_STAGE2;
else if (timer_get_tics() - s->realign_timer > 2*TICS_PER_SECOND)
{
SPLL->ECCR &= ~SPLL_ECCR_ALIGN_EN;
s->realign_state = REALIGN_PPS_INVALID;
}
break;
case REALIGN_STAGE2:
if(s->ld.locked)
{
PPSG->CR = PPSG_CR_CNT_RST | PPSG_CR_CNT_EN;
PPSG->ADJ_UTCLO = 0;
PPSG->ADJ_UTCHI = 0;
PPSG->ADJ_NSEC = 0;
PPSG->ESCR = PPSG_ESCR_SYNC;
s->realign_state = REALIGN_STAGE2_WAIT;
s->realign_timer = timer_get_tics();
}
break;
case REALIGN_STAGE2_WAIT:
if(PPSG->ESCR & PPSG_ESCR_SYNC)
{
PPSG->ESCR = PPSG_ESCR_PPS_VALID | PPSG_ESCR_TM_VALID;
s->realign_state = REALIGN_DONE;
} else if (timer_get_tics() - s->realign_timer > 2*TICS_PER_SECOND)
{
PPSG->ESCR = 0;
s->realign_state = REALIGN_PPS_INVALID;
}
break;
case REALIGN_PPS_INVALID:
case REALIGN_DISABLED:
case REALIGN_DONE:
return ;
}
}
static int external_update( struct spll_external_state *s, int tag, int source)
{
int err, y, y2, yd, ylt;
if(source == s->ref_src)
{
int wrap = tag & (1<<BB_ERROR_BITS) ? 1 : 0;
realign_fsm(s);
tag &= ((1<<BB_ERROR_BITS) - 1);
// mprintf("err %d\n", tag);
if(wrap)
{
if(tag > s->ph_raw_d0)
s->ph_err_offset -= (1<<BB_ERROR_BITS);
else if(tag <= s->ph_raw_d0)
s->ph_err_offset += (1<<BB_ERROR_BITS);
}
s->ph_raw_d0 = tag;
err = (tag + s->ph_err_offset) - s->ph_err_d0;
s->ph_err_d0 = (tag + s->ph_err_offset);
y = pi_update(&s->pi, err);
y2 = lowpass_update(&s->lp_short, y);
ylt = lowpass_update(&s->lp_long, y);
if(! (SPLL->ECCR & SPLL_ECCR_EXT_REF_PRESENT)) /* no reference? de-lock now */
{
ld_init(&s->ld);
y2 = 32000;
}
SPLL->DAC_MAIN = y2 & 0xffff;
spll_debug(DBG_ERR | DBG_EXT, ylt, 0);
spll_debug(DBG_SAMPLE_ID | DBG_EXT, s->sample_n++, 0);
spll_debug(DBG_Y | DBG_EXT, y2, 1);
if(ld_update(&s->ld, y2 - ylt))
return SPLL_LOCKED;
}
return SPLL_LOCKING;
}
static void external_start( struct spll_external_state *s)
{
// mprintf("ExtStartup\n");
SPLL->ECCR = 0;
s->sample_n = 0;
s->realign_state = (s->realign_clocks ? REALIGN_STAGE1 : REALIGN_DISABLED);
SPLL->ECCR = SPLL_ECCR_EXT_EN;
spll_debug(DBG_EVENT | DBG_EXT, DBG_EVT_START, 1);
}
static inline int external_locked( struct spll_external_state *s)
{
return (s->ld.locked && (s->realign_clocks ? s->realign_state == REALIGN_DONE : 1));
}
/* State of the Helper PLL producing a clock (clk_dmtd_i) which is
slightly offset in frequency from the recovered/reference clock (clk_rx_i or clk_ref_i), so the
Main PLL can use it to perform linear phase measurements.
*/
#define SPLL_LOCKED 1
#define SPLL_LOCKING 0
#define HELPER_TAG_WRAPAROUND 100000000
/* Maximum abs value of the phase error. If the error is bigger, it's clamped to this value. */
#define HELPER_ERROR_CLAMP 150000
struct spll_helper_state {
int p_adder; /* anti wrap-around adder */
int p_setpoint, tag_d0;
int ref_src;
int sample_n;
int delock_count;
spll_pi_t pi;
spll_lock_det_t ld;
};
static void helper_init(volatile struct spll_helper_state *s, int ref_channel)
{
/* Phase branch PI controller */
s->pi.y_min = 5;
s->pi.y_max = (1 << DAC_BITS) - 5;
s->pi.kp = (int)(0.3 * 32.0 * 16.0);// / 2;
s->pi.ki = (int)(0.03 * 32.0 * 3.0);// / 2;
s->pi.anti_windup = 1;
/* Phase branch lock detection */
s->ld.threshold = 200;
s->ld.lock_samples = 10000;
s->ld.delock_samples = 100;
s->ref_src = ref_channel;
s->delock_count = 0;
}
static int helper_update(volatile struct spll_helper_state *s, int tag, int source)
{
int err, y;
if(source == s->ref_src)
{
spll_debug(DBG_TAG | DBG_HELPER, tag, 0);
spll_debug(DBG_REF | DBG_HELPER, s->p_setpoint, 0);
if(s->tag_d0 < 0)
{
s->p_setpoint = tag;
s->tag_d0 = tag;
return SPLL_LOCKING;
}
if(s->tag_d0 > tag)
s->p_adder += (1<<TAG_BITS);
err = (tag + s->p_adder) - s->p_setpoint;
if(HELPER_ERROR_CLAMP)
{
if(err < -HELPER_ERROR_CLAMP) err = -HELPER_ERROR_CLAMP;
if(err > HELPER_ERROR_CLAMP) err = HELPER_ERROR_CLAMP;
}
if((tag + s->p_adder) > HELPER_TAG_WRAPAROUND && s->p_setpoint > HELPER_TAG_WRAPAROUND)
{
s->p_adder -= HELPER_TAG_WRAPAROUND;
s->p_setpoint -= HELPER_TAG_WRAPAROUND;
}
s->p_setpoint += (1<<HPLL_N);
s->tag_d0 = tag;
y = pi_update((spll_pi_t *) &s->pi, err);
SPLL->DAC_HPLL = y;
spll_debug(DBG_SAMPLE_ID | DBG_HELPER, s->sample_n++, 0);
spll_debug(DBG_Y | DBG_HELPER, y, 0);
spll_debug(DBG_ERR | DBG_HELPER, err, 1);
if(ld_update((spll_lock_det_t *) &s->ld, err))
return SPLL_LOCKED;
}
return SPLL_LOCKING;
}
static void helper_start(volatile struct spll_helper_state *s)
{
/* Set the bias to the upper end of tuning range. This is to ensure that
the HPLL will always lock on positive frequency offset. */
s->pi.bias = s->pi.y_max;
s->p_setpoint = 0;
s->p_adder = 0;
s->sample_n = 0;
s->tag_d0 = -1;
pi_init((spll_pi_t *) &s->pi);
ld_init((spll_lock_det_t *)&s->ld);
spll_enable_tagger(s->ref_src, 1);
spll_debug(DBG_EVENT | DBG_HELPER, DBG_EVT_START, 1);
}
#define MPLL_TAG_WRAPAROUND 100000000
#define MATCH_NEXT_TAG 0
#define MATCH_WAIT_REF 1
#define MATCH_WAIT_OUT 2
#undef WITH_SEQUENCING
/* State of the Main PLL */
struct spll_main_state {
int state;
spll_pi_t pi;
spll_lock_det_t ld;
int adder_ref, adder_out, tag_ref, tag_out, tag_ref_d, tag_out_d;
// tag sequencing stuff
uint32_t seq_ref, seq_out;
int match_state;
int match_seq;
int phase_shift_target;
int phase_shift_current;
int id_ref, id_out; /* IDs of the reference and the output channel */
int sample_n;
int delock_count;
int dac_index;
};
static void mpll_init(volatile struct spll_main_state *s, int id_ref, int id_out)
{
/* Frequency branch PI controller */
s->pi.y_min = 5;
s->pi.y_max = 65530;
s->pi.anti_windup = 1;
s->pi.bias = 65000;
s->pi.kp = 1100;// / 2;
s->pi.ki = 30;// / 2;
s->delock_count = 0;
/* Freqency branch lock detection */
s->ld.threshold = 1200;
s->ld.lock_samples = 1000;
s->ld.delock_samples = 100;
s->id_ref = id_ref;
s->id_out = id_out;
s->dac_index = id_out - n_chan_ref;
pi_init((spll_pi_t *) &s->pi);
ld_init((spll_lock_det_t *) &s->ld);
}
static void mpll_start(volatile struct spll_main_state *s)
{
s->adder_ref = s->adder_out = 0;
s->tag_ref = -1;
s->tag_out = -1;
s->tag_ref_d = -1;
s->tag_out_d = -1;
s->seq_ref = 0;
s->seq_out = 0;
s->match_state = MATCH_NEXT_TAG;
s->phase_shift_target = 0;
s->phase_shift_current = 0;
s->sample_n= 0;
pi_init((spll_pi_t *) &s->pi);
ld_init((spll_lock_det_t *) &s->ld);
spll_enable_tagger(s->id_ref, 1);
spll_enable_tagger(s->id_out, 1);
spll_debug(DBG_EVENT | DBG_MAIN, DBG_EVT_START, 1);
}
static void mpll_stop(volatile struct spll_main_state *s)
{
spll_enable_tagger(s->id_out, 0);
}
static int mpll_update(volatile struct spll_main_state *s, int tag, int source)
{
int err, y, tmp;
#ifdef WITH_SEQUENCING
int new_ref = -1, new_out = -1;
if(source == s->id_ref)
{
new_ref = tag;
s->seq_ref++;
} else if(source == s->id_out) {
new_out = tag;
s->seq_out++;
}
switch(s->match_state)
{
case MATCH_NEXT_TAG:
if(new_ref > 0 && s->seq_out < s->seq_ref)
{
s->tag_ref = new_ref;
s->match_seq = s->seq_ref;
s->match_state = MATCH_WAIT_OUT;
}
if (new_out > 0 && s->seq_out > s->seq_ref)
{
s->tag_out = new_out;
s->match_seq = s->seq_out;
s->match_state = MATCH_WAIT_REF;
}
break;
case MATCH_WAIT_REF:
if(new_ref > 0 && s->seq_ref == s->match_seq)
{
s->match_state = MATCH_NEXT_TAG;
s->tag_ref = new_ref;
}
break;
case MATCH_WAIT_OUT:
if(new_out > 0 && s->seq_out == s->match_seq)
{
s->match_state = MATCH_NEXT_TAG;
s->tag_out = new_out;
}
break;
}
#else
if(source == s->id_ref)
s->tag_ref = tag;
if(source == s->id_out)
s->tag_out = tag;
#endif
if(s->tag_ref >= 0 && s->tag_out >= 0)
{
if(s->tag_ref_d >= 0 && s->tag_ref_d > s->tag_ref)
s->adder_ref += (1<<TAG_BITS);
if(s->tag_out_d >= 0 && s->tag_out_d > s->tag_out)
s->adder_out += (1<<TAG_BITS);
s->tag_ref_d = s->tag_ref;
s->tag_out_d = s->tag_out;
err = s->adder_ref + s->tag_ref - s->adder_out - s->tag_out;
#ifndef WITH_SEQUENCING
/* Hack: the PLL is locked, so the tags are close to each other. But when we start phase shifting, after reaching
full clock period, one of the reference tags will flip before the other, causing a suddent 2**HPLL_N jump in the error.
So, once the PLL is locked, we just mask out everything above 2**HPLL_N.
Proper solution: tag sequence numbers */
if(s->ld.locked)
{
err &= (1<<HPLL_N)-1;
if(err & (1<<(HPLL_N-1)))
err |= ~((1<<HPLL_N)-1);
}
#endif
y = pi_update((spll_pi_t *) &s->pi, err);
SPLL->DAC_MAIN = SPLL_DAC_MAIN_VALUE_W(y) | SPLL_DAC_MAIN_DAC_SEL_W(s->dac_index);
spll_debug(DBG_MAIN | DBG_REF, s->tag_ref + s->adder_ref, 0);
spll_debug(DBG_MAIN | DBG_TAG, s->tag_out + s->adder_out, 0);
spll_debug(DBG_MAIN | DBG_ERR, err, 0);
spll_debug(DBG_MAIN | DBG_SAMPLE_ID, s->sample_n++, 0);
spll_debug(DBG_MAIN | DBG_Y, y, 1);
s->tag_out = -1;
s->tag_ref = -1;
if(s->adder_ref > 2*MPLL_TAG_WRAPAROUND && s->adder_out > 2*MPLL_TAG_WRAPAROUND)
{
s->adder_ref -= MPLL_TAG_WRAPAROUND;
s->adder_out -= MPLL_TAG_WRAPAROUND;
}
if(s->ld.locked)
{
if(s->phase_shift_current < s->phase_shift_target)
{
s->phase_shift_current++;
s->adder_ref++;
} else if(s->phase_shift_current > s->phase_shift_target) {
s->phase_shift_current--;
s->adder_ref--;
}
}
if(ld_update((spll_lock_det_t *) &s->ld, err))
return SPLL_LOCKED;
}
return SPLL_LOCKING;
}
static int mpll_set_phase_shift(volatile struct spll_main_state *s, int desired_shift)
{
s->phase_shift_target = desired_shift;
}
static int mpll_shifter_busy(volatile struct spll_main_state *s)
{
return s->phase_shift_target != s->phase_shift_current;
}
/* State of a Phase Tracker */
struct spll_ptracker_state {
int id_a, id_b;
int n_avg, acc, avg_count;
int phase_val, ready;
int tag_a, tag_b;
int sample_n;
int preserve_sign;
};
static void ptracker_init(volatile struct spll_ptracker_state *s, int id_a, int id_b, int num_avgs)
{
s->tag_a = s->tag_b = -1;
s->id_a = id_a;
s->id_b = id_b;
s->ready = 0;
s->n_avg = num_avgs;
s->acc = 0;
s->avg_count = 0;
s->sample_n= 0;
s->preserve_sign = 0;
}
static void ptracker_start(volatile struct spll_ptracker_state *s)
{
s->tag_a = s->tag_b = -1;
s->ready = 0;
s->acc = 0;
s->avg_count = 0;
s->sample_n= 0;
s->preserve_sign = 0;
spll_resync_dmtd_counter(s->id_b);
spll_enable_tagger(s->id_a, 1);
spll_enable_tagger(s->id_b, 1);
}
#define PTRACK_WRAP_LO (1<<(HPLL_N-2))
#define PTRACK_WRAP_HI (3*(1<<(HPLL_N-2)))
static int ptracker_update(volatile struct spll_ptracker_state *s, int tag, int source)
{
if(source == s->id_a)
s->tag_a = tag;
if(source == s->id_b)
s->tag_b = tag;
if(s->tag_a >= 0 && s->tag_b >= 0)
{
int delta = (s->tag_a - s->tag_b) & ((1<<HPLL_N) - 1);
s->sample_n++;
if(s->avg_count == 0)
{
if(delta <= PTRACK_WRAP_LO)
s->preserve_sign = -1;
else if (delta >= PTRACK_WRAP_HI)
s->preserve_sign = 1;
else
s->preserve_sign = 0;
s->avg_count++;
s->acc = delta;
} else {
if(delta <= PTRACK_WRAP_LO && s->preserve_sign > 0)
s->acc += delta + (1<<HPLL_N);
else if (delta >= PTRACK_WRAP_HI && s->preserve_sign < 0)
s->acc += delta - (1<<HPLL_N);
else
s->acc += delta;
s->avg_count++;
if(s->avg_count == s->n_avg)
{
s->phase_val = s->acc / s->n_avg;
s->ready = 1;
s->acc = 0;
s->avg_count = 0;
}
}
s->tag_b = s->tag_a = -1;
}
return SPLL_LOCKING;
}
#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} };
volatile struct SYSCON_WB *syscon;
/****************************
* TIMER
***************************/
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;
}
uint32_t timer_get_tics()
{
return syscon->TVR;
}
void timer_delay(uint32_t usecs)
{
uint32_t start, end;
timer_init(1);
start = timer_get_tics();
/* It looks like the counter counts millisecs */
end = start + (usecs + 500) / 1000;
while ((signed)(end - timer_get_tics()) > 0)
;
}
/*
void timer_delay(uint32_t how_long)
{
uint32_t t_start;
// timer_init(1);
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());
}*/
/* return a monotonic seconds count from the counter above; horrible code */
int spec_time(void)
{
static uint32_t prev, secs;
static int rest; /* millisecs */
uint32_t tics = timer_get_tics();
if (!prev) {
prev = tics;
secs = 1; /* Start from a small number! */
return secs;
}
rest += tics - prev;
secs += rest / 1000;
rest %= 1000;
prev = tics;
return secs;
}
/*
* Copyright 2011 Tomasz Wlostowski <tomasz.wlostowski@cern.ch> for CERN
* Modified by Alessandro Rubini for ptp-proposal/proto
*
* GNU LGPL 2.1 or later versions
*/
#include <stdint.h>
#include "../spec.h"
#include <hw/wb_uart.h>
#define CALC_BAUD(baudrate) \
( ((( (unsigned long long)baudrate * 8ULL) << (16 - 7)) + \
(CPU_CLOCK >> 8)) / (CPU_CLOCK >> 7) )
static volatile struct UART_WB *uart;
void spec_uart_init(void)
{
uart = (volatile struct UART_WB *) BASE_UART;
uart->BCR = CALC_BAUD(UART_BAUDRATE);
}
void spec_putc(int c)
{
if(c == '\n')
spec_putc('\r');
while(uart->SR & UART_SR_TX_BUSY)
;
uart->TDR = c;
}
void spec_puts(const char *s)
{
while (*s)
spec_putc(*(s++));
}
int spec_testc(void)
{
return uart->SR & UART_SR_RX_RDY;
}
int spec_uart_poll()
{
return uart->SR & UART_SR_RX_RDY;
}
int spec_getc(void)
{
if(!spec_uart_poll())
return -1;
return uart ->RDR & 0xff;
}
#ifndef __EEPROM_H
#define __EEPROM_H
#define SFP_SECTION_PATTERN 0xdeadbeef
#define SFPS_MAX 4
#define SFP_PN_LEN 16
#define EE_BASE_CAL 4*1024
#define EE_BASE_SFP 4*1024+4
#define EE_BASE_INIT 4*1024+SFPS_MAX*29
#define EE_RET_I2CERR -1
#define EE_RET_DBFULL -2
#define EE_RET_CORRPT -3
#define EE_RET_POSERR -4
extern int32_t sfp_alpha;
extern int32_t sfp_deltaTx;
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__));
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, uint32_t size);
int eeprom_write(uint8_t i2cif, uint8_t i2c_addr, uint32_t offset, uint8_t *buf, uint32_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, uint32_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_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);
#endif
#ifndef __ENDPOINT_H
#define __ENDPOINT_H
#define DMTD_AVG_SAMPLES 256
#define DMTD_MAX_PHASE 16384
#include <stdint.h>
typedef enum {
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_cal_pattern_enable();
int ep_cal_pattern_disable();
void pfilter_new();
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);
void pfilter_load();
void pfilter_init_default();
uint16_t pcs_read(int location);
void pcs_write(int location, int value);
#endif
This diff is collapsed.
This diff is collapsed.
#ifndef __REGS_H
#define __REGS_H
#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;
#define FMC_EEPROM_ADR 0x50
void sdb_find_devices(void);
void sdb_print_devices(void);
#endif
/*
Register definitions for slave core: Mini NIC for WhiteRabbit
* File : minic_regs.h
* Author : auto-generated by wbgen2 from mini_nic.wb
* Created : Tue May 29 15:57:15 2012
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE mini_nic.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_MINI_NIC_WB
#define __WBGEN2_REGDEFS_MINI_NIC_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: miNIC Control Register */
/* definitions for field: TX DMA start in reg: miNIC Control Register */
#define MINIC_MCR_TX_START WBGEN2_GEN_MASK(0, 1)
/* definitions for field: TX DMA idle in reg: miNIC Control Register */
#define MINIC_MCR_TX_IDLE WBGEN2_GEN_MASK(1, 1)
/* definitions for field: TX DMA error in reg: miNIC Control Register */
#define MINIC_MCR_TX_ERROR WBGEN2_GEN_MASK(2, 1)
/* definitions for field: RX DMA ready in reg: miNIC Control Register */
#define MINIC_MCR_RX_READY WBGEN2_GEN_MASK(8, 1)
/* definitions for field: RX DMA buffer full in reg: miNIC Control Register */
#define MINIC_MCR_RX_FULL WBGEN2_GEN_MASK(9, 1)
/* definitions for field: RX DMA enable in reg: miNIC Control Register */
#define MINIC_MCR_RX_EN WBGEN2_GEN_MASK(10, 1)
/* definitions for field: RX Accepted Packet Classes in reg: miNIC Control Register */
#define MINIC_MCR_RX_CLASS_MASK WBGEN2_GEN_MASK(16, 8)
#define MINIC_MCR_RX_CLASS_SHIFT 16
#define MINIC_MCR_RX_CLASS_W(value) WBGEN2_GEN_WRITE(value, 16, 8)
#define MINIC_MCR_RX_CLASS_R(reg) WBGEN2_GEN_READ(reg, 16, 8)
/* definitions for register: TX DMA Address */
/* definitions for register: RX DMA Address */
/* definitions for register: RX buffer size register */
/* definitions for register: RX buffer available words register */
/* definitions for register: TX timestamp register 0 */
/* definitions for field: Timestamp valid in reg: TX timestamp register 0 */
#define MINIC_TSR0_VALID WBGEN2_GEN_MASK(0, 1)
/* definitions for field: Port ID in reg: TX timestamp register 0 */
#define MINIC_TSR0_PID_MASK WBGEN2_GEN_MASK(1, 5)
#define MINIC_TSR0_PID_SHIFT 1
#define MINIC_TSR0_PID_W(value) WBGEN2_GEN_WRITE(value, 1, 5)
#define MINIC_TSR0_PID_R(reg) WBGEN2_GEN_READ(reg, 1, 5)
/* definitions for field: Frame ID in reg: TX timestamp register 0 */
#define MINIC_TSR0_FID_MASK WBGEN2_GEN_MASK(6, 16)
#define MINIC_TSR0_FID_SHIFT 6
#define MINIC_TSR0_FID_W(value) WBGEN2_GEN_WRITE(value, 6, 16)
#define MINIC_TSR0_FID_R(reg) WBGEN2_GEN_READ(reg, 6, 16)
/* definitions for register: TX timestamp register 1 */
/* definitions for field: Timestamp value in reg: TX timestamp register 1 */
#define MINIC_TSR1_TSVAL_MASK WBGEN2_GEN_MASK(0, 32)
#define MINIC_TSR1_TSVAL_SHIFT 0
#define MINIC_TSR1_TSVAL_W(value) WBGEN2_GEN_WRITE(value, 0, 32)
#define MINIC_TSR1_TSVAL_R(reg) WBGEN2_GEN_READ(reg, 0, 32)
/* definitions for register: Debug register */
/* definitions for field: interrupt counter in reg: Debug register */
#define MINIC_DBGR_IRQ_CNT_MASK WBGEN2_GEN_MASK(0, 24)
#define MINIC_DBGR_IRQ_CNT_SHIFT 0
#define MINIC_DBGR_IRQ_CNT_W(value) WBGEN2_GEN_WRITE(value, 0, 24)
#define MINIC_DBGR_IRQ_CNT_R(reg) WBGEN2_GEN_READ(reg, 0, 24)
/* definitions for field: status of wb_irq_o line in reg: Debug register */
#define MINIC_DBGR_WB_IRQ_VAL WBGEN2_GEN_MASK(24, 1)
/* definitions for register: Memory protection reg */
/* definitions for field: address range lo in reg: Memory protection reg */
#define MINIC_MPROT_LO_MASK WBGEN2_GEN_MASK(0, 16)
#define MINIC_MPROT_LO_SHIFT 0
#define MINIC_MPROT_LO_W(value) WBGEN2_GEN_WRITE(value, 0, 16)
#define MINIC_MPROT_LO_R(reg) WBGEN2_GEN_READ(reg, 0, 16)
/* definitions for field: address range hi in reg: Memory protection reg */
#define MINIC_MPROT_HI_MASK WBGEN2_GEN_MASK(16, 16)
#define MINIC_MPROT_HI_SHIFT 16
#define MINIC_MPROT_HI_W(value) WBGEN2_GEN_WRITE(value, 16, 16)
#define MINIC_MPROT_HI_R(reg) WBGEN2_GEN_READ(reg, 16, 16)
/* definitions for register: Interrupt disable register */
/* definitions for field: TX DMA interrupt in reg: Interrupt disable register */
#define MINIC_EIC_IDR_TX WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX DMA interrupt in reg: Interrupt disable register */
#define MINIC_EIC_IDR_RX WBGEN2_GEN_MASK(1, 1)
/* definitions for field: TX timestamp available in reg: Interrupt disable register */
#define MINIC_EIC_IDR_TXTS WBGEN2_GEN_MASK(2, 1)
/* definitions for register: Interrupt enable register */
/* definitions for field: TX DMA interrupt in reg: Interrupt enable register */
#define MINIC_EIC_IER_TX WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX DMA interrupt in reg: Interrupt enable register */
#define MINIC_EIC_IER_RX WBGEN2_GEN_MASK(1, 1)
/* definitions for field: TX timestamp available in reg: Interrupt enable register */
#define MINIC_EIC_IER_TXTS WBGEN2_GEN_MASK(2, 1)
/* definitions for register: Interrupt mask register */
/* definitions for field: TX DMA interrupt in reg: Interrupt mask register */
#define MINIC_EIC_IMR_TX WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX DMA interrupt in reg: Interrupt mask register */
#define MINIC_EIC_IMR_RX WBGEN2_GEN_MASK(1, 1)
/* definitions for field: TX timestamp available in reg: Interrupt mask register */
#define MINIC_EIC_IMR_TXTS WBGEN2_GEN_MASK(2, 1)
/* definitions for register: Interrupt status register */
/* definitions for field: TX DMA interrupt in reg: Interrupt status register */
#define MINIC_EIC_ISR_TX WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX DMA interrupt in reg: Interrupt status register */
#define MINIC_EIC_ISR_RX WBGEN2_GEN_MASK(1, 1)
/* definitions for field: TX timestamp available in reg: Interrupt status register */
#define MINIC_EIC_ISR_TXTS WBGEN2_GEN_MASK(2, 1)
/* [0x0]: REG miNIC Control Register */
#define MINIC_REG_MCR 0x00000000
/* [0x4]: REG TX DMA Address */
#define MINIC_REG_TX_ADDR 0x00000004
/* [0x8]: REG RX DMA Address */
#define MINIC_REG_RX_ADDR 0x00000008
/* [0xc]: REG RX buffer size register */
#define MINIC_REG_RX_SIZE 0x0000000c
/* [0x10]: REG RX buffer available words register */
#define MINIC_REG_RX_AVAIL 0x00000010
/* [0x14]: REG TX timestamp register 0 */
#define MINIC_REG_TSR0 0x00000014
/* [0x18]: REG TX timestamp register 1 */
#define MINIC_REG_TSR1 0x00000018
/* [0x1c]: REG Debug register */
#define MINIC_REG_DBGR 0x0000001c
/* [0x20]: REG Memory protection reg */
#define MINIC_REG_MPROT 0x00000020
/* [0x40]: REG Interrupt disable register */
#define MINIC_REG_EIC_IDR 0x00000040
/* [0x44]: REG Interrupt enable register */
#define MINIC_REG_EIC_IER 0x00000044
/* [0x48]: REG Interrupt mask register */
#define MINIC_REG_EIC_IMR 0x00000048
/* [0x4c]: REG Interrupt status register */
#define MINIC_REG_EIC_ISR 0x0000004c
#endif
/*
Register definitions for slave core: WR Switch PPS generator and RTC
* File : pps_gen_regs.h
* Author : auto-generated by wbgen2 from wrsw_pps_gen.wb
* Created : Thu Oct 27 21:29:19 2011
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE wrsw_pps_gen.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_WRSW_PPS_GEN_WB
#define __WBGEN2_REGDEFS_WRSW_PPS_GEN_WB
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Control Register */
/* definitions for field: Reset counter in reg: Control Register */
#define PPSG_CR_CNT_RST WBGEN2_GEN_MASK(0, 1)
/* definitions for field: Enable counter in reg: Control Register */
#define PPSG_CR_CNT_EN WBGEN2_GEN_MASK(1, 1)
/* definitions for field: Adjust offset in reg: Control Register */
#define PPSG_CR_CNT_ADJ WBGEN2_GEN_MASK(2, 1)
/* definitions for field: Set time in reg: Control Register */
#define PPSG_CR_CNT_SET WBGEN2_GEN_MASK(3, 1)
/* definitions for field: PPS Pulse width in reg: Control Register */
#define PPSG_CR_PWIDTH_MASK WBGEN2_GEN_MASK(4, 28)
#define PPSG_CR_PWIDTH_SHIFT 4
#define PPSG_CR_PWIDTH_W(value) WBGEN2_GEN_WRITE(value, 4, 28)
#define PPSG_CR_PWIDTH_R(reg) WBGEN2_GEN_READ(reg, 4, 28)
/* definitions for register: Nanosecond counter register */
/* definitions for register: UTC Counter register (least-significant part) */
/* definitions for register: UTC Counter register (most-significant part) */
/* definitions for register: Nanosecond adjustment register */
/* definitions for register: UTC Adjustment register (least-significant part) */
/* definitions for register: UTC Adjustment register (most-significant part) */
/* definitions for register: External sync control register */
/* definitions for field: Sync to external PPS input in reg: External sync control register */
#define PPSG_ESCR_SYNC WBGEN2_GEN_MASK(0, 1)
/* definitions for field: PPS output valid in reg: External sync control register */
#define PPSG_ESCR_PPS_VALID WBGEN2_GEN_MASK(1, 1)
/* definitions for field: Timecode output(UTC+cycles) valid in reg: External sync control register */
#define PPSG_ESCR_TM_VALID WBGEN2_GEN_MASK(2, 1)
PACKED struct PPSG_WB {
/* [0x0]: REG Control Register */
uint32_t CR;
/* [0x4]: REG Nanosecond counter register */
uint32_t CNTR_NSEC;
/* [0x8]: REG UTC Counter register (least-significant part) */
uint32_t CNTR_UTCLO;
/* [0xc]: REG UTC Counter register (most-significant part) */
uint32_t CNTR_UTCHI;
/* [0x10]: REG Nanosecond adjustment register */
uint32_t ADJ_NSEC;
/* [0x14]: REG UTC Adjustment register (least-significant part) */
uint32_t ADJ_UTCLO;
/* [0x18]: REG UTC Adjustment register (most-significant part) */
uint32_t ADJ_UTCHI;
/* [0x1c]: REG External sync control register */
uint32_t ESCR;
};
#endif
This diff is collapsed.
/*
Register definitions for slave core: Simple Wishbone UART
* File : ../../../../software/include/hw/wb_uart.h
* Author : auto-generated by wbgen2 from uart.wb
* Created : Mon Feb 21 22:25:02 2011
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE uart.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_UART_WB
#define __WBGEN2_REGDEFS_UART_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#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 */
#define UART_SR_TX_BUSY WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX ready in reg: Status Register */
#define UART_SR_RX_RDY WBGEN2_GEN_MASK(1, 1)
/* definitions for register: Baudrate control register */
/* definitions for register: Transmit data regsiter */
/* definitions for field: Transmit data in reg: Transmit data regsiter */
#define UART_TDR_TX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_TDR_TX_DATA_SHIFT 0
#define UART_TDR_TX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_TDR_TX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: Receive data regsiter */
/* definitions for field: Received data in reg: Receive data regsiter */
#define UART_RDR_RX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_RDR_RX_DATA_SHIFT 0
#define UART_RDR_RX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_RDR_RX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* [0x0]: REG Status Register */
#define UART_REG_SR 0x00000000
/* [0x4]: REG Baudrate control register */
#define UART_REG_BCR 0x00000004
/* [0x8]: REG Transmit data regsiter */
#define UART_REG_TDR 0x00000008
/* [0xc]: REG Receive data regsiter */
#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;
};
#endif
/*
Register definitions for slave core: Virtual UART
* File : wb_vuart.h
* Author : auto-generated by wbgen2 from wb_virtual_uart.wb
* Created : Wed Apr 6 23:02:01 2011
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE wb_virtual_uart.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_WB_VIRTUAL_UART_WB
#define __WBGEN2_REGDEFS_WB_VIRTUAL_UART_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#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 */
#define UART_SR_TX_BUSY WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX ready in reg: Status Register */
#define UART_SR_RX_RDY WBGEN2_GEN_MASK(1, 1)
/* definitions for register: Baudrate control register */
/* definitions for register: Transmit data regsiter */
/* definitions for field: Transmit data in reg: Transmit data regsiter */
#define UART_TDR_TX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_TDR_TX_DATA_SHIFT 0
#define UART_TDR_TX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_TDR_TX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: Receive data regsiter */
/* definitions for field: Received data in reg: Receive data regsiter */
#define UART_RDR_RX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_RDR_RX_DATA_SHIFT 0
#define UART_RDR_RX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_RDR_RX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: FIFO 'UART TX FIFO' data output register 0 */
/* definitions for field: Char sent by UART to TX in reg: FIFO 'UART TX FIFO' data output register 0 */
#define UART_DEBUG_R0_TX_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_DEBUG_R0_TX_SHIFT 0
#define UART_DEBUG_R0_TX_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_DEBUG_R0_TX_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: FIFO 'UART TX FIFO' control/status register */
/* definitions for field: FIFO full flag in reg: FIFO 'UART TX FIFO' control/status register */
#define UART_DEBUG_CSR_FULL WBGEN2_GEN_MASK(16, 1)
/* definitions for field: FIFO empty flag in reg: FIFO 'UART TX FIFO' control/status register */
#define UART_DEBUG_CSR_EMPTY WBGEN2_GEN_MASK(17, 1)
/* definitions for field: FIFO counter in reg: FIFO 'UART TX FIFO' control/status register */
#define UART_DEBUG_CSR_USEDW_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_DEBUG_CSR_USEDW_SHIFT 0
#define UART_DEBUG_CSR_USEDW_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#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;
};
#endif
This diff is collapsed.
#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);
void mi2c_repeat_start(uint8_t i2cif);
void mi2c_stop(uint8_t i2cif);
void mi2c_get_byte(uint8_t i2cif, unsigned char *data, uint8_t last);
unsigned char mi2c_put_byte(uint8_t i2cif, unsigned char data);
void mi2c_delay();
//void mi2c_scan(uint8_t i2cif);
#endif
/* wb-gen file we use insist in using <inttypes.h>: work around them by now */
#include <stdint.h>
#ifndef __IRQ_H
#define __IRQ_H
static inline void clear_irq()
{
unsigned int val = 1;
asm volatile ("wcsr ip, %0"::"r"(val));
}
void disable_irq();
void enable_irq();
#endif
#ifndef __MINIC_H
#define __MINIC_H
#include "inttypes.h"
#define ETH_HEADER_SIZE 14
#define WRPC_FID 0
#define ETH_ALEN 6
#define ETH_P_1588 0x88F7 /* IEEE 1588 Timesync */
void minic_init();
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);
#endif
#ifndef PERSISTENT_MAC_H
#define PERSISTENT_MAC_H
#define ONEWIRE_PORT 0
#define EEPROM_MAC_PAGE 0
#define MAX_DEV1WIRE 8
#define FOUND_DS18B20 0x01
void own_scanbus(uint8_t portnum);
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);
#endif
This diff is collapsed.
/* SFP Detection / management functions */
#ifndef __SFP_H
#define __SFP_H
#include <stdint.h>
/* Returns 1 if there's a SFP transceiver inserted in the socket. */
int sfp_present();
/* Reads the part ID of the SFP from its configuration EEPROM */
int sfp_read_part_id(char *part_id);
#endif
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -8,7 +8,7 @@
*/
#include <ppsi/ppsi.h>
#include <ppsi/diag.h>
#include <timer.h>
#include <syscon.h>
#include "spec.h"
void spec_main_loop(struct pp_instance *ppi)
......
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