Commit 69e157a3 authored by Tomasz Wlostowski's avatar Tomasz Wlostowski Committed by Alessandro Rubini

libswitchhw: added more comments, removed old functions which were commented out…

libswitchhw: added more comments, removed old functions which were commented out or not used (nor planned to use)
parent cfa72dd0
/* Analog Devices AD9516-4 PLL driver */
#include <math.h>
#include <hw/pio.h>
......@@ -5,6 +7,7 @@
#include <hw/ad9516.h>
/* SPI bit delay, in microseconds */
#define SPI_DELAY 50
#define AD9516_OP_READ 0x80
......@@ -22,10 +25,22 @@ struct ad9516_regs {
int shw_ad9516_set_output_delay(int output, float delay_ns, int bypass);
/* for the standard PLL setups - generated by Analog Devices' software */
#include "ad9516_default_regs.h"
/* Indicates whether to generate the reference clock from the local VCTCXO (0)
or the external 10 MHz input (cesium, etc. - 1) */
static int use_ext_ref = 0;
/* Enables/disables locking the 125 MHz reference clock to an externally provided
10 Mhz Reference (when enable = 1). Otherwise, the reference clock is produced
from the local voltage controlled oscillator (which can be locked by the DMPLL
to a reference from one of the uplink ports.
Note: can *ONLY* be called before initializing the libswitchhw. Reference source
cannot be switched on-the-fly. */
int shw_use_external_reference(int enable)
{
if(enable)
......@@ -33,8 +48,7 @@ int shw_use_external_reference(int enable)
use_ext_ref = enable;
}
/* Reads a byte from the AD9516 SPI interface by bit-banging the CPU pins */
static uint8_t ad9516_spi_read8()
{
uint8_t rx = 0;
......@@ -59,6 +73,7 @@ static uint8_t ad9516_spi_read8()
return rx;
}
/* Writes a byte (tx) to the AD9516 SPI interface by bit-banging the CPU pins */
static uint8_t ad9516_spi_write8(uint8_t tx)
{
int i;
......@@ -80,6 +95,7 @@ static uint8_t ad9516_spi_write8(uint8_t tx)
shw_udelay(SPI_DELAY);
}
/* Reads an AD9516 register from address addr and returns its 8-bit value */
static uint8_t ad9516_read_reg(uint16_t addr)
{
uint8_t val;
......@@ -98,6 +114,7 @@ static uint8_t ad9516_read_reg(uint16_t addr)
return val;
}
/* Writes AD9516 register located at addr with value data */
static void ad9516_write_reg(uint16_t addr, uint8_t data)
{
shw_pio_set0(PIN_ad9516_cs);
......@@ -112,15 +129,18 @@ static void ad9516_write_reg(uint16_t addr, uint8_t data)
shw_udelay(SPI_DELAY);
}
/* Performs a HW reset of the AD9516 by asserting it's RSTN pin */
static void ad9516_reset()
{
shw_pio_set0(PIN_ad9516_nrst); // reset the PLL
shw_pio_set0(PIN_ad9516_nrst);
shw_udelay(100);
shw_pio_set1(PIN_ad9516_nrst); // un-reset the PLL
shw_pio_set1(PIN_ad9516_nrst);
shw_udelay(100);
}
/* Checks for the presence of 10 MHz external reference signal on the AD9516 ref input.
Returns non-zero if the signal is present. */
int ad9516_detect_external_ref()
{
ad9516_write_reg(0x4, 0x1); // readback active regs
......@@ -132,45 +152,7 @@ int ad9516_detect_external_ref()
}
static int ad9516_load_regs_from_file(const char *filename, struct ad9516_regs *regs)
{
FILE *f;
char str[1024], tmp[100];
int start_read = 0, n = 0;
uint32_t addr, val;
f = fopen(filename ,"rb");
if(!f)
{
TRACE(TRACE_ERROR, "can't open AD9516 regset file: %s", filename);
return -1;
}
while(!feof(f))
{
fgets(str, 1024, f);
if(!strncmp(str, "Addr(Hex)", 8)) start_read = 1;
if(start_read)
{
if( sscanf(str, "%04x %08s %02x\n", &addr, tmp, &val) == 3)
{
//TRACE(TRACE_INFO, " -> ad9516_reg[0x%x]=0x%x", addr, val);
regs->regs[n].addr = addr;
regs->regs[n].value = val;
n++;
}
}
}
regs->nregs = n;
fclose(f);
return start_read == 1 ? 0 : -1;
}
/* Loads and updates the configuration provided in "regs" into the AD9516. */
static int ad9516_load_state(const struct ad9516_regs *regs)
{
int i;
......@@ -179,11 +161,14 @@ static int ad9516_load_state(const struct ad9516_regs *regs)
for(i=0;i<regs->nregs;i++)
ad9516_write_reg(regs->regs[i].addr, regs->regs[i].value);
ad9516_write_reg(AD9516_UPDATE_ALL, 1); // acknowledge register update
/* Trigger the actual register reload (regs are just buffered after being written),
in order to load the new values simultaneously one must trigger an update. */
ad9516_write_reg(AD9516_UPDATE_ALL, 1);
return 0;
}
/* Checks if the PLL is locked (digital lock detection). Returns non-zero if true */
static int ad9516_check_lock()
{
uint8_t pll_readback = ad9516_read_reg(AD9516_PLLREADBACK);
......@@ -191,21 +176,19 @@ static int ad9516_check_lock()
return pll_readback & 1;
}
static void ad9516_power_down()
{
}
#define assert_init(proc) { int ret; if((ret = proc) < 0) return ret; }
/* Initializes the AD9516: sets up the reference source, PLL multiply/divide ratios,
enables clock outputs. */
int shw_ad9516_init()
{
int retries = 100;
TRACE(TRACE_INFO, "Initializing AD9516 PLL....");
/* The AD9516 uses CPU GPIO pins (it couldn't be connected to the FPGA,
because it supplies clock for it (and a clock-less FPGA wouldn't work). */
shw_pio_configure(PIN_ad9516_cs);
shw_pio_configure(PIN_ad9516_nrst);
shw_pio_configure(PIN_ad9516_refsel);
......@@ -213,42 +196,44 @@ int shw_ad9516_init()
shw_pio_configure(PIN_ad9516_sdio);
shw_pio_configure(PIN_ad9516_sdo);
/* Make sure the pins are stable after the configuration (no glitches, etc.) */
shw_udelay(100);
/* Reset AD9516 and give it some time to recover */
ad9516_reset();
// ad9516_power_down();
shw_udelay(10000);
/* Detect the presence by comparing a read register with it's reset value */
if(ad9516_read_reg(AD9516_SERIALPORT) != 0x18)
{
TRACE(TRACE_FATAL, "AD9516 not responding!");
return -1;
}
if(use_ext_ref)
{
assert_init(ad9516_load_state(&ad9516_regs_ext_10m));
} else {
assert_init(ad9516_load_state(&ad9516_regs_tcxo_25m));
}
/* Now just initialize. There are two pre-defined register sets, one for
the internal 25 MHz VCTCXO and the other for 10 MHz GPS/Cesium external reference */
if(use_ext_ref)
{
assert_init(ad9516_load_state(&ad9516_regs_ext_10m));
} else {
assert_init(ad9516_load_state(&ad9516_regs_tcxo_25m));
}
// wait for the PLL to lock
/* Wait for the PLL to lock. */
while(retries--)
{
if(ad9516_check_lock()) break;
shw_udelay(1000);
}
/* Signal integrity bugfix: delay Uplink 0 PHY clock a bit (to increase tSetup on
the PHY TX inputs */
shw_ad9516_set_output_delay(9, 0.5, 0);
// TRACE(TRACE_INFO, "LockReg: %d\n",
return 0;
}
/* Finds the parameters of the output skew adjustment unit of AD9516 for a given delay value. */
static int find_optimal_params(float delay_ns, int *caps, int *frac, int *ramp, float *best)
{
int r, i, ncaps, f;
......@@ -286,6 +271,8 @@ static int find_optimal_params(float delay_ns, int *caps, int *frac, int *ramp,
}
}
/* Sets the extra delay on given output to delay_ns. Used for de-skewing clocks.
When bypass is 1, the delay block is disabled. */
int shw_ad9516_set_output_delay(int output, float delay_ns, int bypass)
{
uint16_t regbase = 0xa0 + 3*(output - 6);
......@@ -294,15 +281,11 @@ int shw_ad9516_set_output_delay(int output, float delay_ns, int bypass)
find_optimal_params(delay_ns,&caps, &frac, &ramp, &best_dly );
// printf("Opt: caps %d frac %d ramp %d best %.5f req %.5f regbase %x\n", caps, frac, ramp, best_dly, delay_ns, regbase);
ad9516_write_reg(regbase, bypass?1:0);
ad9516_write_reg(regbase+1, (caps << 3) | (ramp));
ad9516_write_reg(regbase+2, frac);
ad9516_write_reg(AD9516_UPDATE_ALL, 1); // acknowledge register update
ad9516_write_reg(AD9516_UPDATE_ALL, 1); /* Acknowledge register update */
return 0;
}
......
/* Pre-defined AD9516 PLL configs, both for 25 MHz TCXO and external 10 MHz reference. */
static const struct ad9516_regs ad9516_regs_tcxo_25m = {
{
......
/* Routines for accessing the timing FPGA */
#include <stdio.h>
#include <stdlib.h>
......@@ -11,12 +13,19 @@
#define SPI_CLKDIV_VAL 50
#define CLKB_IDCODE 0xdeadbeef
/* Some protos */
int shw_clkb_write_reg(uint32_t reg, uint32_t val);
uint32_t shw_clkb_read_reg(uint32_t reg);
/* Initializes the SPI link between the main FPGA and the timing FPGA.
clkdiv = SPI SCLK division ratio. */
static void cmi_init(int clkdiv)
{
uint32_t val = SPICTL_ENABLE(1) | SPICTL_CLKDIV(clkdiv);
_fpga_writel(FPGA_BASE_SPIM+SPI_REG_SPICTL, val);
}
/* Returns non-zero if the SPI controller is busy sending/receiving data */
static inline int cmi_busy()
{
uint32_t ctl;
......@@ -24,6 +33,7 @@ static inline int cmi_busy()
return SPICTL_BUSY(ctl);
}
/* Enables (cs=1) or disables (cs=1) the SPI chip-select line */
static inline int cmi_cs(int cs)
{
uint32_t ctl;
......@@ -33,15 +43,15 @@ static inline int cmi_cs(int cs)
_fpga_writel(FPGA_BASE_SPIM+SPI_REG_SPICTL, ctl);
}
/* Sends/receives a number (n) of 32-bit words (d_in) to/from the timing
FPGA. Received words are stored in (d_out). */
static void cmi_transfer(uint32_t *d_in, uint32_t *d_out, int n)
{
int i;
uint32_t ctl, tmp;
while(cmi_busy());
cmi_cs(1);
for(i=0;i<n;i++)
......@@ -55,14 +65,9 @@ static void cmi_transfer(uint32_t *d_in, uint32_t *d_out, int n)
}
cmi_cs(0);
}
int shw_clkb_write_reg(uint32_t reg, uint32_t val);
uint32_t shw_clkb_read_reg(uint32_t reg);
/* Initializes the Inter-FPGA link (just the link, not the timing FPGA). */
int shw_clkb_init_cmi()
{
TRACE(TRACE_INFO, "initializing Clocking Mezzanine Interface");
......@@ -70,18 +75,20 @@ int shw_clkb_init_cmi()
return 0;
}
/* Initializes the Timing FPGA. Currently the initialization is just
resetting the chip. */
int shw_clkb_init()
{
shw_pio_configure(PIN_clkb_fpga_nrst);
shw_pio_set0(PIN_clkb_fpga_nrst);
shw_udelay(1000);
shw_pio_set1(PIN_clkb_fpga_nrst);
shw_udelay(1000);
}
/* Writes a 32-bit value (val) to the register (reg) in the Timing FPGA.
Returns 0 on success. */
int shw_clkb_write_reg(uint32_t reg, uint32_t val)
{
uint32_t rx[2], tx[2];
......@@ -96,11 +103,12 @@ int shw_clkb_write_reg(uint32_t reg, uint32_t val)
return 0;
}
/* Reads the value of a 32-bit register (reg) from the Timing FPGA and
returns it. */
uint32_t shw_clkb_read_reg(uint32_t reg)
{
uint32_t rx[2], tx[2];
tx[0]=(reg >> 2) | 0x80000000;
tx[1]= 0xffffffff;
cmi_transfer(tx,rx,2);
......
/* FIXME: rewrite this _properly_ */
/* Just remove me from the code. V3 will use the SoftPLL. */
#include <stdio.h>
#include <inttypes.h>
......@@ -10,31 +11,45 @@
#include <hw/clkb_io.h>
#include <hw/dmpll_regs.h>
/* Indices of the DMPLL channels. The DMPLL can lock to Uplink 0/1 or to an external 125 MHz reference
(never tested, used AD9516 locked to 10 MHz instead). */
#define DMPLL_CHANNEL_EXT_REF 2
#define DMPLL_CHANNEL_UP0 0
#define DMPLL_CHANNEL_UP1 1
/* Number of fractional bits of the PI controller gain coefficients. */
#define PI_FRACBITS 12 // was 16
/* PLL parameters */
typedef struct {
/* DMTD deglitcher threshold (see Tom's M.Sc. for explanation */
int deglitch_threshold;
/* PLL loop bandwidth in Hz and damping factor. */
double f_n;
double eta;
/* Fixed-point PI gain coefficients (calculated from f_n and eta). */
int ki;
int kp;
/* Current reference channel */
int channel;
/* Phase shifter setpoints for each reference channel */
double phase_setpoint[4];
} dmpll_params_t;
static dmpll_params_t cur_state;
/* Calculates the gains of the PI controller for a given PLL bandwidth
and damping factor. */
static void dmpll_calc_gain(double f_n, double eta, int *ki, int *kp)
{
const double Kd = 2.6076e+03;
const double Kvco = 0.1816;
const double Fs = 7.6294e+03;
const double Kd = 2.6076e+03; /* phase detector gain */
const double Kvco = 0.1816; /* VCO gain */
const double Fs = 7.6294e+03; /* sampling freq (depends on the parameters of the Helper PLL */
double omega_n = 2*M_PI*f_n;
......@@ -44,6 +59,7 @@ static void dmpll_calc_gain(double f_n, double eta, int *ki, int *kp)
}
/* Sets the deglitcher threshold on a particular channel to thr. */
static void dmpll_set_deglitch_threshold(uint32_t reg, int thr)
{
TRACE(TRACE_INFO, "threshold %d", thr);
......@@ -51,10 +67,9 @@ static void dmpll_set_deglitch_threshold(uint32_t reg, int thr)
}
/* Sets the phase shfit on a given channel to ps_shift. */
static void dmpll_set_phase_shift(int channel, int ps_shift)
{
// TRACE(TRACE_INFO,"SetPS ch %d ps %d\n", channel, ps_shift);
switch(channel)
{
......@@ -69,6 +84,7 @@ static void dmpll_set_phase_shift(int channel, int ps_shift)
}
}
/* Checks if the DMPLL is locked. */
int shw_dmpll_check_lock()
{
uint32_t psr;
......@@ -76,14 +92,17 @@ int shw_dmpll_check_lock()
psr= shw_clkb_read_reg(CLKB_BASE_DMPLL + DMPLL_REG_PSR);
if(psr & DMPLL_PSR_LOCK_LOST) {
/* Clear loss-of-lock bit so it can be updated again by the DMPLL */
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PSR, DMPLL_PSR_LOCK_LOST);
return 0;
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PSR, DMPLL_PSR_LOCK_LOST); // clear loss-of-lock bit
}
// printf("DPSR %x\n",psr & (DMPLL_PSR_FREQ_LK | DMPLL_PSR_PHASE_LK));
return (psr & DMPLL_PSR_FREQ_LK);// && (psr & DMPLL_PSR_PHASE_LK);
return (psr & DMPLL_PSR_FREQ_LK) && (psr & DMPLL_PSR_PHASE_LK);
}
/* Returns non-zero if the phase shifting operation is in progress (i.e. if the
shifter has not reached the given setpoint yet. */
static int dmpll_shifter_busy(int channel)
{
switch(channel)
......@@ -98,8 +117,8 @@ static int dmpll_shifter_busy(int channel)
return 0;
}
\
/* Returns the index of the DMPLL channel corresponding to a given network interface. */
static int iface_to_channel(const char *source)
{
if(!strcmp(source,"wru0"))
......@@ -110,6 +129,7 @@ static int iface_to_channel(const char *source)
return -1;
}
/* Locks the DMPLL to a given reference source (network interface). */
int shw_dmpll_lock(const char *source)
{
int ref_clk = iface_to_channel(source);
......@@ -121,47 +141,56 @@ int shw_dmpll_lock(const char *source)
TRACE(TRACE_INFO,"DMPLL: Set refence input to: %s", source);
/* Disable the DMPLL */
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PCR, 0);
/* Set the deglitcher thresholds on all channels (there's no independent setting) */
dmpll_set_deglitch_threshold(DMPLL_REG_DGCR_IN0, cur_state.deglitch_threshold);
dmpll_set_deglitch_threshold(DMPLL_REG_DGCR_IN1, cur_state.deglitch_threshold);
dmpll_set_deglitch_threshold(DMPLL_REG_DGCR_FB, cur_state.deglitch_threshold);
/* Reset the phase shifters. */
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PSCR_IN0, 0);
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PSCR_IN1, 0);
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PSCR_IN2, 0);
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PSCR_IN3, 0);
// gains & thresholds
/* Set the frequency branch gain (hardcoded - the freq branch is just to speed up the locking
so these params don't really need to be phase noise optimized). */
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_FBGR, DMPLL_FBGR_F_KP_W(-100) | DMPLL_FBGR_F_KI_W(-600));
/* Calculate the phase branch gains */
dmpll_calc_gain(cur_state.f_n, cur_state.eta, &cur_state.ki, &cur_state.kp);
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PBGR, DMPLL_PBGR_P_KP_W(cur_state.kp) | DMPLL_PBGR_P_KI_W(cur_state.ki)); // -1000/-20
/* ... and write them to the PLL */
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PBGR, DMPLL_PBGR_P_KP_W(cur_state.kp) | DMPLL_PBGR_P_KI_W(cur_state.ki));
/* Set the lock detection thresholds, phase shifter speed and enable the channel. */
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_LDCR, DMPLL_LDCR_LD_THR_W(2000) | DMPLL_LDCR_LD_SAMP_W(2000));
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PCR, DMPLL_PCR_ENABLE | DMPLL_PCR_REFSEL_W(ref_clk) | DMPLL_PCR_DAC_CLKSEL_W(2) | DMPLL_PCR_PS_SPEED_W(100) | DMPLL_PCR_SWRST);
cur_state.channel = ref_clk;
return 0;
}
/* Sets the phase shift between the PLL output clock (REFCLK) and the reference source
(Linux network I/F). The phase_shift is given in picoseconds. */
int shw_dmpll_phase_shift(const char *source, int phase_shift)
{
int ref_clk = iface_to_channel(source);
double ps;
// TRACE(TRACE_INFO,"shw_DMPLL_phase_shift source %s ref %d ps %d\n", source, ref_clk, phase_shift);
if(ref_clk < 0) return -1;
/* Convert to the internal timescale (1 REFCLK cycle = the helper PLL frequency offset / 1 REFCLK). */
ps = (double)phase_shift / 8000.0 * (double) shw_hpll_get_divider();
dmpll_set_phase_shift(ref_clk, (int) ps);
return 0;
}
/* Returns 1 if the DMPLL phase shifter has not yet reached the given setpoint on network I/F (source). */
int shw_dmpll_shifter_busy(const char *source)
{
int ref_clk = iface_to_channel(source);
......@@ -169,26 +198,20 @@ int shw_dmpll_shifter_busy(const char *source)
if(ref_clk < 0) return -1;
int busy = dmpll_shifter_busy(ref_clk) ? 1 :0;
// TRACE(TRACE_INFO,"PS-busy: %d\n", busy);
return busy;
}
int shw_dmpll_init()
{
TRACE(TRACE_INFO,"Initializing DMTD main PLL...");
// DMPLL is disabled by default. Just make sure it loads the initial DAC value (middle of TCXO tuning range)
/* DMPLL is disabled by default. Just make sure it loads the initial DAC value (middle of VCTCXO tuning range) */
shw_clkb_write_reg(CLKB_BASE_DMPLL + DMPLL_REG_PCR, DMPLL_PCR_DAC_CLKSEL_W(2) | DMPLL_PCR_SWRST);
// these work
cur_state.f_n = 15.0; // 15.0
cur_state.eta = 0.8; // 1.8
/* Set default values for the bandwidth, damping and deglitcher parameters. */
cur_state.f_n = 15.0;
cur_state.eta = 0.8;
cur_state.deglitch_threshold = 3000;
// cur_state.f_n = 5.0;
// cur_state.eta = 3;
// cur_state.deglitch_threshold = 2000;
return 0;
}
/* Userspace /dev/mem I/O functions for accessing the Main FPGA */
#include <stdio.h>
#include <unistd.h>
......@@ -14,8 +16,10 @@
#define SPI_CLKDIV_VAL 20 // clock divider for CMI SPI bus clock
/* Virtual base address of the Main FPGA address space. */
volatile uint8_t *_fpga_base_virt;
/* Initializes the mapping of the Main FPGA to the CPU address space. */
int shw_fpga_mmap_init()
{
int fd;
......@@ -39,6 +43,7 @@ int shw_fpga_mmap_init()
}
/* Resets the Main FPGA. */
void shw_main_fpga_reset()
{
shw_pio_set0(PIN_main_fpga_nrst);
......@@ -47,8 +52,10 @@ void shw_main_fpga_reset()
usleep(10000);
}
/* Initializes the Main FPGA - that means (currently) just resetting it. */
int shw_main_fpga_init()
{
shw_pio_configure(PIN_main_fpga_nrst);
shw_main_fpga_reset();
return 0;
}
/* The FPGA bootloader
Short explanation of the booting process:
- each FPGA has a "revision ID" block at address 0x0. This block
contains a magic number (so the CPU can detect the presence of a
valid firmware in the FPGA), the revision of the firmware and a
hash of the name of the currently loaded bitstream.
- the loader first attempts to read the Revid. If there's no valid Revid,
it searches for the most recent firmware with matching name (and if no
explicit firmware name is given, it just loads the most recent version of
the default firmware).
- if a valid Revid was found, it checks if the requested firmware name
differs from the currently running firmware (by comparing the name hashes).
If so, it searches for the most recent version of the new firmware and loads it.
- if the name of the firmware running is the same as the name of the requested
firmware, it just looks for an update (and eventually loads it).
Note that this file only deals with the configuration files, versioning, etc. The actual
low-level bootloader is in mblaster.c
*/
#include <stdio.h>
#include <stdlib.h>
#include <inttypes.h>
......@@ -16,36 +38,40 @@
#include "minilzo.h"
// directory (on the switch filesystem) containing the FPGA bitstreams
/* directory (on the switch filesystem) containing the FPGA bitstreams */
#define DEFAULT_FPGA_IMAGE_DIR "/wr/firmware"
static char fpga_image_dir[128] = DEFAULT_FPGA_IMAGE_DIR;
// firmware names for both FPGAs. Can be changed by calling shw_request_fpga_firmware()
static int force_new_firmware = 0;
static char *firmware_main = "board_test";
static char *firmware_clkb = "dmtd_pll_test";
/* Definition of Revid registers/magic value */
#define REVID_MAGIC_VALUE 0xdeadbeef
#define REVID_REG_MAGIC 0x0
#define REVID_REG_FW_HASH 0x8
#define REVID_REG_FW_REVISION 0x4
static char fpga_image_dir[128] = DEFAULT_FPGA_IMAGE_DIR;
/* firmware names for both FPGAs. Can be changed by calling shw_request_fpga_firmware().
When force_new_firmware != 0, the FW is reloaded without any Revid checks. */
static int force_new_firmware = 0;
static char *firmware_main = "board_test";
static char *firmware_clkb = "dmtd_pll_test";
/* Reads the Revid block from a given FPGA (Main/Timing). Returns 0 on success,
negative when no valid Revid has been found. The hash and revision id are stored
at (fw_hash) and (rev_id). */
static int get_fpga_revid(int fpga_id, uint32_t *fw_hash, uint32_t *rev_id)
{
if(fpga_id == FPGA_ID_MAIN)
{
// check the magic register value
/* Check the magic register value. */
if(_fpga_readl(FPGA_BASE_REVID + REVID_REG_MAGIC) != REVID_MAGIC_VALUE) return -1;
*fw_hash = _fpga_readl(FPGA_BASE_REVID + REVID_REG_FW_HASH);
*rev_id = _fpga_readl(FPGA_BASE_REVID + REVID_REG_FW_REVISION);
return 0;
} else if(fpga_id == FPGA_ID_CLKB) {
/* For the Timing FPGA, must use SPI-based access method */
if(shw_clkb_read_reg(CLKB_BASE_REVID + REVID_REG_MAGIC) != REVID_MAGIC_VALUE) return -1;
*fw_hash = shw_clkb_read_reg(CLKB_BASE_REVID + REVID_REG_FW_HASH);
......@@ -56,6 +82,7 @@ static int get_fpga_revid(int fpga_id, uint32_t *fw_hash, uint32_t *rev_id)
return -1;
}
/* Reads a 32-bit little endian word from a file (rval). Returns negative on failure, 0 on success. */
static int read_le32(FILE *f, uint32_t *rval)
{
#if __BYTE_ORDER==__LITTLE_ENDIAN
......@@ -65,6 +92,9 @@ static int read_le32(FILE *f, uint32_t *rval)
#endif
}
/* Reads a string from file, consisting of a 32-bit word containing its length followed by the
actual string. Uses strdup(), so the result must be freed after use. */
static char * read_string(FILE *f)
{
char buf[1024];
......@@ -82,6 +112,7 @@ static char * read_string(FILE *f)
return strdup(buf);
}
/* Reads the header of the FPGA bitstream file. Returns 0 on success. */
static int read_image_header(FILE *f, struct fpga_image_entry *ent)
{
struct fpga_image_header hdr;
......@@ -114,7 +145,7 @@ const char *expand_fpga_id(int fpga_id)
else return "unknown?";
}
/* Checks if the filesystem entry "name" is an ordinary file. */
static int stat_is_file(const char *name)
{
struct stat sb;
......@@ -123,7 +154,10 @@ static int stat_is_file(const char *name)
}
/* Searches for the most recent FPGA image for the FPGA (fpga_id) and firmware name (fw_name). (rev_id) and (fw_hash)
are the values read from the Revid block (when rev_id < 0, no Revid block was found). Returns the allocated FPGA
bitstream entry (ent_h) containing the contents of the config file with the most recent FW version and 0 if a newer
firmware has been found. If there's no newer firmware, returns a negative value. */
static int find_fpga_image(int fpga_id, const char *fw_name, int rev_id, uint32_t fw_hash, struct fpga_image_entry *ent_h)
{
FILE *f;
......@@ -159,7 +193,8 @@ static int find_fpga_image(int fpga_id, const char *fw_name, int rev_id, uint32_
if(!read_image_header(f, &ent))
{
TRACE(TRACE_INFO,"CheckFW: %s [%s] rev %d", ent.fpga_name, ent.fw_name, ent.revision);
if(rev_id) // name-based lookup
/* No firmware in the FPGA? Find one with matching fw_name and the most recent revision ID */
if(rev_id)
{
if(!strcasecmp(ent.fpga_name, expand_fpga_id(fpga_id))
&& !strcasecmp(ent.fw_name, fw_name))
......@@ -172,7 +207,8 @@ static int find_fpga_image(int fpga_id, const char *fw_name, int rev_id, uint32_
strncpy(latest_image_name, namebuf, 1024);
}
}
} else { // revid-based lookup: we look for newer firmware with matching revid
/* Firmware already present? Look for an update (matching hash, rev > current revision) */
} else {
if(ent.hash_reg == fw_hash && (int)ent.revision > max_rev)
{
......@@ -201,6 +237,7 @@ static int find_fpga_image(int fpga_id, const char *fw_name, int rev_id, uint32_
TRACE(TRACE_INFO, "Found most recent image: %s (FPGA: %s, firmware: %s, revision: %d)", latest_image_name, ent_h->fpga_name, ent_h->fw_name, ent_h->revision);
/* Read the contents of the compressed bitstream file. */
ent_h -> image_buf = shw_malloc(ent_h->compressed_size);
fread(ent_h->image_buf, 1, ent_h->compressed_size, f);
fclose(f);
......@@ -208,6 +245,7 @@ static int find_fpga_image(int fpga_id, const char *fw_name, int rev_id, uint32_
return 0;
}
/* Uncompresses the bitstream from (ent) and executes the low-level loader for (fpga_id). */
static int uncompress_and_boot_fpga(int fpga_id, struct fpga_image_entry *ent)
{
uint8_t *bitstream;
......@@ -237,9 +275,7 @@ static int uncompress_and_boot_fpga(int fpga_id, struct fpga_image_entry *ent)
}
/* Boots the FPGA (fpga_id). Returns 0 on success, negative on failure. */
int shw_boot_fpga(int fpga_id)
{
char *fw_name;
......@@ -253,6 +289,7 @@ int shw_boot_fpga(int fpga_id)
TRACE(TRACE_INFO, "%s: reading REV_ID...", fpga_name);
/* Try to read Revid block */
if(get_fpga_revid (fpga_id, &fw_hash, (uint32_t *)&rev_id) < 0)
rev_id = -1;
......@@ -264,31 +301,33 @@ int shw_boot_fpga(int fpga_id)
fw_name = firmware_clkb; break;
}
/* No Revid found or unconditional reboot */
if(rev_id < 0 || force_new_firmware)
{
TRACE(TRACE_INFO, "%s: invalid REV_ID or forced firmware update. Trying to boot the FPGA with the firmware: %s", fpga_name, fw_name)
rc = find_fpga_image(fpga_id, fw_name, -1, 0, &ent);
rc = find_fpga_image(fpga_id, fw_name, -1, 0, &ent);
if(rc < 0) {
TRACE(TRACE_FATAL, "%s: unable to find any image for FPGA!", fpga_name);
shw_exit_fatal();
return -1;
TRACE(TRACE_FATAL, "%s: unable to find any image for FPGA!", fpga_name);
shw_exit_fatal();
return -1;
}
return uncompress_and_boot_fpga(fpga_id, &ent);
} else {
TRACE(TRACE_INFO, "%s: got REV_ID (rev = %d, hash = %x). Looking for newer firmware", fpga_name, rev_id, fw_hash);
rc = find_fpga_image(fpga_id, fw_name, rev_id, fw_hash, &ent);
if(rc < 0) {
TRACE(TRACE_INFO, "%s: no more recent image found", fpga_name);
return 0;
} else return uncompress_and_boot_fpga(fpga_id, &ent);
} else { /* Look for an update */
TRACE(TRACE_INFO, "%s: got REV_ID (rev = %d, hash = %x). Looking for newer firmware", fpga_name, rev_id, fw_hash);
rc = find_fpga_image(fpga_id, fw_name, rev_id, fw_hash, &ent);
if(rc < 0) {
TRACE(TRACE_INFO, "%s: no more recent image found", fpga_name);
return 0;
} else return uncompress_and_boot_fpga(fpga_id, &ent);
}
return -1;
}
/* Requests the firmware for a given FPGA to be loaded during libswitchhw initialization.
Executed by the HAL prior to initializing the libswitchhw. */
int shw_request_fpga_firmware(int fpga_id, const char *firmware_name)
{
switch(fpga_id)
......@@ -301,6 +340,7 @@ int shw_request_fpga_firmware(int fpga_id, const char *firmware_name)
return 0;
}
/* Sets the path to the directory with FPGA images */
int shw_set_fpga_firmware_path(const char *path)
{
strncpy(fpga_image_dir, path, sizeof(fpga_image_dir));
......@@ -308,14 +348,15 @@ int shw_set_fpga_firmware_path(const char *path)
return 0;
}
/* Forces an unconditional FPGA reload. */
void shw_fpga_force_firmware_reload()
{
force_new_firmware = 1;
}
/* Initializes the FPGA bootloader (currently just calls the low-level init function) */
int shw_fpgaboot_init()
{
mblaster_init();
//strncpy(fpga_image_dir, DEFAULT_FPGA_IMAGE_DIR, sizeof(fpga_image_dir));
return 0;
}
/* Helper PLL driver */
/* To be removed and replaced by the SoftPLL in V3 */
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
......@@ -8,18 +10,21 @@
#define FREQ_ERROR_FRACBITS 7
#define DEFAULT_PD_GATE_SEL HPLL_PD_GATE_16K // Phase detector gating = 16384 fbck cycles
#define DEFAULT_FD_GATE_SEL 3 // Frequency gating: 131072 fbck cycles
/* Default values for some HPLL parameters:
Phase detector gating = 16384 fbck cycles */
#define DEFAULT_PD_GATE_SEL HPLL_PD_GATE_16K
/* Frequency measure ment gating: 131072 fbck cycles */
#define DEFAULT_FD_GATE_SEL 3
/* Lock detection thresholds */
#define DEFAULT_LD_SAMPLES 250
#define DEFAULT_LD_THRESHOLD 100
/* Macros for converting floating point PI gains to the fixed point format
used internally by the HPLL */
#define FLOAT_TO_FB_COEF(x) ((int)((x) * (32.0 * 16.0 )))
#define FLOAT_TO_PB_COEF(x) ((int)((x) * (32.0 * 16.0 )))
// 0.00384, 0.0384, // target phase Ki/Kp
// 20.0 , 8.0, // freq Ki/Kp
static const hpll_params_t default_hpll_params = {
20.0 , 8.0, // freq Ki/Kp
0.256, 6.40, // target phase Ki/Kp
......@@ -34,6 +39,10 @@ static const hpll_params_t default_hpll_params = {
0, 0
};
/* current state of the HPLL */
static hpll_params_t cur_params;
/* Wrappers for accessing HPLL regs */
static inline uint32_t hpll_read(uint32_t reg)
{
return shw_clkb_read_reg(CLKB_BASE_HPLL + reg);
......@@ -44,24 +53,17 @@ static inline void hpll_write(uint32_t reg, uint32_t value)
shw_clkb_write_reg(CLKB_BASE_HPLL + reg, value);
}
/* static void hpll_poll_rfifo() */
/* { */
/* while(1) */
/* { */
/* if((hpll_read(HPLL_REG_RFIFO_CSR) & HPLL_RFIFO_CSR_EMPTY) || rfifo_nmeas >= MAX_MEAS) return; */
/* rfifo_record[rfifo_nmeas++] = hpll_read(HPLL_REG_RFIFO_R0); */
/* } */
/* } */
/* Linear interpolation at (step) step out of (nsteps) between (start) and (end) */
static double interpolate(double start, double end, int step, int nsteps)
{
double k = (double)step / (double)(nsteps - 1);
return start * (1.0-k) + k * end;
}
static hpll_params_t cur_params;
/* Ramps the HPLL gain to a new value. It doesn't like step changes int the coefficients,
so they have to be slowly adjusted until they reach the required values. */
void shw_hpll_ramp_gain(double kp_new, double ki_new)
{
uint64_t init_tics = shw_get_tics();
......@@ -73,21 +75,15 @@ void shw_hpll_ramp_gain(double kp_new, double ki_new)
for(step = 0; step < cur_params.phase_gain_steps; step++)
{
// if(shw_get_tics() - init_tics > (uint64_step * cur_params.phase_gain_step_delay)
{
double kp, ki;
kp = interpolate(cur_params.kp_phase_cur,cur_params.kp_phase, step, cur_params.phase_gain_steps);
ki = interpolate(cur_params.ki_phase_cur,cur_params.ki_phase, step, cur_params.phase_gain_steps);
// TRACE(TRACE_INFO, "ramping down the HPLL gain (Kp = %.5f Ki = %.5f)", kp, ki);
hpll_write(HPLL_REG_PBGR,
HPLL_PBGR_P_KP_W(FLOAT_TO_FB_COEF(kp)) |
HPLL_PBGR_P_KI_W(FLOAT_TO_FB_COEF(ki)));
// } else {
usleep(1000);
}
}
cur_params.kp_phase_cur = cur_params.kp_phase;
......@@ -95,7 +91,7 @@ void shw_hpll_ramp_gain(double kp_new, double ki_new)
}
/* Loads the state of the HPLL from (params) structure */
void shw_hpll_load_regs(const hpll_params_t *params)
{
int target_freq_err;
......@@ -155,17 +151,13 @@ void shw_hpll_load_regs(const hpll_params_t *params)
HPLL_PCR_REFSEL_W(params->ref_sel)); // reference select
// init_tics = shw_get_tics();
memcpy(&cur_params, params, sizeof(hpll_params_t));
cur_params.kp_phase_cur = params->kp_phase;
cur_params.ki_phase_cur = params->ki_phase;
// shw_hpll_ramp_gain(0.1, 0.00384);
shw_hpll_ramp_gain(0.0384, 0.00384);
shw_hpll_ramp_gain(0.0384, 0.00384); /* fixme */
}
void shw_hpll_reset()
......@@ -175,16 +167,6 @@ void shw_hpll_reset()
hpll_write(HPLL_REG_PCR, pcr_val);
}
/*void shw_hpll_set_reference(int ref_clk)
{
uint32_t pcr_val = hpll_read(HPLL_REG_PCR);
pcr_val &= ~HPLL_PCR_REFSEL_MASK;
pcr_val |= HPLL_PCR_REFSEL_W(ref_clk);
hpll_write(HPLL_REG_PCR, pcr_val);
}*/
int shw_hpll_check_lock()
{
uint32_t psr;
......@@ -196,17 +178,9 @@ int shw_hpll_check_lock()
hpll_write(HPLL_REG_PSR, HPLL_PSR_LOCK_LOST); // clear loss-of-lock bit
}
printf("PSR %x\n",psr & (HPLL_PSR_FREQ_LK | HPLL_PSR_PHASE_LK));
printf("PCR %x\n", hpll_read(HPLL_REG_PCR));
//
// return 1;
return (psr & HPLL_PSR_FREQ_LK) && (psr & HPLL_PSR_PHASE_LK);
return (psr & HPLL_PSR_FREQ_LK) && (psr & HPLL_PSR_PHASE_LK);
}
int shw_hpll_get_divider()
{
return cur_params.N;
......@@ -221,6 +195,7 @@ int shw_hpll_init()
while(!shw_hpll_check_lock()) usleep(100000);
}
/* Sets the HPLL reference input to network I/F (if_name) and re-initializes the HPLL. */
int shw_hpll_switch_reference(const char *if_name)
{
hpll_params_t my_params;
......
/* Step-by-step switch hardware initialization */
#include <stdio.h>
#include <stdlib.h>
......@@ -5,29 +7,39 @@
#define assert_init(proc) { int ret; if((ret = proc) < 0) return ret; }
int shw_init()
{
/* Map the the FPGA memory space */
assert_init(shw_fpga_mmap_init());
/* Map the CPU GPIO memory space */
assert_init(shw_pio_mmap_init());
assert_init(shw_main_fpga_init());
/* Initialize the AD9516 and the clock distribution. Now we can start accessing the FPGAs. */
assert_init(shw_ad9516_init());
/* Initialize the main FPGA */
assert_init(shw_main_fpga_init());
/* Sets up the directions of all CPU GPIO pins */
assert_init(shw_pio_configure_all_cpu_pins());
/* Initialize the bootloader and try to boot up the Main FPGA. */
assert_init(shw_fpgaboot_init());
assert_init(shw_boot_fpga(FPGA_ID_MAIN));
/* Initialize the main FPGA and its GPIO controller */
assert_init(shw_main_fpga_init());
assert_init(shw_pio_configure_all_fpga_pins());
assert_init(shw_clkb_init_cmi()); // Initialize the CMI link prior to booting the CLKB FPGA, so the FPGA bootloader could check the REVID
/* Initialize the CMI link prior to booting the CLKB FPGA, so the FPGA bootloader could check the REVID. */
assert_init(shw_clkb_init_cmi());
/* Boot up and init the Timing FPGA */
assert_init(shw_boot_fpga(FPGA_ID_CLKB));
assert_init(shw_clkb_init());
assert_init(shw_clkb_init());
/* Start-up the PLLs. */
assert_init(shw_hpll_init());
assert_init(shw_dmpll_init());
/* Initialize the calibrator (requires the DMTD clock to be operational) */
assert_init(shw_cal_init());
/* Start-up the PPS generator */
assert_init(shw_pps_gen_init());
/* ... and the SPI link with the watchdog */
assert_init(shw_watchdog_init());
// shw_fpga_boot();
TRACE(TRACE_INFO, "HW initialization done!");
}
......
/* Altera's MicroBlaster code for programming Cyclone3 FPGAs in Passive Seral mode */
#include <stdio.h>
#include <stdlib.h>
#include <inttypes.h>
......
/* GPIO pin definitions */
#include <hw/pio.h>
#define LED_OFF 0
......
/* PPS Generator driver */
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
......@@ -8,6 +10,7 @@
#include <hw/switch_hw.h>
#include <hw/trace.h>
/* Default width (in 8ns units) of the pulses on the PPS output */
#define PPS_WIDTH 100000
int shw_pps_gen_init()
......@@ -27,6 +30,7 @@ int shw_pps_gen_init()
_fpga_writel(FPGA_BASE_PPS_GEN + PPSG_REG_CR, cr);
}
/* Adjusts the nanosecond (125 MHz refclk cycle) counter by atomically adding (how_much). */
int shw_pps_gen_adjust_nsec(int32_t how_much)
{
uint32_t cr;
......@@ -40,6 +44,7 @@ int shw_pps_gen_adjust_nsec(int32_t how_much)
_fpga_writel(FPGA_BASE_PPS_GEN + PPSG_REG_CR, PPSG_CR_CNT_EN | PPSG_CR_PWIDTH_W(PPS_WIDTH) | PPSG_CR_CNT_ADJ);
}
/* Adjusts the seconds (UTC/TAI) counter by adding (how_much) in an atomic way */
int shw_pps_gen_adjust_utc(int64_t how_much)
{
uint32_t cr;
......@@ -51,6 +56,7 @@ int shw_pps_gen_adjust_utc(int64_t how_much)
_fpga_writel(FPGA_BASE_PPS_GEN + PPSG_REG_CR, PPSG_CR_CNT_EN | PPSG_CR_PWIDTH_W(PPS_WIDTH) | PPSG_CR_CNT_ADJ);
}
/* Returns 1 when the adjustment operation is not yet finished */
int shw_pps_gen_busy()
{
return _fpga_readl(FPGA_BASE_PPS_GEN + PPSG_REG_CR) & PPSG_CR_CNT_ADJ ? 0 : 1;
......
/* Some debug/tracing stuff */
#include <stdio.h>
#include <stdarg.h>
#include <string.h>
......
......@@ -14,6 +14,10 @@ static const pio_pin_t PIN_cs[] = {{PIOB, 15, PIO_MODE_GPIO, PIO_OUT_1}, {0}};
static const pio_pin_t PIN_sdout[] = {{PIOB, 12, PIO_MODE_GPIO, PIO_OUT_1}, {0}};
static const pio_pin_t PIN_sdin[] = {{PIOB, 13, PIO_MODE_GPIO, PIO_IN}, {0}};
#define WD_CMD_SET_LED 1
#define WD_CMD_FEEDBACK 2
#define WD_CMD_GET_UNIQUE_ID 3
static inline void spi_cs(int val)
{
shw_pio_set(PIN_cs, val);
......@@ -25,38 +29,38 @@ static inline uint8_t spi_txrx(uint8_t x)
uint8_t rval = 0;
for(i=0;i<8;i++)
{
shw_udelay(50);
shw_udelay(100);
shw_pio_set(PIN_sdout, x&0x80 ? 1 :0);
shw_udelay(50);
shw_udelay(100);
shw_pio_set0(PIN_sck);
shw_udelay(50);
shw_udelay(100);
rval <<= 1;
if(shw_pio_get(PIN_sdin)) rval |= 1;
shw_udelay(50);
shw_pio_set1(PIN_sck);
shw_udelay(50);
shw_udelay(100);
shw_pio_set1(PIN_sck);
shw_udelay(100);
x<<=1;
}
return rval;
}
/* SPI transfer of (size) 8-bit words to/from the watchdog */
static void wd_spi_xfer(uint8_t *buf, int size)
{
int i;
printf("Xfer: %d bytes\n", size);
spi_cs(0);
for(i=0;i<size;i++)
buf[i]=spi_txrx(buf[i]);
spi_cs(1);
shw_udelay(50);
shw_udelay(500);
}
#define WD_CMD_SET_LED 1
#define WD_CMD_FEEDBACK 2
/* Sets the status of the mini-backplane (V2) leds */
void shw_mbl_set_leds(int port, int led, int mode)
{
uint8_t cmd_buf[4];
......@@ -65,7 +69,7 @@ void shw_mbl_set_leds(int port, int led, int mode)
cmd_buf[1] = port;
cmd_buf[2] = led;
cmd_buf[3] = mode;
wd_spi_xfer(cmd_buf, 4);
}
......@@ -74,12 +78,32 @@ void shw_mbl_cal_feedback(int port, int cmd)
{
uint8_t cmd_buf[4];
cmd_buf[0] = WD_CMD_FEEDBACK;
TRACE(TRACE_INFO, "EnableFeedback: port %d cmd %d", port, cmd);
/* cmd_buf[0] = WD_CMD_FEEDBACK;
cmd_buf[1] = port;
cmd_buf[2] = cmd;
cmd_buf[3] = 0;*/
wd_spi_xfer(cmd_buf, 4);
}
int shw_get_board_id(uint8_t *id)
{
int i;
uint8_t cmd_buf[8];
cmd_buf[0] = WD_CMD_GET_UNIQUE_ID;
cmd_buf[1] = 0;
cmd_buf[2] = 0;
cmd_buf[3] = 0;
for(i=0;i<8;i++) id[i] = 0xff;
wd_spi_xfer(cmd_buf, 4);
shw_udelay(10000);
wd_spi_xfer(id, 8);
return 0;
}
int shw_watchdog_init()
......
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