Commit 80bf6284 authored by Grzegorz Daniluk's avatar Grzegorz Daniluk

testing new softpll

parent 499cc23e
PLATFORM = lm32
OBJS_WRC = wrc_main.o dev/uart.o dev/endpoint.o dev/minic.o dev/pps_gen.o dev/syscon.o dev/i2c.o dev/eeprom.o dev/onewire.o dev/softpll.o lib/mprintf.o monitor/monitor.o dev/ep_pfilter.o dev/dna.o
OBJS_WRC = wrc_main.o dev/uart.o dev/endpoint.o dev/syscon.o dev/softpll_ng.o lib/mprintf.o dev/ep_pfilter.o dev/dna.o
D = ptp-noposix
PTPD_CFLAGS = -ffreestanding -DPTPD_FREESTANDING -DWRPC_EXTRA_SLIM -DPTPD_MSBF -DPTPD_DBG
......@@ -9,20 +9,20 @@ PTPD_CFLAGS += -Wall -ggdb -I$D/wrsw_hal \
-include $D/compat.h -include $D/PTPWRd/dep/trace.h -include $D/libposix/ptpd-wrappers.h
PTPD_CFLAGS += -DPTPD_NO_DAEMON -DNEW_SINGLE_WRFSM -DPTPD_TRACE_MASK=0
OBJS_PTPD = $D/PTPWRd/arith.o
OBJS_PTPD += $D/PTPWRd/bmc.o
OBJS_PTPD += $D/PTPWRd/dep/msg.o
OBJS_PTPD += $D/PTPWRd/dep/net.o
OBJS_PTPD += $D/PTPWRd/dep/servo.o
OBJS_PTPD += $D/PTPWRd/dep/sys.o
OBJS_PTPD += $D/PTPWRd/dep/timer.o
OBJS_PTPD += $D/PTPWRd/dep/wr_servo.o
OBJS_PTPD += $D/PTPWRd/protocol.o
OBJS_PTPD += $D/PTPWRd/wr_protocol.o
OBJS_PTPD_FREE = $D/libposix/freestanding-startup.o
OBJS_PTPD_FREE += $D/libposix/freestanding-display.o
OBJS_PTPD_FREE += $D/libposix/wr_nolibs.o
OBJS_PTPD_FREE += $D/libposix/freestanding-wrapper.o
#OBJS_PTPD = $D/PTPWRd/arith.o
#OBJS_PTPD += $D/PTPWRd/bmc.o
#OBJS_PTPD += $D/PTPWRd/dep/msg.o
#OBJS_PTPD += $D/PTPWRd/dep/net.o
#OBJS_PTPD += $D/PTPWRd/dep/servo.o
#OBJS_PTPD += $D/PTPWRd/dep/sys.o
#OBJS_PTPD += $D/PTPWRd/dep/timer.o
#OBJS_PTPD += $D/PTPWRd/dep/wr_servo.o
#OBJS_PTPD += $D/PTPWRd/protocol.o
#OBJS_PTPD += $D/PTPWRd/wr_protocol.o
#OBJS_PTPD_FREE = $D/libposix/freestanding-startup.o
#OBJS_PTPD_FREE += $D/libposix/freestanding-display.o
#OBJS_PTPD_FREE += $D/libposix/wr_nolibs.o
#OBJS_PTPD_FREE += $D/libposix/freestanding-wrapper.o
ifeq ($(PLATFORM), zpu)
CFLAGS_PLATFORM = -abel -Wl,--relax -Wl,--gc-sections
......
#include <stdio.h>
#include <stdlib.h>
#include "board.h"
#include "timer.h"
#include "trace.h"
#include "hw/softpll_regs.h"
#include "irq.h"
volatile int irq_count = 0,eee,yyy,py;
static volatile struct SPLL_WB *SPLL = (volatile struct SPLL_WB *) BASE_SOFTPLL;
/* The includes below contain code (not only declarations) to enable the compiler
to inline functions where necessary and save some CPU cycles */
#include "spll_defs.h"
#include "spll_common.h"
#include "spll_debug.h"
#include "spll_helper.h"
#include "spll_main.h"
#include "spll_ptracker.h"
static struct spll_helper_state helper;
static struct spll_main_state mpll;
void _irq_entry()
{
volatile uint32_t trr;
int src = -1, tag;
if(! (SPLL->CSR & SPLL_TRR_CSR_EMPTY))
{
trr = SPLL->TRR_R0;
src = SPLL_TRR_R0_CHAN_ID_R(trr);
tag = SPLL_TRR_R0_VALUE_R(trr);
helper_update(&helper, tag, src);
mpll_update(&mpll, tag, src);
}
irq_count++;
//TRACE_DEV("%u\n", irq_count);
clear_irq();
}
void spll_init()
{
volatile int dummy;
disable_irq();
n_chan_ref = SPLL_CSR_N_REF_R(SPLL->CSR);
n_chan_out = SPLL_CSR_N_OUT_R(SPLL->CSR);
TRACE_DEV("SPLL_Init: %d ref channels, %d out channels\n", n_chan_ref, n_chan_out);
SPLL->DAC_HPLL = 0;
TRACE_DEV("delay on\n");
timer_delay(1000);
//GD timer_delay(100000);
//GD
helper_init(&helper, 1);
timer_delay(1000);
TRACE_DEV("delay off\n");
SPLL->CSR= 0 ;
SPLL->OCER = 0;
SPLL->RCER = 0;
SPLL->RCGER = 0;
SPLL->DCCR = 0;
SPLL->DEGLITCH_THR = 1000;
while(! (SPLL->TRR_CSR & SPLL_TRR_CSR_EMPTY)) dummy = SPLL->TRR_R0;
dummy = SPLL->PER_HPLL;
SPLL->EIC_IER = 1;
}
int spll_check_lock()
{
return helper.ld.locked ? 1 : 0;
}
#define CHAN_TCXO 8
void spll_test()
{
int i = 0;
volatile int dummy;
TRACE_DEV("running spll_init\n");
spll_init();
TRACE_DEV("spll_init\n");
helper_start(&helper);
TRACE_DEV("helper start\n");
mpll_init(&mpll, 0, 0); //CHAN_TCXO);
enable_irq();
TRACE_DEV("enable irq\n");
// mpll_init(&mpll, 0, CHAN_TCXO);
while(!helper.ld.locked) ;//TRACE("%d\n", helper.phase.ld.locked);
TRACE_DEV("Helper locked, starting main\n");
mpll_start(&mpll);
}
/*
#define CHAN_AUX 7
#define CHAN_EXT 6
int spll_gm_measure_ext_phase()
{
SPLL->CSR = 0;
SPLL->DCCR = SPLL_DCCR_GATE_DIV_W(25);
SPLL->RCGER = (1<<CHAN_AUX);
SPLL->RCGER = (1<<CHAN_EXT);
}
*/
This diff is collapsed.
/*
White Rabbit Softcore PLL (SoftPLL) - common definitions
Copyright (c) 2010 - 2012 CERN / BE-CO-HT (Tomasz Włostowski)
Licensed under LGPL 2.1.
*/
/* Number of reference/output channels. Currently we support only one SoftPLL instantiation per project,
so these can remain static. */
static int n_chan_ref, n_chan_out;
/* PI regulator state */
typedef struct {
int ki, kp; /* integral and proportional gains (1<<PI_FRACBITS == 1.0f) */
int integrator; /* current integrator value */
int bias; /* DC offset always added to the output */
int anti_windup; /* when non-zero, anti-windup is enabled */
int y_min; /* min/max output range, used by clapming and antiwindup algorithms */
int y_max;
int x, y; /* Current input (x) and output value (y) */
} spll_pi_t;
/* lock detector state */
typedef struct {
int lock_cnt; /* Lock sample counter */
int lock_samples; /* Number of samples below the (threshold) to assume that we are locked */
int delock_samples; /* Accumulated number of samples that causes the PLL go get out of lock.
delock_samples < lock_samples. */
int threshold; /* Error threshold */
int locked; /* Non-zero: we are locked */
} spll_lock_det_t;
/* Processes a single sample (x) with PI control algorithm (pi). Returns the value (y) to
drive the actuator. */
static inline int pi_update(spll_pi_t *pi, int x)
{
int i_new, y;
pi->x = x;
i_new = pi->integrator + x;
y = ((i_new * pi->ki + x * pi->kp) >> PI_FRACBITS) + pi->bias;
/* clamping (output has to be in <y_min, y_max>) and anti-windup:
stop the integrator if the output is already out of range and the output
is going further away from y_min/y_max. */
if(y < pi->y_min)
{
y = pi->y_min;
if((pi->anti_windup && (i_new > pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new;
} else if (y > pi->y_max) {
y = pi->y_max;
if((pi->anti_windup && (i_new < pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new;
} else /* No antiwindup/clamping? */
pi->integrator = i_new;
pi->y = y;
return y;
}
/* initializes the PI controller state. Currently almost a stub. */
static inline void pi_init(spll_pi_t *pi)
{
pi->integrator = 0;
}
/* Lock detector state machine. Takes an error sample (y) and checks if it's withing an acceptable range
(i.e. <-ld.threshold, ld.threshold>. If it has been inside the range for (ld.lock_samples) cyckes, the
FSM assumes the PLL is locked.
Return value:
0: PLL not locked
1: PLL locked
-1: PLL just got out of lock
*/
static inline int ld_update(spll_lock_det_t *ld, int y)
{
if (abs(y) <= ld->threshold)
{
if(ld->lock_cnt < ld->lock_samples)
ld->lock_cnt++;
if(ld->lock_cnt == ld->lock_samples)
{
ld->locked = 1;
return 1;
}
} else {
if(ld->lock_cnt > ld->delock_samples)
ld->lock_cnt--;
if(ld->lock_cnt == ld->delock_samples)
{
ld->lock_cnt= 0;
ld->locked = 0;
return -1;
}
}
return ld->locked;
}
static void ld_init(spll_lock_det_t *ld)
{
ld->locked = 0;
ld->lock_cnt = 0;
}
/* Enables/disables DDMTD tag generation on a given (channel).
Channels (0 ... n_chan_ref - 1) are the reference channels (e.g. transceivers' RX clocks
or a local reference)
Channels (n_chan_ref ... n_chan_out + n_chan_ref-1) are the output channels (local voltage
controlled oscillators). One output (usually the first one) is always used to drive the
oscillator which produces the reference clock for the transceiver. Other outputs can be
used to discipline external oscillators (e.g. on FMCs).
*/
static void spll_enable_tagger(int channel, int enable)
{
if(channel >= n_chan_ref) /* Output channel? */
{
if(enable)
SPLL->OCER |= 1<< (channel - n_chan_ref);
else
SPLL->OCER &= ~ (1<< (channel - n_chan_ref));
} else { /* Reference channel */
if(enable)
SPLL->RCER |= 1<<channel;
else
SPLL->RCER &= ~ (1<<channel);
}
TRACE_DEV("%s: ch %d, OCER 0x%x, RCER 0x%x\n", __FUNCTION__, channel, SPLL->OCER, SPLL->RCER);
}
/*
White Rabbit Softcore PLL (SoftPLL) - debugging/diagnostic interface
The so-called debug inteface is a large, interrupt-driven FIFO which passes
various realtime parameters (e.g. error value, tags, DAC drive) to an external
application where they can be analyzed. It's very useful for optimizing PI coefficients
and/or lock thresholds.
The data is organized as a stream of samples, where each sample can store a number of parameters.
For example, a stream samples with Y and ERR parameters can be used to evaluate the impact of
integral/proportional gains on the response of the system.
*/
#define DBG_Y 0
#define DBG_ERR 1
#define DBG_TAG 2
#define DBG_REF 5
#define DBG_PERIOD 3
#define DBG_EVENT 4
#define DBG_SAMPLE_ID 6
#define DBG_HELPER 0x20 /* Sample source: Helper PLL */
#define DBG_MAIN 0x0 /* ... : Main PLL */
#define DBG_EVT_START 1 /* PLL has just started */
#define DBG_EVT_LOCKED 2 /* PLL has just become locked */
/* Writes a parameter to the debug FIFO.
value: value of the parameter.
what: type of the parameter and its' source. For example,
- DBG_ERR | DBG_HELPER means that (value) contains the phase error of the helper PLL.
- DBG_EVENT indicates an asynchronous event. (value) must contain the event type (DBG_EVT_xxx)
last: when non-zero, indicates the last parameter in a sample.
*/
static inline void spll_debug(int what, int value, int last)
{
SPLL->DFR_SPLL = (last ? 0x80000000 : 0) | (value & 0xffffff) | (what << 24);
}
/*
White Rabbit Softcore PLL (SoftPLL) - common definitions
WARNING: These parameters must be in sync with the generics of the HDL instantiation of wr_softpll_ng.
*/
#include <stdio.h>
/* Reference clock frequency, in [Hz] */
#define CLOCK_FREQ 62500000
/* Number of bits in phase tags generated by the DMTDs. Used to sign-extend the tags.
Corresponding VHDL generic: g_tag_bits. */
#define TAG_BITS 22
/* Helper PLL N divider (2**(-N) is the frequency offset). Must be big enough
to offer reasonable PLL bandwidth, and small enough so the offset frequency fits
within the tuning range of the helper oscillator. */
#define HPLL_N 14
/* Fractional bits in PI controller coefficients */
#define PI_FRACBITS 12
/* Max. allowed number of reference channels. Can be used to tweak memory usage. */
#define MAX_CHAN_REF 7
/* Max. allowed number of output channels */
#define MAX_CHAN_OUT 1
/* Max. allowed number of phase trackers */
#define MAX_TRACKERS 6
/* Number of bits of the DAC(s) driving the oscillator(s). Must be the same for
all the outputs. */
#define DAC_BITS 16
\ No newline at end of file
/* State of the Helper PLL producing a clock (clk_dmtd_i) which is
slightly offset in frequency from the recovered/reference clock (clk_rx_i or clk_ref_i), so the
Main PLL can use it to perform linear phase measurements.
*/
#define SPLL_LOCKED 1
#define SPLL_LOCKING 0
#define HELPER_TAG_WRAPAROUND 100000000
/* Maximum abs value of the phase error. If the error is bigger, it's clamped to this value. */
#define HELPER_ERROR_CLAMP 150000
struct spll_helper_state {
int p_adder; /* anti wrap-around adder */
int p_setpoint, tag_d0;
int ref_src;
int sample_n;
spll_pi_t pi;
spll_lock_det_t ld;
};
static void helper_init(struct spll_helper_state *s, int ref_channel)
{
/* Phase branch PI controller */
s->pi.y_min = 5;
s->pi.y_max = (1 << DAC_BITS) - 5;
s->pi.kp = (int)(0.3 * 32.0 * 16.0);
s->pi.ki = (int)(0.03 * 32.0 * 3.0);
s->pi.anti_windup = 1;
/* Set the bias to the upper end of tuning range. This is to ensure that
the HPLL will always lock on positive frequency offset. */
s->pi.bias = s->pi.y_max;
/* Phase branch lock detection */
s->ld.threshold = 200;
s->ld.lock_samples = 1000;
s->ld.delock_samples = 900;
s->ref_src = ref_channel;
s->p_setpoint = 0;
s->p_adder = 0;
s->sample_n = 0;
s->tag_d0 = -1;
pi_init(&s->pi);
ld_init(&s->ld);
}
static int helper_update(struct spll_helper_state *s, int tag, int source)
{
int err, y;
if(source == s->ref_src)
{
spll_debug(DBG_TAG | DBG_HELPER, tag, 0);
spll_debug(DBG_REF | DBG_HELPER, s->p_setpoint, 0);
if(s->tag_d0 < 0)
{
s->p_setpoint = tag;
s->tag_d0 = tag;
return SPLL_LOCKING;
}
if(s->tag_d0 > tag)
s->p_adder += (1<<TAG_BITS);
err = (tag + s->p_adder) - s->p_setpoint;
TRACE_DEV("hpll 1err=%d\n", err);
if(HELPER_ERROR_CLAMP)
{
if(err < -HELPER_ERROR_CLAMP) err = -HELPER_ERROR_CLAMP;
if(err > HELPER_ERROR_CLAMP) err = HELPER_ERROR_CLAMP;
}
//GD
//TRACE_DEV("hpll 2err=%d\n", err);
if((tag + s->p_adder) > HELPER_TAG_WRAPAROUND && s->p_setpoint > HELPER_TAG_WRAPAROUND)
{
s->p_adder -= HELPER_TAG_WRAPAROUND;
s->p_setpoint -= HELPER_TAG_WRAPAROUND;
}
s->p_setpoint += (1<<HPLL_N);
s->tag_d0 = tag;
y = pi_update(&s->pi, err);
SPLL->DAC_HPLL = y;
spll_debug(DBG_SAMPLE_ID | DBG_HELPER, s->sample_n++, 0);
spll_debug(DBG_Y | DBG_HELPER, y, 0);
spll_debug(DBG_ERR | DBG_HELPER, err, 1);
if(ld_update(&s->ld, err))
return SPLL_LOCKED;
}
return SPLL_LOCKING;
}
static void helper_start(struct spll_helper_state *s)
{
spll_enable_tagger(s->ref_src, 1);
spll_debug(DBG_EVENT | DBG_HELPER, DBG_EVT_START, 1);
}
#define MPLL_TAG_WRAPAROUND 100000000
/* State of the Main PLL */
struct spll_main_state {
int state;
spll_pi_t pi;
spll_lock_det_t ld;
int adder_ref, adder_out, tag_ref, tag_out, tag_ref_d, tag_out_d;
int phase_shift_target;
int phase_shift_current;
int id_ref, id_out; /* IDs of the reference and the output channel */
int sample_n;
};
static void mpll_init(struct spll_main_state *s, int id_ref, int id_out)
{
/* Frequency branch PI controller */
s->pi.y_min = 5;
s->pi.y_max = 65530;
s->pi.anti_windup = 1;
s->pi.bias = 65000;
s->pi.kp = 1100;
s->pi.ki = 30;
/* Freqency branch lock detection */
s->ld.threshold = 120;
s->ld.lock_samples = 400;
s->ld.delock_samples = 390;
s->adder_ref = s->adder_out = 0;
s->tag_ref = -1;
s->tag_out = -1;
s->tag_ref_d = -1;
s->tag_out_d = -1;
s->phase_shift_target = 0;
s->phase_shift_current = 0;
s->id_ref = id_ref;
s->id_out = id_out;
s->sample_n= 0;
pi_init(&s->pi);
ld_init(&s->ld);
}
static void mpll_start(struct spll_main_state *s)
{
spll_enable_tagger(s->id_ref, 1);
spll_enable_tagger(s->id_out, 1);
spll_debug(DBG_EVENT | DBG_MAIN, DBG_EVT_START, 1);
}
static int mpll_update(struct spll_main_state *s, int tag, int source)
{
int err, y, tmp;
if(source == s->id_ref)
s->tag_ref = tag;
if(source == s->id_out)
s->tag_out = tag;
if(s->tag_ref >= 0 && s->tag_out >= 0)
{
if(s->tag_ref_d >= 0 && s->tag_ref_d > s->tag_ref)
s->adder_ref += (1<<TAG_BITS);
if(s->tag_out_d >= 0 && s->tag_out_d > s->tag_out)
s->adder_out += (1<<TAG_BITS);
s->tag_ref_d = s->tag_ref;
s->tag_out_d = s->tag_out;
err = s->adder_ref + s->tag_ref - s->adder_out - s->tag_out;
if(s->adder_ref > MPLL_TAG_WRAPAROUND && s->adder_out > MPLL_TAG_WRAPAROUND)
{
s->adder_ref -= MPLL_TAG_WRAPAROUND;
s->adder_out -= MPLL_TAG_WRAPAROUND;
}
y = pi_update(&s->pi, err);
SPLL->DAC_MAIN = SPLL_DAC_MAIN_VALUE_W(y) | SPLL_DAC_MAIN_DAC_SEL_W(s->id_out);
spll_debug(DBG_MAIN | DBG_REF, s->tag_ref, 0);
spll_debug(DBG_MAIN | DBG_TAG, s->tag_out, 0);
spll_debug(DBG_MAIN | DBG_ERR, err, 0);
spll_debug(DBG_MAIN | DBG_SAMPLE_ID, s->sample_n++, 0);
spll_debug(DBG_MAIN | DBG_Y, y, 1);
s->tag_out = -1;
s->tag_ref = -1;
if(s->phase_shift_current < s->phase_shift_target)
{
s->phase_shift_current++;
s->adder_ref++;
} else if(s->phase_shift_current > s->phase_shift_target) {
s->phase_shift_current--;
s->adder_ref--;
}
if(ld_update(&s->ld, err))
return SPLL_LOCKED;
}
return SPLL_LOCKING;
}
static int mpll_set_phase_shift(struct spll_main_state *s, int desired_shift)
{
s->phase_shift_target = desired_shift;
}
static int mpll_shifter_busy(struct spll_main_state *s)
{
return s->phase_shift_target != s->phase_shift_current;
}
\ No newline at end of file
/* State of a Phase Tracker */
struct spll_ptracker_state {
int id_a, id_b;
int n_avg, acc, avg_count;
int phase_val, ready;
int tag_a, tag_b;
int sample_n;
int preserve_sign;
};
static void ptracker_init(struct spll_ptracker_state *s, int id_a, int id_b, int num_avgs)
{
s->tag_a = s->tag_b = -1;
s->id_a = id_a;
s->id_b = id_b;
s->ready = 0;
s->n_avg = num_avgs;
s->acc = 0;
s->avg_count = 0;
s->sample_n= 0;
s->preserve_sign = 0;
}
static void ptracker_start(struct spll_ptracker_state *s)
{
spll_enable_tagger(s->id_a, 1);
spll_enable_tagger(s->id_b, 1);
}
#define PTRACK_WRAP_LO (1<<(HPLL_N-2))
#define PTRACK_WRAP_HI (3*(1<<(HPLL_N-2)))
static int ptracker_update(struct spll_ptracker_state *s, int tag, int source)
{
if(source == s->id_a)
s->tag_a = tag;
if(source == s->id_b)
s->tag_b = tag;
if(s->tag_a >= 0 && s->tag_b >= 0)
{
int delta = (s->tag_a - s->tag_b) & ((1<<HPLL_N) - 1);
if(s->avg_count == 0)
{
if(delta <= PTRACK_WRAP_LO)
s->preserve_sign = -1;
else if (delta >= PTRACK_WRAP_HI)
s->preserve_sign = 1;
else
s->preserve_sign = 0;
s->acc = delta;
} else {
if(delta <= PTRACK_WRAP_LO && s->preserve_sign > 0)
s->acc += delta + (1<<HPLL_N);
else if (delta >= PTRACK_WRAP_HI && s->preserve_sign < 0)
s->acc += delta - (1<<HPLL_N);
else
s->acc += delta;
s->avg_count++;
if(s->avg_count == s->n_avg)
{
s->phase_val = s->acc / s->n_avg;
s->ready = 1;
s->acc = 0;
s->avg_count = 0;
}
}
s->tag_b = s->tag_a = -1;
}
return SPLL_LOCKING;
}
......@@ -6,65 +6,65 @@
#include "syscon.h"
#include "uart.h"
#include "endpoint.h"
#include "minic.h"
#include "pps_gen.h"
#include "ptpd.h"
#include "ptpd_netif.h"
#include "i2c.h"
#include "eeprom.h"
#include "onewire.h"
RunTimeOpts rtOpts = {
.announceInterval = DEFAULT_ANNOUNCE_INTERVAL,
.syncInterval = DEFAULT_SYNC_INTERVAL,
.clockQuality.clockAccuracy = DEFAULT_CLOCK_ACCURACY,
.clockQuality.clockClass = DEFAULT_CLOCK_CLASS,
.clockQuality.offsetScaledLogVariance = DEFAULT_CLOCK_VARIANCE,
.priority1 = DEFAULT_PRIORITY1,
.priority2 = DEFAULT_PRIORITY2,
.domainNumber = DEFAULT_DOMAIN_NUMBER,
.currentUtcOffset = DEFAULT_UTC_OFFSET,
.noResetClock = DEFAULT_NO_RESET_CLOCK,
.noAdjust = NO_ADJUST,
.inboundLatency.nanoseconds = DEFAULT_INBOUND_LATENCY,
.outboundLatency.nanoseconds = DEFAULT_OUTBOUND_LATENCY,
.s = DEFAULT_DELAY_S,
.ap = DEFAULT_AP,
.ai = DEFAULT_AI,
.max_foreign_records = DEFAULT_MAX_FOREIGN_RECORDS,
#ifdef WRPC_SLAVE
.slaveOnly = TRUE,
#else
.slaveOnly = FALSE,
#endif
/**************** White Rabbit *************************/
.autoPortDiscovery = FALSE, /*if TRUE: automagically discovers how many ports we have (and how many up-s); else takes from .portNumber*/
.portNumber = 1,
.calPeriod = WR_DEFAULT_CAL_PERIOD,
.E2E_mode = TRUE,
.wrStateRetry = WR_DEFAULT_STATE_REPEAT,
.wrStateTimeout= WR_DEFAULT_STATE_TIMEOUT_MS,
.deltasKnown = TRUE, //WR_DEFAULT_DELTAS_KNOWN,
.knownDeltaTx = 0,//WR_DEFAULT_DELTA_TX,
.knownDeltaRx = 0,//WR_DEFAULT_DELTA_RX,
/*SLAVE only or MASTER only*/
#ifdef WRPC_SLAVE
.primarySource = FALSE,
.wrConfig = WR_S_ONLY,
.masterOnly = FALSE,
#endif
#ifdef WRPC_MASTER
.primarySource = TRUE,
.wrConfig = WR_M_ONLY,
.masterOnly = TRUE,
#endif
/********************************************************/
};
static PtpPortDS *ptpPortDS;
static PtpClockDS ptpClockDS;
//#include "minic.h"
//#include "pps_gen.h"
//#include "ptpd.h"
//#include "ptpd_netif.h"
//#include "i2c.h"
//#include "eeprom.h"
//#include "onewire.h"
//RunTimeOpts rtOpts = {
// .announceInterval = DEFAULT_ANNOUNCE_INTERVAL,
// .syncInterval = DEFAULT_SYNC_INTERVAL,
// .clockQuality.clockAccuracy = DEFAULT_CLOCK_ACCURACY,
// .clockQuality.clockClass = DEFAULT_CLOCK_CLASS,
// .clockQuality.offsetScaledLogVariance = DEFAULT_CLOCK_VARIANCE,
// .priority1 = DEFAULT_PRIORITY1,
// .priority2 = DEFAULT_PRIORITY2,
// .domainNumber = DEFAULT_DOMAIN_NUMBER,
// .currentUtcOffset = DEFAULT_UTC_OFFSET,
// .noResetClock = DEFAULT_NO_RESET_CLOCK,
// .noAdjust = NO_ADJUST,
// .inboundLatency.nanoseconds = DEFAULT_INBOUND_LATENCY,
// .outboundLatency.nanoseconds = DEFAULT_OUTBOUND_LATENCY,
// .s = DEFAULT_DELAY_S,
// .ap = DEFAULT_AP,
// .ai = DEFAULT_AI,
// .max_foreign_records = DEFAULT_MAX_FOREIGN_RECORDS,
//#ifdef WRPC_SLAVE
// .slaveOnly = TRUE,
//#else
// .slaveOnly = FALSE,
//#endif
//
// /**************** White Rabbit *************************/
// .autoPortDiscovery = FALSE, /*if TRUE: automagically discovers how many ports we have (and how many up-s); else takes from .portNumber*/
// .portNumber = 1,
// .calPeriod = WR_DEFAULT_CAL_PERIOD,
// .E2E_mode = TRUE,
// .wrStateRetry = WR_DEFAULT_STATE_REPEAT,
// .wrStateTimeout= WR_DEFAULT_STATE_TIMEOUT_MS,
// .deltasKnown = TRUE, //WR_DEFAULT_DELTAS_KNOWN,
// .knownDeltaTx = 0,//WR_DEFAULT_DELTA_TX,
// .knownDeltaRx = 0,//WR_DEFAULT_DELTA_RX,
///*SLAVE only or MASTER only*/
//#ifdef WRPC_SLAVE
// .primarySource = FALSE,
// .wrConfig = WR_S_ONLY,
// .masterOnly = FALSE,
//#endif
//#ifdef WRPC_MASTER
// .primarySource = TRUE,
// .wrConfig = WR_M_ONLY,
// .masterOnly = TRUE,
//#endif
// /********************************************************/
//};
//static PtpPortDS *ptpPortDS;
//static PtpClockDS ptpClockDS;
......@@ -200,23 +200,14 @@ void wrc_initialize()
mprintf("wr_core: starting up (press G to launch the GUI and D for extra debug messages)....\n");
//SFP
#if 0
get_sfp_id(sfp_pn);
if( !access_eeprom(sfp_pn, &sfp_alpha, &sfp_deltaTx, &sfp_deltaRx) )
{
mprintf("SFP: alpha=%d, deltaTx=%d, deltaRx=%d\n", sfp_alpha, sfp_deltaTx, sfp_deltaRx);
}
#endif
//Generate MAC address
ow_init();
if( ds18x_read_serial(ds18_id) == 0 )
TRACE_DEV("Found DS18xx sensor: %x:%x:%x:%x:%x:%x:%x:%x\n",
ds18_id[7], ds18_id[6], ds18_id[5], ds18_id[4],
ds18_id[3], ds18_id[2], ds18_id[1], ds18_id[0]);
else
TRACE_DEV("DS18B20 not found\n");
//ow_init();
//if( ds18x_read_serial(ds18_id) == 0 )
// TRACE_DEV("Found DS18xx sensor: %x:%x:%x:%x:%x:%x:%x:%x\n",
// ds18_id[7], ds18_id[6], ds18_id[5], ds18_id[4],
// ds18_id[3], ds18_id[2], ds18_id[1], ds18_id[0]);
//else
// TRACE_DEV("DS18B20 not found\n");
mac_addr[0] = 0x08; //
mac_addr[1] = 0x00; // CERN OUI
......@@ -229,19 +220,19 @@ void wrc_initialize()
ep_init(mac_addr);
ep_enable(1, 1);
minic_init();
pps_gen_init();
//minic_init();
//pps_gen_init();
// for(;;);
// rx_test();
netStartup();
//netStartup();
wr_servo_man_adjust_phase(-11600 + 1700);
//wr_servo_man_adjust_phase(-11600 + 1700);
displayConfigINFO(&rtOpts);
//displayConfigINFO(&rtOpts);
ptpPortDS = ptpdStartup(0, NULL, &ret, &rtOpts, &ptpClockDS);
initDataClock(&rtOpts, &ptpClockDS);
//ptpPortDS = ptpdStartup(0, NULL, &ret, &rtOpts, &ptpClockDS);
//initDataClock(&rtOpts, &ptpClockDS);
}
#define LINK_WENT_UP 1
......@@ -271,7 +262,7 @@ int wrc_check_link()
return rv;
}
int wrc_extra_debug = 0;
int wrc_extra_debug = 1;
int wrc_gui_mode = 0;
void wrc_debug_printf(int subsys, const char *fmt, ...)
......@@ -282,7 +273,7 @@ void wrc_debug_printf(int subsys, const char *fmt, ...)
va_start(ap, fmt);
if(wrc_extra_debug || (!wrc_extra_debug && (subsys & TRACE_SERVO)))
if(wrc_extra_debug )// || (!wrc_extra_debug && (subsys & TRACE_SERVO)))
vprintf(fmt, ap);
va_end(ap);
......@@ -303,7 +294,7 @@ void wrc_handle_input()
wrc_gui_mode = 1 - wrc_gui_mode;
if(!wrc_gui_mode)
{
m_term_clear();
//m_term_clear();
wrc_debug_printf(0, "Exiting GUI mode\n");
}
break;
......@@ -317,7 +308,7 @@ void wrc_handle_input()
case 't':
wrc_enable_tracking = 1 - wrc_enable_tracking;
wr_servo_enable_tracking(wrc_enable_tracking);
//wr_servo_enable_tracking(wrc_enable_tracking);
wrc_debug_printf(0,"Phase tracking %s.\n", wrc_enable_tracking ? "enabled" : "disabled");
break;
......@@ -326,7 +317,7 @@ void wrc_handle_input()
case '-':
wrc_man_phase += (x=='+' ? 100 : -100);
wrc_debug_printf(0,"Manual phase adjust: %d\n", wrc_man_phase);
wr_servo_man_adjust_phase(wrc_man_phase);
//wr_servo_man_adjust_phase(wrc_man_phase);
break;
......@@ -342,6 +333,11 @@ int main(void)
{
wrc_initialize();
spll_test();
#if 0
for(;;)
{
wrc_handle_input();
......@@ -373,5 +369,7 @@ int main(void)
protocol_nonblock(&rtOpts, ptpPortDS);
}
#endif
}
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