Commit 8523c575 authored by Tomasz Wlostowski's avatar Tomasz Wlostowski

rt firmware snapshot for IPC debugging

parent be661bdc
CROSS_COMPILE ?= /opt/gcc-lm32/bin/lm32-elf-
OBJS = main.o dev/uart.o dev/timer.o lib/mprintf.o dev/ad9516.o dev/softpll_ng.o
OBJS = main.o dev/uart.o dev/timer.o lib/mprintf.o dev/ad9516.o dev/softpll_ng.o ipc/minipc-mem-server.o ipc_test.o
CFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled
LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -nostdlib -T target/lm32/ram.ld
......@@ -9,8 +9,8 @@ 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 -Iinclude -include include/trace.h -Wall
LDFLAGS= $(LDFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -Iinclude
CFLAGS= $(CFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -Iinclude -include include/trace.h -Wall -ffreestanding -Iipc
LDFLAGS= $(LDFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -Iinclude -ffreestanding
SIZE = $(CROSS_COMPILE)size
OBJS += $(OBJS_PLATFORM)
......
......@@ -36,9 +36,6 @@ static volatile struct spll_main_state mpll;
static volatile struct spll_pmeas_channel pmeas[MAX_CHAN_REF + MAX_CHAN_OUT];
static void pmeas_update(struct spll_pmeas_channel *chan, int tag)
{
chan->n_tags++;
......@@ -78,7 +75,6 @@ void _irq_entry()
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);
}
......@@ -113,7 +109,7 @@ void spll_init()
int spll_check_lock()
{
return helper.phase.ld.locked ? 1 : 0;
return helper.ld.locked ? 1 : 0;
}
#define CHAN_TCXO 8
......@@ -123,17 +119,35 @@ void spll_test()
int i = 0;
volatile int dummy;
SPLL->DAC_HPLL = 0;
SPLL->DAC_MAIN = 0;
timer_delay(10000);
spll_init();
helper_start(&helper, 0);
mpll_init(&mpll, 0, CHAN_TCXO);
enable_irq();
// mpll_init(&mpll, 0, CHAN_TCXO);
while(!helper.phase.ld.locked) ;//TRACE("%d\n", helper.phase.ld.locked);
TRACE("Helper locked, starting main\n");
uint32_t t1 = timer_get_tics();
helper_init(&helper, 2);
helper_start(&helper);
mpll_init(&mpll, 2, CHAN_TCXO);
enable_irq();
while(!helper.ld.locked) ;//TRACE("%d\n", helper.phase.ld.locked);
mpll_start(&mpll);
while(!mpll.ld.locked) ;//TRACE("%d\n", helper.phase.ld.locked);
uint32_t t2 = timer_get_tics();
TRACE("SoftPLL locked (time = %d tics)\n", t2-t1);
/* for(;;)
{
TRACE("Left...\n");
mpll_set_phase_shift(&mpll, -4000);
while(mpll_shifter_busy(&mpll));
TRACE("Right...\n");
mpll_set_phase_shift(&mpll, 4000);
while(mpll_shifter_busy(&mpll));
}*/
}
/*
......
......@@ -2,24 +2,41 @@
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 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 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 claming and antiwindup algorithms */
int y_min; /* min/max output range, used by clapming and antiwindup algorithms */
int y_max;
int x,y; /* Current input and output value */
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) using PI controller (pi). Returns the value (y) which should
be used to drive the actuator. */
/* 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;
......@@ -29,23 +46,22 @@ static inline int pi_update(spll_pi_t *pi, int 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 integretor if the output is already out of range and the output
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) {
} 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
pi->integrator = i_new;
} else /* No antiwindup/clamping? */
pi->integrator = i_new;
pi->y = y;
return y;
return y;
}
/* initializes the PI controller state. Currently almost a stub. */
......@@ -54,19 +70,17 @@ static inline void pi_init(spll_pi_t *pi)
pi->integrator = 0;
}
/* lock detector state */
typedef struct {
int lock_cnt;
int lock_samples;
int delock_samples;
int threshold;
int locked;
} spll_lock_det_t;
/* 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. */
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)
......@@ -75,7 +89,10 @@ static inline int ld_update(spll_lock_det_t *ld, int y)
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--;
......@@ -84,6 +101,7 @@ static inline int ld_update(spll_lock_det_t *ld, int y)
{
ld->lock_cnt= 0;
ld->locked = 0;
return -1;
}
}
return ld->locked;
......@@ -96,6 +114,18 @@ static void ld_init(spll_lock_det_t *ld)
}
/* 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? */
......@@ -104,11 +134,12 @@ static void spll_enable_tagger(int channel, int enable)
SPLL->OCER |= 1<< (channel - n_chan_ref);
else
SPLL->OCER &= ~ (1<< (channel - n_chan_ref));
} else {
} else { /* Reference channel */
if(enable)
SPLL->RCER |= 1<<channel;
else
SPLL->RCER &= ~ (1<<channel);
}
TRACE("spll_enable_channel: ch %d, OCER %x, RCER %x\n", channel, SPLL->OCER, SPLL->RCER);
}
\ No newline at end of file
TRACE("%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
......@@ -6,11 +21,22 @@
#define DBG_EVENT 4
#define DBG_SAMPLE_ID 6
#define DBG_HELPER 0x20
#define DBG_MAIN 0x0
#define DBG_PRELOCK 0x40
#define DBG_EVT_START 1
#define DBG_EVT_LOCKED 2
#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)
{
......
......@@ -2,26 +2,37 @@
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 */
/* Reference clock frequency, in [Hz] */
#define CLOCK_FREQ 62500000
/* Bit size of phase tags generated by the DMTDs. Used to sign-extend the tags. */
/* 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 (1/2**N is the frequency offset) */
/* 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. number of reference channels */
/* Max. allowed number of reference channels. Can be used to tweak memory usage. */
#define MAX_CHAN_REF 7
/* Max. number of output channels */
/* 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. This structure keeps the state of the pre-locking
stage */
struct spll_helper_prelock_state {
spll_pi_t pi;
spll_lock_det_t ld;
int f_setpoint;
int ref_select;
};
volatile int serr;
void helper_prelock_init(struct spll_helper_prelock_state *s)
{
/* Frequency branch PI controller */
s->pi.y_min = 5;
s->pi.y_max = 65530;
s->pi.anti_windup = 0;
s->pi.kp = 28*32*16;
s->pi.ki = 50*32*16;
s->pi.bias = 32000;
/* Freqency branch lock detection */
s->ld.threshold = 2;
s->ld.lock_samples = 100;
s->ld.delock_samples = 90;
s->f_setpoint = -131072 / (1<<HPLL_N);
pi_init(&s->pi);
ld_init(&s->ld);
}
void helper_prelock_enable(int ref_channel, int enable)
{
volatile int dummy;
SPLL->CSR = 0;
dummy = SPLL->PER_HPLL; /* clean any pending frequency measurement to avoid distubing the control loop */
if(enable)
SPLL->CSR = SPLL_CSR_PER_SEL_W(ref_channel) | SPLL_CSR_PER_EN;
else
SPLL->CSR = 0;
}
Main PLL can use it to perform linear phase measurements.
*/
#define SPLL_LOCKED 1
#define SPLL_LOCKING 0
int helper_prelock_update(struct spll_helper_prelock_state *s)
{
int y;
volatile uint32_t per = SPLL->PER_HPLL;
if(per & SPLL_PER_HPLL_VALID)
{
short err = (short) (per & 0xffff);
err -= s->f_setpoint;
serr = (int)err;
#define HELPER_TAG_WRAPAROUND 100000000
y = pi_update(&s->pi, err);
SPLL->DAC_HPLL = y;
spll_debug(DBG_Y | DBG_PRELOCK | DBG_HELPER, y, 0);
spll_debug(DBG_ERR | DBG_PRELOCK | DBG_HELPER, err, 1);
if(ld_update(&s->ld, err))
{
spll_debug(DBG_EVENT | DBG_PRELOCK | DBG_HELPER, DBG_EVT_LOCKED, 1);
return SPLL_LOCKED;
}
}
return SPLL_LOCKED;//ING;
}
/* 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_phase_state {
int p_adder;
struct spll_helper_state {
int p_adder; /* anti wrap-around adder */
int p_setpoint, tag_d0;
int ref_src;
int sample_n;
......@@ -92,20 +21,19 @@ struct spll_helper_phase_state {
spll_lock_det_t ld;
};
void helper_phase_init(struct spll_helper_phase_state *s, int ref_channel)
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 = 65530;
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);
SPLL->DAC_HPLL = 0;
timer_delay(100000);
s->pi.anti_windup = 1;
s->pi.bias = 32000;
/* 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;
......@@ -115,22 +43,13 @@ void helper_phase_init(struct spll_helper_phase_state *s, int ref_channel)
s->p_setpoint = 0;
s->p_adder = 0;
s->sample_n = 0;
s->tag_d0 = 0;
s->tag_d0 = -1;
pi_init(&s->pi);
ld_init(&s->ld);
}
void helper_phase_enable(int ref_channel, int enable)
{
spll_enable_tagger(ref_channel, enable);
// spll_debug(DBG_EVENT | DBG_HELPER, DBG_EVT_START, 1);
}
volatile int delta;
#define TAG_WRAPAROUND 100000000
int helper_phase_update(struct spll_helper_phase_state *s, int tag, int source)
static int helper_update(struct spll_helper_state *s, int tag, int source)
{
int err, y;
......@@ -139,19 +58,33 @@ int helper_phase_update(struct spll_helper_phase_state *s, int tag, int source)
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;
s->tag_d0 = tag;
s->p_setpoint += (1<<HPLL_N);
if(s->p_adder > TAG_WRAPAROUND)
if(HELPER_ERROR_CLAMP)
{
if(err < -HELPER_ERROR_CLAMP) err = -HELPER_ERROR_CLAMP;
if(err > HELPER_ERROR_CLAMP) err = HELPER_ERROR_CLAMP;
}
if((tag + s->p_adder) > HELPER_TAG_WRAPAROUND && s->p_setpoint > HELPER_TAG_WRAPAROUND)
{
s->p_adder -= TAG_WRAPAROUND;
s->p_setpoint -= 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;
......@@ -163,47 +96,13 @@ int helper_phase_update(struct spll_helper_phase_state *s, int tag, int source)
if(ld_update(&s->ld, err))
return SPLL_LOCKED;
}
return SPLL_LOCKING;
}
#define HELPER_PRELOCKING 1
#define HELPER_PHASE 2
#define HELPER_LOCKED 3
struct spll_helper_state {
struct spll_helper_prelock_state prelock;
struct spll_helper_phase_state phase;
int state;
int ref_channel;
};
void helper_start(struct spll_helper_state *s, int ref_channel)
static void helper_start(struct spll_helper_state *s)
{
s->state = HELPER_PRELOCKING;
s->ref_channel = ref_channel;
helper_prelock_init(&s->prelock);
helper_phase_init(&s->phase, ref_channel);
helper_prelock_enable(ref_channel, 1);
spll_debug(DBG_EVENT | DBG_PRELOCK | DBG_HELPER, DBG_EVT_START, 1);
spll_enable_tagger(s->ref_src, 1);
spll_debug(DBG_EVENT | DBG_HELPER, DBG_EVT_START, 1);
}
int helper_update(struct spll_helper_state *s, int tag, int source)
{
switch(s->state)
{
case HELPER_PRELOCKING:
if(helper_prelock_update(&s->prelock) == SPLL_LOCKED)
{
s->state = HELPER_PHASE;
helper_prelock_enable(s->ref_channel, 0);
s->phase.pi.bias = s->prelock.pi.y;
helper_phase_enable(s->ref_channel, 1);
}
return SPLL_LOCKING;
case HELPER_PHASE:
return helper_phase_update(&s->phase, tag, source);
}
return SPLL_LOCKING;
}
\ No newline at end of file
#define MPLL_DISABLED -1
#define MPLL_FREQ 0
#define MPLL_PHASE 1
#define PER_REF_READY 1
#define PER_OUT_READY 2
#define MPLL_TAG_WRAPAROUND 100000000
/* State of the Main PLL */
struct spll_main_state {
int state;
struct {
spll_pi_t pi;
spll_lock_det_t ld;
int period_ref, period_out;
int flags;
} freq ;
struct {
spll_pi_t pi;
spll_lock_det_t ld;
} phase ;
int tag_ref_d, tag_out_d;
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 */
......@@ -30,146 +16,105 @@ struct spll_main_state {
};
volatile int serr;
void mpll_init(struct spll_main_state *s, int id_ref, int id_out)
static void mpll_init(struct spll_main_state *s, int id_ref, int id_out)
{
/* Frequency branch PI controller */
s->freq.pi.y_min = 5;
s->freq.pi.y_max = 65530;
s->freq.pi.anti_windup = 0;
s->freq.pi.bias = 32000;
s->freq.pi.kp = 100;
s->freq.pi.ki = 600;
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->freq.ld.threshold = 200;
s->freq.ld.lock_samples = 1000;
s->freq.ld.delock_samples = 990;
s->freq.flags = 0;
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;
s->state = MPLL_DISABLED;
pi_init(&s->freq.pi);
ld_init(&s->freq.ld);
pi_init(&s->pi);
ld_init(&s->ld);
}
void mpll_start(struct spll_main_state *s)
static void mpll_start(struct spll_main_state *s)
{
s->state = MPLL_FREQ;
spll_enable_tagger(s->id_ref, 1);
spll_enable_tagger(s->id_out, 1);
spll_debug(DBG_EVENT | DBG_PRELOCK | DBG_MAIN, DBG_EVT_START, 1);
spll_debug(DBG_EVENT | DBG_MAIN, DBG_EVT_START, 1);
}
int mpll_freq_update(struct spll_main_state *s, int tag, int source)
static int mpll_update(struct spll_main_state *s, int tag, int source)
{
int err, y, tmp;
/* calculate the periods on both reference and output channel */
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)
{
//spll_debug(DBG_REF | DBG_PRELOCK | DBG_MAIN, tag, 1);
if(s->tag_ref_d >= 0)
{
tmp = tag - s->tag_ref_d;
if(tmp < 0)
tmp += (1<<TAG_BITS);
s->freq.period_ref = tmp;
s->freq.flags |= PER_REF_READY;
}
s->tag_ref_d = tag;
} else if(source == s->id_out) {
//spll_debug(DBG_TAG | DBG_PRELOCK | DBG_MAIN, tag, 1);
if(s->tag_out_d >= 0)
{
tmp = tag - s->tag_out_d;
if(tmp < 0)
tmp += (1<<TAG_BITS);
s->freq.period_out = tmp;
s->freq.flags |= PER_OUT_READY;
}
s->tag_out_d = tag;
}
/* if we have two fresh period measurements, calculate the error and adjust the DAC */
if((s->freq.flags & PER_OUT_READY) && (s->freq.flags & PER_REF_READY))
{
s->freq.flags &= ~(PER_OUT_READY | PER_REF_READY);
err = s->freq.period_ref - s->freq.period_out;
y = pi_update(&s->freq.pi, err);
SPLL->DAC_MAIN = SPLL_DAC_MAIN_VALUE_W(y) | SPLL_DAC_MAIN_DAC_SEL_W(s->id_out);
spll_debug(DBG_ERR | DBG_PRELOCK | DBG_MAIN, err, 0);
spll_debug(DBG_SAMPLE_ID | DBG_PRELOCK | DBG_MAIN, s->sample_n++, 0);
spll_debug(DBG_Y | DBG_PRELOCK | DBG_MAIN, y, 1);
if(ld_update(&s->freq.ld, err))
return SPLL_LOCKED;
}
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;
}
int mpll_phase_update(struct spll_main_state *s, int tag, int source)
static int mpll_set_phase_shift(struct spll_main_state *s, int desired_shift)
{
return SPLL_LOCKING;
s->phase_shift_target = desired_shift;
}
int mpll_update(struct spll_main_state *s, int tag, int source)
static int mpll_shifter_busy(struct spll_main_state *s)
{
switch(s->state)
{
case MPLL_DISABLED:
break;
case MPLL_FREQ:
if(mpll_freq_update(s, tag, source) == SPLL_LOCKED)
{
s->state = MPLL_PHASE;
s->phase.pi.bias = s->freq.pi.y;
}
return SPLL_LOCKING;
case MPLL_PHASE:
{
#if 0
if(tag_ref >= 0)
dmpll->tag_ref_d0 = tag_ref;
tag_ref = dmpll->tag_ref_d0 ;
tag_fb += (dmpll->setpoint >> SETPOINT_FRACBITS);
tag_fb &= (1<<TAG_BITS) - 1;
if(fb_ready)
{
tag_ref &= 0x3fff; //while (tag_ref > 16384 ) tag_ref-=16384; /* fixme */
tag_fb &= 0x3fff; //while (tag_fb > 16384 ) tag_fb-=16384;
err = tag_ref - tag_fb;
y = pi_update(&dmpll->pi_phase, err);
*dac = y;
ld_update(&dmpll->ld_phase, err);
if(dmpll->setpoint < dmpll->phase_shift)
dmpll->setpoint++;
else if(dmpll->setpoint > dmpll->phase_shift)
dmpll->setpoint--;
}
}
#endif
}
break;
// return helper_phase_update(&s->phase, tag, source);
}
return SPLL_LOCKING;
return s->phase_shift_target != s->phase_shift_current;
}
\ No newline at end of file
#ifndef __GPIO_H
#define __GPIO_H
#include <inttypes.h>
#include <stdint.h>
#include "board.h"
......
......@@ -14,7 +14,7 @@
#ifndef __WBGEN2_REGDEFS_SPLL_WB_SLAVE_WB
#define __WBGEN2_REGDEFS_SPLL_WB_SLAVE_WB
#include <inttypes.h>
#include <stdint.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
......
......@@ -14,7 +14,7 @@
#ifndef __WBGEN2_REGDEFS_UART_WB
#define __WBGEN2_REGDEFS_UART_WB
#include <inttypes.h>
#include <stdint.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
......
#ifndef __ARCH_LM32_STDINT_H__
#define __ARCH_LM32_STDINT_H__
/*
* We miss a stdint.h in our compiler, so provide some types here,
* knowing the CPU is 32-bits and uses LP32 model
*/
typedef unsigned char uint8_t;
typedef unsigned short uint16_t;
typedef unsigned long uint32_t;
typedef signed char int8_t;
typedef signed short int16_t;
typedef signed long int32_t;
#endif /* __ARCH_LM32_STDINT_H__ */
#ifndef __FREESTANDING_TRACE_H__
#define __FREESTANDING_TRACE_H__
int mprintf(char const *format, ...);
#define TRACE(...) mprintf(__VA_ARGS__)
#endif
/*
* Private definition for mini-ipc
*
* Copyright (C) 2011 CERN (www.cern.ch)
* Author: Alessandro Rubini <rubini@gnudd.com>
* Based on ideas by 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 2 of the License, or
* (at your option) any later version.
*/
#ifndef __MINIPC_INT_H__
#define __MINIPC_INT_H__
#include <sys/types.h>
#if __STDC_HOSTED__ /* freestanding servers have less material */
#include <sys/un.h>
#include <sys/select.h>
#endif
#include "minipc.h"
/* be safe, in case some other header had them slightly differntly */
#undef container_of
#undef offsetof
#undef ARRAY_SIZE
/* We are strongly based on container_of internally */
#define container_of(ptr, type, member) ({ \
const typeof( ((type *)0)->member ) *__mptr = (ptr); \
(type *)( (char *)__mptr - offsetof(type,member) );})
#define offsetof(TYPE, MEMBER) ((size_t) &((TYPE *)0)->MEMBER)
#define ARRAY_SIZE(arr) (sizeof(arr) / sizeof((arr)[0]))
/*
* While public symbols are minipc_* internal ones are mpc_* to be shorter.
* The connection includes an fd, which is the only thing returned back
*/
/* The list of functions attached to a service */
struct mpc_flist {
const struct minipc_pd *pd;
struct mpc_flist *next;
};
/*
* The main server or client structure. Server links have client sockets
* hooking on it.
*/
struct mpc_link {
struct minipc_ch ch;
int magic;
int pid;
int flags;
struct mpc_link *nextl;
struct mpc_flist *flist;
void *memaddr;
int memsize;
#if __STDC_HOSTED__ /* these fields are not used in freestanding uC */
FILE *logf;
struct sockaddr_un addr;
int fd[MINIPC_MAX_CLIENTS];
fd_set fdset;
#endif
char name[MINIPC_MAX_NAME];
};
#define MPC_MAGIC 0xc0ffee99
#define MPC_FLAG_SERVER 0x00010000
#define MPC_FLAG_CLIENT 0x00020000
#define MPC_FLAG_SHMEM 0x00040000
#define MPC_FLAG_DEVMEM 0x00080000
#define MPC_USER_FLAGS(x) ((x) & 0xffff)
/* The request packet being transferred */
struct mpc_req_packet {
char name[MINIPC_MAX_NAME];
uint32_t args[MINIPC_MAX_ARGUMENTS];
};
/* The reply packet being transferred */
struct mpc_rep_packet {
uint32_t type;
uint8_t val[MINIPC_MAX_REPLY];
};
/* A structure for shared memory (takes more than 2kB) */
struct mpc_shmem {
uint32_t nrequest; /* incremented at each request */
uint32_t nreply; /* incremented at each reply */
struct mpc_req_packet request;
struct mpc_rep_packet reply;
};
#define MPC_TIMEOUT 1000 /* msec, hardwired */
static inline struct mpc_link *mpc_get_link(struct minipc_ch *ch)
{
return container_of(ch, struct mpc_link, ch);
}
#define CHECK_LINK(link) /* Horrible shortcut, don't tell around... */ \
if ((link)->magic != MPC_MAGIC) { \
errno = EINVAL; \
return -1; \
}
extern struct mpc_link *__mpc_base;
extern void mpc_free_flist(struct mpc_link *link, struct mpc_flist *flist);
extern struct minipc_ch *__minipc_link_create(const char *name, int flags);
/* Used for lists and structures -- sizeof(uint32_t) is 4, is it? */
#define MINIPC_GET_ANUM(len) (((len) + 3) >> 2)
#endif /* __MINIPC_INT_H__ */
/*
* Mini-ipc: Exported functions for freestanding server
*
* Copyright (C) 2012 CERN (www.cern.ch)
* Author: Alessandro Rubini <rubini@gnudd.com>
*
* This replicates some code of minipc-core and minipc-server.
* It implements the functions needed to make a freestanding server
* (for example, an lm32 running on an FPGA -- the case I actually need).
*/
#include "minipc-int.h"
#include <string.h>
#include <sys/errno.h>
/* HACK: use a static link, one only */
static struct mpc_link __static_link;
/* The create function just picks an hex address from the name "mem:AABBCC" */
struct minipc_ch *minipc_server_create(const char *name, int flags)
{
struct mpc_link *link = &__static_link;
int i, c, addr = 0;
int memsize = sizeof(struct mpc_shmem);
if (link->magic) {
errno = EBUSY;
return NULL;
}
/* Most code from __minipc_link_create and __minipc_memlink_create */
flags |= MPC_FLAG_SERVER;
if (strncmp(name, "mem:", 4)) {
errno = EINVAL;
return NULL;
}
/* Ok, valid name. Hopefully */
link->magic = MPC_MAGIC;
link->flags = flags;
strncpy(link->name, name, sizeof(link->name) -1);
/* Parse the hex address */
for (i = 4; (c = name[i]); i++) {
addr *= 0x10;
if (c >= '0' && c <= '9') addr += c - '0';
if (c >= 'a' && c <= 'f') addr += c - 'a' + 10;
if (c >= 'A' && c <= 'F') addr += c - 'A' + 10;
}
link->flags |= MPC_FLAG_SHMEM; /* needed? */
mprintf("BaseAddr: 0x%x\n", addr);
link->memaddr = (void *)addr;
link->memsize = memsize;
link->pid = 0; /* hack: nrequest */
if (link->flags & MPC_FLAG_SERVER)
memset(link->memaddr, 0, memsize);
return &link->ch;
}
/* Close only marks the link as available */
int minipc_close(struct minipc_ch *ch)
{
struct mpc_link *link = mpc_get_link(ch);
CHECK_LINK(link);
link->magic = 0; /* available */
return 0;
}
/* HACK: use a static array of flist, to avoid malloc and free */
static struct mpc_flist __static_flist[MINIPC_MAX_EXPORT];
static void *calloc(size_t unused, size_t unused2)
{
int i;
struct mpc_flist *p;
for (p = __static_flist, i = 0; i < MINIPC_MAX_EXPORT; p++, i++)
if (!p->next)
break;
if (i == MINIPC_MAX_EXPORT) {
errno = ENOMEM;
return NULL;
}
return p;
}
static void free(void *ptr)
{
struct mpc_flist *p = ptr;
p->next = NULL;
}
/* From: minipc-core.c, but relying on fake free above */
void mpc_free_flist(struct mpc_link *link, struct mpc_flist *flist)
{
struct mpc_flist **nextp;
/* Look for flist and release it*/
for (nextp = &link->flist; (*nextp); nextp = &(*nextp)->next)
if (*nextp == flist)
break;
if (!*nextp) {
return;
}
*nextp = flist->next;
free(flist);
}
/* From: minipc-server.c -- but no log and relies on fake calloc above */
int minipc_export(struct minipc_ch *ch, const struct minipc_pd *pd)
{
struct mpc_link *link = mpc_get_link(ch);
struct mpc_flist *flist;
CHECK_LINK(link);
flist = calloc(1, sizeof(*flist));
if (!flist)
return -1;
flist->pd = pd;
flist->next = link->flist;
link->flist = flist;
return 0;
}
/* From: minipc-server.c -- but no log file */
int minipc_unexport(struct minipc_ch *ch, const struct minipc_pd *pd)
{
struct mpc_link *link = mpc_get_link(ch);
struct mpc_flist *flist;
CHECK_LINK(link);
/* We must find the flist that points to pd */
for (flist = link->flist; flist; flist = flist->next)
if (flist->pd == pd)
break;
if (!flist) {
errno = EINVAL;
return -1;
}
flist = container_of(&pd, struct mpc_flist, pd);
mpc_free_flist(link, flist);
return 0;
}
/* From: minipc-server.c */
uint32_t *minipc_get_next_arg(uint32_t arg[], uint32_t atype)
{
int asize;
char *s = (void *)arg;
if (MINIPC_GET_ATYPE(atype) != MINIPC_ATYPE_STRING)
asize = MINIPC_GET_ANUM(MINIPC_GET_ASIZE(atype));
else
asize = MINIPC_GET_ANUM(strlen(s) + 1);
return arg + asize;
}
/* From: minipc-server.c (mostly: mpc_handle_client) */
int minipc_server_action(struct minipc_ch *ch, int timeoutms)
{
struct mpc_link *link = mpc_get_link(ch);
struct mpc_req_packet *p_in;
struct mpc_rep_packet *p_out;
struct mpc_shmem *shm = link->memaddr;
const struct minipc_pd *pd;
struct mpc_flist *flist;
int i;
CHECK_LINK(link);
/* keep track of the request in an otherwise unused field */
if (shm->nrequest == link->pid)
return 0;
link->pid = shm->nrequest;
p_in = &shm->request;
p_out = &shm->reply;
/* use p_in->name to look for the function */
for (flist = link->flist; flist; flist = flist->next)
if (!(strcmp(p_in->name, flist->pd->name)))
break;
if (!flist) {
p_out->type = MINIPC_ARG_ENCODE(MINIPC_ATYPE_ERROR, int);
*(int *)(&p_out->val) = EOPNOTSUPP;
goto send_reply;
}
pd = flist->pd;
/* call the function and send back stuff */
i = pd->f(pd, p_in->args, p_out->val);
if (i < 0) {
p_out->type = MINIPC_ARG_ENCODE(MINIPC_ATYPE_ERROR, int);
*(int *)(&p_out->val) = errno;
} else {
/* Use retval, but fix the length for strings */
if (MINIPC_GET_ATYPE(pd->retval) == MINIPC_ATYPE_STRING) {
int size = strlen((char *)p_out->val) + 1;
size = (size + 3) & ~3; /* align */
p_out->type =
__MINIPC_ARG_ENCODE(MINIPC_ATYPE_STRING, size);
} else {
p_out->type = pd->retval;
}
}
send_reply:
shm->nreply++; /* message already in place */
return 0;
}
/*
* Public definition for mini-ipc
*
* Copyright (C) 2011 CERN (www.cern.ch)
* Author: Alessandro Rubini <rubini@gnudd.com>
* Based on ideas by 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 2 of the License, or
* (at your option) any later version.
*/
#ifndef __MINIPC_H__
#define __MINIPC_H__
#include <stdio.h>
#include <stdint.h>
#if __STDC_HOSTED__ /* freestanding servers have less material */
#include <stdio.h>
#include <sys/select.h>
#endif
/* Hard limits */
#define MINIPC_MAX_NAME 20 /* includes trailing 0 */
#define MINIPC_MAX_CLIENTS 64
#define MINIPC_MAX_ARGUMENTS 256 /* Also, max size of packet words -- 1k */
#define MINIPC_MAX_REPLY 1024 /* bytes */
#if !__STDC_HOSTED__
#define MINIPC_MAX_EXPORT 12 /* freestanding: static allocation */
#endif
/* The base pathname, mkdir is performed as needed */
#define MINIPC_BASE_PATH "/tmp/.minipc"
/* Default polling interval for memory-based channels */
#define MINIPC_DEFAULT_POLL (10*1000)
/* Argument type (and retval type). The size is encoded in the same word */
enum minipc_at {
MINIPC_ATYPE_ERROR = 0xffff,
MINIPC_ATYPE_NONE = 0, /* used as terminator */
MINIPC_ATYPE_INT = 1,
MINIPC_ATYPE_INT64,
MINIPC_ATYPE_DOUBLE, /* float is promoted to double */
MINIPC_ATYPE_STRING, /* size of strings is strlen() each time */
MINIPC_ATYPE_STRUCT
};
/* Encoding of argument type and size in one word */
#define __MINIPC_ARG_ENCODE(atype, asize) (((atype) << 16) | (asize))
#define MINIPC_ARG_ENCODE(atype, type) __MINIPC_ARG_ENCODE(atype, sizeof(type))
#define MINIPC_GET_ATYPE(word) ((word) >> 16)
#define MINIPC_GET_ASIZE(word) ((word) & 0xffff)
#define MINIPC_ARG_END __MINIPC_ARG_ENCODE(MINIPC_ATYPE_NONE, 0) /* zero */
/* The exported procedure looks like this */
struct minipc_pd;
typedef int (minipc_f)(const struct minipc_pd *, uint32_t *args, void *retval);
/* This is the "procedure definition" */
struct minipc_pd {
minipc_f *f; /* pointer to the function */
char name[MINIPC_MAX_NAME]; /* name of the function */
uint32_t flags;
uint32_t retval; /* type of return value */
uint32_t args[]; /* zero-terminated */
};
/* Flags: verbosity is about argument and retval marshall/unmarshall */
#define MINIPC_FLAG_VERBOSE 1
/* This is the channel definition */
struct minipc_ch {
int fd;
};
static inline int minipc_fileno(struct minipc_ch *ch) {return ch->fd;}
/* These return NULL with errno on error, name is the socket pathname */
struct minipc_ch *minipc_server_create(const char *name, int flags);
struct minipc_ch *minipc_client_create(const char *name, int flags);
int minipc_close(struct minipc_ch *ch);
/* Generic: set the default polling interval for mem-based channels */
int minipc_set_poll(int usec);
/* Server: register exported functions */
int minipc_export(struct minipc_ch *ch, const struct minipc_pd *pd);
int minipc_unexport(struct minipc_ch *ch, const struct minipc_pd *pd);
/* Server: helpers to unmarshall a string or struct from a request */
uint32_t *minipc_get_next_arg(uint32_t arg[], uint32_t atype);
/* Handle a request if pending, otherwise -1 and EAGAIN */
int minipc_server_action(struct minipc_ch *ch, int timeoutms);
#if __STDC_HOSTED__
/* Generic: attach diagnostics to a log file */
int minipc_set_logfile(struct minipc_ch *ch, FILE *logf);
/* Return an fdset for the user to select() on the service */
int minipc_server_get_fdset(struct minipc_ch *ch, fd_set *setptr);
/* Client: make requests */
int minipc_call(struct minipc_ch *ch, int millisec_timeout,
const struct minipc_pd *pd, void *ret, ...);
#endif /* __STDC_HOSTED__ */
#endif /* __MINIPC_H__ */
/*
* Mini-ipc: an example freestanding server, based in memory
*
* Copyright (C) 2011,2012 CERN (www.cern.ch)
* Author: Alessandro Rubini <rubini@gnudd.com>
*
* This code is copied from trivial-server, and made even more trivial
*/
#include <string.h>
#include <errno.h>
#include <sys/types.h>
#include "minipc.h"
/* A function that ignores the RPC and is written normally */
static int ss_do_sum(int a, int b)
{
return a + b;
}
/* The following ones are RPC-aware */
static int ss_sum_function(const struct minipc_pd *pd,
uint32_t *args, void *ret)
{
int i;
i = ss_do_sum(args[0], args[1]);
*(int *)ret = i;
return 0;
}
static int ss_mul_function(const struct minipc_pd *pd,
uint32_t *args, void *ret)
{
int a, b;
a = *(int *)args;
b = *(int *)(args + 1);
*(int *)ret = a * b;
return 0;
}
/* Describe the two functions above */
const struct minipc_pd ss_sum_struct = {
.f = ss_sum_function,
.name = "sum",
.retval = MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int),
.args = {
MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int),
MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int),
MINIPC_ARG_END,
},
};
const struct minipc_pd ss_mul_struct = {
.f = ss_mul_function,
.name = "mul",
.retval = MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int),
.args = {
MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int),
MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int),
MINIPC_ARG_END,
},
};
/* The mailbox is mapped at 0x3000 in the linker script */
static __attribute__((section(".mbox"))) _mailbox[1024];
int ipc_test()
{
struct minipc_ch *server;
// char str[];
server = minipc_server_create("mem:3000", 0);
if (!server)
return 1;
minipc_export(server, &ss_sum_struct);
minipc_export(server, &ss_mul_struct);
while (1) {
/* do something else... */
mprintf(".");
minipc_server_action(server, 1000);
}
}
......@@ -2,18 +2,17 @@
#include "uart.h"
#include "timer.h"
#include "minipc.h"
//void _irq_entry() {};
main()
{
uart_init();
ad9516_init();
spll_test();
char tmp[100];
for(;;)
{
mprintf("Ping [lock %d]!\n", spll_check_lock());
timer_delay(TICS_PER_SECOND);
}
// spll_test();
ipc_test();
}
\ No newline at end of file
......@@ -31,13 +31,15 @@ GROUP(-lgcc -lc)
MEMORY
{
ram : ORIGIN = 0x00000000, LENGTH = 0x4000
ram : ORIGIN = 0x00000000, LENGTH = 0x3000
mbox : ORIGIN = 0x3000, LENGTH = 0x1000
}
SECTIONS
{
.boot : { *(.boot) } > ram
/* Code */
.text :
......@@ -108,6 +110,13 @@ SECTIONS
_end = .;
PROVIDE (end = .);
} > ram
.mbox :
{
. = ALIGN(4);
_fmbox = .;
*(.mbox)
} > mbox
/* First location in stack is highest address in RAM */
PROVIDE(_fstack = ORIGIN(ram) + LENGTH(ram) - 4);
......
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