Commit 94e24ddc authored by Tomasz Wlostowski's avatar Tomasz Wlostowski

New RX timestamper phase transition (t24p) calibration procedure.

New procedure that does not require PTP traffic, is much faster and doesn't kill the stack.
Requires recent endpoint version (wr-cores commit: 4713a98a).
Todo: modify locking functions in libptpnetif to automatically perform the calibration whenever
PTP enters slave mode.
parent fc1c9384
......@@ -91,7 +91,6 @@ LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled \
-nostdlib -T $(LDS)
include shell/shell.mk
include tests/tests.mk
include lib/lib.mk
include pp_printf/printf.mk
include sockitowm/sockitowm.mk
......
......@@ -9,4 +9,5 @@ obj-y += \
dev/uart.o \
dev/sfp.o \
dev/onewire.o \
dev/sdb.o
dev/sdb.o \
dev/rxts_calibrator.o
......@@ -186,3 +186,10 @@ int ep_cal_pattern_disable()
return 0;
}
int ep_timestamper_cal_pulse()
{
EP->TSCR |= EP_TSCR_RX_CAL_START;
timer_delay(1);
return EP->TSCR & EP_TSCR_RX_CAL_RESULT ? 1 : 0;
}
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2012 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#include <stdio.h>
#include <inttypes.h>
#include <stdarg.h>
#include <wrc.h>
#include "board.h"
#include "trace.h"
#include "syscon.h"
#include "endpoint.h"
#include "softpll_ng.h"
/* New calibrator for the transition phase value. A major pain in the ass for the folks who frequently rebuild
their gatewares. The idea is described below:
- lock the PLL to the master
- scan the whole phase shifter range
- at each scanning step, generate a fake RX timestamp.
- check if the rising edge counter is ahead of the falling edge counter (added a special bit for it in the TSU).
- determine phases at which positive/negative transitions occur
- transition phase value is in the middle between the rising and falling edges.
This calibration procedure is fast enough to be run on slave nodes whenever the link goes up. For master mode,
the core must be run at least once as a slave to calibrate itself and store the current transition phase value
in the EEPROM.
*/
/* how finely we scan the phase shift range to determine where we have the bit flip */
#define CAL_SCAN_STEP 100
/* deglitcher threshold (to remove 1->0->1 flip bit glitches that might occur due to jitter) */
#define CAL_DEGLITCH_THRESHOLD 5
/* we scan at least one clock period to look for rising->falling edge transition plus some headroom */
#define CAL_SCAN_RANGE (REF_CLOCK_PERIOD_PS + (3 * CAL_DEGLITCH_THRESHOLD * CAL_SCAN_STEP))
#define TD_WAIT_INACTIVE 0
#define TD_GOT_TRANSITION 1
#define TD_DONE 2
/* state of transition detector */
struct trans_detect_state {
int prev_val;
int sample_count;
int state;
int trans_phase;
};
/* finds the transition in the value of flip_bit and returns phase associated with it.
If no transition phase has been found yet, returns 0. Non-zero polarity means we are looking for
positive transitions, 0 - negative transitions */
static int lookup_transition(struct trans_detect_state *state, int flip_bit,
int phase, int polarity)
{
if (polarity)
polarity = 1;
switch (state->state) {
case TD_WAIT_INACTIVE:
/* first, wait until we have at least CAL_DEGLITCH_THRESHOLD of inactive state samples */
if (flip_bit != polarity)
state->sample_count++;
else
state->sample_count = 0;
if (state->sample_count >= CAL_DEGLITCH_THRESHOLD) {
state->state = TD_GOT_TRANSITION;
state->sample_count = 0;
}
break;
case TD_GOT_TRANSITION:
if (flip_bit != polarity)
state->sample_count = 0;
else {
state->sample_count++;
if (state->sample_count >= CAL_DEGLITCH_THRESHOLD) {
state->state = TD_DONE;
state->trans_phase =
phase -
CAL_DEGLITCH_THRESHOLD * CAL_SCAN_STEP;
}
}
break;
case TD_DONE:
return 1;
break;
}
return 0;
}
static struct trans_detect_state det_rising, det_falling;
static int cal_cur_phase;
/* Starts RX timestamper calibration process state machine. Invoked by ptpnetif's check lock function when the PLL
has already locked, to avoid complicating the API of ptp-noposix/ppsi. */
void rxts_calibration_start()
{
cal_cur_phase = 0;
det_rising.prev_val = det_falling.prev_val = -1;
det_rising.state = det_falling.state = TD_WAIT_INACTIVE;
spll_set_phase_shift(0, 0);
}
/* Updates RX timestamper state machine. Non-zero return value means that calibration is done. */
int rxts_calibration_update(int *t24p_value)
{
if (spll_shifter_busy(0))
return 0;
/* generate a fake RX timestamp and check if falling edge counter is ahead of rising edge counter */
int flip = ep_timestamper_cal_pulse();
/* look for transitions (with deglitching) */
lookup_transition(&det_rising, flip, cal_cur_phase, 1);
lookup_transition(&det_falling, flip, cal_cur_phase, 0);
if (cal_cur_phase >= CAL_SCAN_RANGE) {
if (det_rising.state != TD_DONE || det_falling.state != TD_DONE) {
TRACE_DEV("RXTS calibration error.\n");
return -1;
}
if (det_rising.trans_phase > det_falling.trans_phase)
det_falling.trans_phase += REF_CLOCK_PERIOD_PS;
int ttrans =
(det_falling.trans_phase + det_rising.trans_phase) / 2;
/* normalize */
if (ttrans < 0)
ttrans += REF_CLOCK_PERIOD_PS;
else if (ttrans >= REF_CLOCK_PERIOD_PS)
ttrans -= REF_CLOCK_PERIOD_PS;
TRACE_DEV("RXTS calibration: R@%dps, F@%dps, transition@%dps\n",
det_rising.trans_phase, det_falling.trans_phase,
ttrans);
*t24p_value = ttrans;
return 1;
}
cal_cur_phase += CAL_SCAN_STEP;
spll_set_phase_shift(0, cal_cur_phase);
return 0;
}
/* legacy function for 'calibration force' command */
int measure_t24p(int *value)
{
int rv;
mprintf("Waiting for link...\n");
while (!ep_link_up(NULL))
timer_delay(100);
spll_init(SPLL_MODE_SLAVE, 0, 1);
printf("Locking PLL...\n");
while (!spll_check_lock(0))
timer_delay(100);
printf("\n");
printf("Calibrating RX timestamper...\n");
rxts_calibration_start();
while (!(rv = rxts_calibration_update(value))) ;
return rv;
}
......@@ -27,6 +27,7 @@ int ep_get_deltas(uint32_t * delta_tx, uint32_t * delta_rx);
int ep_get_psval(int32_t * psval);
int ep_cal_pattern_enable();
int ep_cal_pattern_disable();
int ep_timestamper_cal_pulse();
void pfilter_init_default();
......
......@@ -3,7 +3,7 @@
* File : endpoint_regs.h
* Author : auto-generated by wbgen2 from ep_wishbone_controller.wb
* Created : Sun Oct 30 00:20:59 2011
* Created : Fri Mar 15 17:03:12 2013
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE ep_wishbone_controller.wb
......@@ -74,6 +74,12 @@
/* definitions for field: Timestamping counter synchronization done in reg: Timestamping Control Register */
#define EP_TSCR_CS_DONE WBGEN2_GEN_MASK(3, 1)
/* definitions for field: Start calibration of RX timestamper in reg: Timestamping Control Register */
#define EP_TSCR_RX_CAL_START WBGEN2_GEN_MASK(4, 1)
/* definitions for field: RX timestamper calibration result flag in reg: Timestamping Control Register */
#define EP_TSCR_RX_CAL_RESULT WBGEN2_GEN_MASK(5, 1)
/* definitions for register: RX Deframer Control Register */
/* definitions for field: RX accept runts in reg: RX Deframer Control Register */
......@@ -266,6 +272,7 @@
/* definitions for field: DMTD Phase shift value ready in reg: DMTD Status register */
#define EP_DMSR_PS_RDY WBGEN2_GEN_MASK(24, 1)
/* definitions for RAM: Event counters memory */
#define EP_RMON_RAM_BASE 0x00000080 /* base address */
#define EP_RMON_RAM_BYTES 0x00000080 /* size in bytes */
#define EP_RMON_RAM_WORDS 0x00000020 /* size in 32-bit words, 32-bit aligned */
......
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2012 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __RXTS_CALIBRATOR_H
#define __RXTS_CALIBRATOR_H
void rxts_calibration_start();
int rxts_calibration_update(int *t24p_value);
int measure_t24p(int *value);
#endif
......@@ -8,18 +8,17 @@
* Released according to the GNU GPL, version 2 or any later version.
*/
/* Command: gui
Arguments: none
/* Command: calibration
Arguments: [force]
Description: launches the WR Core monitor GUI */
Description: launches RX timestamper calibration. */
#include <string.h>
#include <wrc.h>
#include "shell.h"
#include "eeprom.h"
#include "syscon.h"
extern int measure_t24p(uint32_t *value);
#include "rxts_calibrator.h"
int cmd_calib(const char *args[])
{
......
PLATFORM = lm32
OBJS_COMMON = ../dev/uart.o ../dev/endpoint.o ../dev/minic.o ../dev/pps_gen.o ../dev/syscon.o ../dev/softpll_ng.o ../lib/mprintf.o ../dev/ep_pfilter.o \
../dev/dna.o ../dev/i2c.o ../ptp-noposix/libposix/freestanding-wrapper.o \
../ptp-noposix/PTPWRd/dep/msg.o
OBJS_TEST = testtool.o
INCLUDE_DIR = -I../include -I../ptp-noposix/PTPWRd
CROSS_COMPILE ?= lm32-elf-
CFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled
LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -nostdlib -T ../target/lm32/ram.ld
OBJS_PLATFORM=../target/lm32/crt0.o ../target/lm32/irq.o
CC=$(CROSS_COMPILE)gcc
OBJCOPY=$(CROSS_COMPILE)objcopy
OBJDUMP=$(CROSS_COMPILE)objdump
CFLAGS= $(CFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -include ../include/trace.h -I../include/ -I../ptp-noposix/libptpnetif -I../ptp-noposix/PTPWRd
LDFLAGS= $(LDFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os
SIZE = $(CROSS_COMPILE)size
OBJS=$(OBJS_PLATFORM) $(OBJS_COMMON) $(OBJS_TEST)
OUTPUT = testtool
all: $(OBJS)
$(SIZE) -t $(OBJS)
${CC} -o $(OUTPUT).elf $(OBJS) $(LDFLAGS)
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
clean:
rm -f $(OBJS) $(OUTPUT).elf $(OUTPUT).bin
%.o: %.c
${CC} $(CFLAGS) -c $^ -o $@
load:
../tools/lm32-loader $(OUTPUT).bin
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2012 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#include <stdio.h>
#include <inttypes.h>
#include <stdarg.h>
#include <wrc.h>
#define INET_ADDRSTRLEN 16
#include "syscon.h"
#include "uart.h"
#include "endpoint.h"
#include "hw/endpoint_mdio.h"
#include "minic.h"
#include "pps_gen.h"
#include "softpll_ng.h"
#undef PACKED
#include "ptpd_netif.h"
#ifdef CONFIG_PPSI
#include <ppsi/ppsi.h>
#else
#include "ptpd.h"
#endif
#if 0 /* not used, currently */
static int get_bitslide(int ep)
{
return (pcs_read(16) >> 4) & 0x1f;
}
#endif
struct meas_entry {
int delta_ns;
int phase;
int phase_sync;
int ahead;
};
static void purge_socket(wr_socket_t *sock, char *buf)
{
wr_sockaddr_t from;
update_rx_queues();
while (ptpd_netif_recvfrom(sock, &from, buf, 128, NULL) > 0)
update_rx_queues();
}
#ifdef CONFIG_PPSI
extern struct pp_instance ppi_static;
static struct pp_instance *ppi = &ppi_static;
static int meas_phase_range(wr_socket_t * sock, int phase_min, int phase_max,
int phase_step, struct meas_entry *results)
{
char buf[128];
TimeInternal ts_rx, ts_sync = {0,};
MsgHeader *mhdr;
int setpoint = phase_min, i = 0, phase;
mhdr = &ppi->msg_tmp_header;
spll_set_phase_shift(SPLL_ALL_CHANNELS, phase_min);
while (spll_shifter_busy(0)) ;
purge_socket(sock, buf);
i = 0;
while (setpoint <= phase_max) {
ptpd_netif_get_dmtd_phase(sock, &phase);
update_rx_queues();
int n = pp_recv_packet(ppi, buf, 128, &ts_rx);
if (n > 0) {
msg_unpack_header(ppi, buf);
if (mhdr->messageType == 0)
ts_sync = ts_rx;
else if (mhdr->messageType == 8 && ts_sync.correct) {
MsgFollowUp fup;
msg_unpack_follow_up(buf, &fup);
mprintf("Shift: %d/%dps [step %dps] \r",
setpoint, phase_max, phase_step);
results[i].phase = phase;
results[i].phase_sync = ts_sync.phase;
results[i].ahead = ts_sync.raw_ahead;
results[i].delta_ns =
fup.preciseOriginTimestamp.
nanosecondsField - ts_sync.nanoseconds;
results[i].delta_ns +=
(fup.preciseOriginTimestamp.secondsField.
lsb - ts_sync.seconds) * 1000000000;
setpoint += phase_step;
spll_set_phase_shift(0, setpoint);
while (spll_shifter_busy(0)) ;
purge_socket(sock, buf);
ts_sync.correct = 0;
i++;
}
}
}
mprintf("\n");
return i;
}
#else
static int meas_phase_range(wr_socket_t * sock, int phase_min, int phase_max,
int phase_step, struct meas_entry *results)
{
char buf[128];
wr_timestamp_t ts_rx, ts_sync = {0,};
wr_sockaddr_t from;
MsgHeader mhdr;
int setpoint = phase_min, i = 0, phase;
spll_set_phase_shift(SPLL_ALL_CHANNELS, phase_min);
while (spll_shifter_busy(0)) ;
purge_socket(sock, buf);
i = 0;
while (setpoint <= phase_max) {
ptpd_netif_get_dmtd_phase(sock, &phase);
update_rx_queues();
int n = ptpd_netif_recvfrom(sock, &from, buf, 128, &ts_rx);
if (n > 0) {
msgUnpackHeader(buf, &mhdr);
if (mhdr.messageType == 0)
ts_sync = ts_rx;
else if (mhdr.messageType == 8 && ts_sync.correct) {
MsgFollowUp fup;
msgUnpackFollowUp(buf, &fup);
mprintf("Shift: %d/%dps [step %dps] \r",
setpoint, phase_max, phase_step);
results[i].phase = phase;
results[i].phase_sync = ts_sync.phase;
results[i].ahead = ts_sync.raw_ahead;
results[i].delta_ns =
fup.preciseOriginTimestamp.
nanosecondsField - ts_sync.nsec;
results[i].delta_ns +=
(fup.preciseOriginTimestamp.secondsField.
lsb - ts_sync.sec) * 1000000000;
setpoint += phase_step;
spll_set_phase_shift(0, setpoint);
while (spll_shifter_busy(0)) ;
purge_socket(sock, buf);
ts_sync.correct = 0;
i++;
}
}
}
mprintf("\n");
return i;
}
#endif /* CONFIG_PPSI else CONFIG_PTPNOPOSIX*/
static int find_transition(struct meas_entry *results, int n, int positive)
{
int i;
for (i = 0; i < n; i++) {
if ((results[i].ahead ^ results[(i + 1) % n].ahead)
&& (results[(i + 1) % n].ahead == positive))
return i;
}
return -1;
}
extern void ptpd_netif_set_phase_transition(wr_socket_t * sock, int phase);
int measure_t24p(int *value)
{
wr_socket_t *sock;
wr_sockaddr_t sock_addr;
int i, nr;
struct meas_entry results[128];
#ifdef CONFIG_PPSI
if (!NP(ppi)->inited) {
if (pp_net_init(ppi) < 0)
return -1;
NP(ppi)->inited = 1;
}
#endif
spll_enable_ptracker(0, 1);
sock_addr.family = PTPD_SOCK_RAW_ETHERNET; // socket type
sock_addr.ethertype = 0x88f7;
sock_addr.mac[0] = 0x1;
sock_addr.mac[1] = 0x1b;
sock_addr.mac[2] = 0x19;
sock_addr.mac[3] = 0;
sock_addr.mac[4] = 0;
sock_addr.mac[5] = 0;
mprintf("LNK: ");
while (!ep_link_up(NULL)) {
mprintf(".");
timer_delay(1000);
}
mprintf("\nPLL: ");
spll_init(SPLL_MODE_SLAVE, 0, 1);
while (!spll_check_lock(0)) ;
mprintf("\n");
if (ptpd_netif_init() != 0)
return -1;
sock = ptpd_netif_create_socket(PTPD_SOCK_RAW_ETHERNET, 0, &sock_addr);
nr = meas_phase_range(sock, 0, 8000, 1000, results);
int tplus = find_transition(results, nr, 1);
int tminus = find_transition(results, nr, 0);
int approx_plus = results[tplus].phase;
int approx_minus = results[tminus].phase;
nr = meas_phase_range(sock, approx_plus - 1000, approx_plus + 1000, 100,
results);
tplus = find_transition(results, nr, 1);
int phase_plus = results[tplus].phase;
nr = meas_phase_range(sock, approx_minus - 1000, approx_minus + 1000,
100, results);
tminus = find_transition(results, nr, 0);
int phase_minus = results[tminus].phase;
mprintf("Transitions found: positive @ %d ps, negative @ %d ps.\n",
phase_plus, phase_minus);
int ttrans = phase_minus - 1000;
if (ttrans < 0)
ttrans += 8000;
mprintf("(t2/t4)_phase_transition = %dps\n", ttrans);
ptpd_netif_set_phase_transition(sock, ttrans);
mprintf("Verification... \n");
nr = meas_phase_range(sock, 0, 16000, 500, results);
#ifdef CONFIG_PPSI
pp_net_shutdown(ppi);
NP(ppi)->inited = 0;
#endif
for (i = 0; i < nr; i++)
mprintf("phase_dmtd: %d delta_ns: %d, phase_sync: %d\n",
results[i].phase, results[i].delta_ns,
results[i].phase_sync);
if (value)
*value = ttrans;
ptpd_netif_close_socket(sock);
return 0;
}
obj-y += tests/measure_t24p.o
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