Commit b22ba144 authored by Peter Jansweijer's avatar Peter Jansweijer

clbv2, clbv4 use low phase drift phy via mdio

parent 4545a83c
Pipeline #5094 failed with stage
in 5 minutes and 20 seconds
......@@ -68,6 +68,21 @@ config TARGET_SIS8300KU
help
Struck SIS8300KU MTCA.4 Card (Kintex Ultrascale)
config TARGET_CLB_V2
bool "CLB_V2"
help
KM3NeT Central Logic Board (Version 2 based on Kintex-7)
config TARGET_CLB_V3
bool "CLB_V3"
help
KM3NeT Central Logic Board (Version 3 based on Artix-7)
config TARGET_CLB_V4
bool "CLB_V4"
help
KM3NeT Central Logic Board (Version 4 based on Kintex-7)
config TARGET_PXIE_FMC
bool "ZU7 PXIe FMC Carrier"
help
......
......@@ -18,6 +18,9 @@ obj-$(CONFIG_TARGET_ERTM14) += \
boards/ertm14/wrpc-uart-link.o \
boards/ertm14/sdbfs-custom-image.o
obj-$(CONFIG_TARGET_CLB_V2) += boards/clbv2/board.o boards/clbv2/phy_calibration.o
obj-$(CONFIG_TARGET_CLB_V3) += boards/clbv3/board.o
obj-$(CONFIG_TARGET_CLB_V4) += boards/clbv4/board.o boards/clbv4/phy_calibration.o
obj-$(CONFIG_TARGET_PXIE_FMC) += boards/pxie-fmc/board.o
obj-$(CONFIG_TARGET_WR2RF_VME) += boards/wr2rf-vme/board.o boards/wr2rf-vme/sdbfs-custom-image.o boards/ertm14/phy_calibration.o
......
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2022 Nikhef (www.Nikhef.nl)
* Author: Peter Jansweijer <peterj@nikhef.nl> based on work
* from Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "board.h"
#include "wrc.h"
#include "wrc-debug.h"
#include "dev/bb_spi.h"
#include "dev/bb_i2c.h"
#include "dev/w1.h"
#include "dev/spi_flash.h"
#include "dev/i2c_eeprom.h"
#include "dev/syscon.h"
#include "dev/endpoint.h"
#include "storage.h"
struct i2c_bus i2c_wrc_eeprom;
struct i2c_eeprom_device wrc_eeprom_dev;
int wrc_board_early_init()
{
int memtype;
uint32_t sdbfs_entry;
uint32_t sector_size;
if (EEPROM_STORAGE) {
/* EEPROM support */
bb_i2c_create( &i2c_wrc_eeprom,
&pin_sysc_fmc_scl,
&pin_sysc_fmc_sda );
bb_i2c_init( &i2c_wrc_eeprom );
i2c_eeprom_create( &wrc_eeprom_dev, &i2c_wrc_eeprom, FMC_EEPROM_ADR, 2);
storage_i2ceeprom_create( &wrc_storage_dev, &wrc_eeprom_dev );
} else {
/* Flash support */
/*
* declare GPIO pins and configure their directions for bit-banging SPI
* limit SPI speed to 10MHz by setting bit_delay = CPU_CLOCK / 10^6
*/
bb_spi_create( &spi_wrc_flash,
&pin_sysc_spi_ncs,
&pin_sysc_spi_mosi,
&pin_sysc_spi_miso,
&pin_sysc_spi_sclk, CPU_CLOCK / 10000000 );
spi_wrc_flash.rd_falling_edge = 1;
/*
* Read from gateware info about used memory. Currently only base
* address and sector size for memtype flash is supported.
*/
get_storage_info(&memtype, &sdbfs_entry, &sector_size);
/*
* Initialize SPI flash and read its ID
*/
spi_flash_create( &wrc_flash_dev, &spi_wrc_flash, sector_size, sdbfs_entry);
/*
* Initialize storage subsystem with newly created SPI Flash
*/
storage_spiflash_create( &wrc_storage_dev, &wrc_flash_dev );
}
/*
* Mount SDBFS filesystem from storage.
*/
storage_mount( &wrc_storage_dev );
return 0;
}
static int board_get_persistent_mac(uint8_t *mac)
{
int i;
struct w1_dev *d;
/* Try from SDB */
if (storage_get_persistent_mac(0, mac) == 0)
return 0;
/* Get from one-wire (derived from unique id) */
w1_scan_bus(&wrpc_w1_bus);
for (i = 0; i < W1_MAX_DEVICES; i++) {
d = wrpc_w1_bus.devs + i;
if (d->rom) {
mac[0] = 0x22;
mac[1] = 0x33;
mac[2] = 0xff & (d->rom >> 32);
mac[3] = 0xff & (d->rom >> 24);
mac[4] = 0xff & (d->rom >> 16);
mac[5] = 0xff & (d->rom >> 8);
return 0;
}
}
/* Not found */
return -1;
}
int wrc_board_init()
{
uint8_t mac_addr[6];
/*
* Try reading MAC addr stored in flash
*/
if (board_get_persistent_mac(mac_addr) < 0) {
board_dbg("Failed to get MAC address from the flash. Using fallback address.\n");
mac_addr[0] = 0x22;
mac_addr[1] = 0x33;
mac_addr[2] = 0x44;
mac_addr[3] = 0x55;
mac_addr[4] = 0x66;
mac_addr[5] = 0x77;
}
ep_set_mac_addr(&wrc_endpoint_dev, mac_addr);
ep_pfilter_init_default(&wrc_endpoint_dev);
return 0;
}
int wrc_board_create_tasks()
{
wrc_task_create( "phy-cal", phy_calibration_init, phy_calibration_poll );
return 0;
}
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#include <netconsole.h>
#ifndef __BOARD_WRC_H
#define __BOARD_WRC_H
/*
* This is meant to be automatically included by the Makefile,
* when wrpc-sw is build for wrc (node) -- as opposed to wrs (switch)
*/
/* Board-specific parameters */
#define TICS_PER_SECOND 1000
/* WR Core system/CPU clock frequency in Hz */
#define CPU_CLOCK 62500000ULL
/* WR Reference clock period (picoseconds) and frequency (Hz) */
/* CLB_V2 has GENERIC_PHY_16BIT */
#define NS_PER_CLOCK 16
#define REF_CLOCK_PERIOD_PS 16000
#define REF_CLOCK_FREQ_HZ 62500000
/* Maximum number of simultaneously created sockets */
#define NET_MAX_SOCKETS 12
/* Socket buffer size, determines the max. RX packet size */
#define NET_MAX_SKBUF_SIZE 512
/* Number of auxillary clock channels - usually equal to the number of FMCs */
#define NUM_AUX_CLOCKS 1
/* spll parameter that are board-specific */
/* CLB_V2 has GENERIC_PHY_16BIT */
#define BOARD_DIVIDE_DMTD_CLOCKS 0
/* Number of reference channels (RX clocks) */
#define BOARD_MAX_CHAN_REF 1
/* Number of external pll that can be disciplined */
#define BOARD_MAX_CHAN_AUX 2
/* Should be the same as reference channels */
#define BOARD_MAX_PTRACKERS 1
/* Events are not used on this platform */
#define BOARD_USE_EVENTS 0
/* Use one uart at 115200 baud. May add extra uart. */
#define BOARD_CONSOLE_DEVICES 1
#define CONSOLE_UART_BAUDRATE 115200
/* Maximum number of files in the sdb filesystem.
Need at least 4: ., sfp database, init script and calibration
MAC address could also be written on sdbfs. */
#define SDBFS_REC 5
/* Specific to this board (see board.c) */
/* I2C address of the storage eeprom */
#define FMC_EEPROM_ADR 0x50
#define EEPROM_STORAGE 1
void sdb_find_devices(void);
void sdb_print_devices(void);
extern int phy_calibration_poll(void);
extern void phy_calibration_init(void);
extern void phy_calibration_disable(void);
extern int phy_calibration_done(void);
#endif /* __BOARD_WRC_H */
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2023 Nikhef (www.Nikhef.nl)
* Author: Peter Jansweijer <peterj@nikhef.nl> based on work
* from Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
PHY Calibration code.
Specific for Kintex-7 devices using wr_gtx_phy_family7_lp
(based on CPLL)
*/
#include <string.h>
#include <board.h>
#include "dev/syscon.h"
#include "dev/endpoint.h"
#include <softpll_ng.h>
#include "storage.h"
#include "util.h"
#include "wrc-debug.h"
#include "wrc-task.h"
#include <hw/ep_mdio_regs.h>
#include <hw/lpdc_mdio_regs.h>
/* TX Target phase is measured at tx_out_clk of the PHY.
Clk_ref_62m5 and tx_out_clk are phase locked but have an offset.
Add a safe offset such that the TxData and TxK (clk_ref_62m5 domain)
are safely clocked into the PHY (tx_out_clk domain).
set tx_out_clk 4 ns before clk_ref_62m5 so there is 12 ns setup time.
*/
#define LPDC_COARSE_PHASE_MIN_PS 11750 /* ps */
#define LPDC_COARSE_PHASE_MAX_PS 12250 /* ps */
#define LPDC_FINE_PHASE_TOLLERANCE_PS 20 /* ps */
#define LPDC_MAX_ATTEMPS_TX_SETUP_STATE_RESET_PCS 2000
#define LPDC_MAX_ATTEMPS_RX_SETUP_STATE_RESET_PCS 100
// number of raw DDMTD phase samples used to measure the RX/TX clock phases
#define LPDC_NUM_PTRACKER_SAMPLES 10
#define LPDC_TARGET_COMMA_POS 0
#define LPDC_MDIO_CTRL_DMTD_SOURCE_TXOUTCLK (1 << LPDC_MDIO_CTRL_DMTD_CLK_SEL_SHIFT)
#define LPDC_MDIO_CTRL_DMTD_SOURCE_RXRECCLK (0 << LPDC_MDIO_CTRL_DMTD_CLK_SEL_SHIFT)
#define TX_SETUP_STATE_START 0
#define TX_SETUP_STATE_RESET_PCS 1
#define TX_SETUP_STATE_WAIT_TX_PLL_LOCK 2
#define TX_SETUP_STATE_MEASURE_PHASE 3
#define TX_SETUP_DONE 4
#define TX_SETUP_VALIDATE 5
#define TX_SETUP_STATE_DISABLED 6
#define TX_SETUP_STATE_WAIT_SPLL_LOCK 7
#define TX_SETUP_STATE_WAIT_TX_CLK_STABILIZE 8
#define RX_SETUP_STATE_INIT 0
#define RX_SETUP_STATE_RESET_PCS 1
#define RX_SETUP_STATE_WAIT_LOCK 2
#define RX_SETUP_STATE_MEASURE_PHASE 3
#define RX_SETUP_DONE 4
#define RX_SETUP_VALIDATE 5
#define RX_SETUP_STATE_DISABLED 6
#define FSM_DEBUG_REFRESH_PERIOD_MS 1000
#define FSM_PHY_LOCK_TIMEOUT_MS 1000
#define FSM_SPLL_LOCK_TIMEOUT_MS 10000
#define FSM_DMTD_TIMEOUT_MS 100
#define FSM_EARLY_LINK_UP_TIMEOUT_MS 100
#define FSM_STABILIZE_TIMEOUT_MS 100
struct wrc_port_tx_setup_state
{
int state;
int cnt;
int attempts;
int cal_saved_phase;
int cal_saved_phase_valid;
int cal_file_updated;
int measured_phase;
int expected_phase;
int tollerance;
int update_cnt;
int expected_phase_valid;
timeout_t phy_lock_timeout;
timeout_t spll_lock_timeout;
timeout_t dmtd_timeout;
};
struct wrc_port_rx_setup_state
{
int cpos_stat[20];
int state;
int attempts;
int prev_link_up;
timeout_t link_timeout;
timeout_t stabilize_timeout;
};
struct wrc_lpdc_state
{
struct wrc_port_tx_setup_state tx_state;
struct wrc_port_rx_setup_state rx_state;
struct wr_endpoint_device *endpoint;
};
static inline void mdio_lpdc_write(struct wrc_lpdc_state *lpdc, int location, uint16_t value)
{
ep_pcs_write(lpdc->endpoint, location + EP_MDIO_PHY_SPECIFIC_REGS, value);
}
static inline uint16_t mdio_lpdc_read(struct wrc_lpdc_state *lpdc, int location)
{
return ep_pcs_read(lpdc->endpoint, location + EP_MDIO_PHY_SPECIFIC_REGS);
}
static void mdio_lpdc_set_bits( struct wrc_lpdc_state *lpdc, uint16_t reg, uint16_t mask )
{
uint16_t rdbk = mdio_lpdc_read( lpdc, reg );
rdbk |= mask;
mdio_lpdc_write( lpdc, reg, rdbk );
}
static void mdio_lpdc_clear_bits( struct wrc_lpdc_state *lpdc, uint16_t reg, uint16_t mask )
{
uint16_t rdbk = mdio_lpdc_read( lpdc, reg );
rdbk &= ~mask;
mdio_lpdc_write( lpdc, reg, rdbk );
}
static void tx_fsm_init(struct wrc_port_tx_setup_state *fsm)
{
fsm->attempts = 0;
fsm->state = TX_SETUP_STATE_START;
fsm->expected_phase = 0;
fsm->expected_phase_valid = 0;
fsm->tollerance = 300;
fsm->update_cnt = 0;
fsm->cal_saved_phase_valid = 0;
fsm->cal_saved_phase = 0;
fsm->cal_file_updated = 0;
fsm->cnt = 0;
/* FIXME: is cal_saved_phase unsigned? uint32_t? declare it so
* at the wrc_port_tx_setup_state structure */
if( !storage_get_calibration_parameter( CAL_PARAM_PHY_TARGET_TX_PHASE, (uint32_t *)&fsm->cal_saved_phase )
&& fsm->cal_saved_phase != -1)
{
phy_dbg("[lpdc] TX target phase from calibration data: %d ps\n", fsm->cal_saved_phase);
fsm->cal_saved_phase_valid = 1;
}
}
static int tx_fsm_update(struct wrc_lpdc_state *lpdc)
{
struct wrc_port_tx_setup_state *fsm = &lpdc->tx_state;
switch (fsm->state)
{
case TX_SETUP_STATE_START:
{
spll_init( SPLL_MODE_FREE_RUNNING_MASTER, 0, 0 );
spll_set_ptracker_average_samples( 0, LPDC_NUM_PTRACKER_SAMPLES );
tmo_init(&fsm->spll_lock_timeout, FSM_SPLL_LOCK_TIMEOUT_MS);
ep_sfp_enable( lpdc->endpoint, 0 );
fsm->state = TX_SETUP_STATE_WAIT_SPLL_LOCK;
break;
}
case TX_SETUP_STATE_WAIT_SPLL_LOCK:
{
if( tmo_expired( &fsm->spll_lock_timeout ) )
{
phy_dbg("[lpdc] can't lock the SoftPLL. This is necessary for PHY calibration to continue. Retrying...\n");
tmo_restart( &fsm->spll_lock_timeout );
fsm->state = TX_SETUP_STATE_START;
break;
}
if( spll_check_lock( 0 ) )
{
spll_enable_ptracker(0, 0);
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_SW_RESET | LPDC_MDIO_CTRL_DMTD_SOURCE_TXOUTCLK );
fsm->state = TX_SETUP_STATE_RESET_PCS;
phy_dbg("[lpdc] SPLL locked\n");
}
break;
}
case TX_SETUP_STATE_RESET_PCS:
{
//phy_dbg("[lpdc] TX reset PCS\n");
spll_enable_ptracker(0, 0);
// reset the CPLL, TX reset and gtx_comma_detect_lp reset (= AUX_RESET)
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_TX_SW_RESET | LPDC_MDIO_CTRL_PLL_SW_RESET | LPDC_MDIO_CTRL_AUX_RESET);
usleep(2);
// Un-reset CPLL
mdio_lpdc_clear_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_PLL_SW_RESET );
//phy_dbg("CPLL: wait for lock\n");
while ( !(mdio_lpdc_read(lpdc, LPDC_MDIO_STAT) & LPDC_MDIO_STAT_PLL_LOCKED ))
usleep(1);
//phy_dbg("CPLL OK\n");
// CPLL ok: un-reset TX path
mdio_lpdc_clear_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_TX_SW_RESET );
// Before transitioning to TX_SETUP_STATE_WAIT_TX_PLL_LOCK
// GTXE2 tx_reset_done is already signalled (few us)
// before clocks are stable... Give it some time.
usleep(100);
fsm->state = TX_SETUP_STATE_WAIT_TX_PLL_LOCK;
tmo_init( &fsm->phy_lock_timeout, FSM_PHY_LOCK_TIMEOUT_MS );
break;
}
case TX_SETUP_STATE_WAIT_TX_PLL_LOCK:
{
uint32_t stat = mdio_lpdc_read(lpdc, LPDC_MDIO_STAT);
if (stat & LPDC_MDIO_STAT_TX_RST_DONE)
{
fsm->attempts++;
fsm->state = TX_SETUP_STATE_WAIT_TX_CLK_STABILIZE;
tmo_init(&fsm->phy_lock_timeout, 10 );
}
else if( tmo_expired(&fsm->phy_lock_timeout) )
{
fsm->state = TX_SETUP_STATE_RESET_PCS;
phy_dbg("PHY PLL lock timeout, retrying...[LPDC_STAT=0x%04x]\n", stat );
}
break;
}
case TX_SETUP_STATE_WAIT_TX_CLK_STABILIZE:
{
if( !tmo_expired( &fsm->phy_lock_timeout ) )
return 0;
spll_set_ptracker_average_samples( 0, LPDC_NUM_PTRACKER_SAMPLES );
spll_enable_ptracker(0, 1);
tmo_init( &fsm->dmtd_timeout, FSM_DMTD_TIMEOUT_MS );
fsm->state = TX_SETUP_STATE_MEASURE_PHASE;
break;
}
case TX_SETUP_STATE_MEASURE_PHASE:
{
int32_t phase;
int enabled; //, p2;
int rv = spll_read_ptracker(0, &phase, &enabled);
if (!rv)
{
if( tmo_expired( &fsm->dmtd_timeout ) )
{
phy_dbg("[lpdc] TX Phase measurement timeout, retrying...\n");
fsm->state = TX_SETUP_STATE_RESET_PCS;
}
return 0;
}
if (!fsm->expected_phase_valid)
{
if ( fsm->cal_saved_phase_valid )
{
if ( within_range( fsm->cal_saved_phase, LPDC_COARSE_PHASE_MIN_PS, LPDC_COARSE_PHASE_MAX_PS, 16000 ) )
{
fsm->expected_phase = fsm->cal_saved_phase;
fsm->tollerance = LPDC_FINE_PHASE_TOLLERANCE_PS;
phy_dbg("[lpdc] Using the previous phase setpoint = %d ps as the target with tollerance = %d ps\n",
fsm->cal_saved_phase,
fsm->tollerance);
} else {
fsm->expected_phase = (LPDC_COARSE_PHASE_MAX_PS + LPDC_COARSE_PHASE_MIN_PS) / 2;
fsm->tollerance = (LPDC_COARSE_PHASE_MAX_PS - LPDC_COARSE_PHASE_MIN_PS) / 2;
fsm->cal_saved_phase_valid = 0;
phy_dbg("[lpdc] Previous phase setpoint (%d ps) out of range. Old calibration algorithm? Restarting from scratch.\n", fsm->cal_saved_phase);
}
}
else // find a sane default
{
fsm->expected_phase = (LPDC_COARSE_PHASE_MAX_PS + LPDC_COARSE_PHASE_MIN_PS) / 2;
fsm->tollerance = (LPDC_COARSE_PHASE_MAX_PS - LPDC_COARSE_PHASE_MIN_PS) / 2;
phy_dbg("[lpdc] No LPDC TX Calibration data found. Restarting from scratch.\n" );
}
fsm->expected_phase_valid = 1;
}
int phase_min = fsm->expected_phase - fsm->tollerance;
int phase_max = fsm->expected_phase + fsm->tollerance;
phy_dbg("[lpdc] TX phase = %d ps\n", phase);
if (within_range(phase, phase_min, phase_max, 16000))
{
fsm->measured_phase = phase;
//phy_dbg("[lpdc] Fix phase = %d ps\n", fsm->measured_phase );
fsm->state = TX_SETUP_VALIDATE;
}
else
{
if (fsm->attempts >= LPDC_MAX_ATTEMPS_TX_SETUP_STATE_RESET_PCS)
{
phy_dbg("[lpdc] No proper TX phase found at %d ps after %d attempts. Clear stored PHY_TARGET_TX_PHASE.\n", fsm->cal_saved_phase, fsm->attempts);
phy_dbg("[lpdc] Old calibration due to new gateware?\n");
storage_remove_calibration_parameter(CAL_PARAM_PHY_TARGET_TX_PHASE);
storage_save_calibration();
fsm->attempts = 0;
fsm->cal_saved_phase_valid = 0;
fsm->expected_phase_valid = 0;
}
else
fsm->state = TX_SETUP_STATE_RESET_PCS;
}
break;
}
case TX_SETUP_VALIDATE:
{
phy_dbg("[lpdc] TX calibration complete (phase %d ps, after %d attempts)\n", fsm->measured_phase, fsm->attempts);
spll_enable_ptracker(0, 0);
// enable the PCS+SFP on the port
mdio_lpdc_write( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_TX_ENABLE | LPDC_MDIO_CTRL_DMTD_SOURCE_RXRECCLK );
ep_sfp_enable( lpdc->endpoint, 1 );
if( !fsm->cal_saved_phase_valid )
{
phy_dbg("[lpdc] Saving established target phase as calibration parameter: %d ps\n", fsm->measured_phase);
storage_set_calibration_parameter_and_save( CAL_PARAM_PHY_TARGET_TX_PHASE, fsm->measured_phase);
}
fsm->state = TX_SETUP_DONE;
break;
}
case TX_SETUP_DONE:
{
return 1;
break;
}
}
return 0;
}
static void rx_fsm_init(struct wrc_port_rx_setup_state* fsm)
{
fsm->attempts = 0;
fsm->state = RX_SETUP_STATE_INIT;
fsm->prev_link_up = 0;
memset(fsm->cpos_stat, 0, sizeof(fsm->cpos_stat ));
}
static int rx_fsm_update(struct wrc_lpdc_state *lpdc)
{
struct wrc_port_rx_setup_state* fsm = &lpdc->rx_state;
struct wrc_port_tx_setup_state* fsm_tx = &lpdc->tx_state;
uint16_t lpc_stat = mdio_lpdc_read(lpdc, LPDC_MDIO_STAT);
int early_link_up = lpc_stat & LPDC_MDIO_STAT_LINK_UP;
if( fsm_tx->state != TX_SETUP_DONE )
{
fsm->state = RX_SETUP_STATE_INIT;
return 0;
}
switch( fsm->state )
{
case RX_SETUP_STATE_INIT:
{
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_TARGET_COMMA_POS );
if (early_link_up) {
if ( fsm_tx->state == TX_SETUP_DONE )
{
phy_dbg("[lpdc] RX calibration started.\n");
fsm->state = RX_SETUP_STATE_RESET_PCS;
}
}
fsm->attempts = 0;
break;
}
case RX_SETUP_STATE_RESET_PCS:
{
if (early_link_up)
{
fsm->state = RX_SETUP_STATE_WAIT_LOCK;
// Reset RX path and gtx_comma_detect_lp reset (= AUX_RESET)
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_SW_RESET | LPDC_MDIO_CTRL_AUX_RESET );
usleep(1);
// Un-Reset RX path and gtx_comma_detect_lp reset (= AUX_RESET)
mdio_lpdc_clear_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_SW_RESET | LPDC_MDIO_CTRL_AUX_RESET );
usleep(10000);
fsm->attempts++;
tmo_init(&fsm->link_timeout, FSM_EARLY_LINK_UP_TIMEOUT_MS);
}
break;
}
case RX_SETUP_STATE_WAIT_LOCK:
{
int rx_aligned = lpc_stat & LPDC_MDIO_STAT_LINK_ALIGNED;
if ( tmo_expired(&fsm->link_timeout) && !early_link_up) {
fsm->state = RX_SETUP_STATE_INIT;
}
else
{
if ( !early_link_up )
return 0;
if( rx_aligned )
{
fsm->state = RX_SETUP_VALIDATE;
tmo_init( &fsm->stabilize_timeout, FSM_STABILIZE_TIMEOUT_MS );
} else {
// In rare occasions the comma can't be found at the proper tap, even after
// multiple PCS resets. In such a case a full GTHE4 reset is needed.
if (fsm-> attempts % LPDC_MAX_ATTEMPS_RX_SETUP_STATE_RESET_PCS == 0) {
phy_dbg("[lpdc] No RX calibration yet... Restarting TX calibration from scratch.\n");
tx_fsm_init(&lpdc->tx_state);
} else {
fsm->state = RX_SETUP_STATE_RESET_PCS;
}
}
}
break;
}
case RX_SETUP_VALIDATE:
{
if( !tmo_expired( &fsm->stabilize_timeout ))
return 0;
int rx_aligned = lpc_stat & LPDC_MDIO_STAT_LINK_ALIGNED;
int rx_comma_pos = (lpc_stat & LPDC_MDIO_STAT_COMMA_CURRENT_POS_MASK) > LPDC_MDIO_STAT_COMMA_CURRENT_POS_SHIFT;
int rx_comma_valid = lpc_stat & LPDC_MDIO_STAT_COMMA_POS_VALID;
if ( early_link_up && rx_aligned && rx_comma_valid && (rx_comma_pos == LPDC_TARGET_COMMA_POS) )
{
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_ENABLE );
ep_pcs_write(lpdc->endpoint, EP_MDIO_MCR, EP_MDIO_MCR_SPEED1000 | EP_MDIO_MCR_FULLDPLX | EP_MDIO_MCR_ANENABLE | EP_MDIO_MCR_ANRESTART);
phy_dbg("[lpdc] RX calibration complete (after %d attempts) comma @ %d taps.\n", fsm->attempts, rx_comma_pos );
spll_enable_ptracker( 0, 0 );
spll_set_ptracker_average_samples( 0, PTRACKER_AVERAGE_SAMPLES );
fsm->state = RX_SETUP_DONE;
} else {
phy_dbg("[lpdc] Stabilize link...\n");
fsm->state = RX_SETUP_STATE_RESET_PCS;
}
break;
}
case RX_SETUP_DONE:
{
int link_up = ep_link_up(&wrc_endpoint_dev, NULL);
if( !early_link_up /*|| ( ( fsm->prev_link_up && !link_up ) )*/ )
{
phy_dbg("port went down, need RX recalibration.\n");
fsm->state = RX_SETUP_STATE_INIT;
fsm->prev_link_up = link_up;
return 0;
}
fsm->prev_link_up = link_up;
return 1;
break;
}
default:
break;
}
return 0;
}
static struct wrc_lpdc_state lpdc;
int phy_calibration_poll(void)
{
tx_fsm_update(&lpdc);
rx_fsm_update(&lpdc);
return 1;
}
int phy_calibration_done(void)
{
return (lpdc.rx_state.state == RX_SETUP_DONE);
}
void phy_calibration_init(void)
{
// fixme: do we want more than one in the WRC? maybe soon...
lpdc.endpoint = &wrc_endpoint_dev;
phy_dbg("[lpdc] Initializing PHY calibrator...\n");
ep_pcs_write(lpdc.endpoint, EP_MDIO_MCR, EP_MDIO_MCR_PDOWN); /* reset the PHY */
timer_delay_ms(200);
ep_pcs_write(lpdc.endpoint, EP_MDIO_MCR, EP_MDIO_MCR_RESET); /* reset the PHY */
ep_pcs_write(lpdc.endpoint, EP_MDIO_MCR, 0); /* reset the PHY */
mdio_lpdc_write( &lpdc, LPDC_MDIO_CTRL, 0 );
mdio_lpdc_write( &lpdc, LPDC_MDIO_CTRL2, 0 );
tx_fsm_init(&lpdc.tx_state);
rx_fsm_init(&lpdc.rx_state);
}
void phy_calibration_disable(void)
{
lpdc.tx_state.state = TX_SETUP_STATE_DISABLED;
lpdc.rx_state.state = RX_SETUP_STATE_DISABLED;
}
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2022 Nikhef (www.Nikhef.nl)
* Author: Peter Jansweijer <peterj@nikhef.nl> based on work
* from Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "board.h"
#include "wrc.h"
#include "wrc-debug.h"
#include "dev/bb_spi.h"
#include "dev/bb_i2c.h"
#include "dev/w1.h"
#include "dev/spi_flash.h"
#include "dev/i2c_eeprom.h"
#include "dev/syscon.h"
#include "dev/endpoint.h"
#include "storage.h"
#include "softpll_ng.h"
static spll_gain_schedule_t spll_main_ocxo_gain_sched;
static void clbv3_spll_setup(void)
{
/* configure a suitable PI gain schedule for the SoftPLL: */
spll_gain_schedule_t* gs= &spll_main_ocxo_gain_sched;
/* CLB_V4 uses CRYSTEC_CVPD992 VCXO */
gs->stages[0].kp = -5500;
gs->stages[0].ki = -30;
gs->stages[0].lock_samples = 10000;
gs->stages[0].shift = 12;
gs->n_stages = 1; // 1 stage: CRYSTEC_CVPD992
board_dbg("Oscillator gain schedule: 1st stage CRYSTEC_CVPD992 setup\n");
spll_set_gain_schedule( gs );
}
struct i2c_bus i2c_wrc_eeprom;
struct i2c_eeprom_device wrc_eeprom_dev;
int wrc_board_early_init()
{
int memtype;
uint32_t sdbfs_entry;
uint32_t sector_size;
if (EEPROM_STORAGE) {
/* EEPROM support */
bb_i2c_create( &i2c_wrc_eeprom,
&pin_sysc_fmc_scl,
&pin_sysc_fmc_sda );
bb_i2c_init( &i2c_wrc_eeprom );
i2c_eeprom_create( &wrc_eeprom_dev, &i2c_wrc_eeprom, FMC_EEPROM_ADR, 2);
storage_i2ceeprom_create( &wrc_storage_dev, &wrc_eeprom_dev );
} else {
/* Flash support */
/*
* declare GPIO pins and configure their directions for bit-banging SPI
* limit SPI speed to 10MHz by setting bit_delay = CPU_CLOCK / 10^6
*/
bb_spi_create( &spi_wrc_flash,
&pin_sysc_spi_ncs,
&pin_sysc_spi_mosi,
&pin_sysc_spi_miso,
&pin_sysc_spi_sclk, CPU_CLOCK / 10000000 );
spi_wrc_flash.rd_falling_edge = 1;
/*
* Read from gateware info about used memory. Currently only base
* address and sector size for memtype flash is supported.
*/
get_storage_info(&memtype, &sdbfs_entry, &sector_size);
/*
* Initialize SPI flash and read its ID
*/
spi_flash_create( &wrc_flash_dev, &spi_wrc_flash, sector_size, sdbfs_entry);
/*
* Initialize storage subsystem with newly created SPI Flash
*/
storage_spiflash_create( &wrc_storage_dev, &wrc_flash_dev );
}
/*
* Mount SDBFS filesystem from storage.
*/
storage_mount( &wrc_storage_dev );
/* Setup the SoftPLL for the OCXO we have */
clbv3_spll_setup();
return 0;
}
static int board_get_persistent_mac(uint8_t *mac)
{
int i;
struct w1_dev *d;
/* Try from SDB */
if (storage_get_persistent_mac(0, mac) == 0)
return 0;
/* Get from one-wire (derived from unique id) */
w1_scan_bus(&wrpc_w1_bus);
for (i = 0; i < W1_MAX_DEVICES; i++) {
d = wrpc_w1_bus.devs + i;
if (d->rom) {
mac[0] = 0x22;
mac[1] = 0x33;
mac[2] = 0xff & (d->rom >> 32);
mac[3] = 0xff & (d->rom >> 24);
mac[4] = 0xff & (d->rom >> 16);
mac[5] = 0xff & (d->rom >> 8);
return 0;
}
}
/* Not found */
return -1;
}
int wrc_board_init()
{
uint8_t mac_addr[6];
/*
* Try reading MAC addr stored in flash
*/
if (board_get_persistent_mac(mac_addr) < 0) {
board_dbg("Failed to get MAC address from the flash. Using fallback address.\n");
mac_addr[0] = 0x22;
mac_addr[1] = 0x33;
mac_addr[2] = 0x44;
mac_addr[3] = 0x55;
mac_addr[4] = 0x66;
mac_addr[5] = 0x77;
}
ep_set_mac_addr(&wrc_endpoint_dev, mac_addr);
ep_pfilter_init_default(&wrc_endpoint_dev);
return 0;
}
int wrc_board_create_tasks()
{
return 0;
}
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#include <netconsole.h>
#ifndef __BOARD_WRC_H
#define __BOARD_WRC_H
/*
* This is meant to be automatically included by the Makefile,
* when wrpc-sw is build for wrc (node) -- as opposed to wrs (switch)
*/
/* Board-specific parameters */
#define TICS_PER_SECOND 1000
/* WR Core system/CPU clock frequency in Hz */
#define CPU_CLOCK 62500000ULL
/* WR Reference clock period (picoseconds) and frequency (Hz) */
/* CLB_V3 has GENERIC_PHY_16BIT */
#define NS_PER_CLOCK 16
#define REF_CLOCK_PERIOD_PS 16000
#define REF_CLOCK_FREQ_HZ 62500000
/* Maximum number of simultaneously created sockets */
#define NET_MAX_SOCKETS 12
/* Socket buffer size, determines the max. RX packet size */
#define NET_MAX_SKBUF_SIZE 512
/* Number of auxillary clock channels - usually equal to the number of FMCs */
#define NUM_AUX_CLOCKS 1
/* spll parameter that are board-specific */
/* CLB_V3 has GENERIC_PHY_16BIT */
#define BOARD_DIVIDE_DMTD_CLOCKS 0
/* Number of reference channels (RX clocks) */
#define BOARD_MAX_CHAN_REF 1
/* Number of external pll that can be disciplined */
#define BOARD_MAX_CHAN_AUX 2
/* Should be the same as reference channels */
#define BOARD_MAX_PTRACKERS 1
/* Events are not used on this platform */
#define BOARD_USE_EVENTS 0
/* Use one uart at 115200 baud. May add extra uart. */
#define BOARD_CONSOLE_DEVICES 1
#define CONSOLE_UART_BAUDRATE 115200
/* Maximum number of files in the sdb filesystem.
Need at least 4: ., sfp database, init script and calibration
MAC address could also be written on sdbfs. */
#define SDBFS_REC 5
/* Specific to this board (see board.c) */
/* I2C address of the storage eeprom */
#define FMC_EEPROM_ADR 0x50
#define EEPROM_STORAGE 1
void sdb_find_devices(void);
void sdb_print_devices(void);
#endif /* __BOARD_WRC_H */
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2022 Nikhef (www.Nikhef.nl)
* Author: Peter Jansweijer <peterj@nikhef.nl> based on work
* from Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "board.h"
#include "wrc.h"
#include "wrc-debug.h"
#include "dev/bb_spi.h"
#include "dev/bb_i2c.h"
#include "dev/w1.h"
#include "dev/spi_flash.h"
#include "dev/i2c_eeprom.h"
#include "dev/syscon.h"
#include "dev/endpoint.h"
#include "storage.h"
#include "softpll_ng.h"
static spll_gain_schedule_t spll_main_ocxo_gain_sched;
static void clbv4_spll_setup(void)
{
/* configure a suitable PI gain schedule for the SoftPLL: */
spll_gain_schedule_t* gs= &spll_main_ocxo_gain_sched;
/* CLB_V4 uses CRYSTEC_CVPD992 VCXO */
gs->stages[0].kp = -5500;
gs->stages[0].ki = -30;
gs->stages[0].lock_samples = 10000;
gs->stages[0].shift = 12;
gs->n_stages = 1; // 1 stage: CRYSTEC_CVPD992
board_dbg("Oscillator gain schedule: 1st stage CRYSTEC_CVPD992 setup\n");
spll_set_gain_schedule( gs );
}
struct i2c_bus i2c_wrc_eeprom;
struct i2c_eeprom_device wrc_eeprom_dev;
int wrc_board_early_init()
{
int memtype;
uint32_t sdbfs_entry;
uint32_t sector_size;
if (EEPROM_STORAGE) {
/* EEPROM support */
bb_i2c_create( &i2c_wrc_eeprom,
&pin_sysc_fmc_scl,
&pin_sysc_fmc_sda );
bb_i2c_init( &i2c_wrc_eeprom );
i2c_eeprom_create( &wrc_eeprom_dev, &i2c_wrc_eeprom, FMC_EEPROM_ADR, 2);
storage_i2ceeprom_create( &wrc_storage_dev, &wrc_eeprom_dev );
} else {
/* Flash support */
/*
* declare GPIO pins and configure their directions for bit-banging SPI
* limit SPI speed to 10MHz by setting bit_delay = CPU_CLOCK / 10^6
*/
bb_spi_create( &spi_wrc_flash,
&pin_sysc_spi_ncs,
&pin_sysc_spi_mosi,
&pin_sysc_spi_miso,
&pin_sysc_spi_sclk, CPU_CLOCK / 10000000 );
spi_wrc_flash.rd_falling_edge = 1;
/*
* Read from gateware info about used memory. Currently only base
* address and sector size for memtype flash is supported.
*/
get_storage_info(&memtype, &sdbfs_entry, &sector_size);
/*
* Initialize SPI flash and read its ID
*/
spi_flash_create( &wrc_flash_dev, &spi_wrc_flash, sector_size, sdbfs_entry);
/*
* Initialize storage subsystem with newly created SPI Flash
*/
storage_spiflash_create( &wrc_storage_dev, &wrc_flash_dev );
}
/*
* Mount SDBFS filesystem from storage.
*/
storage_mount( &wrc_storage_dev );
/* Setup the SoftPLL for the OCXO we have */
clbv4_spll_setup();
return 0;
}
static int board_get_persistent_mac(uint8_t *mac)
{
int i;
struct w1_dev *d;
/* Try from SDB */
if (storage_get_persistent_mac(0, mac) == 0)
return 0;
/* Get from one-wire (derived from unique id) */
w1_scan_bus(&wrpc_w1_bus);
for (i = 0; i < W1_MAX_DEVICES; i++) {
d = wrpc_w1_bus.devs + i;
if (d->rom) {
mac[0] = 0x22;
mac[1] = 0x33;
mac[2] = 0xff & (d->rom >> 32);
mac[3] = 0xff & (d->rom >> 24);
mac[4] = 0xff & (d->rom >> 16);
mac[5] = 0xff & (d->rom >> 8);
return 0;
}
}
/* Not found */
return -1;
}
int wrc_board_init()
{
uint8_t mac_addr[6];
/*
* Try reading MAC addr stored in flash
*/
if (board_get_persistent_mac(mac_addr) < 0) {
board_dbg("Failed to get MAC address from the flash. Using fallback address.\n");
mac_addr[0] = 0x22;
mac_addr[1] = 0x33;
mac_addr[2] = 0x44;
mac_addr[3] = 0x55;
mac_addr[4] = 0x66;
mac_addr[5] = 0x77;
}
ep_set_mac_addr(&wrc_endpoint_dev, mac_addr);
ep_pfilter_init_default(&wrc_endpoint_dev);
return 0;
}
int wrc_board_create_tasks()
{
wrc_task_create( "phy-cal", phy_calibration_init, phy_calibration_poll );
return 0;
}
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#include <netconsole.h>
#ifndef __BOARD_WRC_H
#define __BOARD_WRC_H
/*
* This is meant to be automatically included by the Makefile,
* when wrpc-sw is build for wrc (node) -- as opposed to wrs (switch)
*/
/* Board-specific parameters */
#define TICS_PER_SECOND 1000
/* WR Core system/CPU clock frequency in Hz */
#define CPU_CLOCK 62500000ULL
/* WR Reference clock period (picoseconds) and frequency (Hz) */
/* CLB_V4 has GENERIC_PHY_16BIT */
#define NS_PER_CLOCK 16
#define REF_CLOCK_PERIOD_PS 16000
#define REF_CLOCK_FREQ_HZ 62500000
/* Maximum number of simultaneously created sockets */
#define NET_MAX_SOCKETS 12
/* Socket buffer size, determines the max. RX packet size */
#define NET_MAX_SKBUF_SIZE 512
/* Number of auxillary clock channels - usually equal to the number of FMCs */
#define NUM_AUX_CLOCKS 1
/* spll parameter that are board-specific */
/* CLB_V4 has GENERIC_PHY_16BIT */
#define BOARD_DIVIDE_DMTD_CLOCKS 0
/* Number of reference channels (RX clocks) */
#define BOARD_MAX_CHAN_REF 1
/* Number of external pll that can be disciplined */
#define BOARD_MAX_CHAN_AUX 2
/* Should be the same as reference channels */
#define BOARD_MAX_PTRACKERS 1
/* Events are not used on this platform */
#define BOARD_USE_EVENTS 0
/* Use one uart at 115200 baud. May add extra uart. */
#define BOARD_CONSOLE_DEVICES 1
#define CONSOLE_UART_BAUDRATE 115200
/* Maximum number of files in the sdb filesystem.
Need at least 4: ., sfp database, init script and calibration
MAC address could also be written on sdbfs. */
#define SDBFS_REC 5
/* Specific to this board (see board.c) */
/* I2C address of the storage eeprom */
#define FMC_EEPROM_ADR 0x50
#define EEPROM_STORAGE 1
void sdb_find_devices(void);
void sdb_print_devices(void);
extern int phy_calibration_poll(void);
extern void phy_calibration_init(void);
extern void phy_calibration_disable(void);
extern int phy_calibration_done(void);
#endif /* __BOARD_WRC_H */
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2023 Nikhef (www.Nikhef.nl)
* Author: Peter Jansweijer <peterj@nikhef.nl> based on work
* from Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
PHY Calibration code.
Specific for Kintex-7 devices using wr_gtx_phy_family7_lp
(based on CPLL)
*/
#include <string.h>
#include <board.h>
#include "dev/syscon.h"
#include "dev/endpoint.h"
#include <softpll_ng.h>
#include "storage.h"
#include "util.h"
#include "wrc-debug.h"
#include "wrc-task.h"
#include <hw/ep_mdio_regs.h>
#include <hw/lpdc_mdio_regs.h>
/* TX Target phase is measured at tx_out_clk of the PHY.
Clk_ref_62m5 and tx_out_clk are phase locked but have an offset.
Add a safe offset such that the TxData and TxK (clk_ref_62m5 domain)
are safely clocked into the PHY (tx_out_clk domain).
set tx_out_clk 4 ns before clk_ref_62m5 so there is 12 ns setup time.
*/
#define LPDC_COARSE_PHASE_MIN_PS 11750 /* ps */
#define LPDC_COARSE_PHASE_MAX_PS 12250 /* ps */
#define LPDC_FINE_PHASE_TOLLERANCE_PS 20 /* ps */
#define LPDC_MAX_ATTEMPS_TX_SETUP_STATE_RESET_PCS 2000
#define LPDC_MAX_ATTEMPS_RX_SETUP_STATE_RESET_PCS 100
// number of raw DDMTD phase samples used to measure the RX/TX clock phases
#define LPDC_NUM_PTRACKER_SAMPLES 10
#define LPDC_TARGET_COMMA_POS 0
#define LPDC_MDIO_CTRL_DMTD_SOURCE_TXOUTCLK (1 << LPDC_MDIO_CTRL_DMTD_CLK_SEL_SHIFT)
#define LPDC_MDIO_CTRL_DMTD_SOURCE_RXRECCLK (0 << LPDC_MDIO_CTRL_DMTD_CLK_SEL_SHIFT)
#define TX_SETUP_STATE_START 0
#define TX_SETUP_STATE_RESET_PCS 1
#define TX_SETUP_STATE_WAIT_TX_PLL_LOCK 2
#define TX_SETUP_STATE_MEASURE_PHASE 3
#define TX_SETUP_DONE 4
#define TX_SETUP_VALIDATE 5
#define TX_SETUP_STATE_DISABLED 6
#define TX_SETUP_STATE_WAIT_SPLL_LOCK 7
#define TX_SETUP_STATE_WAIT_TX_CLK_STABILIZE 8
#define RX_SETUP_STATE_INIT 0
#define RX_SETUP_STATE_RESET_PCS 1
#define RX_SETUP_STATE_WAIT_LOCK 2
#define RX_SETUP_STATE_MEASURE_PHASE 3
#define RX_SETUP_DONE 4
#define RX_SETUP_VALIDATE 5
#define RX_SETUP_STATE_DISABLED 6
#define FSM_DEBUG_REFRESH_PERIOD_MS 1000
#define FSM_PHY_LOCK_TIMEOUT_MS 1000
#define FSM_SPLL_LOCK_TIMEOUT_MS 10000
#define FSM_DMTD_TIMEOUT_MS 100
#define FSM_EARLY_LINK_UP_TIMEOUT_MS 100
#define FSM_STABILIZE_TIMEOUT_MS 100
struct wrc_port_tx_setup_state
{
int state;
int cnt;
int attempts;
int cal_saved_phase;
int cal_saved_phase_valid;
int cal_file_updated;
int measured_phase;
int expected_phase;
int tollerance;
int update_cnt;
int expected_phase_valid;
timeout_t phy_lock_timeout;
timeout_t spll_lock_timeout;
timeout_t dmtd_timeout;
};
struct wrc_port_rx_setup_state
{
int cpos_stat[20];
int state;
int attempts;
int prev_link_up;
timeout_t link_timeout;
timeout_t stabilize_timeout;
};
struct wrc_lpdc_state
{
struct wrc_port_tx_setup_state tx_state;
struct wrc_port_rx_setup_state rx_state;
struct wr_endpoint_device *endpoint;
};
static inline void mdio_lpdc_write(struct wrc_lpdc_state *lpdc, int location, uint16_t value)
{
ep_pcs_write(lpdc->endpoint, location + EP_MDIO_PHY_SPECIFIC_REGS, value);
}
static inline uint16_t mdio_lpdc_read(struct wrc_lpdc_state *lpdc, int location)
{
return ep_pcs_read(lpdc->endpoint, location + EP_MDIO_PHY_SPECIFIC_REGS);
}
static void mdio_lpdc_set_bits( struct wrc_lpdc_state *lpdc, uint16_t reg, uint16_t mask )
{
uint16_t rdbk = mdio_lpdc_read( lpdc, reg );
rdbk |= mask;
mdio_lpdc_write( lpdc, reg, rdbk );
}
static void mdio_lpdc_clear_bits( struct wrc_lpdc_state *lpdc, uint16_t reg, uint16_t mask )
{
uint16_t rdbk = mdio_lpdc_read( lpdc, reg );
rdbk &= ~mask;
mdio_lpdc_write( lpdc, reg, rdbk );
}
static void tx_fsm_init(struct wrc_port_tx_setup_state *fsm)
{
fsm->attempts = 0;
fsm->state = TX_SETUP_STATE_START;
fsm->expected_phase = 0;
fsm->expected_phase_valid = 0;
fsm->tollerance = 300;
fsm->update_cnt = 0;
fsm->cal_saved_phase_valid = 0;
fsm->cal_saved_phase = 0;
fsm->cal_file_updated = 0;
fsm->cnt = 0;
/* FIXME: is cal_saved_phase unsigned? uint32_t? declare it so
* at the wrc_port_tx_setup_state structure */
if( !storage_get_calibration_parameter( CAL_PARAM_PHY_TARGET_TX_PHASE, (uint32_t *)&fsm->cal_saved_phase )
&& fsm->cal_saved_phase != -1)
{
phy_dbg("[lpdc] TX target phase from calibration data: %d ps\n", fsm->cal_saved_phase);
fsm->cal_saved_phase_valid = 1;
}
}
static int tx_fsm_update(struct wrc_lpdc_state *lpdc)
{
struct wrc_port_tx_setup_state *fsm = &lpdc->tx_state;
switch (fsm->state)
{
case TX_SETUP_STATE_START:
{
spll_init( SPLL_MODE_FREE_RUNNING_MASTER, 0, 0 );
spll_set_ptracker_average_samples( 0, LPDC_NUM_PTRACKER_SAMPLES );
tmo_init(&fsm->spll_lock_timeout, FSM_SPLL_LOCK_TIMEOUT_MS);
ep_sfp_enable( lpdc->endpoint, 0 );
fsm->state = TX_SETUP_STATE_WAIT_SPLL_LOCK;
break;
}
case TX_SETUP_STATE_WAIT_SPLL_LOCK:
{
if( tmo_expired( &fsm->spll_lock_timeout ) )
{
phy_dbg("[lpdc] can't lock the SoftPLL. This is necessary for PHY calibration to continue. Retrying...\n");
tmo_restart( &fsm->spll_lock_timeout );
fsm->state = TX_SETUP_STATE_START;
break;
}
if( spll_check_lock( 0 ) )
{
spll_enable_ptracker(0, 0);
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_SW_RESET | LPDC_MDIO_CTRL_DMTD_SOURCE_TXOUTCLK );
fsm->state = TX_SETUP_STATE_RESET_PCS;
phy_dbg("[lpdc] SPLL locked\n");
}
break;
}
case TX_SETUP_STATE_RESET_PCS:
{
//phy_dbg("[lpdc] TX reset PCS\n");
spll_enable_ptracker(0, 0);
// reset the CPLL, TX reset and gtx_comma_detect_lp reset (= AUX_RESET)
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_TX_SW_RESET | LPDC_MDIO_CTRL_PLL_SW_RESET | LPDC_MDIO_CTRL_AUX_RESET);
usleep(2);
// Un-reset CPLL
mdio_lpdc_clear_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_PLL_SW_RESET );
//phy_dbg("CPLL: wait for lock\n");
while ( !(mdio_lpdc_read(lpdc, LPDC_MDIO_STAT) & LPDC_MDIO_STAT_PLL_LOCKED ))
usleep(1);
//phy_dbg("CPLL OK\n");
// CPLL ok: un-reset TX path
mdio_lpdc_clear_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_TX_SW_RESET );
// Before transitioning to TX_SETUP_STATE_WAIT_TX_PLL_LOCK
// GTXE2 tx_reset_done is already signalled (few us)
// before clocks are stable... Give it some time.
usleep(100);
fsm->state = TX_SETUP_STATE_WAIT_TX_PLL_LOCK;
tmo_init( &fsm->phy_lock_timeout, FSM_PHY_LOCK_TIMEOUT_MS );
break;
}
case TX_SETUP_STATE_WAIT_TX_PLL_LOCK:
{
uint32_t stat = mdio_lpdc_read(lpdc, LPDC_MDIO_STAT);
if (stat & LPDC_MDIO_STAT_TX_RST_DONE)
{
fsm->attempts++;
fsm->state = TX_SETUP_STATE_WAIT_TX_CLK_STABILIZE;
tmo_init(&fsm->phy_lock_timeout, 10 );
}
else if( tmo_expired(&fsm->phy_lock_timeout) )
{
fsm->state = TX_SETUP_STATE_RESET_PCS;
phy_dbg("PHY PLL lock timeout, retrying...[LPDC_STAT=0x%04x]\n", stat );
}
break;
}
case TX_SETUP_STATE_WAIT_TX_CLK_STABILIZE:
{
if( !tmo_expired( &fsm->phy_lock_timeout ) )
return 0;
spll_set_ptracker_average_samples( 0, LPDC_NUM_PTRACKER_SAMPLES );
spll_enable_ptracker(0, 1);
tmo_init( &fsm->dmtd_timeout, FSM_DMTD_TIMEOUT_MS );
fsm->state = TX_SETUP_STATE_MEASURE_PHASE;
break;
}
case TX_SETUP_STATE_MEASURE_PHASE:
{
int32_t phase;
int enabled; //, p2;
int rv = spll_read_ptracker(0, &phase, &enabled);
if (!rv)
{
if( tmo_expired( &fsm->dmtd_timeout ) )
{
phy_dbg("[lpdc] TX Phase measurement timeout, retrying...\n");
fsm->state = TX_SETUP_STATE_RESET_PCS;
}
return 0;
}
if (!fsm->expected_phase_valid)
{
if ( fsm->cal_saved_phase_valid )
{
if ( within_range( fsm->cal_saved_phase, LPDC_COARSE_PHASE_MIN_PS, LPDC_COARSE_PHASE_MAX_PS, 16000 ) )
{
fsm->expected_phase = fsm->cal_saved_phase;
fsm->tollerance = LPDC_FINE_PHASE_TOLLERANCE_PS;
phy_dbg("[lpdc] Using the previous phase setpoint = %d ps as the target with tollerance = %d ps\n",
fsm->cal_saved_phase,
fsm->tollerance);
} else {
fsm->expected_phase = (LPDC_COARSE_PHASE_MAX_PS + LPDC_COARSE_PHASE_MIN_PS) / 2;
fsm->tollerance = (LPDC_COARSE_PHASE_MAX_PS - LPDC_COARSE_PHASE_MIN_PS) / 2;
fsm->cal_saved_phase_valid = 0;
phy_dbg("[lpdc] Previous phase setpoint (%d ps) out of range. Old calibration algorithm? Restarting from scratch.\n", fsm->cal_saved_phase);
}
}
else // find a sane default
{
fsm->expected_phase = (LPDC_COARSE_PHASE_MAX_PS + LPDC_COARSE_PHASE_MIN_PS) / 2;
fsm->tollerance = (LPDC_COARSE_PHASE_MAX_PS - LPDC_COARSE_PHASE_MIN_PS) / 2;
phy_dbg("[lpdc] No LPDC TX Calibration data found. Restarting from scratch.\n" );
}
fsm->expected_phase_valid = 1;
}
int phase_min = fsm->expected_phase - fsm->tollerance;
int phase_max = fsm->expected_phase + fsm->tollerance;
phy_dbg("[lpdc] TX phase = %d ps\n", phase);
if (within_range(phase, phase_min, phase_max, 16000))
{
fsm->measured_phase = phase;
//phy_dbg("[lpdc] Fix phase = %d ps\n", fsm->measured_phase );
fsm->state = TX_SETUP_VALIDATE;
}
else
{
if (fsm->attempts >= LPDC_MAX_ATTEMPS_TX_SETUP_STATE_RESET_PCS)
{
phy_dbg("[lpdc] No proper TX phase found at %d ps after %d attempts. Clear stored PHY_TARGET_TX_PHASE.\n", fsm->cal_saved_phase, fsm->attempts);
phy_dbg("[lpdc] Old calibration due to new gateware?\n");
storage_remove_calibration_parameter(CAL_PARAM_PHY_TARGET_TX_PHASE);
storage_save_calibration();
fsm->attempts = 0;
fsm->cal_saved_phase_valid = 0;
fsm->expected_phase_valid = 0;
}
else
fsm->state = TX_SETUP_STATE_RESET_PCS;
}
break;
}
case TX_SETUP_VALIDATE:
{
phy_dbg("[lpdc] TX calibration complete (phase %d ps, after %d attempts)\n", fsm->measured_phase, fsm->attempts);
spll_enable_ptracker(0, 0);
// enable the PCS+SFP on the port
mdio_lpdc_write( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_TX_ENABLE | LPDC_MDIO_CTRL_DMTD_SOURCE_RXRECCLK );
ep_sfp_enable( lpdc->endpoint, 1 );
if( !fsm->cal_saved_phase_valid )
{
phy_dbg("[lpdc] Saving established target phase as calibration parameter: %d ps\n", fsm->measured_phase);
storage_set_calibration_parameter_and_save( CAL_PARAM_PHY_TARGET_TX_PHASE, fsm->measured_phase);
}
fsm->state = TX_SETUP_DONE;
break;
}
case TX_SETUP_DONE:
{
return 1;
break;
}
}
return 0;
}
static void rx_fsm_init(struct wrc_port_rx_setup_state* fsm)
{
fsm->attempts = 0;
fsm->state = RX_SETUP_STATE_INIT;
fsm->prev_link_up = 0;
memset(fsm->cpos_stat, 0, sizeof(fsm->cpos_stat ));
}
static int rx_fsm_update(struct wrc_lpdc_state *lpdc)
{
struct wrc_port_rx_setup_state* fsm = &lpdc->rx_state;
struct wrc_port_tx_setup_state* fsm_tx = &lpdc->tx_state;
uint16_t lpc_stat = mdio_lpdc_read(lpdc, LPDC_MDIO_STAT);
int early_link_up = lpc_stat & LPDC_MDIO_STAT_LINK_UP;
if( fsm_tx->state != TX_SETUP_DONE )
{
fsm->state = RX_SETUP_STATE_INIT;
return 0;
}
switch( fsm->state )
{
case RX_SETUP_STATE_INIT:
{
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_TARGET_COMMA_POS );
if (early_link_up) {
if ( fsm_tx->state == TX_SETUP_DONE )
{
phy_dbg("[lpdc] RX calibration started.\n");
fsm->state = RX_SETUP_STATE_RESET_PCS;
}
}
fsm->attempts = 0;
break;
}
case RX_SETUP_STATE_RESET_PCS:
{
if (early_link_up)
{
fsm->state = RX_SETUP_STATE_WAIT_LOCK;
// Reset RX path and gtx_comma_detect_lp reset (= AUX_RESET)
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_SW_RESET | LPDC_MDIO_CTRL_AUX_RESET );
usleep(1);
// Un-Reset RX path and gtx_comma_detect_lp reset (= AUX_RESET)
mdio_lpdc_clear_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_SW_RESET | LPDC_MDIO_CTRL_AUX_RESET );
usleep(10000);
fsm->attempts++;
tmo_init(&fsm->link_timeout, FSM_EARLY_LINK_UP_TIMEOUT_MS);
}
break;
}
case RX_SETUP_STATE_WAIT_LOCK:
{
int rx_aligned = lpc_stat & LPDC_MDIO_STAT_LINK_ALIGNED;
if ( tmo_expired(&fsm->link_timeout) && !early_link_up) {
fsm->state = RX_SETUP_STATE_INIT;
}
else
{
if ( !early_link_up )
return 0;
if( rx_aligned )
{
fsm->state = RX_SETUP_VALIDATE;
tmo_init( &fsm->stabilize_timeout, FSM_STABILIZE_TIMEOUT_MS );
} else {
// In rare occasions the comma can't be found at the proper tap, even after
// multiple PCS resets. In such a case a full GTHE4 reset is needed.
if (fsm-> attempts % LPDC_MAX_ATTEMPS_RX_SETUP_STATE_RESET_PCS == 0) {
phy_dbg("[lpdc] No RX calibration yet... Restarting TX calibration from scratch.\n");
tx_fsm_init(&lpdc->tx_state);
} else {
fsm->state = RX_SETUP_STATE_RESET_PCS;
}
}
}
break;
}
case RX_SETUP_VALIDATE:
{
if( !tmo_expired( &fsm->stabilize_timeout ))
return 0;
int rx_aligned = lpc_stat & LPDC_MDIO_STAT_LINK_ALIGNED;
int rx_comma_pos = (lpc_stat & LPDC_MDIO_STAT_COMMA_CURRENT_POS_MASK) > LPDC_MDIO_STAT_COMMA_CURRENT_POS_SHIFT;
int rx_comma_valid = lpc_stat & LPDC_MDIO_STAT_COMMA_POS_VALID;
if ( early_link_up && rx_aligned && rx_comma_valid && (rx_comma_pos == LPDC_TARGET_COMMA_POS) )
{
mdio_lpdc_set_bits( lpdc, LPDC_MDIO_CTRL, LPDC_MDIO_CTRL_RX_ENABLE );
ep_pcs_write(lpdc->endpoint, EP_MDIO_MCR, EP_MDIO_MCR_SPEED1000 | EP_MDIO_MCR_FULLDPLX | EP_MDIO_MCR_ANENABLE | EP_MDIO_MCR_ANRESTART);
phy_dbg("[lpdc] RX calibration complete (after %d attempts) comma @ %d taps.\n", fsm->attempts, rx_comma_pos );
spll_enable_ptracker( 0, 0 );
spll_set_ptracker_average_samples( 0, PTRACKER_AVERAGE_SAMPLES );
fsm->state = RX_SETUP_DONE;
} else {
phy_dbg("[lpdc] Stabilize link...\n");
fsm->state = RX_SETUP_STATE_RESET_PCS;
}
break;
}
case RX_SETUP_DONE:
{
int link_up = ep_link_up(&wrc_endpoint_dev, NULL);
if( !early_link_up /*|| ( ( fsm->prev_link_up && !link_up ) )*/ )
{
phy_dbg("port went down, need RX recalibration.\n");
fsm->state = RX_SETUP_STATE_INIT;
fsm->prev_link_up = link_up;
return 0;
}
fsm->prev_link_up = link_up;
return 1;
break;
}
default:
break;
}
return 0;
}
static struct wrc_lpdc_state lpdc;
int phy_calibration_poll(void)
{
tx_fsm_update(&lpdc);
rx_fsm_update(&lpdc);
return 1;
}
int phy_calibration_done(void)
{
return (lpdc.rx_state.state == RX_SETUP_DONE);
}
void phy_calibration_init(void)
{
// fixme: do we want more than one in the WRC? maybe soon...
lpdc.endpoint = &wrc_endpoint_dev;
phy_dbg("[lpdc] Initializing PHY calibrator...\n");
ep_pcs_write(lpdc.endpoint, EP_MDIO_MCR, EP_MDIO_MCR_PDOWN); /* reset the PHY */
timer_delay_ms(200);
ep_pcs_write(lpdc.endpoint, EP_MDIO_MCR, EP_MDIO_MCR_RESET); /* reset the PHY */
ep_pcs_write(lpdc.endpoint, EP_MDIO_MCR, 0); /* reset the PHY */
mdio_lpdc_write( &lpdc, LPDC_MDIO_CTRL, 0 );
mdio_lpdc_write( &lpdc, LPDC_MDIO_CTRL2, 0 );
tx_fsm_init(&lpdc.tx_state);
rx_fsm_init(&lpdc.rx_state);
}
void phy_calibration_disable(void)
{
lpdc.tx_state.state = TX_SETUP_STATE_DISABLED;
lpdc.rx_state.state = RX_SETUP_STATE_DISABLED;
}
#
# Automatically generated file; DO NOT EDIT.
# WR PTP Core software configuration
#
# CONFIG_ARCH_LM32 is not set
CONFIG_ARCH_RISCV=y
# CONFIG_RISCV_COMP_INSTR is not set
CONFIG_DATASIZE=2048
# CONFIG_TARGET_GENERIC_PHY_8BIT is not set
# CONFIG_TARGET_GENERIC_PHY_16BIT is not set
# CONFIG_TARGET_WR_SWITCH is not set
# CONFIG_TARGET_AFCZ_V1 is not set
# CONFIG_TARGET_AFCZ_V2 is not set
# CONFIG_TARGET_ERTM14 is not set
# CONFIG_TARGET_SIS8300KU is not set
CONFIG_TARGET_CLB_V2=y
# CONFIG_TARGET_CLB_V3 is not set
# CONFIG_TARGET_CLB_V4 is not set
# CONFIG_TARGET_PXIE_FMC is not set
# CONFIG_TARGET_WR2RF_VME is not set
# CONFIG_TARGET_SPEC_SILABS is not set
# CONFIG_WR_NODE_SIM is not set
CONFIG_WR_NODE=y
CONFIG_STACKSIZE=2048
CONFIG_PRINT_BUFSIZE=256
CONFIG_RAMSIZE=131072
CONFIG_TEMP_POLL_INTERVAL=15
CONFIG_TEMP_HIGH_THRESHOLD=70
CONFIG_TEMP_HIGH_RAPPEL=60
CONFIG_VLAN=y
CONFIG_VLAN_NR=10
CONFIG_VLAN_1_FOR_CLASS7=20
CONFIG_VLAN_2_FOR_CLASS7=30
CONFIG_VLAN_FOR_CLASS6=100
# CONFIG_HOST_PROCESS is not set
CONFIG_EMBEDDED_NODE=y
CONFIG_WRPC_PPSI=y
CONFIG_LATENCY_ETHTYPE=291
#
# features
#
#
# PPSI config
#
CONFIG_ARCH="wrpc"
CONFIG_ARCH_CFLAGS=""
CONFIG_ARCH_LDFLAGS=""
#
# Options
#
#
# PTP Protocol Options
#
CONFIG_E2E=y
# CONFIG_P2P is not set
CONFIG_E2E_ONLY=y
CONFIG_HAS_P2P=0
# CONFIG_PTP_OVERWRITE_BASIC_ATTRIBUTES is not set
# CONFIG_PTP_OPT_OVERWRITE_ATTRIBUTES is not set
CONFIG_LEAP_SECONDS_VAL=37
#
# Enabled profiles
#
CONFIG_PROFILE_WR=y
# CONFIG_PROFILE_HA is not set
# CONFIG_PROFILE_CUSTOM is not set
CONFIG_PROFILE_PTP=y
CONFIG_HAS_EXT_WR=1
CONFIG_HAS_EXT_L1SYNC=0
CONFIG_HAS_EXT_NONE=0
CONFIG_HAS_PROFILE_PTP=1
CONFIG_HAS_PROFILE_HA=0
CONFIG_HAS_PROFILE_WR=1
CONFIG_HAS_PROFILE_CUSTOM=0
CONFIG_PPSI_VLAN=y
CONFIG_VLAN_ARRAY_SIZE=1
# CONFIG_PPSI_ASSERT is not set
CONFIG_NR_FOREIGN_RECORDS=1
CONFIG_SINGLE_FMASTER=y
CONFIG_NR_PORTS=1
CONFIG_NR_INSTANCES_PER_PORT=1
#
# Code optimization
#
CONFIG_CODEOPT_ENABLED=y
CONFIG_SINGLE_INSTANCE_PER_PORT=y
CONFIG_SINGLE_INSTANCE=y
CONFIG_SINGLE_PORT=y
# CONFIG_CODEOPT_SINGLE_PORT is not set
# CONFIG_CODEOPT_SINGLE_FMASTER is not set
# CONFIG_CODEOPT_SINGLE_INSTANCE_PER_PORT is not set
CONFIG_CODEOPT_WRPC_SIZE=y
CONFIG_CODEOPT_EXT_PORT_CONF_FORCE_DISABLED=y
CONFIG_CODEOPT_SO_FORCE_DISABLED=y
CONFIG_CODEOPT_MO_FORCE_DISABLED=y
CONFIG_CODEOPT_EPC_SO_DISABLED=y
CONFIG_OPTIMIZATION="-Os -ggdb"
# CONFIG_FAULT_INJECTION_MECHANISM is not set
# CONFIG_NO_PTPDUMP is not set
CONFIG_HAS_FAULT_INJECTION_MECHANISM=0
CONFIG_HAS_WRPC_FAULTS=0
CONFIG_HAS_CODEOPT_SINGLE_FMASTER=0
CONFIG_HAS_CODEOPT_SINGLE_PORT=0
CONFIG_HAS_CODEOPT_SINGLE_INSTANCE_PER_PORT=0
CONFIG_HAS_CODEOPT_CODEOPT_WRPC_SIZE=1
CONFIG_HAS_CODEOPT_EXT_PORT_CONF_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_SO_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_MO_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_EPC_ENABLED=0
CONFIG_HAS_CODEOPT_SO_ENABLED=0
CONFIG_ARCH_IS_WRS=0
CONFIG_ARCH_IS_WRPC=1
CONFIG_HAS_PPSI_ASSERT=0
CONFIG_IP=y
# CONFIG_SYSLOG is not set
# CONFIG_ETHERBONE is not set
CONFIG_SNMP=y
CONFIG_SNMP_SET=y
CONFIG_SNMP_INIT=y
CONFIG_SNMP_SDB=y
CONFIG_SNMP_CMD=y
CONFIG_WR_DIAG=y
CONFIG_ABSCAL=y
CONFIG_LLDP=y
# CONFIG_NETCONSOLE is not set
# CONFIG_TEMP_SENSORS is not set
# CONFIG_GENERIC_SENSORS is not set
CONFIG_W1=y
# CONFIG_W1_EEPROM is not set
# CONFIG_FRAC_SPLL is not set
#
# commands
#
# CONFIG_CMD_CONFIG is not set
CONFIG_BUILD_INIT=y
CONFIG_INIT_COMMAND="vlan off;ptp stop;sfp match;mode slave;ptp start"
CONFIG_HAS_FLASH_INIT=1
CONFIG_FLASH_INIT=y
# CONFIG_CMD_CALIBRATION_SHOW is not set
# CONFIG_CMD_REFRESH is not set
# CONFIG_CMD_PPS is not set
CONFIG_CMD_SFP_INFO=y
# CONFIG_SFP_DOM is not set
# CONFIG_CMD_LEAPSEC is not set
# CONFIG_CMD_PTP_ADV is not set
# CONFIG_CMD_MONITOR_SERVO_ERR is not set
# CONFIG_FREQUENCY_MONITOR is not set
#
# wrpc-sw is tainted if you change the following options
#
# CONFIG_DEVELOPER is not set
# CONFIG_TRACE_MSGS is not set
CONFIG_TRACE_ALL=0
CONFIG_TRACE_MAIN=0
CONFIG_TRACE_STORAGE=0
CONFIG_TRACE_DEVICES=0
CONFIG_TRACE_BOARD=0
CONFIG_TRACE_MAC=0
CONFIG_TRACE_PHY=0
CONFIG_LTO=y
# CONFIG_PRINTF_XINT is not set
CONFIG_PRINTF_FULL=y
# CONFIG_PRINTF_MINI is not set
# CONFIG_PRINTF_NONE is not set
#
# Automatically generated file; DO NOT EDIT.
# WR PTP Core software configuration
#
# CONFIG_ARCH_LM32 is not set
CONFIG_ARCH_RISCV=y
# CONFIG_RISCV_COMP_INSTR is not set
CONFIG_DATASIZE=2048
# CONFIG_TARGET_GENERIC_PHY_8BIT is not set
# CONFIG_TARGET_GENERIC_PHY_16BIT is not set
# CONFIG_TARGET_WR_SWITCH is not set
# CONFIG_TARGET_AFCZ_V1 is not set
# CONFIG_TARGET_AFCZ_V2 is not set
# CONFIG_TARGET_ERTM14 is not set
# CONFIG_TARGET_SIS8300KU is not set
# CONFIG_TARGET_CLB_V2 is not set
CONFIG_TARGET_CLB_V3=y
# CONFIG_TARGET_CLB_V4 is not set
# CONFIG_TARGET_PXIE_FMC is not set
# CONFIG_TARGET_WR2RF_VME is not set
# CONFIG_TARGET_SPEC_SILABS is not set
# CONFIG_WR_NODE_SIM is not set
CONFIG_WR_NODE=y
CONFIG_STACKSIZE=2048
CONFIG_PRINT_BUFSIZE=256
CONFIG_RAMSIZE=131072
CONFIG_TEMP_POLL_INTERVAL=15
CONFIG_TEMP_HIGH_THRESHOLD=70
CONFIG_TEMP_HIGH_RAPPEL=60
CONFIG_VLAN=y
CONFIG_VLAN_NR=10
CONFIG_VLAN_1_FOR_CLASS7=20
CONFIG_VLAN_2_FOR_CLASS7=30
CONFIG_VLAN_FOR_CLASS6=100
# CONFIG_HOST_PROCESS is not set
CONFIG_EMBEDDED_NODE=y
CONFIG_WRPC_PPSI=y
CONFIG_LATENCY_ETHTYPE=291
#
# features
#
#
# PPSI config
#
CONFIG_ARCH="wrpc"
CONFIG_ARCH_CFLAGS=""
CONFIG_ARCH_LDFLAGS=""
#
# Options
#
#
# PTP Protocol Options
#
CONFIG_E2E=y
# CONFIG_P2P is not set
CONFIG_E2E_ONLY=y
CONFIG_HAS_P2P=0
# CONFIG_PTP_OVERWRITE_BASIC_ATTRIBUTES is not set
# CONFIG_PTP_OPT_OVERWRITE_ATTRIBUTES is not set
CONFIG_LEAP_SECONDS_VAL=37
#
# Enabled profiles
#
CONFIG_PROFILE_WR=y
# CONFIG_PROFILE_HA is not set
# CONFIG_PROFILE_CUSTOM is not set
CONFIG_PROFILE_PTP=y
CONFIG_HAS_EXT_WR=1
CONFIG_HAS_EXT_L1SYNC=0
CONFIG_HAS_EXT_NONE=0
CONFIG_HAS_PROFILE_PTP=1
CONFIG_HAS_PROFILE_HA=0
CONFIG_HAS_PROFILE_WR=1
CONFIG_HAS_PROFILE_CUSTOM=0
CONFIG_PPSI_VLAN=y
CONFIG_VLAN_ARRAY_SIZE=1
# CONFIG_PPSI_ASSERT is not set
CONFIG_NR_FOREIGN_RECORDS=1
CONFIG_SINGLE_FMASTER=y
CONFIG_NR_PORTS=1
CONFIG_NR_INSTANCES_PER_PORT=1
#
# Code optimization
#
CONFIG_CODEOPT_ENABLED=y
CONFIG_SINGLE_INSTANCE_PER_PORT=y
CONFIG_SINGLE_INSTANCE=y
CONFIG_SINGLE_PORT=y
# CONFIG_CODEOPT_SINGLE_PORT is not set
# CONFIG_CODEOPT_SINGLE_FMASTER is not set
# CONFIG_CODEOPT_SINGLE_INSTANCE_PER_PORT is not set
CONFIG_CODEOPT_WRPC_SIZE=y
CONFIG_CODEOPT_EXT_PORT_CONF_FORCE_DISABLED=y
CONFIG_CODEOPT_SO_FORCE_DISABLED=y
CONFIG_CODEOPT_MO_FORCE_DISABLED=y
CONFIG_CODEOPT_EPC_SO_DISABLED=y
CONFIG_OPTIMIZATION="-Os -ggdb"
# CONFIG_FAULT_INJECTION_MECHANISM is not set
# CONFIG_NO_PTPDUMP is not set
CONFIG_HAS_FAULT_INJECTION_MECHANISM=0
CONFIG_HAS_WRPC_FAULTS=0
CONFIG_HAS_CODEOPT_SINGLE_FMASTER=0
CONFIG_HAS_CODEOPT_SINGLE_PORT=0
CONFIG_HAS_CODEOPT_SINGLE_INSTANCE_PER_PORT=0
CONFIG_HAS_CODEOPT_CODEOPT_WRPC_SIZE=1
CONFIG_HAS_CODEOPT_EXT_PORT_CONF_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_SO_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_MO_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_EPC_ENABLED=0
CONFIG_HAS_CODEOPT_SO_ENABLED=0
CONFIG_ARCH_IS_WRS=0
CONFIG_ARCH_IS_WRPC=1
CONFIG_HAS_PPSI_ASSERT=0
CONFIG_IP=y
# CONFIG_SYSLOG is not set
# CONFIG_ETHERBONE is not set
CONFIG_SNMP=y
CONFIG_SNMP_SET=y
CONFIG_SNMP_INIT=y
CONFIG_SNMP_SDB=y
CONFIG_SNMP_CMD=y
CONFIG_WR_DIAG=y
CONFIG_ABSCAL=y
CONFIG_LLDP=y
# CONFIG_NETCONSOLE is not set
# CONFIG_TEMP_SENSORS is not set
# CONFIG_GENERIC_SENSORS is not set
CONFIG_W1=y
# CONFIG_W1_EEPROM is not set
# CONFIG_FRAC_SPLL is not set
#
# commands
#
# CONFIG_CMD_CONFIG is not set
CONFIG_BUILD_INIT=y
CONFIG_INIT_COMMAND="vlan off;ptp stop;sfp match;mode slave;ptp start"
CONFIG_HAS_FLASH_INIT=1
CONFIG_FLASH_INIT=y
# CONFIG_CMD_CALIBRATION_SHOW is not set
# CONFIG_CMD_REFRESH is not set
# CONFIG_CMD_PPS is not set
CONFIG_CMD_SFP_INFO=y
# CONFIG_SFP_DOM is not set
# CONFIG_CMD_LEAPSEC is not set
# CONFIG_CMD_PTP_ADV is not set
# CONFIG_CMD_MONITOR_SERVO_ERR is not set
# CONFIG_FREQUENCY_MONITOR is not set
#
# wrpc-sw is tainted if you change the following options
#
# CONFIG_DEVELOPER is not set
# CONFIG_TRACE_MSGS is not set
CONFIG_TRACE_ALL=0
CONFIG_TRACE_MAIN=0
CONFIG_TRACE_STORAGE=0
CONFIG_TRACE_DEVICES=0
CONFIG_TRACE_BOARD=0
CONFIG_TRACE_MAC=0
CONFIG_TRACE_PHY=0
CONFIG_LTO=y
# CONFIG_PRINTF_XINT is not set
CONFIG_PRINTF_FULL=y
# CONFIG_PRINTF_MINI is not set
# CONFIG_PRINTF_NONE is not set
#
# Automatically generated file; DO NOT EDIT.
# WR PTP Core software configuration
#
# CONFIG_ARCH_LM32 is not set
CONFIG_ARCH_RISCV=y
# CONFIG_RISCV_COMP_INSTR is not set
CONFIG_DATASIZE=2048
# CONFIG_TARGET_GENERIC_PHY_8BIT is not set
# CONFIG_TARGET_GENERIC_PHY_16BIT is not set
# CONFIG_TARGET_WR_SWITCH is not set
# CONFIG_TARGET_AFCZ_V1 is not set
# CONFIG_TARGET_AFCZ_V2 is not set
# CONFIG_TARGET_ERTM14 is not set
# CONFIG_TARGET_SIS8300KU is not set
# CONFIG_TARGET_CLB_V2 is not set
# CONFIG_TARGET_CLB_V3 is not set
CONFIG_TARGET_CLB_V4=y
# CONFIG_TARGET_PXIE_FMC is not set
# CONFIG_TARGET_WR2RF_VME is not set
# CONFIG_TARGET_SPEC_SILABS is not set
# CONFIG_WR_NODE_SIM is not set
CONFIG_WR_NODE=y
CONFIG_STACKSIZE=2048
CONFIG_PRINT_BUFSIZE=256
CONFIG_RAMSIZE=131072
CONFIG_TEMP_POLL_INTERVAL=15
CONFIG_TEMP_HIGH_THRESHOLD=70
CONFIG_TEMP_HIGH_RAPPEL=60
CONFIG_VLAN=y
CONFIG_VLAN_NR=10
CONFIG_VLAN_1_FOR_CLASS7=20
CONFIG_VLAN_2_FOR_CLASS7=30
CONFIG_VLAN_FOR_CLASS6=100
# CONFIG_HOST_PROCESS is not set
CONFIG_EMBEDDED_NODE=y
CONFIG_WRPC_PPSI=y
CONFIG_LATENCY_ETHTYPE=291
#
# features
#
#
# PPSI config
#
CONFIG_ARCH="wrpc"
CONFIG_ARCH_CFLAGS=""
CONFIG_ARCH_LDFLAGS=""
#
# Options
#
#
# PTP Protocol Options
#
CONFIG_E2E=y
# CONFIG_P2P is not set
CONFIG_E2E_ONLY=y
CONFIG_HAS_P2P=0
# CONFIG_PTP_OVERWRITE_BASIC_ATTRIBUTES is not set
# CONFIG_PTP_OPT_OVERWRITE_ATTRIBUTES is not set
CONFIG_LEAP_SECONDS_VAL=37
#
# Enabled profiles
#
CONFIG_PROFILE_WR=y
# CONFIG_PROFILE_HA is not set
# CONFIG_PROFILE_CUSTOM is not set
CONFIG_PROFILE_PTP=y
CONFIG_HAS_EXT_WR=1
CONFIG_HAS_EXT_L1SYNC=0
CONFIG_HAS_EXT_NONE=0
CONFIG_HAS_PROFILE_PTP=1
CONFIG_HAS_PROFILE_HA=0
CONFIG_HAS_PROFILE_WR=1
CONFIG_HAS_PROFILE_CUSTOM=0
CONFIG_PPSI_VLAN=y
CONFIG_VLAN_ARRAY_SIZE=1
# CONFIG_PPSI_ASSERT is not set
CONFIG_NR_FOREIGN_RECORDS=1
CONFIG_SINGLE_FMASTER=y
CONFIG_NR_PORTS=1
CONFIG_NR_INSTANCES_PER_PORT=1
#
# Code optimization
#
CONFIG_CODEOPT_ENABLED=y
CONFIG_SINGLE_INSTANCE_PER_PORT=y
CONFIG_SINGLE_INSTANCE=y
CONFIG_SINGLE_PORT=y
# CONFIG_CODEOPT_SINGLE_PORT is not set
# CONFIG_CODEOPT_SINGLE_FMASTER is not set
# CONFIG_CODEOPT_SINGLE_INSTANCE_PER_PORT is not set
CONFIG_CODEOPT_WRPC_SIZE=y
CONFIG_CODEOPT_EXT_PORT_CONF_FORCE_DISABLED=y
CONFIG_CODEOPT_SO_FORCE_DISABLED=y
CONFIG_CODEOPT_MO_FORCE_DISABLED=y
CONFIG_CODEOPT_EPC_SO_DISABLED=y
CONFIG_OPTIMIZATION="-Os -ggdb"
# CONFIG_FAULT_INJECTION_MECHANISM is not set
# CONFIG_NO_PTPDUMP is not set
CONFIG_HAS_FAULT_INJECTION_MECHANISM=0
CONFIG_HAS_WRPC_FAULTS=0
CONFIG_HAS_CODEOPT_SINGLE_FMASTER=0
CONFIG_HAS_CODEOPT_SINGLE_PORT=0
CONFIG_HAS_CODEOPT_SINGLE_INSTANCE_PER_PORT=0
CONFIG_HAS_CODEOPT_CODEOPT_WRPC_SIZE=1
CONFIG_HAS_CODEOPT_EXT_PORT_CONF_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_SO_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_MO_FORCE_DISABLED=1
CONFIG_HAS_CODEOPT_EPC_ENABLED=0
CONFIG_HAS_CODEOPT_SO_ENABLED=0
CONFIG_ARCH_IS_WRS=0
CONFIG_ARCH_IS_WRPC=1
CONFIG_HAS_PPSI_ASSERT=0
CONFIG_IP=y
# CONFIG_SYSLOG is not set
# CONFIG_ETHERBONE is not set
CONFIG_SNMP=y
CONFIG_SNMP_SET=y
CONFIG_SNMP_INIT=y
CONFIG_SNMP_SDB=y
CONFIG_SNMP_CMD=y
CONFIG_WR_DIAG=y
CONFIG_ABSCAL=y
CONFIG_LLDP=y
# CONFIG_NETCONSOLE is not set
# CONFIG_TEMP_SENSORS is not set
# CONFIG_GENERIC_SENSORS is not set
CONFIG_W1=y
# CONFIG_W1_EEPROM is not set
# CONFIG_FRAC_SPLL is not set
#
# commands
#
# CONFIG_CMD_CONFIG is not set
CONFIG_BUILD_INIT=y
CONFIG_INIT_COMMAND="vlan off;ptp stop;sfp match;mode slave;ptp start"
CONFIG_HAS_FLASH_INIT=1
CONFIG_FLASH_INIT=y
# CONFIG_CMD_CALIBRATION_SHOW is not set
# CONFIG_CMD_REFRESH is not set
# CONFIG_CMD_PPS is not set
CONFIG_CMD_SFP_INFO=y
# CONFIG_SFP_DOM is not set
# CONFIG_CMD_LEAPSEC is not set
# CONFIG_CMD_PTP_ADV is not set
# CONFIG_CMD_MONITOR_SERVO_ERR is not set
# CONFIG_FREQUENCY_MONITOR is not set
#
# wrpc-sw is tainted if you change the following options
#
# CONFIG_DEVELOPER is not set
# CONFIG_TRACE_MSGS is not set
CONFIG_TRACE_ALL=0
CONFIG_TRACE_MAIN=0
CONFIG_TRACE_STORAGE=0
CONFIG_TRACE_DEVICES=0
CONFIG_TRACE_BOARD=0
CONFIG_TRACE_MAC=0
CONFIG_TRACE_PHY=0
CONFIG_LTO=y
# CONFIG_PRINTF_XINT is not set
CONFIG_PRINTF_FULL=y
# CONFIG_PRINTF_MINI is not set
# CONFIG_PRINTF_NONE is not set
......@@ -43,6 +43,12 @@
# include "boards/ertm14/board.h"
#elif defined(CONFIG_TARGET_SIS8300KU)
# include "boards/sis8300ku/board.h"
#elif defined(CONFIG_TARGET_CLB_V2)
# include "boards/clbv2/board.h"
#elif defined(CONFIG_TARGET_CLB_V3)
# include "boards/clbv3/board.h"
#elif defined(CONFIG_TARGET_CLB_V4)
# include "boards/clbv4/board.h"
#elif defined(CONFIG_TARGET_PXIE_FMC)
# include "boards/pxie-fmc/board-config.h"
#elif defined(CONFIG_TARGET_WR2RF_VME)
......
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