Commit d9cc882d authored by Alessandro Rubini's avatar Alessandro Rubini

rt: removed subdirectory, we now rely on wrpc-sw code

Signed-off-by: Alessandro Rubini's avatarAlessandro Rubini <rubini@gnudd.com>
parent 8bd8fb9f
......@@ -12,13 +12,8 @@ wrs_echo "--- Deploying FPGA firmware"
FWDIR="${WRS_OUTPUT_DIR}/images/wr/lib/firmware"
mkdir -p "$FWDIR"
if [ -f "${WRS_BASE_DIR}/../rt/rt_cpu.bin" ]; then
echo "Using self-compiled RT firmware"
cp ${WRS_BASE_DIR}/../rt/rt_cpu.bin "$FWDIR"
else
echo "Using pre-compiled (binaries/) RT firmware"
cp ${WRS_BASE_DIR}/../binaries/rt_cpu.bin "$FWDIR"
fi
echo "Using pre-compiled (binaries/) RT firmware"
cp ${WRS_BASE_DIR}/../binaries/rt_cpu.bin "$FWDIR"
if [ "$WRS_HW_DIR" != "" ]; then
wrs_echo "Copying binaries from $WRS_HW_DIR"
......
*.bin
*.elf
*.o
*.sh
*.stp
revision.*
\ No newline at end of file
CROSS_COMPILE ?= lm32-elf-
LIBSOFTPLL_DIR = softpll
OBJS = main.o dev/uart.o dev/timer-wrs.o dev/ad9516.o ipc/minipc-mem-server.o ipc/rt_ipc.o
include pp_printf/printf.mk
include softpll/softpll.mk
OBJS += $(obj-y)
CFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -Idev
LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled -nostdlib -T arch/lm32/ram.ld
OBJS_PLATFORM=arch/lm32/crt0.o arch/lm32/irq.o
CC=$(CROSS_COMPILE)gcc
OBJCOPY=$(CROSS_COMPILE)objcopy
OBJDUMP=$(CROSS_COMPILE)objdump
CFLAGS= $(CFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -Iinclude/std -Iinclude -include include/trace.h -ffreestanding -Iipc -I$(LIBSOFTPLL_DIR) -I. -DCONFIG_WR_SWITCH
LDFLAGS= $(LDFLAGS_PLATFORM) -Wl,--gc-sections -Os -Iinclude -ffreestanding \
-lgcc -lc
SIZE = $(CROSS_COMPILE)size
OBJS += $(OBJS_PLATFORM)
REVISION=$(shell git describe --always --dirty=+ | sed 's/wr-switch-sw-//')
OUTPUT=rt_cpu
# temporary fix for pp_printf
CONFIG_PRINTF_XINT=y
CFLAGS += -I$(CURDIR)/pp_printf -DCONFIG_PRINT_BUFSIZE=256
all: $(OBJS)
$(SIZE) -t $(OBJS)
echo "const char *build_revision = \"$(REVISION)\";" > revision.c
echo "const char *build_date = __DATE__ \" \" __TIME__;" >> revision.c
$(CC) $(CFLAGS) -c revision.c
${CC} -o $(OUTPUT).elf $(OBJS) revision.o $(LDFLAGS)
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
clean:
rm -f $(OBJS) $(OUTPUT).elf $(OUTPUT).bin $(OUTPUT).ram
scp: all
scp rt_cpu.bin root@pcbe12132:/tftpboot/rootfs/wr/lib/firmware
install: all
cp $(OUTPUT).bin ../binaries
%.o: %.c
${CC} $(CFLAGS) $(LIB_DIR) -c $^ -o $@
/****************************************************************************
**
** Name: crt0ram.S
**
** Description:
** Implements boot-code that calls LatticeDDInit (that calls main())
** Implements exception handlers (actually, redirectors)
**
** $Revision: $
**
** Disclaimer:
**
** This source code is intended as a design reference which
** illustrates how these types of functions can be implemented. It
** is the user's responsibility to verify their design for
** consistency and functionality through the use of formal
** verification methods. Lattice Semiconductor provides no warranty
** regarding the use or functionality of this code.
**
** --------------------------------------------------------------------
**
** Lattice Semiconductor Corporation
** 5555 NE Moore Court
** Hillsboro, OR 97214
** U.S.A
**
** TEL: 1-800-Lattice (USA and Canada)
** (503)268-8001 (other locations)
**
** web: http://www.latticesemi.com
** email: techsupport@latticesemi.com
**
** --------------------------------------------------------------------------
**
** Change History (Latest changes on top)
**
** Ver Date Description
** --------------------------------------------------------------------------
** 3.8 Apr-15-2011 Added __MICO_USER_<handler>_HANDLER__ preprocessor to
** allow customers to implement their own handlers for:
** DATA_ABORT, INST_ABORT
**
** 3.1 Jun-18-2008 Added __MICO_NO_INTERRUPTS__ preprocessor
** option to exclude invoking MicoISRHandler
** to reduce code-size in apps that don't use
** interrupts
**
** 3.0 Mar-25-2008 Added Header
**
**---------------------------------------------------------------------------
*****************************************************************************/
/*
* LatticeMico32 C startup code.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*/
/* From include/sys/signal.h */
#define SIGINT 2 /* interrupt */
#define SIGTRAP 5 /* trace trap */
#define SIGFPE 8 /* arithmetic exception */
#define SIGSEGV 11 /* segmentation violation */
//#define MICO32_FULL_CONTEXT_SAVE_RESTORE
/* Exception handlers - Must be 32 bytes long. */
.section .boot, "ax", @progbits
.global _start
_start:
.global _reset_handler
.type _reset_handler, @function
_reset_handler:
xor r0, r0, r0
wcsr IE, r0
wcsr IM, r0
mvhi r1, hi(_reset_handler)
ori r1, r1, lo(_reset_handler)
wcsr EBA, r1
calli _crt0
nop
.size _reset_handler, .-_reset_handler
.extern _irq_entry
.org 0xc0
.global _interrupt_handler
.type _interrupt_handler, @function
_interrupt_handler:
sw (sp+0), ra
calli _save_all
mvi r1, SIGINT
#ifndef __MICO_NO_INTERRUPTS__
calli _irq_entry
#else
wcsr IE, r0
#endif
bi _restore_all_and_return
nop
nop
nop
.org 0x100
.global _crt0
.type _crt0, @function
_crt0:
/* Clear r0 */
xor r0, r0, r0
/* Setup stack and global pointer */
mvhi sp, hi(_fstack)
ori sp, sp, lo(_fstack)
mvhi gp, hi(_gp)
ori gp, gp, lo(_gp)
mvhi r1, hi(_fbss)
ori r1, r1, lo(_fbss)
mvi r2, 0
mvhi r3, hi(_ebss)
ori r3, r3, lo(_ebss)
sub r3, r3, r1
calli memset
mvi r1, 0
mvi r2, 0
mvi r3, 0
calli main
loopf:
bi loopf
.global _save_all
.type _save_all, @function
_save_all:
#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
addi sp, sp, -128
#else
addi sp, sp, -60
#endif
sw (sp+4), r1
sw (sp+8), r2
sw (sp+12), r3
sw (sp+16), r4
sw (sp+20), r5
sw (sp+24), r6
sw (sp+28), r7
sw (sp+32), r8
sw (sp+36), r9
sw (sp+40), r10
#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
sw (sp+44), r11
sw (sp+48), r12
sw (sp+52), r13
sw (sp+56), r14
sw (sp+60), r15
sw (sp+64), r16
sw (sp+68), r17
sw (sp+72), r18
sw (sp+76), r19
sw (sp+80), r20
sw (sp+84), r21
sw (sp+88), r22
sw (sp+92), r23
sw (sp+96), r24
sw (sp+100), r25
sw (sp+104), r26
sw (sp+108), r27
sw (sp+120), ea
sw (sp+124), ba
/* ra and sp need special handling, as they have been modified */
lw r1, (sp+128)
sw (sp+116), r1
mv r1, sp
addi r1, r1, 128
sw (sp+112), r1
#else
sw (sp+52), ea
sw (sp+56), ba
/* ra and sp need special handling, as they have been modified */
lw r1, (sp+60)
sw (sp+48), r1
mv r1, sp
addi r1, r1, 60
sw (sp+44), r1
#endif
// xor r1, r1, r1
// wcsr ie, r1
ret
.size _save_all, .-_save_all
.global _restore_all_and_return
.type _restore_all_and_return, @function
/* Restore all registers and return from exception */
_restore_all_and_return:
// addi r1, r0, 2
// wcsr ie, r1
lw r1, (sp+4)
lw r2, (sp+8)
lw r3, (sp+12)
lw r4, (sp+16)
lw r5, (sp+20)
lw r6, (sp+24)
lw r7, (sp+28)
lw r8, (sp+32)
lw r9, (sp+36)
lw r10, (sp+40)
#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
lw r11, (sp+44)
lw r12, (sp+48)
lw r13, (sp+52)
lw r14, (sp+56)
lw r15, (sp+60)
lw r16, (sp+64)
lw r17, (sp+68)
lw r18, (sp+72)
lw r19, (sp+76)
lw r20, (sp+80)
lw r21, (sp+84)
lw r22, (sp+88)
lw r23, (sp+92)
lw r24, (sp+96)
lw r25, (sp+100)
lw r26, (sp+104)
lw r27, (sp+108)
lw ra, (sp+116)
lw ea, (sp+120)
lw ba, (sp+124)
/* Stack pointer must be restored last, in case it has been updated */
lw sp, (sp+112)
#else
lw ra, (sp+48)
lw ea, (sp+52)
lw ba, (sp+56)
/* Stack pointer must be restored last, in case it has been updated */
lw sp, (sp+44)
#endif
nop
eret
.size _restore_all_and_return, .-_restore_all_and_return
This diff is collapsed.
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2011 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#include "irq.h"
void disable_irq()
{
unsigned int ie, im;
unsigned int Mask = ~1;
/* disable peripheral interrupts in case they were enabled */
asm volatile ("rcsr %0,ie":"=r" (ie));
ie &= (~0x1);
asm volatile ("wcsr ie, %0"::"r" (ie));
/* disable mask-bit in im */
asm volatile ("rcsr %0, im":"=r" (im));
im &= Mask;
asm volatile ("wcsr im, %0"::"r" (im));
}
void enable_irq()
{
unsigned int ie, im;
unsigned int Mask = 1;
/* disable peripheral interrupts in-case they were enabled */
asm volatile ("rcsr %0,ie":"=r" (ie));
ie &= (~0x1);
asm volatile ("wcsr ie, %0"::"r" (ie));
/* enable mask-bit in im */
asm volatile ("rcsr %0, im":"=r" (im));
im |= Mask;
asm volatile ("wcsr im, %0"::"r" (im));
ie |= 0x1;
asm volatile ("wcsr ie, %0"::"r" (ie));
}
/*
* Link script for Lattice Mico32. Very loosely based on
* code contributed by Jon Beniston <jon@beniston.com>
*
* Jon's license (BSD-style):
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*/
OUTPUT_FORMAT("elf32-lm32")
ENTRY(_start)
MEMORY
{
ram : ORIGIN = 0x00000000, LENGTH = 0x7000
mbox : ORIGIN = 0x7000, LENGTH = 0x1000
}
SECTIONS
{
.boot : { *(.boot) } > ram
.text : { *(.text .text.*) } > ram =0
.rodata : { *(.rodata .rodata.*) } > ram
.data : {
*(.data .data.*)
_gp = ALIGN(16) + 0x7ff0; /* FIXME: what is this? */
} > ram
.bss : {
_fbss = .;
*(.bss .bss.*)
*(COMMON)
_ebss = .;
} > ram
.mbox : {
. = ALIGN(4);
_fmbox = .;
*(.mbox)
} > mbox
/* First location in stack is highest address in RAM */
PROVIDE(_fstack = ORIGIN(ram) + LENGTH(ram) - 4);
}
/* We need to provide mprintf to ptp-noposix object files, if missing */
PROVIDE(mprintf = pp_printf);
/*
* Trivial pll programmer using an spi controoler.
* PLL is AD9516, SPI is opencores
* Tomasz Wlostowski, Alessandro Rubini, 2011, for CERN.
*/
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include "board.h"
#include "syscon.h"
#include "gpio-wrs.h"
#include "rt_ipc.h"
#ifndef ARRAY_SIZE
#define ARRAY_SIZE(a) (sizeof(a)/sizeof(a[0]))
#endif
static inline void writel(uint32_t data, void *where)
{
* (volatile uint32_t *)where = data;
}
static inline uint32_t readl(void *where)
{
return * (volatile uint32_t *)where;
}
struct ad9516_reg {
uint16_t reg;
uint8_t val;
};
#include "ad9516_config.h"
/*
* SPI stuff, used by later code
*/
#define SPI_REG_RX0 0
#define SPI_REG_TX0 0
#define SPI_REG_RX1 4
#define SPI_REG_TX1 4
#define SPI_REG_RX2 8
#define SPI_REG_TX2 8
#define SPI_REG_RX3 12
#define SPI_REG_TX3 12
#define SPI_REG_CTRL 16
#define SPI_REG_DIVIDER 20
#define SPI_REG_SS 24
#define SPI_CTRL_ASS (1<<13)
#define SPI_CTRL_IE (1<<12)
#define SPI_CTRL_LSB (1<<11)
#define SPI_CTRL_TXNEG (1<<10)
#define SPI_CTRL_RXNEG (1<<9)
#define SPI_CTRL_GO_BSY (1<<8)
#define SPI_CTRL_CHAR_LEN(x) ((x) & 0x7f)
#define GPIO_PLL_RESET_N 1
#define GPIO_SYS_CLK_SEL 0
#define GPIO_PERIPH_RESET_N 3
#define CS_PLL 0 /* AD9516 on SPI CS0 */
static void *oc_spi_base;
int oc_spi_init(void *base_addr)
{
oc_spi_base = base_addr;
writel(100, oc_spi_base + SPI_REG_DIVIDER);
return 0;
}
int oc_spi_txrx(int ss, int nbits, uint32_t in, uint32_t *out)
{
uint32_t rval;
if (!out)
out = &rval;
writel(SPI_CTRL_ASS | SPI_CTRL_CHAR_LEN(nbits)
| SPI_CTRL_TXNEG,
oc_spi_base + SPI_REG_CTRL);
writel(in, oc_spi_base + SPI_REG_TX0);
writel((1 << ss), oc_spi_base + SPI_REG_SS);
writel(SPI_CTRL_ASS | SPI_CTRL_CHAR_LEN(nbits)
| SPI_CTRL_TXNEG | SPI_CTRL_GO_BSY,
oc_spi_base + SPI_REG_CTRL);
while(readl(oc_spi_base + SPI_REG_CTRL) & SPI_CTRL_GO_BSY)
;
*out = readl(oc_spi_base + SPI_REG_RX0);
return 0;
}
/*
* AD9516 stuff, using SPI, used by later code.
* "reg" is 12 bits, "val" is 8 bits, but both are better used as int
*/
static void ad9516_write_reg(int reg, int val)
{
oc_spi_txrx(CS_PLL, 24, (reg << 8) | val, NULL);
}
static int ad9516_read_reg(int reg)
{
uint32_t rval;
oc_spi_txrx(CS_PLL, 24, (reg << 8) | (1 << 23), &rval);
return rval & 0xff;
}
static void ad9516_load_regset(const struct ad9516_reg *regs, int n_regs, int commit)
{
int i;
for(i=0; i<n_regs; i++)
ad9516_write_reg(regs[i].reg, regs[i].val);
if(commit)
ad9516_write_reg(0x232, 1);
}
static void ad9516_wait_lock()
{
while ((ad9516_read_reg(0x1f) & 1) == 0);
}
#define SECONDARY_DIVIDER 0x100
int ad9516_set_output_divider(int output, int ratio, int phase_offset)
{
uint8_t lcycles = (ratio/2) - 1;
uint8_t hcycles = (ratio - (ratio / 2)) - 1;
int secondary = (output & SECONDARY_DIVIDER) ? 1 : 0;
output &= 0xf;
if(output >= 0 && output < 6) /* LVPECL outputs */
{
uint16_t base = (output / 2) * 0x3 + 0x190;
if(ratio == 1) /* bypass the divider */
{
uint8_t div_ctl = ad9516_read_reg(base + 1);
ad9516_write_reg(base + 1, div_ctl | (1<<7) | (phase_offset & 0xf));
} else {
uint8_t div_ctl = ad9516_read_reg(base + 1);
TRACE("DivCtl: %x\n", div_ctl);
ad9516_write_reg(base + 1, (div_ctl & (~(1<<7))) | (phase_offset & 0xf)); /* disable bypass bit */
ad9516_write_reg(base, (lcycles << 4) | hcycles);
}
} else { /* LVDS/CMOS outputs */
uint16_t base = ((output - 6) / 2) * 0x5 + 0x199;
TRACE("Output [divider %d]: %d ratio: %d base %x lc %d hc %d\n", secondary, output, ratio, base, lcycles ,hcycles);
if(!secondary)
{
if(ratio == 1) /* bypass the divider 1 */
ad9516_write_reg(base + 3, ad9516_read_reg(base + 3) | 0x10);
else {
ad9516_write_reg(base, (lcycles << 4) | hcycles);
ad9516_write_reg(base + 1, phase_offset & 0xf);
}
} else {
if(ratio == 1) /* bypass the divider 2 */
ad9516_write_reg(base + 3, ad9516_read_reg(base + 3) | 0x20);
else {
ad9516_write_reg(base + 2, (lcycles << 4) | hcycles);
// ad9516_write_reg(base + 1, phase_offset & 0xf);
}
}
}
/* update */
ad9516_write_reg(0x232, 0x0);
ad9516_write_reg(0x232, 0x1);
ad9516_write_reg(0x232, 0x0);
}
int ad9516_set_vco_divider(int ratio) /* Sets the VCO divider (2..6) or 0 to enable static output */
{
if(ratio == 0)
ad9516_write_reg(0x1e0, 0x5); /* static mode */
else
ad9516_write_reg(0x1e0, (ratio-2));
ad9516_write_reg(0x232, 0x1);
}
void ad9516_sync_outputs()
{
/* VCO divider: static mode */
ad9516_write_reg(0x1E0, 0x7);
ad9516_write_reg(0x232, 0x1);
/* Sync the outputs when they're inactive to avoid +-1 cycle uncertainity */
ad9516_write_reg(0x230, 1);
ad9516_write_reg(0x232, 1);
ad9516_write_reg(0x230, 0);
ad9516_write_reg(0x232, 1);
}
int ad9516_init(int ref_source)
{
TRACE("Initializing AD9516 PLL...\n");
oc_spi_init((void *)BASE_SPI);
gpio_out(GPIO_SYS_CLK_SEL, 0); /* switch to the standby reference clock, since the PLL is off after reset */
/* reset the PLL */
gpio_out(GPIO_PLL_RESET_N, 0);
timer_delay(10);
gpio_out(GPIO_PLL_RESET_N, 1);
timer_delay(10);
/* Use unidirectional SPI mode */
ad9516_write_reg(0x000, 0x99);
/* Check the presence of the chip */
if (ad9516_read_reg(0x3) != 0xc3) {
TRACE("Error: AD9516 PLL not responding.\n");
return -1;
}
ad9516_load_regset(ad9516_base_config, ARRAY_SIZE(ad9516_base_config), 0);
ad9516_load_regset(ad9516_ref_tcxo, ARRAY_SIZE(ad9516_ref_tcxo), 1);
ad9516_wait_lock();
ad9516_sync_outputs();
ad9516_set_output_divider(9, 4, 0); /* AUX/SWCore = 187.5 MHz */
ad9516_set_output_divider(7, 12, 0); /* REF = 62.5 MHz */
ad9516_set_output_divider(4, 12, 0); /* GTX = 62.5 MHz */
ad9516_sync_outputs();
ad9516_set_vco_divider(2);
TRACE("AD9516 locked.\n");
gpio_out(GPIO_SYS_CLK_SEL, 1); /* switch the system clock to the PLL reference */
gpio_out(GPIO_PERIPH_RESET_N, 0); /* reset all peripherals which use AD9516-provided clocks */
gpio_out(GPIO_PERIPH_RESET_N, 1);
return 0;
}
int rts_debug_command(int command, int value)
{
switch(command)
{
case RTS_DEBUG_ENABLE_SERDES_CLOCKS:
if(value)
{
ad9516_write_reg(0xf4, 0x08); // OUT4 enabled
ad9516_write_reg(0x232, 0x0);
ad9516_write_reg(0x232, 0x1);
} else {
ad9516_write_reg(0xf4, 0x0a); // OUT4 power-down, no serdes clock
ad9516_write_reg(0x232, 0x0);
ad9516_write_reg(0x232, 0x1);
}
break;
}
}
/* Base configuration (global dividers, output config, reference-independent) */
const struct ad9516_reg ad9516_base_config[] = {
{0x0000, 0x99},
{0x0001, 0x00},
{0x0002, 0x10},
{0x0003, 0xC3},
{0x0004, 0x00},
{0x0010, 0x7C},
{0x0011, 0x05},
{0x0012, 0x00},
{0x0013, 0x0C},
{0x0014, 0x12},
{0x0015, 0x00},
{0x0016, 0x05},
{0x0017, 0x88},
{0x0018, 0x07},
{0x0019, 0x00},
{0x001A, 0x00},
{0x001B, 0x00},
{0x001C, 0x02},
{0x001D, 0x00},
{0x001E, 0x00},
{0x001F, 0x0E},
{0x00A0, 0x01},
{0x00A1, 0x00},
{0x00A2, 0x00},
{0x00A3, 0x01},
{0x00A4, 0x00},
{0x00A5, 0x00},
{0x00A6, 0x01},
{0x00A7, 0x00},
{0x00A8, 0x00},
{0x00A9, 0x01},
{0x00AA, 0x00},
{0x00AB, 0x00},
{0x00F0, 0x0A},
{0x00F1, 0x0A},
{0x00F2, 0x0A},
{0x00F3, 0x0A},
{0x00F4, 0x08},
{0x00F5, 0x08},
{0x0140, 0x43},
{0x0141, 0x42},
{0x0142, 0x43},
{0x0143, 0x42},
{0x0190, 0x00},
{0x0191, 0x80},
{0x0192, 0x00},
{0x0193, 0xBB},
{0x0194, 0x00},
{0x0195, 0x00},
{0x0196, 0x00},
{0x0197, 0x00},
{0x0198, 0x00},
{0x0199, 0x11},
{0x019A, 0x00},
{0x019B, 0x11},
{0x019C, 0x20},
{0x019D, 0x00},
{0x019E, 0x11},
{0x019F, 0x00},
{0x01A0, 0x11},
{0x01A1, 0x20},
{0x01A2, 0x00},
{0x01A3, 0x00},
{0x01E0, 0x04},
{0x01E1, 0x02},
{0x0230, 0x00},
{0x0231, 0x00},
};
/* Config for 25 MHz VCTCXO reference (RDiv = 5, use REF1) */
const struct ad9516_reg ad9516_ref_tcxo[] = {
{0x0011, 0x05},
{0x0012, 0x00}, /* RDiv = 5 */
{0x001C, 0x06} /* Use REF1 */
};
/* Config for 10 MHz external reference (RDiv = 2, use REF2) */
const struct ad9516_reg ad9516_ref_ext[] = {
{0x0011, 0x02},
{0x0012, 0x00}, /* RDiv = 2 */
{0x001C, 0x46} /* Use REF1 */
};
const struct {int reg; uint8_t val} ad9516_regs[] = {
{0x0000, 0x99},
{0x0001, 0x00},
{0x0002, 0x10},
{0x0003, 0xC3},
{0x0004, 0x00},
{0x0010, 0x7C},
{0x0011, 0x01},
{0x0012, 0x00},
{0x0013, 0x04},
{0x0014, 0x07},
{0x0015, 0x00},
{0x0016, 0x04},
{0x0017, 0x00},
{0x0018, 0x07},
{0x0019, 0x00},
{0x001A, 0x00},
{0x001B, 0x00},
{0x001C, 0x46},
{0x001D, 0x00},
{0x001E, 0x00},
{0x001F, 0x0E},
{0x00A0, 0x01},
{0x00A1, 0x00},
{0x00A2, 0x00},
{0x00A3, 0x01},
{0x00A4, 0x00},
{0x00A5, 0x00},
{0x00A6, 0x01},
{0x00A7, 0x00},
{0x00A8, 0x00},
{0x00A9, 0x01},
{0x00AA, 0x00},
{0x00AB, 0x00},
{0x00F0, 0x0A},
{0x00F1, 0x0A},
{0x00F2, 0x0A},
{0x00F3, 0x0A},
{0x00F4, 0x08},
{0x00F5, 0x0A},
{0x0140, 0x43},
{0x0141, 0x43},
{0x0142, 0x43},
{0x0143, 0x43},
{0x0190, 0x00},
{0x0191, 0x80},
{0x0192, 0x00},
{0x0193, 0xBB},
{0x0194, 0x00},
{0x0195, 0x00},
{0x0196, 0x00},
{0x0197, 0x00},
{0x0198, 0x00},
{0x0199, 0x22},
{0x019A, 0x00},
{0x019B, 0x11},
{0x019C, 0x00},
{0x019D, 0x00},
{0x019E, 0x22},
{0x019F, 0x00},
{0x01A0, 0x11},
{0x01A1, 0x00},
{0x01A2, 0x00},
{0x01A3, 0x00},
{0x01E0, 0x04},
{0x01E1, 0x02},
{0x0230, 0x00},
{0x0231, 0x00},
{0x0232, 0x00},
{-1, 0}};
#include "board.h"
#include "syscon.h"
uint32_t timer_get_tics()
{
return *(volatile uint32_t *) (BASE_TIMER);
}
void timer_delay(uint32_t how_long)
{
uint32_t t_start;
t_start = timer_get_tics();
if(t_start + how_long < t_start)
while(t_start + how_long < timer_get_tics());
while(t_start + how_long > timer_get_tics());
}
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2011 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#include <inttypes.h>
#include "board.h"
#include "uart.h"
#include <hw/wb_vuart.h>
#define CALC_BAUD(baudrate) \
( ((( (unsigned long long)baudrate * 8ULL) << (16 - 7)) + \
(CPU_CLOCK >> 8)) / (CPU_CLOCK >> 7) )
volatile struct UART_WB *uart;
void uart_init_hw()
{
uart = (volatile struct UART_WB *)BASE_UART;
uart->BCR = CALC_BAUD(UART_BAUDRATE);
}
void __attribute__((weak)) uart_init_sw(void)
{}
void uart_write_byte(int b)
{
if (b == '\n')
uart_write_byte('\r');
while (uart->SR & UART_SR_TX_BUSY)
;
uart->TDR = b;
}
int uart_write_string(const char *s)
{
const char *t = s;
while (*s)
uart_write_byte(*(s++));
return s - t;
}
static int uart_poll()
{
return uart->SR & UART_SR_RX_RDY;
}
int uart_read_byte()
{
if (!uart_poll())
return -1;
return uart->RDR & 0xff;
}
int puts(const char *s)
__attribute__((alias("uart_write_string")));
/* The next alias is for ppsi log messages, that go to sw_uart if built */
int uart_sw_write_string(const char *s)
__attribute__((alias("uart_write_string"), weak));
#ifndef __BOARD_H
#define __BOARD_H
/* RT CPU Memory layout */
#define CPU_CLOCK 62500000
#define UART_BAUDRATE 115200
#define BASE_UART 0x10000
#define BASE_SOFTPLL 0x10100
#define BASE_SPI 0x10200
#define BASE_GPIO 0x10300
#define BASE_TIMER 0x10400
#define BASE_PPS_GEN 0x10500
#endif
#ifndef __GPIO_H
#define __GPIO_H
#include <stdint.h>
#include "board.h"
struct GPIO_WB
{
uint32_t CODR; /*Clear output register*/
uint32_t SODR; /*Set output register*/
uint32_t DDR; /*Data direction register (1 means out)*/
uint32_t PSR; /*Pin state register*/
};
static volatile struct GPIO_WB *__gpio = (volatile struct GPIO_WB *) BASE_GPIO;
static inline void gpio_out(int pin, int val)
{
if(val)
__gpio->SODR = (1<<pin);
else
__gpio->CODR = (1<<pin);
}
static inline void gpio_dir(int pin, int val)
{
if(val)
__gpio->DDR |= (1<<pin);
else
__gpio->DDR &= ~(1<<pin);
}
static inline int gpio_in(int bank, int pin)
{
return __gpio->PSR & (1<<pin) ? 1: 0;
}
#endif
/*
Register definitions for slave core: Virtual UART
* File : wb_vuart.h
* Author : auto-generated by wbgen2 from wb_virtual_uart.wb
* Created : Wed Apr 6 23:02:01 2011
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE wb_virtual_uart.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_WB_VIRTUAL_UART_WB
#define __WBGEN2_REGDEFS_WB_VIRTUAL_UART_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Status Register */
/* definitions for field: TX busy in reg: Status Register */
#define UART_SR_TX_BUSY WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX ready in reg: Status Register */
#define UART_SR_RX_RDY WBGEN2_GEN_MASK(1, 1)
/* definitions for register: Baudrate control register */
/* definitions for register: Transmit data regsiter */
/* definitions for field: Transmit data in reg: Transmit data regsiter */
#define UART_TDR_TX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_TDR_TX_DATA_SHIFT 0
#define UART_TDR_TX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_TDR_TX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: Receive data regsiter */
/* definitions for field: Received data in reg: Receive data regsiter */
#define UART_RDR_RX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_RDR_RX_DATA_SHIFT 0
#define UART_RDR_RX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_RDR_RX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: FIFO 'UART TX FIFO' data output register 0 */
/* definitions for field: Char sent by UART to TX in reg: FIFO 'UART TX FIFO' data output register 0 */
#define UART_DEBUG_R0_TX_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_DEBUG_R0_TX_SHIFT 0
#define UART_DEBUG_R0_TX_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_DEBUG_R0_TX_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: FIFO 'UART TX FIFO' control/status register */
/* definitions for field: FIFO full flag in reg: FIFO 'UART TX FIFO' control/status register */
#define UART_DEBUG_CSR_FULL WBGEN2_GEN_MASK(16, 1)
/* definitions for field: FIFO empty flag in reg: FIFO 'UART TX FIFO' control/status register */
#define UART_DEBUG_CSR_EMPTY WBGEN2_GEN_MASK(17, 1)
/* definitions for field: FIFO counter in reg: FIFO 'UART TX FIFO' control/status register */
#define UART_DEBUG_CSR_USEDW_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_DEBUG_CSR_USEDW_SHIFT 0
#define UART_DEBUG_CSR_USEDW_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_DEBUG_CSR_USEDW_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
PACKED struct UART_WB {
/* [0x0]: REG Status Register */
uint32_t SR;
/* [0x4]: REG Baudrate control register */
uint32_t BCR;
/* [0x8]: REG Transmit data regsiter */
uint32_t TDR;
/* [0xc]: REG Receive data regsiter */
uint32_t RDR;
/* [0x10]: REG FIFO 'UART TX FIFO' data output register 0 */
uint32_t DEBUG_R0;
/* [0x14]: REG FIFO 'UART TX FIFO' control/status register */
uint32_t DEBUG_CSR;
};
#endif
#ifndef __IRQ_H
#define __IRQ_H
static inline void clear_irq()
{
unsigned int val = 1;
asm volatile ("wcsr ip, %0"::"r" (val));
}
void disable_irq();
void enable_irq();
#endif
#ifndef __WRAPPED_INTTYPES_H
#define __WRAPPED_INTTYPES_H
typedef unsigned char uint8_t;
typedef unsigned short uint16_t;
typedef unsigned int uint32_t;
typedef signed long long uint64_t;
typedef signed char int8_t;
typedef signed short int16_t;
typedef signed int int32_t;
typedef signed long long int64_t;
#define UINT32_MAX 4294967295U
#endif
#ifndef __STDINT_H__
#define __STDINT_H__
#include<inttypes.h>
#endif
/* usleep */
#include <syscon.h>
#ifndef __SYSCON_H
#define __SYSCON_H
#include <stdint.h>
#define TICS_PER_SECOND 100000
uint32_t timer_get_tics();
void timer_delay(uint32_t how_long);
int timer_expired(uint32_t t_start, uint32_t how_long);
#endif
#ifndef __FREESTANDING_TRACE_H__
#define __FREESTANDING_TRACE_H__
#include <pp-printf.h>
#define TRACE(...) pp_printf(__VA_ARGS__)
#define TRACE_DEV(...) pp_printf(__VA_ARGS__)
#endif
#ifndef __UART_H
#define __UART_H
void uart_init_sw(void);
void uart_init_hw(void);
void uart_write_byte(int b);
int uart_write_string(const char *s);
int puts(const char *s);
int uart_read_byte(void);
/* uart-sw is used by ppsi (but may be wrapped to normal uart) */
int uart_sw_write_string(const char *s);
#endif
#ifndef __WRC_H
#define __WRC_H
#include "syscon.h"
#define mprintf pp_printf
#define PPS_WIDTH (10 * 1000 * 1000 / 16) /* 10ms */
#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? */
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->pd)
break;
if (i == MINIPC_MAX_EXPORT) {
errno = ENOMEM;
return NULL;
}
return p;
}
static void free(void *ptr)
{
struct mpc_flist *p = ptr;
p->pd = 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 <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"
#define RTIPC_EXPORT_STRUCTURES
#include "rt_ipc.h"
#include <softpll_ng.h>
static struct rts_pll_state pstate;
static void clear_state()
{
int i;
for(i=0;i<RTS_PLL_CHANNELS;i++)
{
pstate.channels[i].priority = 0;
pstate.channels[i].phase_setpoint = 0;
pstate.channels[i].phase_loopback = 0;
pstate.channels[i].flags = CHAN_REF_VALID;
}
pstate.flags = 0;
pstate.current_ref = 0;
pstate.mode = RTS_MODE_DISABLED;
pstate.ipc_count = 0;
}
/* Sets the phase setpoint on a given channel */
int rts_adjust_phase(int channel, int32_t phase_setpoint)
{
// TRACE("Adjusting phase: ref channel %d, setpoint=%d ps.\n", channel, phase_setpoint);
spll_set_phase_shift(0, phase_setpoint);
pstate.channels[channel].phase_setpoint = phase_setpoint;
return 0;
}
/* Sets the RT subsystem mode (Boundary Clock or Grandmaster) */
int rts_set_mode(int mode)
{
int i;
const struct {
int mode_rt;
int mode_spll;
int do_init;
char *desc;
} options[] = {
{ RTS_MODE_GM_EXTERNAL, SPLL_MODE_GRAND_MASTER, 1, "Grand Master (external clock)" },
{ RTS_MODE_GM_FREERUNNING, SPLL_MODE_FREE_RUNNING_MASTER, 1, "Grand Master (free-running clock)" },
{ RTS_MODE_BC, SPLL_MODE_SLAVE, 0, "Boundary Clock (slave)" },
{ RTS_MODE_DISABLED, SPLL_MODE_DISABLED, 1, "PLL disabled" },
{ 0,0,0, NULL }
};
pstate.mode = mode;
for(i=0;options[i].desc != NULL;i++)
if(mode == options[i].mode_rt)
{
TRACE("RT: Setting mode to %s.\n", options[i].desc);
if(options[i].do_init)
spll_init(options[i].mode_spll, 0, 1);
else
spll_init(SPLL_MODE_DISABLED, 0, 0);
}
return 0;
}
/* Reference channel configuration (BC mode only) */
int rts_lock_channel(int channel, int priority)
{
if(pstate.mode != RTS_MODE_BC)
{
TRACE("trying to lock while not in slave mode,..\n");
return -1;
}
TRACE("RT [slave]: Locking to: %d (prio %d)\n", channel, priority);
spll_init(SPLL_MODE_SLAVE, channel, 0);
pstate.current_ref = channel;
return 0;
}
int rts_init()
{
clear_state();
}
void rts_update()
{
int i;
int n_ref;
int enabled;
spll_get_num_channels(&n_ref, NULL);
pstate.flags = (spll_check_lock(0) ? RTS_DMTD_LOCKED | RTS_REF_LOCKED : 0);
for(i=0;i<RTS_PLL_CHANNELS;i++)
{
#define CH pstate.channels[i]
CH.flags = 0;
CH.phase_loopback = 0;
CH.phase_current = 0;
// CH.phase_setpoint = 0;
CH.phase_loopback = 0;
if(i >= n_ref)
CH.flags = CHAN_DISABLED;
else {
if(i==pstate.current_ref)
{
spll_get_phase_shift(0, &CH.phase_current, NULL);
if(spll_shifter_busy(0))
CH.flags |= CHAN_SHIFTING;
}
if(spll_read_ptracker(i, &CH.phase_loopback, &enabled))
CH.flags |= CHAN_PMEAS_READY;
CH.flags |= (enabled ? CHAN_PTRACKER_ENABLED : 0);
}
#undef CH
}
}
/* fixme: this assumes the host is BE */
static int htonl(int i)
{
return i;
}
static int rts_get_state_func(const struct minipc_pd *pd, uint32_t *args, void *ret)
{
struct rts_pll_state *tmp = (struct rts_pll_state *)ret;
int i;
pstate.ipc_count++;
/* gaaaah, somebody should write a SWIG plugin for generating this stuff. */
tmp->current_ref = htonl(pstate.current_ref);
tmp->flags = htonl(pstate.flags);
tmp->holdover_duration = htonl(pstate.holdover_duration);
tmp->mode = htonl(pstate.mode);
tmp->delock_count = spll_get_delock_count();
tmp->ipc_count = pstate.ipc_count;
for(i=0; i<RTS_PLL_CHANNELS;i++)
{
tmp->channels[i].priority = htonl(pstate.channels[i].priority);
tmp->channels[i].phase_setpoint = htonl(pstate.channels[i].phase_setpoint);
tmp->channels[i].phase_current = htonl(pstate.channels[i].phase_current);
tmp->channels[i].phase_loopback = htonl(pstate.channels[i].phase_loopback);
tmp->channels[i].flags = htonl(pstate.channels[i].flags);
}
return 0;
}
static int rts_set_mode_func(const struct minipc_pd *pd, uint32_t *args, void *ret)
{
pstate.ipc_count++;
*(int *) ret = rts_set_mode(args[0]);
}
static int rts_lock_channel_func(const struct minipc_pd *pd, uint32_t *args, void *ret)
{
pstate.ipc_count++;
*(int *) ret = rts_lock_channel(args[0], (int)args[1]);
}
static int rts_adjust_phase_func(const struct minipc_pd *pd, uint32_t *args, void *ret)
{
pstate.ipc_count++;
*(int *) ret = rts_adjust_phase((int)args[0], (int)args[1]);
}
static int rts_enable_ptracker_func(const struct minipc_pd *pd, uint32_t *args, void *ret)
{
pstate.ipc_count++;
spll_enable_ptracker((int)args[0], (int)args[1]);
*(int *) ret = 0;
}
static int rts_debug_command_func(const struct minipc_pd *pd, uint32_t *args, void *ret)
{
pstate.ipc_count++;
*(int *) ret = rts_debug_command((int)args[0], (int)args[1]);
}
/* The mailbox is mapped at 0x7000 in the linker script */
static __attribute__((section(".mbox"))) _mailbox[1024];
static struct minipc_ch *server;
int rtipc_init()
{
server = minipc_server_create("mem:7000", 0);
if (!server)
return 1;
rtipc_rts_set_mode_struct.f = rts_set_mode_func;
rtipc_rts_get_state_struct.f = rts_get_state_func;
rtipc_rts_lock_channel_struct.f = rts_lock_channel_func;
rtipc_rts_adjust_phase_struct.f = rts_adjust_phase_func;
rtipc_rts_enable_ptracker_struct.f = rts_enable_ptracker_func;
rtipc_rts_debug_command_struct.f = rts_debug_command_func;
minipc_export(server, &rtipc_rts_set_mode_struct);
minipc_export(server, &rtipc_rts_get_state_struct);
minipc_export(server, &rtipc_rts_lock_channel_struct);
minipc_export(server, &rtipc_rts_adjust_phase_struct);
minipc_export(server, &rtipc_rts_enable_ptracker_struct);
minipc_export(server, &rtipc_rts_debug_command_struct);
return 0;
}
void rtipc_action()
{
minipc_server_action(server, 1000);
}
#ifndef __RT_IPC_H
#define __RT_IPC_H
#include <stdint.h>
#define RTS_PLL_CHANNELS 18
/* Individual channel flags */
/* Reference input frequency valid */
#define CHAN_REF_VALID (1<<0)
/* Frequency out of range */
#define CHAN_FREQ_OUT_OF_RANGE (1<<1)
/* Phase is drifting too fast */
#define CHAN_DRIFTING (1<<2)
/* Channel phase measurement is ready */
#define CHAN_PMEAS_READY (1<<3)
/* Channel not available/disabled */
#define CHAN_DISABLED (1<<4)
/* Channel is busy adjusting phase */
#define CHAN_SHIFTING (1<<5)
/* Channel is busy adjusting phase */
#define CHAN_PTRACKER_ENABLED (1<<6)
/* DMTD clock is present */
#define RTS_DMTD_LOCKED (1<<0)
/* 125 MHz reference locked */
#define RTS_REF_LOCKED (1<<1)
/* External 10 MHz reference present */
#define RTS_EXT_10M_VALID (1<<2)
/* External 1-PPS present */
#define RTS_EXT_PPS_VALID (1<<3)
/* External 10 MHz frequency out-of-range */
#define RTS_EXT_10M_OUT_OF_RANGE (1<<4)
/* External 1-PPS frequency out-of-range */
#define RTS_EXT_PPS_OUT_OF_RANGE (1<<5)
/* Holdover mode active */
#define RTS_HOLDOVER_ACTIVE (1<<6)
/* Grandmaster mode active (uses 10 MHz / 1-PPS reference) */
#define RTS_MODE_GM_EXTERNAL 1
/* Free-running grandmaster (uses local TCXO) */
#define RTS_MODE_GM_FREERUNNING 2
/* Boundary clock mode active (uses network reference) */
#define RTS_MODE_BC 3
/* PLL disabled */
#define RTS_MODE_DISABLED 4
/* null reference input */
#define REF_NONE 255
/* RT Subsystem debug commands, handled via rts_debug_command() */
/* Serdes reference clock enable/disable */
#define RTS_DEBUG_ENABLE_SERDES_CLOCKS 1
struct rts_pll_state {
/* State of an individual input channel (i.e. switch port) */
struct channel {
/* Switchover priority: 0 = highest, 1 - 254 = high..low, 255 = channel disabled (a master port) */
uint32_t priority;
/* channel phase setpoint in picoseconds. Used only when channel is a slave. */
int32_t phase_setpoint;
/* current phase shift in picoseconds. Used only when channel is a slave. */
int32_t phase_current;
/* TX-RX Loopback phase measurement in picoseconds. */
int32_t phase_loopback;
/* flags (per channel - see CHAN_xxx defines) */
uint32_t flags;
} channels[RTS_PLL_CHANNELS];
/* flags (global - RTS_xxx defines) */
uint32_t flags;
/* duration of current holdover period in 10us units */
int32_t holdover_duration;
/* current reference source - or REF_NONE if free-running or grandmaster */
uint32_t current_ref;
/* mode of operation (RTS_MODE_xxx) */
uint32_t mode;
uint32_t delock_count;
uint32_t ipc_count;
uint32_t debug_data[8];
};
/* API */
/* Connects to the RT CPU */
int rts_connect();
/* Queries the RT CPU PLL state */
int rts_get_state(struct rts_pll_state *state);
/* Sets the phase setpoint on a given channel */
int rts_adjust_phase(int channel, int32_t phase_setpoint);
/* Sets the RT subsystem mode (Boundary Clock or Grandmaster) */
int rts_set_mode(int mode);
/* Reference channel configuration (BC mode only) */
int rts_lock_channel(int channel, int priority);
/* Enabled/disables phase tracking on a particular port */
int rts_enable_ptracker(int channel, int enable);
/* Enabled/disables phase tracking on a particular port */
int rts_debug_command(int param, int value);
#ifdef RTIPC_EXPORT_STRUCTURES
static struct minipc_pd rtipc_rts_get_state_struct = {
.name = "aaaa",
.retval = MINIPC_ARG_ENCODE(MINIPC_ATYPE_STRUCT, struct rts_pll_state),
.args = {
MINIPC_ARG_END
},
};
static struct minipc_pd rtipc_rts_set_mode_struct = {
.name = "bbbb",
.retval = MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int),
.args = {
MINIPC_ARG_ENCODE(MINIPC_ATYPE_INT, int ),
MINIPC_ARG_END
},
};
static struct minipc_pd rtipc_rts_lock_channel_struct = {
.name = "cccc",
.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
},
};
static struct minipc_pd rtipc_rts_adjust_phase_struct = {
.name = "dddd",
.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
},
};
static struct minipc_pd rtipc_rts_enable_ptracker_struct = {
.name = "eeee",
.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
},
};
static struct minipc_pd rtipc_rts_debug_command_struct = {
.name = "ffff",
.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
},
};
#endif
#endif
#include "uart.h"
#include "syscon.h"
#include "softpll_ng.h"
#include "minipc.h"
const char *build_revision;
const char *build_date;
main()
{
uint32_t start_tics = 0;
uart_init_hw();
TRACE("WR Switch Real Time Subsystem (c) CERN 2011 - 2013\n");
TRACE("Revision: %s, built %s.\n", build_revision, build_date);
TRACE("--");
ad9516_init();
rts_init();
rtipc_init();
for(;;)
{
uint32_t tics = timer_get_tics();
if(tics - start_tics > TICS_PER_SECOND/5)
{
// TRACE("tick!\n");
spll_show_stats();
start_tics = tics;
}
rts_update();
rtipc_action();
}
return 0;
}
This diff is collapsed.
# Alessandro Rubini for CERN, 2011 -- public domain
AS = $(CROSS_COMPILE)as
LD = $(CROSS_COMPILE)ld
CC = $(CROSS_COMPILE)gcc
CPP = $(CC) -E
AR = $(CROSS_COMPILE)ar
NM = $(CROSS_COMPILE)nm
STRIP = $(CROSS_COMPILE)strip
OBJCOPY = $(CROSS_COMPILE)objcopy
OBJDUMP = $(CROSS_COMPILE)objdump
CFLAGS += -I. -Os -ggdb -Wall
obj-$(CONFIG_PRINTF_FULL) += vsprintf-full.o
obj-$(CONFIG_PRINTF_MINI) += vsprintf-mini.o
obj-$(CONFIG_PRINTF_NONE) += vsprintf-none.o
obj-$(CONFIG_PRINTF_XINT) += vsprintf-xint.o
# set full as a default if nothing is selected
obj-y ?= vsprintf-full.o
obj-y += printf.o
# There is a static variable in pp-printf.c to accumulate stuff
CONFIG_PRINT_BUFSIZE ?= 256
CFLAGS += -DCONFIG_PRINT_BUFSIZE=$(CONFIG_PRINT_BUFSIZE)
# Targets. You may want to make them different in your package
all: pp-printf.o example-printf
pp-printf.o: $(obj-y)
$(LD) -r $(obj-y) -o $@
example-printf: example-printf.c pp-printf.o
$(CC) $(CFLAGS) $^ -o $@
.c.o:
$(CC) -c $(CFLAGS) $< -o $@
clean:
rm -f *.o *~ example-printf
\ No newline at end of file
This is the "poor programmer's" printf implementation. It is meant to
be used in small environments, like microcontrollers or soft
processors. Actually, that's where I needed it years ago and where
I'm still using it.
It is a complete printf (it only misses the %[charset] feature, and
obviously floating point support). It relies on an external "puts"
function for the actual output; the full version also needs strnlen.
Unfortunately, the stdio puts adds a trailing newline (while most
embedded implementations do not). The sprintf function is included
as pp_sprintf.
The printf engine, vsprintf(), comes in four flavours:
In summary:
- the "full" version is a normal printf (GPL2, from older Linux kernel)
- the "xint" version accepts all formats and prints hex and int only
- the "mini" version accepts all formats but only prints hex (GPL2)
- the "none" version accepts all formats and prints nothing (PD)
The version you use can be selected at compile time, so you can
develop with a full-featured printf and install the minimal one in
production, saving a few kilobytes and still not loosing information
in messages. At the end I list compiled sizes for a few use cases.
While I use this very code in several projects, the only example here
is a stupid main that prints something. You are expected to pick these
files and copy them to your projects, rather than use this "package"
as a system library.
The full implementation in detail
=================================
This comes from u-boot, which means that it is an earlier printf as
used in the Linux kernel. It is licensed according to the GNU GPL
version 2. It includes all formats and prefixes and so on. It is
clearly bugless because everybody is using it.
It is selected at compile time by setting the make variable
"CONFIG_PRINTF_FULL" to "y". You can do that in the environment,
or use Kconfig in your application.
(The Makefile selects this by default if you set nothing in the
environment or make variables)
Example calls (example-printf.c):
pp_printf("integer %5i %5i %05i\n", 1024, 666, 53);
pp_printf("octal %5o %5o %05o\n", 1024, 666, 53);
pp_printf("hex %5x %5x %05x\n", 1024, 666, 53);
pp_printf("HEX etc %5X %+5d %-5i\n", 1024, 666, 53);
pp_printf("neg %5i %05i %05x\n", -5, -10, -15);
pp_printf("char: %c string %s %5s %.5s\n", 65, "foo", "foo",
"verylongstring");
pp_printf("hour %02d:%02d:%02d\n", 12, 9, 0);
Result (as you see, format modifiers are respected):
integer 1024 666 00053
octal 2000 1232 00065
hex 400 29a 00035
HEX etc 400 +666 53
neg -5 -0010 fffffff1
char: A string foo foo veryl
hour 12:09:00
Footprint: 1400-3200 bytes, plus 100-400 bytes for the frontend.
The xint implementation in detail
================================
This prints correctly "%c", "%s", "%i", "%x". Formats "%u" and "%d"
are synonyms of "%i", and "%p" is a synonym for "%x". The only
supported attributes are '0' and a one-digit width (e.g.: "%08x"
works). I personally use it a lot but I don't like it much, because it
is not powerful enough nor low-level as real hacker's too should be.
However, it matches the requirement of some projects with a little
user interface, where the "full" code reveals too large and the "mini"
code is too unfair to the reader. To compile it and link the example,
please set "CONFIG_PRINTF_XINT=y" in your environment or Makefile.
This is the result of the example. As expected, data is aligned and
has leading zeroes when requested, but bot other formats are obeyed:
integer 1024 666 00053
octal 2000 1232 00065
hex 400 29a 00035
HEX etc 400 666 53
neg -5 -0010 fffffff1
char: A string foo foo verylongstring
hour 12:09:00
Footprint: 350-800 bytes, plus 100-400 bytes for the frontend
The miminal implementation in detail
===================================
It is derived from the full one. I left all format parsing intact, but
only print "%s" and "%c". Everything else is printed as hex numbers
like "<badc0ffe>". This means your 47 printed as "%03i" will be output
as "<0000002f>" instead of "047". Still, the standard format is
accepted without errors and no information is lost.
I have made no checks nor reasoning about 32-bit vs 64-bit. I only
used it on 32-bit computers and never printed "long long". Now that it
is published, I have an incentive to do it, though.
It is selected at compile time by setting CONFIG_PRINTF_MINI=y as a
make variable, possibly inherited by the environment. It is licensed
as GPL version 2 because it's derived from the full one -- I left the
parsing as I found in there.
Result of example-printf (you can "make CONFIG_PRINTF_MINI=y):
integer <00000400> <0000029a> <00000035>
octal <00000400> <0000029a> <00000035>
hex <00000400> <0000029a> <00000035>
HEX etc <00000400> <0000029a> <00000035>
neg <fffffffb> <fffffff6> <fffffff1>
char: A string foo foo verylongstring
hour <0000000c>:<00000009>:<00000000>
As promised, %c and %s is printed correctly, but without obeying the
format modifiers, but all integer value are printed in hex.
Footprint: 200-600 bytes, plus 100-400 for the frontend.
The empty implementation in detail
==================================
The empty implementation, called "none" to respect the 4-letter
pattern of "full" and "mini" doesn't parse any format. It simply
prints the format string and nothing more. This allows to keep the
most important messages, like the welcome string or a "Panic" string,
while saving code space.
It is selected at compile time by setting CONFIG_PRINTF_NONE.
Result of example-printf (you can "make CONFIG_PRINTF_MINI=y):
integer %5i %5i %05i
octal %5o %5o %05o
hex %5x %5x %05x
HEX etc %5X %+5d %-5i
neg %5i %05i %05x
char: %c string %s %5s %.5s
hour %02d:%02d:%02d
Footprint: 25-110 bytes, plus 100-400 for the frontend.
If you want to remove all printf overhead in production, you should
use a preprocessor macro to completely kill the printf calls. This
would save you the parameter-passing overhead in the caller and all
the constant strings in .rodata. I don't support this in the package,
though, and I discourage from doing it, for the usual
preprocessor-related reasons.
Footprint of the various implementations
========================================
This table excludes the static buffer (256 in .bss by default) and
only lists the code size (command "size", column "text"), compiled
with -Os as for this Makefile.
printf.o is the frontend and is linked in all four configurations,
the other ones are exclusive one another:
printf.o full xint mini none
x86, gcc-4.4.5 87 1715 476 258 48
x86-64, gcc-4.4.5 418 2325 712 433 77
x86, gcc-4.6.2 255 2210 577 330 110
arm, gcc-4.2.2 156 2408 684 356 52
arm, gcc-4.5.2 128 2235 645 353 44
arm, gcc-4.5.2 thumb2 80 1443 373 209 26
lm32, gcc-4.5.3 196 3228 792 576 44
mips, gcc-4.4.1 184 2616 824 504 72
powerpc, gcc-4.4.1 328 2895 881 521 48
coldfire, gcc-4.4.1 96 2025 485 257 42
sh4, gcc-4.4.1 316 2152 608 408 34
#include <stdio.h>
#include <pp-printf.h>
int main(int argc, char **argv)
{
pp_printf("integer %5i %5i %05i\n", 1024, 666, 53);
pp_printf("octal %5o %5o %05o\n", 1024, 666, 53);
pp_printf("hex %5x %5x %05x\n", 1024, 666, 53);
pp_printf("HEX etc %5X %+5d %-5i\n", 1024, 666, 53);
pp_printf("neg %5i %05i %05x\n", -5, -10, -15);
pp_printf("char: %c string %s %5s %.5s\n", 65, "foo", "foo",
"verylongstring");
pp_printf("hour %02d:%02d:%02d\n", 12, 9, 0);
return 0;
}
#include <stdarg.h>
extern int pp_printf(const char *fmt, ...)
__attribute__((format(printf,1,2)));
extern int pp_sprintf(char *s, const char *fmt, ...)
__attribute__((format(printf,2,3)));
extern int pp_vprintf(const char *fmt, va_list args);
extern int pp_vsprintf(char *buf, const char *, va_list)
__attribute__ ((format (printf, 2, 0)));
/* This is what we rely on for output */
extern int puts(const char *s);
/*
* Basic printf based on vprintf based on vsprintf
*
* Alessandro Rubini for CERN, 2011 -- public domain
* (please note that the vsprintf is not public domain but GPL)
*/
#include <stdarg.h>
#include <pp-printf.h>
static char print_buf[CONFIG_PRINT_BUFSIZE];
int pp_vprintf(const char *fmt, va_list args)
{
int ret;
ret = pp_vsprintf(print_buf, fmt, args);
puts(print_buf);
return ret;
}
int pp_sprintf(char *s, const char *fmt, ...)
{
va_list args;
int ret;
va_start(args, fmt);
ret = pp_vsprintf(s, fmt, args);
va_end(args);
return ret;
}
int pp_printf(const char *fmt, ...)
{
va_list args;
int ret;
va_start(args, fmt);
ret = pp_vprintf(fmt, args);
va_end(args);
return ret;
}
# This is included from ../Makefile, for the wrc build system.
# The Makefile in this directory is preserved from the upstream version
obj-y += pp_printf/printf.o
ppprintf-$(CONFIG_PRINTF_FULL) += pp_printf/vsprintf-full.o
ppprintf-$(CONFIG_PRINTF_MINI) += pp_printf/vsprintf-mini.o
ppprintf-$(CONFIG_PRINTF_NONE) += pp_printf/vsprintf-none.o
ppprintf-$(CONFIG_PRINTF_XINT) += pp_printf/vsprintf-xint.o
ppprintf-y ?= pp_printf/vsprintf-xint.o
obj-y += $(ppprintf-y)
This diff is collapsed.
#include <stdarg.h>
/*
* minimal vsprintf: only %s and hex values
* Alessandro Rubini 2010, based on code in u-boot (from older Linux)
* GNU GPL version 2.
*/
int pp_vsprintf(char *buf, const char *fmt, va_list args)
{
int i, j;
static char hex[] = "0123456789abcdef";
char *s;
char *str = buf;
for (; *fmt ; ++fmt) {
if (*fmt != '%') {
*str++ = *fmt;
continue;
}
repeat:
fmt++; /* Skip '%' initially, other stuff later */
/* Skip the complete format string */
switch(*fmt) {
case '\0':
goto ret;
case '*':
/* should be precision, just eat it */
i = va_arg(args, int);
/* fall through: discard unknown stuff */
default:
goto repeat;
/* Special cases for conversions */
case 'c': /* char: supported */
*str++ = (unsigned char) va_arg(args, int);
break;
case 's': /* string: supported */
s = va_arg(args, char *);
while (*s)
*str++ = *s++;
break;
case 'n': /* number-thus-far: not supported */
break;
case '%': /* supported */
*str++ = '%';
break;
/* all integer (and pointer) are printed as <%08x> */
case 'o':
case 'x':
case 'X':
case 'd':
case 'i':
case 'u':
case 'p':
i = va_arg(args, int);
*str++ = '<';
for (j = 28; j >= 0; j -= 4)
*str++ = hex[(i>>j)&0xf];
*str++ = '>';
break;
}
}
ret:
*str = '\0';
return str - buf;
}
#include <stdarg.h>
#include <pp-printf.h>
/*
* empty vsprintf: only the format string. Public domain
*/
int pp_vsprintf(char *buf, const char *fmt, va_list args)
{
char *str = buf;
for (; *fmt ; ++fmt)
*str++ = *fmt;
*str++ = '\0';
return str - buf;
}
/*
* vsprintf-xint: a possible free-software replacement for mprintf
*
* public domain
*/
#include <stdarg.h>
#include <stdint.h>
static const char hex[] = "0123456789abcdef";
static int number(char *out, unsigned value, int base, int lead, int wid)
{
char tmp[16];
int i = 16, ret, negative = 0;
/* No error checking at all: it is as ugly as possible */
if ((signed)value < 0 && base == 10) {
negative = 1;
value = -value;
}
while (value && i) {
tmp[--i] = hex[value % base];
value /= base;
}
if (i == 16)
tmp[--i] = '0';
if (negative && lead == ' ') {
tmp[--i] = '-';
negative = 0;
}
while (i > 16 - wid + negative)
tmp[--i] = lead;
if (negative)
tmp[--i] = '-';
ret = 16 - i;
while (i < 16)
*(out++) = tmp[i++];
return ret;
}
int pp_vsprintf(char *buf, const char *fmt, va_list args)
{
char *s, *str = buf;
int base, lead, wid;
for (; *fmt ; ++fmt) {
if (*fmt != '%') {
*str++ = *fmt;
continue;
}
base = 10;
lead = ' ';
wid = 1;
repeat:
fmt++; /* Skip '%' initially, other stuff later */
switch(*fmt) {
case '\0':
goto ret;
case '0':
lead = '0';
goto repeat;
case '*':
/* should be precision, just eat it */
base = va_arg(args, int);
/* fall through: discard unknown stuff */
default:
if (*fmt >= '1' && *fmt <= '9')
wid = *fmt - '0';
goto repeat;
/* Special cases for conversions */
case 'c': /* char: supported */
*str++ = (unsigned char) va_arg(args, int);
break;
case 's': /* string: supported */
s = va_arg(args, char *);
while (*s)
*str++ = *s++;
break;
case 'n': /* number-thus-far: not supported */
break;
case '%': /* supported */
*str++ = '%';
break;
/* integers are more or less printed */
case 'p':
case 'x':
case 'X':
base = 16;
case 'o':
if (base == 10) /* yet unchaged */
base = 8;
case 'd':
case 'i':
case 'u':
str += number(str, va_arg(args, int), base, lead, wid);
break;
}
}
ret:
*str = '\0';
return str - buf;
}
/*
Register definitions for slave core: WR Switch PPS generator and RTC
* File : pps_gen_regs.h
* Author : auto-generated by wbgen2 from pps_gen_wb.wb
* Created : Fri Jul 26 15:09:09 2013
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE pps_gen_wb.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_PPS_GEN_WB_WB
#define __WBGEN2_REGDEFS_PPS_GEN_WB_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Control Register */
/* definitions for field: Reset counter in reg: Control Register */
#define PPSG_CR_CNT_RST WBGEN2_GEN_MASK(0, 1)
/* definitions for field: Enable counter in reg: Control Register */
#define PPSG_CR_CNT_EN WBGEN2_GEN_MASK(1, 1)
/* definitions for field: Adjust offset in reg: Control Register */
#define PPSG_CR_CNT_ADJ WBGEN2_GEN_MASK(2, 1)
/* definitions for field: Set time in reg: Control Register */
#define PPSG_CR_CNT_SET WBGEN2_GEN_MASK(3, 1)
/* definitions for field: PPS Pulse width in reg: Control Register */
#define PPSG_CR_PWIDTH_MASK WBGEN2_GEN_MASK(4, 28)
#define PPSG_CR_PWIDTH_SHIFT 4
#define PPSG_CR_PWIDTH_W(value) WBGEN2_GEN_WRITE(value, 4, 28)
#define PPSG_CR_PWIDTH_R(reg) WBGEN2_GEN_READ(reg, 4, 28)
/* definitions for register: Nanosecond counter register */
/* definitions for register: UTC Counter register (least-significant part) */
/* definitions for register: UTC Counter register (most-significant part) */
/* definitions for register: Nanosecond adjustment register */
/* definitions for register: UTC Adjustment register (least-significant part) */
/* definitions for register: UTC Adjustment register (most-significant part) */
/* definitions for register: External sync control register */
/* definitions for field: Sync to external PPS input in reg: External sync control register */
#define PPSG_ESCR_SYNC WBGEN2_GEN_MASK(0, 1)
/* definitions for field: PPS output valid in reg: External sync control register */
#define PPSG_ESCR_PPS_VALID WBGEN2_GEN_MASK(1, 1)
/* definitions for field: Timecode output(UTC+cycles) valid in reg: External sync control register */
#define PPSG_ESCR_TM_VALID WBGEN2_GEN_MASK(2, 1)
/* definitions for field: Set seconds counter in reg: External sync control register */
#define PPSG_ESCR_SEC_SET WBGEN2_GEN_MASK(3, 1)
/* definitions for field: Set nanoseconds counter in reg: External sync control register */
#define PPSG_ESCR_NSEC_SET WBGEN2_GEN_MASK(4, 1)
PACKED struct PPSG_WB {
/* [0x0]: REG Control Register */
uint32_t CR;
/* [0x4]: REG Nanosecond counter register */
uint32_t CNTR_NSEC;
/* [0x8]: REG UTC Counter register (least-significant part) */
uint32_t CNTR_UTCLO;
/* [0xc]: REG UTC Counter register (most-significant part) */
uint32_t CNTR_UTCHI;
/* [0x10]: REG Nanosecond adjustment register */
uint32_t ADJ_NSEC;
/* [0x14]: REG UTC Adjustment register (least-significant part) */
uint32_t ADJ_UTCLO;
/* [0x18]: REG UTC Adjustment register (most-significant part) */
uint32_t ADJ_UTCHI;
/* [0x1c]: REG External sync control register */
uint32_t ESCR;
};
#endif
This diff is collapsed.
obj-y += \
softpll/spll_common.o \
softpll/spll_external.o \
softpll/spll_helper.o \
softpll/spll_main.o \
softpll/spll_ptracker.o \
softpll/softpll_ng.o
\ No newline at end of file
This diff is collapsed.
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2010 - 2013 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
/* softpll_ng.h: public SoftPLL API header */
#ifndef __SOFTPLL_NG_H
#define __SOFTPLL_NG_H
#include <stdint.h>
/* SoftPLL operating modes, for mode parameter of spll_init(). */
/* Grand Master - lock to 10 MHz external reference */
#define SPLL_MODE_GRAND_MASTER 1
/* Free running master - 125 MHz refrence free running, DDMTD locked to it */
#define SPLL_MODE_FREE_RUNNING_MASTER 2
/* Slave mode - 125 MHz reference locked to one of the input clocks */
#define SPLL_MODE_SLAVE 3
/* Disabled mode: SoftPLL inactive */
#define SPLL_MODE_DISABLED 4
/* Shortcut for 'channels' parameter in various API functions to perform operation on all channels */
#define SPLL_ALL_CHANNELS 0xffffffff
/* Aux clock flags */
#define SPLL_AUX_ENABLED (1<<0) /* Locking the particular aux channel to the WR reference is enabled */
#define SPLL_AUX_LOCKED (1<<1) /* The particular aux clock is already locked to WR reference */
/* Phase detector types */
#define SPLL_PD_DDMTD 0
#define SPLL_PD_BANGBANG 1
/* Note on channel naming:
- ref_channel means a PHY recovered clock input. There can be one (as in WR core) or more (WR switch).
- out_channel means an output channel, which represents PLL feedback signal from a local, tunable oscillator. Every SPLL implementation
has at least one output channel, connected to the 125 / 62.5 MHz transceiver (WR) reference. This channel has always
index 0 and is compared against all reference channels by the phase tracking mechanism.
*/
/* PUBLIC API */
/*
Initializes the SoftPLL to work in mode (mode). Extra parameters depend on choice of the mode:
- for SPLL_MODE_GRAND_MASTER: non-zero (align_pps) value enables realignment of the WR reference rising edge to the
rising edge of 10 MHz external clock that comes immediately after a PPS pulse
- for SPLL_MODE_SLAVE: (ref_channel) indicates the reference channel to which we are locking our PLL.
*/
void spll_init(int mode, int ref_channel, int align_pps);
/* Disables the SoftPLL and cleans up stuff */
void spll_shutdown();
/* Returns number of reference and output channels implemented in HW. */
void spll_get_num_channels(int *n_ref, int *n_out);
/* Starts locking output channel (out_channel) */
void spll_start_channel(int out_channel);
/* Stops locking output channel (out_channel) */
void spll_stop_channel(int out_channel);
/* Returns non-zero if output channel (out_channel) is locked to a WR reference */
int spll_check_lock(int out_channel);
/* Sets phase setpoint for given output channel. */
void spll_set_phase_shift(int out_channel, int32_t value_picoseconds);
/* Retreives the current phase shift and desired setpoint for given output channel */
void spll_get_phase_shift(int out_channel, int32_t *current, int32_t *target);
/* Returns non-zero if the given output channel is busy phase shifting to a new preset */
int spll_shifter_busy(int out_channel);
/* Returns phase detector type used by particular output channel. There are two phase detectors available:
- DDMTD: locks only 62.5 / 125 MHz. Provides independent phase shift control for each output.
- Bang-Bang: locks to any frequency that is a result of rational (M/N) multiplication of the reference frequency.
The frequency can be set by spll_set_aux_frequency(). BB detector follows phase setpoint of channel 0 (WR reference),
there is no per-output shift control.
*/
int spll_get_phase_detector_type(int out_channel);
/* Sets the aux clock freuency when a BB detector is in use.
Must be called prior to spll_start_channel(). If the frequency is out of available range,
returns negative value */
int spll_set_aux_frequency(int out_channel, int32_t frequency);
/* Enables/disables phase tracking on channel (ref_channel). Phase is always measured between
the WR local reference (out_channel 0) and ref_channel */
void spll_enable_ptracker(int ref_channel, int enable);
/* Reads tracked phase shift value for given reference channel */
int spll_read_ptracker(int ref_channel, int32_t *phase_ps, int *enabled);
/* Calls aux clock handling state machine. Must be called regularly (although it is not time-critical)
in the main loop of the program if aux clocks are used in the design. */
int spll_update_aux_clocks();
/* Returns the status of given aux clock output (SPLL_AUX_) */
int spll_get_aux_status(int out_channel);
const char *spll_get_aux_status_string(int channel);
/* Debug/testing functions */
/* Returns how many time the PLL has de-locked since last call of spll_init() */
int spll_get_delock_count();
void spll_show_stats(void);
/* Sets VCXO tuning DAC corresponding to output (out_channel) to a given value */
void spll_set_dac(int out_channel, int value);
/* Returns current DAC sample value for output (out_channel) */
int spll_get_dac(int out_channel);
#endif // __SOFTPLL_NG_H
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2010 - 2013 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
/* spll_common.c - common data structures and functions used by the SoftPLL */
#include <string.h>
#include "spll_defs.h"
#include "spll_common.h"
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;
}
void pi_init(spll_pi_t *pi)
{
pi->integrator = 0;
pi->y = pi->bias;
}
/* 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
*/
int ld_update(spll_lock_det_t *ld, int y)
{
ld->lock_changed = 0;
if (abs(y) <= ld->threshold) {
if (ld->lock_cnt < ld->lock_samples)
ld->lock_cnt++;
if (ld->lock_cnt == ld->lock_samples) {
ld->lock_changed = 1;
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->lock_changed = 1;
ld->locked = 0;
return -1;
}
}
return ld->locked;
}
void ld_init(spll_lock_det_t *ld)
{
ld->locked = 0;
ld->lock_cnt = 0;
ld->lock_changed = 0;
}
void lowpass_init(spll_lowpass_t *lp, int alpha)
{
lp->y_d = 0x80000000;
lp->alpha = alpha;
}
int lowpass_update(spll_lowpass_t *lp, int x)
{
if (lp->y_d == 0x80000000) {
lp->y_d = x;
return x;
} else {
int scaled = (lp->alpha * (x - lp->y_d)) >> 15;
lp->y_d = lp->y_d + (scaled >> 1) + (scaled & 1);
return lp->y_d;
}
}
/* Enables/disables DDMTD tag generation on a given (channel).
Channels (0 ... splL_n_chan_ref - 1) are the reference channels
(e.g. transceivers' RX clocks or a local reference)
Channels (spll_n_chan_ref ... spll_n_chan_out + spll_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).
*/
void spll_enable_tagger(int channel, int enable)
{
if (channel >= spll_n_chan_ref) { /* Output channel? */
if (enable)
SPLL->OCER |= 1 << (channel - spll_n_chan_ref);
else
SPLL->OCER &= ~(1 << (channel - spll_n_chan_ref));
} else { /* Reference channel */
if (enable)
SPLL->RCER |= 1 << channel;
else
SPLL->RCER &= ~(1 << channel);
}
// TRACE("%s: ch %d, OCER 0x%x, RCER 0x%x\n", __FUNCTION__, channel, SPLL->OCER, SPLL->RCER);
}
void biquad_init(spll_biquad_t *bq, const int *coefs, int shift)
{
memset(bq, 0, sizeof(spll_biquad_t));
memcpy(bq->coefs, coefs, 5 * sizeof(int));
bq->shift = shift;
}
int biquad_update(spll_biquad_t *bq, int x)
{
register int y = 0;
y += bq->coefs[0] * x;
y += bq->coefs[1] * bq->xd[0];
y += bq->coefs[2] * bq->xd[1];
y -= bq->coefs[3] * bq->yd[0];
y -= bq->coefs[4] * bq->yd[1];
y >>= bq->shift;
bq->xd[1] = bq->xd[0];
bq->xd[0] = x;
bq->yd[1] = bq->yd[0];
bq->yd[0] = y;
return y;
}
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2010 - 2013 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
/* spll_common.h - common data structures and functions used by the SoftPLL */
#ifndef __SPLL_COMMON_H
#define __SPLL_COMMON_H
#include <stdint.h>
#include <stdlib.h>
#include <syscon.h>
#include <hw/softpll_regs.h>
#include <hw/pps_gen_regs.h>
#include "spll_defs.h"
#define SPLL_LOCKED 1
#define SPLL_LOCKING 0
/* Number of reference/output channels. We don't plan to have more than one
SoftPLL instantiation per project, so these can remain global. */
extern int spll_n_chan_ref, spll_n_chan_out;
extern volatile struct SPLL_WB *SPLL;
extern volatile struct PPSG_WB *PPSG;
/* 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 */
int lock_changed;
} spll_lock_det_t;
/* simple, 1st-order lowpass filter */
typedef struct {
int alpha;
int y_d;
} spll_lowpass_t;
typedef struct {
int coefs[5]; /* Biquad coefficients: b0 b1 b2 a1 a2 */
int shift; /* bit shift for the coeffs / output */
int yd[2], xd[2]; /* I/O delay lines */
} spll_biquad_t;
/* initializes the PI controller state. Currently almost a stub. */
void pi_init(spll_pi_t *pi);
/* Processes a single sample (x) with PI control algorithm
(pi). Returns the value (y) to drive the actuator. */
int pi_update(spll_pi_t *pi, int x);
void ld_init(spll_lock_det_t *ld);
int ld_update(spll_lock_det_t *ld, int y);
void lowpass_init(spll_lowpass_t *lp, int alpha);
int lowpass_update(spll_lowpass_t *lp, int x);
void spll_enable_tagger(int channel, int enable);
void biquad_init(spll_biquad_t *bq, const int *coefs, int shift);
int biquad_update(spll_biquad_t *bq, int x);
#endif // __SPLL_COMMON_H
/*
White Rabbit Softcore PLL (SoftPLL) - common definitions
Copyright (c) 2010 - 2012 CERN / BE-CO-HT (Tomasz Włostowski)
Licensed under LGPL 2.1.
spll_debug.h - 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 are further 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_EXT 0x40 /* Sample source: External Reference 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);
}
This diff is collapsed.
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2010 - 2013 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
/* spll_external.h - definitions & prototypes for the
external (10 MHz - Grandmaster mode) reference channel */
#ifndef __SPLL_EXTERNAL_H
#define __SPLL_EXTERNAL_H
#include "spll_common.h"
/* Alignment FSM states */
/* 1st alignment stage, done before starting the ext channel PLL:
alignment of the rising edge of the external clock (10 MHz), with
the rising edge of the local reference (62.5/125 MHz) and the PPS
signal. Because of non-integer ratio (6.25 or 12.5), the PLL must
know which edges shall be kept at phase==0. We align to the edge of
the 10 MHz clock which comes right after the edge of the PPS pulse
(see drawing below):
PLL reference (62.5 MHz) ____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|
External clock (10 MHz) ^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|___
External PPS ___________|^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
*/
#define REALIGN_STAGE1 1
#define REALIGN_STAGE1_WAIT 2
/* 2nd alignment stage, done after the ext channel PLL has locked. We
make sure that the switch's internal PPS signal is produced exactly
on the edge of PLL reference in-phase with 10 MHz clock edge, which
has come right after the PPS input
PLL reference (62.5 MHz) ____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|^^^^|____|
External clock (10 MHz) ^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|________________________|^^^^^^^^^^^^^^^^^^^^^^^^^|___
External PPS ___________|^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Internal PPS __________________________________|^^^^^^^^^|______________________________________________________________________
^ aligned clock edges and PPS
*/
#define REALIGN_STAGE2 3
#define REALIGN_STAGE2_WAIT 4
/* Error state - PPS signal missing or of bad frequency */
#define REALIGN_PPS_INVALID 5
/* Realignment is disabled (i.e. the switch inputs only the reference
* frequency, but not time) */
#define REALIGN_DISABLED 6
/* Realignment done */
#define REALIGN_DONE 7
struct spll_external_state {
int ref_src;
int sample_n;
int ph_err_offset, ph_err_cur, ph_err_d0, ph_raw_d0;
int realign_clocks;
int realign_state;
int realign_timer;
spll_pi_t pi;
spll_lowpass_t lp_short, lp_long;
spll_lock_det_t ld;
};
void external_init(volatile struct spll_external_state *s, int ext_ref,
int realign_clocks);
int external_update(struct spll_external_state *s, int tag, int source);
void external_start(struct spll_external_state *s);
int external_locked(struct spll_external_state *s);
#endif // __SPLL_EXTERNAL_H
This diff is collapsed.
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2010 - 2013 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
/* spll_helper.h - 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. */
#ifndef __SPLL_HELPER_H
#define __SPLL_HELPER_H
#include "spll_common.h"
#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;
int delock_count;
spll_pi_t pi;
spll_lock_det_t ld;
spll_biquad_t precomp;
};
void helper_init(struct spll_helper_state *s, int ref_channel);
int helper_update(struct spll_helper_state *s, int tag,
int source);
void helper_start(struct spll_helper_state *s);
#endif // __SPLL_HELPER_H
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2010 - 2013 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
/* spll_ptracker.h - data structures & prototypes for phase trackers. */
#ifndef __SPLL_PTRACKER_H
#define __SPLL_PTRACKER_H
#include "spll_common.h"
struct spll_ptracker_state {
int enabled, id;
int n_avg, acc, avg_count, preserve_sign;
int phase_val, ready;
};
void ptracker_init(struct spll_ptracker_state *s, int id, int num_avgs);
void ptracker_start(struct spll_ptracker_state *s);
int ptrackers_update(struct spll_ptracker_state *ptrackers, int tag, int source);
#endif // __SPLL_PTRACKER_H
This diff is collapsed.
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