Commit 3c2d0e1e authored by Tomasz Wlostowski's avatar Tomasz Wlostowski Committed by Tomasz Wlostowski

Initial SVEC version, cleanup & some bugfixing

parent e43f6a68
......@@ -13,7 +13,9 @@ subdirs-ccflags-y = $(ccflags-y)
obj-m := fmc-tdc.o
fmc-tdc-objs = acam.o calibration.o ft-spec.o ft-core.o onewire.o time.o ft-irq.o ft-zio.o ../fmc-bus/sdb-lib/access.o ../fmc-bus/sdb-lib/glue.o
fmc-tdc-objs = acam.o calibration.o fmc-util.o ft-spec.o \
ft-svec.o ft-core.o onewire.o ft-time.o ft-irq.o ft-zio.o \
../fmc-bus/sdb-lib/access.o ../fmc-bus/sdb-lib/glue.o
all: modules
......
......@@ -24,29 +24,27 @@
static struct {
int reg;
u32 value;
} acam_config [NB_ACAM_REGS] =
{
{ 0, AR0_ROsc | AR0_HQSel | AR0_TRiseEn(0) |
AR0_TRiseEn(1) | AR0_TRiseEn(2) |
AR0_TRiseEn(3) | AR0_TRiseEn(4) |
AR0_TRiseEn(5) |
AR0_TFallEn(1) | AR0_TFallEn(2) |
AR0_TFallEn(3) | AR0_TFallEn(4) |
AR0_TFallEn(5)},
{ 1, 0 },
{ 2, AR2_IMode |
AR2_Disable(6) | AR2_Disable(7) | AR2_Disable(8) },
{ 3, 0 },
{ 4, AR4_StartTimer(15) | AR4_EFlagHiZN },
{ 5, AR5_StartOff1(2000) },
{ 6, AR6_Fill(0xfc) },
{ 7, AR7_RefClkDiv(7) | AR7_HSDiv(234) | AR7_NegPhase | AR7_ResAdj },
{ 11, AR11_HFifoErrU(0) | AR11_HFifoErrU(1) |
AR11_HFifoErrU(2) | AR11_HFifoErrU(3) |
AR11_HFifoErrU(4) | AR11_HFifoErrU(5) |
AR11_HFifoErrU(6) | AR11_HFifoErrU(7) },
{ 12, AR12_StartNU | AR12_HFifoE },
{ 14, 0 }
} acam_config[NB_ACAM_REGS] = {
{
0, AR0_ROsc | AR0_HQSel | AR0_TRiseEn(0) |
AR0_TRiseEn(1) | AR0_TRiseEn(2) |
AR0_TRiseEn(3) | AR0_TRiseEn(4) |
AR0_TRiseEn(5) |
AR0_TFallEn(1) | AR0_TFallEn(2) |
AR0_TFallEn(3) | AR0_TFallEn(4) | AR0_TFallEn(5)}, {
1, 0}, {
2, AR2_IMode | AR2_Disable(6) | AR2_Disable(7) | AR2_Disable(8)}, {
3, 0}, {
4, AR4_StartTimer(15) | AR4_EFlagHiZN}, {
5, AR5_StartOff1(2000)}, {
6, AR6_Fill(0xfc)}, {
7, AR7_RefClkDiv(7) | AR7_HSDiv(234) | AR7_NegPhase | AR7_ResAdj}, {
11, AR11_HFifoErrU(0) | AR11_HFifoErrU(1) |
AR11_HFifoErrU(2) | AR11_HFifoErrU(3) |
AR11_HFifoErrU(4) | AR11_HFifoErrU(5) |
AR11_HFifoErrU(6) | AR11_HFifoErrU(7)}, {
12, AR12_StartNU | AR12_HFifoE}, {
14, 0}
};
static inline int acam_is_pll_locked(struct fmctdc_dev *ft)
......@@ -54,43 +52,42 @@ static inline int acam_is_pll_locked(struct fmctdc_dev *ft)
uint32_t status;
ft_writel(ft, TDC_CTRL_READ_ACAM_CFG, TDC_REG_CTRL);
udelay(100);
status = ft_readl(ft, TDC_REG_ACAM_READBACK(12));
return !(status & AR12_NotLocked);
return !(status & AR12_NotLocked);
}
int ft_acam_init(struct fmctdc_dev *ft)
{
int i;
unsigned long tmo;
unsigned long tmo;
pr_debug("%s: initializing ACAM TDC...\n", __func__);
ft_writel(ft, TDC_CTRL_RESET_ACAM, TDC_REG_CTRL);
udelay(100);
for(i = 0; i < NB_ACAM_REGS; i++)
{
if(acam_config[i].reg == 0)
ft->acam_r0 = acam_config[i].value;
ft_writel(ft, acam_config[i].value, TDC_REG_ACAM_CONFIG (acam_config[i].reg));
for (i = 0; i < NB_ACAM_REGS; i++) {
ft_writel(ft, acam_config[i].value,
TDC_REG_ACAM_CONFIG(acam_config[i].reg));
}
ft_writel(ft, TDC_CTRL_LOAD_ACAM_CFG, TDC_REG_CTRL);
/* commit ACAM config regs */
ft_writel(ft, TDC_CTRL_LOAD_ACAM_CFG, TDC_REG_CTRL);
udelay(100);
ft_writel(ft, TDC_CTRL_RESET_ACAM, TDC_REG_CTRL);
/* and reset the chip (keeps configuration) */
ft_writel(ft, TDC_CTRL_RESET_ACAM, TDC_REG_CTRL);
udelay(100);
/* wait for the ACAM's PLL to lock (2 seconds) */
tmo = jiffies + 2 * HZ;
while (time_before(jiffies, tmo))
{
if(acam_is_pll_locked(ft))
{
dev_info(&ft->fmc->dev, "%s: ACAM initialization OK.\n", __func__);
while (time_before(jiffies, tmo)) {
if (acam_is_pll_locked(ft)) {
dev_info(&ft->fmc->dev, "%s: ACAM initialization OK.\n",
__func__);
return 0;
}
}
......@@ -99,24 +96,13 @@ int ft_acam_init(struct fmctdc_dev *ft)
return -EIO;
}
void dump_acam_regs(struct fmctdc_dev *ft)
{
int i;
ft_writel(ft, TDC_CTRL_READ_ACAM_CFG, TDC_REG_CTRL);
udelay(1000);
for(i = 0; i <= 14 ; i++)
printk("ACAM reg %d: 0x%x\n", i, ft_readl(ft, TDC_REG_ACAM_READBACK(i)));
}
void ft_acam_exit(struct fmctdc_dev *ft)
{
/* Disable ACAM inputs and PLL */
ft_writel(ft, TDC_CTRL_DIS_ACQ, TDC_REG_CTRL);
ft_writel(ft, 0, TDC_REG_ACAM_CONFIG (0));
ft_writel(ft, 0, TDC_REG_ACAM_CONFIG (7));
ft_writel(ft, TDC_CTRL_LOAD_ACAM_CFG, TDC_REG_CTRL);
ft_writel(ft, 0, TDC_REG_ACAM_CONFIG(0));
ft_writel(ft, 0, TDC_REG_ACAM_CONFIG(7));
ft_writel(ft, TDC_CTRL_LOAD_ACAM_CFG, TDC_REG_CTRL);
udelay(100);
}
......@@ -21,17 +21,17 @@
/* dummy calibration data - used in case of empty/corrupted EEPROM */
static struct ft_calibration default_calibration = {
{ 0, 86, 609, 572, 335}, /* zero_offset */
43343 /* vcxo_default_tune */
{0, 86, 609, 572, 335}, /* zero_offset */
43343 /* vcxo_default_tune */
};
/* sdbfs-related function */
static int ft_read_calibration_eeprom(struct fmc_device *fmc, void *buf, int length)
static int ft_read_calibration_eeprom(struct fmc_device *fmc, void *buf,
int length)
{
int i, ret = 0;
static struct sdbfs fs;
fs.data = fmc->eeprom;
fs.datalen = fmc->eeprom_len;
......@@ -76,16 +76,17 @@ int ft_handle_eeprom_calibration(struct fmctdc_dev *ft)
offsets that could be added to TDC timestamps right away (picoseconds, referenced to WR) */
calib->zero_offset[0] = 0;
for(i = FT_CH_1 + 1; i < FT_NUM_CHANNELS; i++)
calib->zero_offset[i] = le32_to_cpu(raw_calib[i - 1]) / 100 - calib->zero_offset[0];
for (i = FT_CH_1 + 1; i < FT_NUM_CHANNELS; i++)
calib->zero_offset[i] =
le32_to_cpu(raw_calib[i - 1]) / 100 - calib->zero_offset[0];
calib->vcxo_default_tune = le32_to_cpu(raw_calib[4]);
for (i = 0; i < ARRAY_SIZE(calib->zero_offset); i++)
dev_info(d, "calib: zero_offset[%i] = %li\n", i,
(long)calib->zero_offset[i]);
dev_info(d, "calib: zero_offset[%i] = %li\n", i,
(long)calib->zero_offset[i]);
dev_info(d, "calib: vcxo_default_tune %i\n", calib->vcxo_default_tune);
return 0;
return 0;
}
......@@ -14,14 +14,14 @@
#ifndef __FMC_TDC_H__
#define __FMC_TDC_H__
#ifdef __KERNEL__ /* All the rest is only of kernel users */
#ifdef __KERNEL__ /* All the rest is only of kernel users */
#include <linux/spinlock.h>
#include <linux/timer.h>
#include <linux/fmc.h>
#include <linux/version.h>
#endif
#define FT_VERSION 2 /* version of the driver */
#define FT_VERSION 2 /* version of the driver */
/* default gatewares */
#define FT_GATEWARE_SVEC "fmc/svec-fmc-tdc.bin"
......@@ -32,164 +32,166 @@
#define FT_CH_1 1
#define FT_NUM_CHANNELS 5
enum ft_channel_flags {
FT_FLAG_CH_TERMINATED = 0,
FT_FLAG_CH_DO_INPUT,
FT_FLAG_CH_INPUT_READY
};
enum ft_zattr_dev_idx {
FT_ATTR_DEV_VERSION = 0,
FT_ATTR_DEV_SECONDS,
FT_ATTR_DEV_COARSE,
FT_ATTR_DEV_COMMAND, /* see below for commands */
FT_ATTR_DEV_TEMP,
FT_ATTR_DEV_RESERVE_6,
FT_ATTR_DEV_RESERVE_7,
FT_ATTR_DEV__LAST,
FT_ATTR_DEV_VERSION = 0,
FT_ATTR_DEV_SECONDS,
FT_ATTR_DEV_COARSE,
FT_ATTR_DEV_COMMAND, /* see below for commands */
FT_ATTR_DEV_TEMP,
FT_ATTR_DEV_ENABLE_INPUTS,
FT_ATTR_DEV_RESERVE_7,
FT_ATTR_DEV__LAST,
};
enum ft_zattr_in_idx {
/* PLEASE check "NOTE:" above if you edit this*/
FT_ATTR_TDC_SECONDS = FT_ATTR_DEV__LAST,
FT_ATTR_TDC_COARSE,
FT_ATTR_TDC_FRAC,
FT_ATTR_TDC_SEQ,
FT_ATTR_TDC_TERMINATION,
FT_ATTR_TDC_OFFSET,
FT_ATTR_TDC_USER_OFFSET,
FT_ATTR_TDC_PURGE_FIFO,
FT_ATTR_TDC__LAST,
/* PLEASE check "NOTE:" above if you edit this */
FT_ATTR_TDC_SECONDS = FT_ATTR_DEV__LAST,
FT_ATTR_TDC_COARSE,
FT_ATTR_TDC_FRAC,
FT_ATTR_TDC_SEQ,
FT_ATTR_TDC_TERMINATION,
FT_ATTR_TDC_OFFSET,
FT_ATTR_TDC_USER_OFFSET,
FT_ATTR_TDC__LAST,
};
enum ft_command {
FT_CMD_WR_ENABLE = 0,
FT_CMD_WR_DISABLE,
FT_CMD_WR_QUERY,
FT_CMD_IDENTIFY_ON,
FT_CMD_IDENTIFY_OFF
FT_CMD_WR_ENABLE = 0,
FT_CMD_WR_DISABLE,
FT_CMD_WR_QUERY,
FT_CMD_IDENTIFY_ON,
FT_CMD_IDENTIFY_OFF
};
/* rest of the file is kernel-only */
#ifdef __KERNEL__
enum ft_channel_flags {
FT_FLAG_CH_TERMINATED = 0,
FT_FLAG_CH_DO_INPUT,
FT_FLAG_CH_INPUT_READY
};
/* Carrier-specific operations (gateware does not fully decouple carrier specific stuff, such as
DMA or resets, from mezzanine-specific operations). */
struct fmctdc_dev;
struct ft_carrier_specific {
char *gateware_name;
int (*init)(struct fmctdc_dev *);
int (*reset_core)(struct fmctdc_dev *);
int (*copy_timestamps) (struct fmctdc_dev *, int base_addr, int size, void *dst );
int (*setup_irqs)(struct fmctdc_dev *, irq_handler_t handler);
int (*disable_irqs)(struct fmctdc_dev *);
int (*ack_irq)(struct fmctdc_dev *);
char *gateware_name;
int (*init) (struct fmctdc_dev *);
int (*reset_core) (struct fmctdc_dev *);
int (*copy_timestamps) (struct fmctdc_dev *, int base_addr, int size,
void *dst);
int (*setup_irqs) (struct fmctdc_dev *, irq_handler_t handler);
int (*disable_irqs) (struct fmctdc_dev *);
int (*ack_irq) (struct fmctdc_dev *, int irq_id);
void (*exit) (struct fmctdc_dev *);
};
struct ft_calibration { /* All of these are big endian in the EEPROM */
/* Input-to-WR timebase offset in ps. */
int32_t zero_offset[5];
struct ft_calibration { /* All of these are big endian */
/* Input-to-internal-timebase offset in ps. Add to all timestamps. */
int32_t zero_offset[5];
/* Default DAC value for VCXO. Set during init and for local timing */
uint32_t vcxo_default_tune;
/* Default DAC value for VCXO. Set during init and for local timing */
uint32_t vcxo_default_tune;
};
/* Hardware TDC timestamp */
struct ft_hw_timestamp {
uint32_t bins; /* In BIN (81 ps resolution) */
uint32_t coarse; /* 8 ns resolution */
uint32_t utc; /* 1 second resolution */
uint32_t metadata; /* channel, polarity, etc. */
uint32_t bins; /* In ACAM bins (81 ps) */
uint32_t coarse; /* 8 ns resolution */
uint32_t utc; /* 1 second resolution */
uint32_t metadata; /* channel, polarity, etc. */
} __packed;
/* White Rabbit timestamp */
struct ft_wr_timestamp {
uint64_t seconds;
uint32_t coarse;
uint32_t frac;
int seq_id;
int channel;
uint64_t seconds;
uint32_t coarse;
uint32_t frac;
int seq_id;
int channel;
};
struct ft_sw_fifo {
unsigned long head, tail, count, size;
struct ft_wr_timestamp *t;
unsigned long head, tail, count, size;
struct ft_wr_timestamp *t;
};
struct ft_channel_state {
unsigned long flags;
int expected_edge;
int cur_seq_id;
int32_t user_offset;
struct ft_wr_timestamp prev_ts;
struct ft_sw_fifo fifo;
unsigned long flags;
int expected_edge;
int cur_seq_id;
int32_t user_offset;
struct ft_wr_timestamp prev_ts;
struct ft_sw_fifo fifo;
};
/* Main TDC device context */
struct fmctdc_dev {
spinlock_t lock;
int ft_core_base;
/* HW buffer/FIFO access lock */
spinlock_t lock;
/* base addresses, taken from SDB */
int ft_core_base;
int ft_i2c_base;
int ft_owregs_base;
int ft_dma_base;
int ft_carrier_base;
int ft_irq_base;
struct fmc_device *fmc;
struct zio_device *zdev, *hwzdev;
struct timer_list temp_timer;
struct ft_carrier_specific *carrier_specific;
void *carrier_data;
struct ft_calibration calib;
struct tasklet_struct readout_tasklet;
int initialized;
int wr_mode_active;
uint8_t ds18_id[8];
unsigned long next_t;
int temp; /* temperature: scaled by 4 bits */
int temp_ready;
int verbose;
uint32_t acam_r0;
struct ft_channel_state channels[FT_NUM_CHANNELS];
uint32_t cur_wr_ptr, prev_wr_ptr;
struct ft_hw_timestamp *raw_events;
int ft_carrier_base;
int ft_irq_base;
/* IRQ base index (for SVEC) */
int irq_shift;
struct fmc_device *fmc;
struct zio_device *zdev, *hwzdev;
/* is acquisition mode active? */
int acquisition_on;
/* temperature readout timer */
struct timer_list temp_timer;
/* carrier specific functions (init/exit/reset/readout/irq handling) */
struct ft_carrier_specific *carrier_specific;
/* carrier private data */
void *carrier_data;
/* current calibration block */
struct ft_calibration calib;
struct tasklet_struct readout_tasklet;
int initialized;
/* DS18S20 temperature sensor 1-wire ID */
uint8_t ds18_id[8];
/* next temperature measurement pending? */
unsigned long next_t;
/* temperature, degrees Celsius scaled by 16 and its ready flag */
int temp;
int temp_ready;
/* output lots of debug stuff? */
int verbose;
struct ft_channel_state channels[FT_NUM_CHANNELS];
/* hardware buffer pointers / dacapo regs */
uint32_t cur_wr_ptr, prev_wr_ptr;
/* DMA buffer */
struct ft_hw_timestamp *raw_events;
};
extern struct ft_carrier_specific ft_carrier_spec;
extern struct ft_carrier_specific ft_carrier_svec;
static inline uint32_t ft_readl(struct fmctdc_dev *ft, unsigned long reg)
{
return fmc_readl(ft->fmc, ft->ft_core_base + reg);
return fmc_readl(ft->fmc, ft->ft_core_base + reg);
}
static inline void ft_writel(struct fmctdc_dev *ft, uint32_t v, unsigned long reg)
static inline void ft_writel(struct fmctdc_dev *ft, uint32_t v,
unsigned long reg)
{
fmc_writel(ft->fmc, v, ft->ft_core_base + reg);
fmc_writel(ft->fmc, v, ft->ft_core_base + reg);
}
void ft_enable_acquisition(struct fmctdc_dev *ft, int enable);
int ft_acam_init(struct fmctdc_dev *ft);
void ft_acam_exit(struct fmctdc_dev *ft);
int ft_acam_enable_channel(struct fmctdc_dev *ft, int channel, int enable);
int ft_acam_enable_termination(struct fmctdc_dev *dev, int channel, int enable);
int ft_acam_enable_acquisition(struct fmctdc_dev *ft, int enable);
int ft_onewire_init(struct fmctdc_dev *ft);
void ft_onewire_exit(struct fmctdc_dev *ft);
......@@ -198,13 +200,14 @@ int ft_read_temp(struct fmctdc_dev *ft, int verbose);
int ft_pll_init(struct fmctdc_dev *ft);
void ft_pll_exit(struct fmctdc_dev *ft);
void ft_ts_apply_offset(struct ft_wr_timestamp *ts, int32_t offset_picos );
void ft_ts_sub (struct ft_wr_timestamp *a, struct ft_wr_timestamp *b);
void ft_ts_apply_offset(struct ft_wr_timestamp *ts, int32_t offset_picos);
void ft_ts_sub(struct ft_wr_timestamp *a, struct ft_wr_timestamp *b);
int ft_set_tai_time(struct fmctdc_dev *ft, uint64_t seconds, uint32_t coarse);
int ft_get_tai_time(struct fmctdc_dev *ft, uint64_t *seconds, uint32_t *coarse);
int ft_enable_wr_mode (struct fmctdc_dev *ft, int enable);
int ft_check_wr_mode (struct fmctdc_dev *ft);
int ft_get_tai_time(struct fmctdc_dev *ft, uint64_t * seconds,
uint32_t * coarse);
int ft_enable_wr_mode(struct fmctdc_dev *ft, int enable);
int ft_check_wr_mode(struct fmctdc_dev *ft);
int ft_handle_eeprom_calibration(struct fmctdc_dev *ft);
......@@ -221,9 +224,14 @@ void ft_zio_exit(struct fmctdc_dev *ft);
struct zio_channel;
int ft_read_sw_fifo(struct fmctdc_dev *ft, int channel, struct zio_channel *chan);
int ft_read_sw_fifo(struct fmctdc_dev *ft, int channel,
struct zio_channel *chan);
int ft_enable_termination(struct fmctdc_dev *ft, int channel, int enable);
#endif
signed long fmc_find_sdb_device_ext(struct sdb_array *tree,
uint64_t vid, uint32_t did, int index,
unsigned long *sz);
#endif
#endif // __KERNEL__
#endif // __FMC_TDC_H__
/*
* Some utility functions not supported in the current version of fmc-bus.
*
* Copyright (C) 2012-2013 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
* Author: Alessandro Rubini <rubini@gnudd.com>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* version 2 as published by the Free Software Foundation or, at your
* option, any later version.
*/
#include <linux/fmc.h>
#include <linux/fmc-sdb.h>
#include <linux/err.h>
#include <asm/byteorder.h>
#include "fmc-tdc.h"
/* Finds index-th SDB device that matches (vid/did) pair. */
signed long fmc_find_sdb_device_ext(struct sdb_array *tree,
uint64_t vid, uint32_t did, int index,
unsigned long *sz)
{
signed long res = -ENODEV;
union sdb_record *r;
struct sdb_product *p;
struct sdb_component *c;
int i, n = tree->len;
uint64_t last, first;
int ci = 0;
/* FIXME: what if the first interconnect is not at zero? */
for (i = 0; i < n; i++) {
r = &tree->record[i];
c = &r->dev.sdb_component;
p = &c->product;
if (!IS_ERR(tree->subtree[i]))
res = fmc_find_sdb_device(tree->subtree[i],
vid, did, sz);
/* FIXME: this index SHOULD be recursive, too */
if (ci == index && res >= 0)
return res + tree->baseaddr;
if (r->empty.record_type != sdb_type_device)
continue;
if (__be64_to_cpu(p->vendor_id) != vid)
continue;
if (__be32_to_cpu(p->device_id) != did)
continue;
/* found */
last = __be64_to_cpu(c->addr_last);
first = __be64_to_cpu(c->addr_first);
if (sz)
*sz = (typeof(*sz)) (last + 1 - first);
if (ci == index)
return first + tree->baseaddr;
ci++;
}
return res;
}
......@@ -32,46 +32,48 @@
/* Module parameters */
static int ft_verbose = 0;
module_param_named(verbose, ft_verbose, int, 0444);
MODULE_PARM_DESC(verbose, "Print a lot of debugging messages.");
static struct fmc_driver ft_drv; /* forward declaration */
static struct fmc_driver ft_drv; /* forward declaration */
FMC_PARAM_BUSID(ft_drv);
FMC_PARAM_GATEWARE(ft_drv);
static int ft_show_sdb;
module_param_named(show_sdb, ft_show_sdb, int, 0444);
MODULE_PARM_DESC(verbose, "Print a dump of the gateware's SDB tree.");
static int ft_buffer_size = 8192;
module_param_named(buffer_size, ft_buffer_size, int, 0444);
MODULE_PARM_DESC(verbose,
"Number of timestamps in each channel's software FIFO buffer.");
static void ft_timer_handler(unsigned long arg)
static void ft_temp_timer_handler(unsigned long arg)
{
struct fmctdc_dev *ft = (struct fmctdc_dev *) arg;
struct fmctdc_dev *ft = (struct fmctdc_dev *)arg;
ft_read_temp(ft, ft->verbose);
mod_timer(&ft->temp_timer, jiffies + 5 * HZ);
}
static int ft_init_channel (struct fmctdc_dev *ft, int channel)
static int ft_init_channel(struct fmctdc_dev *ft, int channel)
{
struct ft_channel_state *st = &ft->channels[channel - 1];
st->expected_edge = 1;
st->fifo.size = ft_buffer_size;
st->fifo.t = kmalloc(sizeof(struct ft_wr_timestamp) * st->fifo.size, GFP_KERNEL);
if(!st->fifo.t)
st->fifo.t =
kmalloc(sizeof(struct ft_wr_timestamp) * st->fifo.size, GFP_KERNEL);
if (!st->fifo.t)
return -ENOMEM;
return 0;
}
static void ft_purge_fifo (struct fmctdc_dev *ft, int channel)
static void ft_purge_fifo(struct fmctdc_dev *ft, int channel)
{
struct ft_channel_state *st = &ft->channels[channel - 1];
spin_lock(&ft->lock);
st->fifo.head = 0;
st->fifo.tail = 0;
......@@ -84,21 +86,21 @@ int ft_enable_termination(struct fmctdc_dev *ft, int channel, int enable)
struct ft_channel_state *st;
uint32_t ien;
if ( channel < FT_CH_1 || channel > FT_NUM_CHANNELS )
if (channel < FT_CH_1 || channel > FT_NUM_CHANNELS)
return -EINVAL;
st = &ft->channels[channel - 1];
ien = ft_readl(ft, TDC_REG_INPUT_ENABLE);
if(enable)
if (enable)
ien |= (1 << (channel - 1));
else
ien &= ~(1 << (channel - 1));
ft_writel(ft, ien, TDC_REG_INPUT_ENABLE);
if(enable)
if (enable)
set_bit(FT_FLAG_CH_TERMINATED, &st->flags);
else
clear_bit(FT_FLAG_CH_TERMINATED, &st->flags);
......@@ -106,36 +108,39 @@ int ft_enable_termination(struct fmctdc_dev *ft, int channel, int enable)
return 0;
}
static void ft_enable_acquisition(struct fmctdc_dev *ft, int enable)
void ft_enable_acquisition(struct fmctdc_dev *ft, int enable)
{
uint32_t ien, cmd;
int i;
ien = ft_readl(ft, TDC_REG_INPUT_ENABLE);
if(enable)
{
if (enable) {
ien |= TDC_INPUT_ENABLE_FLAG;
cmd = TDC_CTRL_EN_ACQ;
} else {
ien &= ~TDC_INPUT_ENABLE_FLAG;
cmd = TDC_CTRL_DIS_ACQ;
for (i = FT_CH_1; i <= FT_NUM_CHANNELS; i++)
ft_purge_fifo(ft, i);
}
ft_writel(ft, ien, TDC_REG_INPUT_ENABLE);
ft_writel(ft, TDC_CTRL_CLEAR_DACAPO_FLAG, TDC_REG_CTRL);
ft_writel(ft, cmd, TDC_REG_CTRL);
ft->acquisition_on = enable;
}
static int ft_channels_init(struct fmctdc_dev *ft)
{
int i, ret;
for (i = FT_CH_1; i <= FT_NUM_CHANNELS; i++)
{
for (i = FT_CH_1; i <= FT_NUM_CHANNELS; i++) {
ret = ft_init_channel(ft, i);
if(ret < 0)
if (ret < 0)
return ret;
ft_enable_termination(ft, i, 1);
/* termination is off by default */
ft_enable_termination(ft, i, 0);
}
return 0;
}
......@@ -144,24 +149,23 @@ static void ft_channels_exit(struct fmctdc_dev *ft)
{
int i;
for (i = FT_CH_1; i <= FT_NUM_CHANNELS; i++)
kfree( ft->channels[i - 1].fifo.t);
kfree(ft->channels[i - 1].fifo.t);
}
struct ft_modlist {
char *name;
int (*init)(struct fmctdc_dev *);
void (*exit)(struct fmctdc_dev *);
int (*init) (struct fmctdc_dev *);
void (*exit) (struct fmctdc_dev *);
};
static struct ft_modlist init_subsystems [] = {
{ "acam-tdc", ft_acam_init, ft_acam_exit },
{ "onewire", ft_onewire_init, ft_onewire_exit },
{ "time", ft_time_init, ft_time_exit },
{ "channels", ft_channels_init, ft_channels_exit },
{ "zio", ft_zio_init, ft_zio_exit }
static struct ft_modlist init_subsystems[] = {
{"acam-tdc", ft_acam_init, ft_acam_exit},
{"onewire", ft_onewire_init, ft_onewire_exit},
{"time", ft_time_init, ft_time_exit},
{"channels", ft_channels_init, ft_channels_exit},
{"zio", ft_zio_init, ft_zio_exit}
};
/* probe and remove are called by the FMC bus core */
int ft_probe(struct fmc_device *fmc)
{
......@@ -171,16 +175,15 @@ int ft_probe(struct fmc_device *fmc)
char *fwname;
int i, index, ret;
printk("ft-probe executed\n");
ft = kzalloc(sizeof(struct fmctdc_dev), GFP_KERNEL);
if (!ft) {
dev_err(dev, "can't allocate device\n");
return -ENOMEM;
}
ft->raw_events = kzalloc(sizeof(struct ft_hw_timestamp) * FT_BUFFER_EVENTS, GFP_KERNEL);
ft->raw_events =
kzalloc(sizeof(struct ft_hw_timestamp) * FT_BUFFER_EVENTS,
GFP_KERNEL);
if (!ft->raw_events) {
dev_err(dev, "can't allocate buffer\n");
return -ENOMEM;
......@@ -193,23 +196,23 @@ int ft_probe(struct fmc_device *fmc)
return -ENODEV;
}
fmc->mezzanine_data = ft;
ft->fmc = fmc;
ft->verbose = ft_verbose;
/* apply carrier-specific hacks and workarounds */
if(!strcmp(fmc->carrier_name, "SPEC"))
if (!strcmp(fmc->carrier_name, "SPEC"))
ft->carrier_specific = &ft_carrier_spec;
else if (!strcmp(fmc->carrier_name, "SVEC"))
ft->carrier_specific = &ft_carrier_svec;
else {
dev_err(dev, "unsupported carrier\n");
return -ENODEV;
}
if (ft_drv.gw_n)
fwname = ""; /* reprogram will pick from module parameter */
else
fwname = ""; /* reprogram will pick from module parameter */
else
fwname = ft->carrier_specific->gateware_name;
/* reprogram the card, but do not try to read the SDB.
......@@ -224,24 +227,25 @@ int ft_probe(struct fmc_device *fmc)
KBUILD_MODNAME, index);
return -ENODEV;
}
return ret; /* other error: pass over */
return ret; /* other error: pass over */
}
dev_info(dev, "Gateware successfully loaded \n");
ret = ft->carrier_specific->init(ft);
if(ret < 0)
if (ret < 0)
return ret;
ret = ft->carrier_specific->reset_core(ft);
if(ret < 0)
if (ret < 0)
return ret;
/* Now that the PLL is locked, we can read the SDB info */
ret = fmc_scan_sdb_tree(fmc, 0);
if( ret < 0 )
{
dev_err(dev, "%s: no SDB in the bitstream. Are you sure you've provided the correct one?\n", KBUILD_MODNAME);
if (ret < 0) {
dev_err(dev,
"%s: no SDB in the bitstream. Are you sure you've provided the correct one?\n",
KBUILD_MODNAME);
return ret;
}
......@@ -250,58 +254,81 @@ int ft_probe(struct fmc_device *fmc)
fmc_show_sdb_tree(fmc);
/* Now use SDB to find the base addresses */
ft->ft_core_base = fmc_find_sdb_device(fmc->sdb, 0xce42, 0x604, NULL);
ft->ft_owregs_base = fmc_find_sdb_device(fmc->sdb, 0xce42, 0x602, NULL);
ft->ft_dma_base = fmc_find_sdb_device(fmc->sdb, 0xce42, 0x601, NULL);
ft->ft_carrier_base = fmc_find_sdb_device(fmc->sdb, 0xce42, 0x603, NULL);
ft->ft_core_base =
fmc_find_sdb_device_ext(fmc->sdb, 0xce42, 0x604, fmc->slot_id,
NULL);
ft->ft_carrier_base =
fmc_find_sdb_device(fmc->sdb, 0xce42, 0x603, NULL);
ft->ft_irq_base = fmc_find_sdb_device(fmc->sdb, 0xce42, 0x605, NULL);
/* FIXME/UGLY HACK: enumerate sub-cores via SDB (requires some HDL cleanup:
at least the whole Wishbone interconnect must be clocked before we proceed
with enumeration) */
if (!strcmp(fmc->carrier_name, "SPEC")) {
ft->ft_owregs_base =
fmc_find_sdb_device(fmc->sdb, 0xce42, 0x602, NULL);
ft->ft_dma_base =
fmc_find_sdb_device(fmc->sdb, 0xce42, 0x601, NULL);
/* FIXME: the HDL uses custom IRQ controller (not the VIC). IRQ lines are hardcoded. */
ft->irq_shift = 0;
} else {
ft->ft_owregs_base = ft->ft_core_base + 0x1000;
ft->irq_shift = fmc->slot_id * 3;
}
if (ft_verbose) {
dev_info(dev,
"Base addrs: core 0x%x, carrier_csr 0x%x, irq 0x%x, 1wire 0x%x\n",
ft->ft_core_base, ft->ft_carrier_base, ft->ft_irq_base,
ft->ft_owregs_base);
}
spin_lock_init(&ft->lock);
/* Retrieve calibration from the eeprom, and validate */
ret = ft_handle_eeprom_calibration(ft);
if (ret < 0)
return ret;
/* init all subsystems */
for (i = 0, m = init_subsystems; i < ARRAY_SIZE(init_subsystems); i++, m++) {
for (i = 0, m = init_subsystems; i < ARRAY_SIZE(init_subsystems);
i++, m++) {
ret = m->init(ft);
if (ret < 0)
if (ret < 0)
goto err;
}
ret = ft_irq_init(ft);
if(ret < 0)
if (ret < 0)
goto err;
ft_enable_acquisition(ft, 1);
/* start temperature polling timer */
setup_timer(&ft->temp_timer, ft_timer_handler, (unsigned long)ft);
setup_timer(&ft->temp_timer, ft_temp_timer_handler, (unsigned long)ft);
mod_timer(&ft->temp_timer, jiffies + 5 * HZ);
ft->initialized = 1;
return 0;
err:
return 0;
err:
while (--m, --i >= 0)
if (m->exit)
m->exit(ft);
return ret;
}
int ft_remove(struct fmc_device *fmc)
{
struct ft_modlist *m;
struct fmctdc_dev *ft = fmc->mezzanine_data;
int i = ARRAY_SIZE(init_subsystems);
if(!ft->initialized)
return 0; /* No init, no exit */
if (!ft->initialized)
return 0; /* No init, no exit */
del_timer_sync(&ft->temp_timer);
......@@ -313,26 +340,29 @@ int ft_remove(struct fmc_device *fmc)
if (m->exit)
m->exit(ft);
}
ft->carrier_specific->exit(ft);
return 0;
}
static struct fmc_fru_id ft_fru_id[] = {
{
.product_name = "FmcTdc1ns5cha",
},
{
.product_name = "FmcTdc1ns5cha",
},
};
static struct fmc_driver ft_drv = {
.version = FMC_VERSION,
.driver.name = KBUILD_MODNAME,
.probe = ft_probe,
.remove = ft_remove,
.id_table = {
.fru_id = ft_fru_id,
.fru_id_nr = ARRAY_SIZE(ft_fru_id),
},
.version = FMC_VERSION,
.driver.name = KBUILD_MODNAME,
.probe = ft_probe,
.remove = ft_remove,
.id_table = {
.fru_id = ft_fru_id,
.fru_id_nr = ARRAY_SIZE(ft_fru_id),
},
};
static int ft_init(void)
{
int ret;
......@@ -358,4 +388,4 @@ static void ft_exit(void)
module_init(ft_init);
module_exit(ft_exit);
MODULE_LICENSE("GPL and additional rights"); /* LGPL */
MODULE_LICENSE("GPL and additional rights"); /* LGPL */
......@@ -13,10 +13,7 @@
* option, any later version.
*/
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/moduleparam.h>
#include <linux/init.h>
#include <linux/timer.h>
#include <linux/jiffies.h>
......@@ -30,7 +27,10 @@
#include "fmc-tdc.h"
#include "hw/tdc_regs.h"
int ft_read_sw_fifo(struct fmctdc_dev *ft, int channel, struct zio_channel *chan)
static void ft_readout_tasklet(unsigned long arg);
int ft_read_sw_fifo(struct fmctdc_dev *ft, int channel,
struct zio_channel *chan)
{
struct zio_control *ctrl;
struct zio_ti *ti = chan->cset->ti;
......@@ -51,15 +51,15 @@ int ft_read_sw_fifo(struct fmctdc_dev *ft, int channel, struct zio_channel *chan
spin_lock_irqsave(&ft->lock, flags);
ts = st->fifo.t[st->fifo.tail];
st->fifo.tail++;
if(st->fifo.tail == st->fifo.size)
if (st->fifo.tail == st->fifo.size)
st->fifo.tail = 0;
st->fifo.count--;
spin_unlock_irqrestore(&ft->lock, flags);
/* Write the timestamp in the trigger, it will reach the control */
ti->tstamp.tv_sec = ts.seconds;
ti->tstamp.tv_sec = ts.seconds;
ti->tstamp.tv_nsec = ts.coarse * 8;
ti->tstamp_extra = ts.frac;
ti->tstamp_extra = ts.frac;
/*
* This is different than it was. We used to fill the active block,
......@@ -76,26 +76,27 @@ int ft_read_sw_fifo(struct fmctdc_dev *ft, int channel, struct zio_channel *chan
v = ctrl->attr_channel.ext_val;
v[FT_ATTR_TDC_SECONDS] = ts.seconds;
v[FT_ATTR_TDC_COARSE] = ts.coarse;
v[FT_ATTR_TDC_FRAC] = ts.frac;
v[FT_ATTR_TDC_SEQ] = ts.seq_id;
v[FT_ATTR_TDC_OFFSET] = ft->calib.zero_offset[channel - 1];
v[FT_ATTR_TDC_USER_OFFSET] = st->user_offset;
v[FT_ATTR_TDC_SECONDS] = ts.seconds;
v[FT_ATTR_TDC_COARSE] = ts.coarse;
v[FT_ATTR_TDC_FRAC] = ts.frac;
v[FT_ATTR_TDC_SEQ] = ts.seq_id;
v[FT_ATTR_TDC_OFFSET] = ft->calib.zero_offset[channel - 1];
v[FT_ATTR_TDC_USER_OFFSET] = st->user_offset;
return 0;
}
static inline void enqueue_timestamp ( struct fmctdc_dev *ft, int channel, struct ft_wr_timestamp *ts )
static inline void enqueue_timestamp(struct fmctdc_dev *ft, int channel,
struct ft_wr_timestamp *ts)
{
struct ft_sw_fifo *fifo = &ft->channels[channel - 1].fifo;
unsigned long flags;
/* fixme: consider independent locks for each channel. */
spin_lock_irqsave(&ft->lock, flags);
fifo->t[ fifo->head ] = *ts;
fifo->t[fifo->head] = *ts;
fifo->head = (fifo->head + 1) % fifo->size;
if(fifo->count < fifo->size)
if (fifo->count < fifo->size)
fifo->count++;
else {
fifo->tail = (fifo->tail + 1) % fifo->size;
......@@ -103,7 +104,9 @@ static inline void enqueue_timestamp ( struct fmctdc_dev *ft, int channel, struc
spin_unlock_irqrestore(&ft->lock, flags);
}
static inline void process_timestamp( struct fmctdc_dev *ft, struct ft_hw_timestamp *hwts, int dacapo_flag )
static inline void process_timestamp(struct fmctdc_dev *ft,
struct ft_hw_timestamp *hwts,
int dacapo_flag)
{
struct ft_channel_state *st;
struct ft_wr_timestamp ts;
......@@ -111,7 +114,7 @@ static inline void process_timestamp( struct fmctdc_dev *ft, struct ft_hw_timest
int channel, edge, frac;
channel = (hwts->metadata & 0x7) + 1;
edge = hwts->metadata & (1<<4) ? 1 : 0;
edge = hwts->metadata & (1 << 4) ? 1 : 0;
st = &ft->channels[channel - 1];
......@@ -120,11 +123,11 @@ static inline void process_timestamp( struct fmctdc_dev *ft, struct ft_hw_timest
ts.channel = channel;
ts.seconds = hwts->utc;
frac = hwts->bins * 81 * 64 / 125; /* reduce fraction to avoid 64-bit division */
frac = hwts->bins * 81 * 64 / 125; /* reduce fraction to avoid 64-bit division */
ts.coarse = hwts->coarse + frac / 4096;
ts.frac = frac % 4096;
/* the addition above may result with the coarse counter goint out of range: */
if (unlikely(ts.coarse >= 125000000)) {
ts.coarse -= 125000000;
......@@ -135,30 +138,33 @@ static inline void process_timestamp( struct fmctdc_dev *ft, struct ft_hw_timest
and drop pulses that are narrower than 100 ns.
We are waiting for a falling edge, but a rising one occurs - ignore it.
*/
if(unlikely(edge != st->expected_edge))
st->expected_edge = 1; /* wait unconditionally for next rising edge */
*/
if (unlikely(edge != st->expected_edge))
st->expected_edge = 1; /* wait unconditionally for next rising edge */
else {
if(st->expected_edge == 0) { /* got a falling edge after a rising one */
if (st->expected_edge == 0) { /* got a falling edge after a rising one */
struct ft_wr_timestamp diff = ts;
ft_ts_sub(&diff, &st->prev_ts);
/* Check timestamp width. Must be at least 100 ns (coarse = 12, frac = 2048) */
if (likely(diff.seconds || diff.coarse > 12 || (diff.coarse == 12 && diff.frac >= 2048)))
{
ft_ts_apply_offset(&ts, ft->calib.zero_offset[channel - 1]);
if(st->user_offset)
ft_ts_apply_offset(&ts, st->user_offset);
if (likely
(diff.seconds || diff.coarse > 12
|| (diff.coarse == 12 && diff.frac >= 2048))) {
ft_ts_apply_offset(&ts,
ft->calib.
zero_offset[channel - 1]);
if (st->user_offset)
ft_ts_apply_offset(&ts,
st->user_offset);
/* Got a dacapo flag? make a gap in the sequence ID to indicate
an unknow loss of timestamps */
an unknown loss of timestamps */
ts.seq_id = st->cur_seq_id++;
if(dacapo_flag)
{
if (dacapo_flag) {
ts.seq_id++;
st->cur_seq_id++;
}
......@@ -166,7 +172,7 @@ static inline void process_timestamp( struct fmctdc_dev *ft, struct ft_hw_timest
/* Put the timestamp in the FIFO */
enqueue_timestamp(ft, channel, &ts);
}
} else
} else
st->prev_ts = ts;
st->expected_edge = 1 - st->expected_edge;
......@@ -178,31 +184,37 @@ static irqreturn_t ft_irq_handler(int irq, void *dev_id)
struct fmc_device *fmc = dev_id;
struct fmctdc_dev *ft = fmc->mezzanine_data;
tasklet_schedule(&ft->readout_tasklet);
/* called outside an IRQ context - probably from the polling timer simulating
not-yet-supported IRQs on the SVEC */
if (unlikely(!in_interrupt())) {
ft_readout_tasklet((unsigned long)ft);
} else
tasklet_schedule(&ft->readout_tasklet);
return IRQ_HANDLED;
}
static inline int check_lost_events(uint32_t curr_wr_ptr, uint32_t prev_wr_ptr, int *count)
static inline int check_lost_events(uint32_t curr_wr_ptr, uint32_t prev_wr_ptr,
int *count)
{
uint32_t dacapo_prev, dacapo_curr;
int dacapo_diff, ptr_diff = 0;
dacapo_prev = prev_wr_ptr >> 12;
dacapo_curr = curr_wr_ptr >> 12;
curr_wr_ptr &= 0x00fff; /* Pick last 12 bits */
curr_wr_ptr &= 0x00fff; /* Pick last 12 bits */
curr_wr_ptr >>= 4; /* Remove last 4 bits. */
prev_wr_ptr &= 0x00fff; /* Pick last 12 bits */
prev_wr_ptr &= 0x00fff; /* Pick last 12 bits */
prev_wr_ptr >>= 4; /* Remove last 4 bits. */
dacapo_diff = dacapo_curr - dacapo_prev;
switch(dacapo_diff) {
switch (dacapo_diff) {
case 1:
ptr_diff = curr_wr_ptr - prev_wr_ptr;
if (ptr_diff > 0) {
*count = FT_BUFFER_EVENTS;
return 1; /* We lost data */
return 1; /* We lost data */
}
*count = curr_wr_ptr - prev_wr_ptr + FT_BUFFER_EVENTS;
break;
......@@ -221,44 +233,46 @@ static inline int check_lost_events(uint32_t curr_wr_ptr, uint32_t prev_wr_ptr,
static void ft_readout_tasklet(unsigned long arg)
{
struct fmctdc_dev *ft = (struct fmctdc_dev *) arg;
struct fmctdc_dev *ft = (struct fmctdc_dev *)arg;
struct fmc_device *fmc = ft->fmc;
struct zio_device *zdev = ft->zdev;
uint32_t rd_ptr;
int count, dacapo, i;
ft->prev_wr_ptr = ft->cur_wr_ptr;
ft->cur_wr_ptr = ft_readl(ft, TDC_REG_BUFFER_PTR);
/* read the timestamps via DMA - we read the whole buffer, it doesn't really matter
for the HW if it's 16 bytes or on 4k page */
for the HW if it's 16 bytes or a 4k page */
if( ft->carrier_specific->copy_timestamps(ft, 0, FT_BUFFER_EVENTS * sizeof(struct ft_hw_timestamp), ft->raw_events) < 0)
return; /* we can do nothing about this */
if (ft->carrier_specific->copy_timestamps(ft, 0,
FT_BUFFER_EVENTS *
sizeof(struct
ft_hw_timestamp),
ft->raw_events) < 0)
return; /* we can do nothing about this */
dacapo = check_lost_events(ft->cur_wr_ptr, ft->prev_wr_ptr, &count);
/* Start reading from the oldest event */
if(count == FT_BUFFER_EVENTS)
rd_ptr = (ft->cur_wr_ptr >> 4) & 0x000ff; /* The oldest is curr_wr_ptr */
if (count == FT_BUFFER_EVENTS)
rd_ptr = (ft->cur_wr_ptr >> 4) & 0x000ff; /* The oldest is curr_wr_ptr */
else
rd_ptr = (ft->prev_wr_ptr >> 4) & 0x000ff; /* The oldest is prev_wr_ptr */
rd_ptr = (ft->prev_wr_ptr >> 4) & 0x000ff; /* The oldest is prev_wr_ptr */
for ( ; count > 0; count--) {
process_timestamp(ft, &ft->raw_events[rd_ptr], dacapo);
for (; count > 0; count--) {
process_timestamp(ft, &ft->raw_events[rd_ptr], dacapo);
rd_ptr = (rd_ptr + 1) % FT_BUFFER_EVENTS;
}
if(!zdev)
if (!zdev)
goto out;
for(i = FT_CH_1; i <= FT_NUM_CHANNELS; i++) {
struct ft_channel_state *st = &ft->channels[i-1];
for (i = FT_CH_1; i <= FT_NUM_CHANNELS; i++) {
struct ft_channel_state *st = &ft->channels[i - 1];
/* FIXME: race condition */
if (test_bit(FT_FLAG_CH_INPUT_READY, &st->flags)) {
struct zio_cset *cset = &zdev->cset[i-1];
struct zio_cset *cset = &zdev->cset[i - 1];
/* there is an active block, try reading an accumulated sample */
if (ft_read_sw_fifo(ft, i, cset->chan) == 0) {
clear_bit(FT_FLAG_CH_INPUT_READY, &st->flags);
......@@ -267,22 +281,28 @@ static void ft_readout_tasklet(unsigned long arg)
}
}
out:
out:
/* ack the irq */
fmc_writel(ft->fmc, TDC_IRQ_TDC_TSTAMP, ft->ft_irq_base + TDC_REG_IRQ_STATUS);
fmc_writel(ft->fmc, TDC_IRQ_TDC_TSTAMP << ft->irq_shift,
ft->ft_irq_base + TDC_REG_IRQ_STATUS);
fmc->op->irq_ack(fmc);
}
int ft_irq_init(struct fmctdc_dev *ft)
{
tasklet_init(&ft->readout_tasklet, ft_readout_tasklet, (unsigned long)ft);
uint32_t irq_en;
tasklet_init(&ft->readout_tasklet, ft_readout_tasklet,
(unsigned long)ft);
/* disable coalescing, it's currently broken */
ft_writel(ft, 1, TDC_REG_IRQ_THRESHOLD);
ft_writel(ft, 0, TDC_REG_IRQ_TIMEOUT);
/* enable timestamp readout irq */
fmc_writel(ft->fmc, TDC_IRQ_TDC_TSTAMP, ft->ft_irq_base + TDC_REG_IRQ_ENABLE);
irq_en = fmc_readl(ft->fmc, ft->ft_irq_base + TDC_REG_IRQ_ENABLE);
fmc_writel(ft->fmc, irq_en | (TDC_IRQ_TDC_TSTAMP << ft->irq_shift),
ft->ft_irq_base + TDC_REG_IRQ_ENABLE);
/* configure the actual handler via a carrier-specific mechanism */
return ft->carrier_specific->setup_irqs(ft, ft_irq_handler);
......@@ -293,4 +313,4 @@ void ft_irq_exit(struct fmctdc_dev *ft)
fmc_writel(ft->fmc, 0, ft->ft_irq_base + TDC_REG_IRQ_ENABLE);
ft->carrier_specific->disable_irqs(ft);
}
\ No newline at end of file
}
......@@ -3,7 +3,6 @@
*
* Copyright (C) 2012-2013 CERN (http://www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
* Author: Alessandro Rubini <rubini@gnudd.com>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
......@@ -27,35 +26,32 @@ struct ft_spec_data {
static inline uint32_t dma_readl(struct fmctdc_dev *ft, unsigned long reg)
{
uint32_t rv = fmc_readl(ft->fmc, ft->ft_dma_base + reg);
//printk("dma_readl: addr %x val %x\n", ft->ft_dma_base + reg, rv);
return rv;
return fmc_readl(ft->fmc, ft->ft_dma_base + reg);
}
static inline void dma_writel(struct fmctdc_dev *ft, uint32_t v, unsigned long reg)
static inline void dma_writel(struct fmctdc_dev *ft, uint32_t v,
unsigned long reg)
{
//printk("dma_writel: addr %x val %x\n", ft->ft_dma_base + reg, v);
fmc_writel(ft->fmc, v, ft->ft_dma_base + reg);
}
static int spec_ft_init ( struct fmctdc_dev *ft )
static int ft_spec_init(struct fmctdc_dev *ft)
{
ft->carrier_data = kzalloc(sizeof(struct ft_spec_data), GFP_KERNEL );
ft->carrier_data = kzalloc(sizeof(struct ft_spec_data), GFP_KERNEL);
if(!ft->carrier_data)
if (!ft->carrier_data)
return -ENOMEM;
return 0;
}
static int spec_ft_reset( struct fmctdc_dev *dev )
static int ft_spec_reset(struct fmctdc_dev *ft)
{
struct spec_dev *spec = (struct spec_dev *) dev->fmc->carrier_data;
struct spec_dev *spec = (struct spec_dev *)ft->fmc->carrier_data;
dev_info(&dev->fmc->dev, "%s: resetting TDC core through Gennum.\n", __func__);
dev_info(&ft->fmc->dev, "%s: resetting TDC core through Gennum.\n",
__func__);
/* set local bus clock to 160 MHz. The FPGA can't handle more. */
/* set local bus clock to 160 MHz. The FPGA can't handle more. */
gennum_writel(spec, 0xE001F04C, 0x808);
/* fixme: there is no possibility of doing a software reset of the TDC core
......@@ -66,52 +62,53 @@ static int spec_ft_reset( struct fmctdc_dev *dev )
mdelay(10);
gennum_writel(spec, 0x00025000, GNPCI_SYS_CFG_SYSTEM);
msleep(3000); /* it takes a while for the PLL to bootstrap.... or not!
We have no possibility to check :( */
msleep(3000); /* it takes a while for the PLL to bootstrap.... or not!
We have no possibility to check :( */
return 0;
}
static int spec_ft_copy_timestamps (struct fmctdc_dev *dev, int base_addr, int size, void *dst )
static int ft_spec_copy_timestamps(struct fmctdc_dev *ft, int base_addr,
int size, void *dst)
{
struct ft_spec_data *hw = dev->carrier_data;
struct ft_spec_data *cspec = ft->carrier_data;
uint32_t status;
int i, ret;
hw->dma_addr = dma_map_single(dev->fmc->hwdev, (char *)dst, size, DMA_FROM_DEVICE);
if (dma_mapping_error(dev->fmc->hwdev, hw->dma_addr)) {
dev_err(&dev->fmc->dev, "dma_map_single failed\n");
cspec->dma_addr =
dma_map_single(ft->fmc->hwdev, (char *)dst, size, DMA_FROM_DEVICE);
if (dma_mapping_error(cspec->dma_addr)) {
dev_err(&ft->fmc->dev, "dma_map_single failed\n");
return -ENOMEM;
}
dma_writel(dev, 0, TDC_REG_DMA_CTRL);
dma_writel(dev, base_addr, TDC_REG_DMA_C_START);
dma_writel(dev, hw->dma_addr & 0xffffffff, TDC_REG_DMA_H_START_L);
dma_writel(dev, ((uint64_t)hw->dma_addr >> 32) & 0x00ffffffff, TDC_REG_DMA_H_START_H);
dma_writel(dev, 0, TDC_REG_DMA_NEXT_L);
dma_writel(dev, 0, TDC_REG_DMA_NEXT_H);
dma_writel(ft, 0, TDC_REG_DMA_CTRL);
dma_writel(ft, base_addr, TDC_REG_DMA_C_START);
dma_writel(ft, cspec->dma_addr & 0xffffffff, TDC_REG_DMA_H_START_L);
dma_writel(ft, ((uint64_t) cspec->dma_addr >> 32) & 0x00ffffffff,
TDC_REG_DMA_H_START_H);
dma_writel(ft, 0, TDC_REG_DMA_NEXT_L);
dma_writel(ft, 0, TDC_REG_DMA_NEXT_H);
/* Write the DMA length */
dma_writel(dev, size, TDC_REG_DMA_LEN);
dma_writel(ft, size, TDC_REG_DMA_LEN);
/* No chained xfers, PCIe to host */
dma_writel(dev, 0, TDC_REG_DMA_ATTRIB);
dma_writel(ft, 0, TDC_REG_DMA_ATTRIB);
/* Start the transfer */
dma_writel(dev, 1, TDC_REG_DMA_CTRL);
udelay(50);
dma_writel(dev, 0, TDC_REG_DMA_CTRL);
dma_writel(ft, 1, TDC_REG_DMA_CTRL);
udelay(1);
dma_writel(ft, 0, TDC_REG_DMA_CTRL);
/* Don't bother about end-of-DMA IRQ, it only makes the driver unnecessarily complicated. */
for(i = 0; i < 1000; i++)
{
status = dma_readl (dev, TDC_REG_DMA_STAT) & TDC_DMA_STAT_MASK;
for (i = 0; i < 1000; i++) {
status = dma_readl(ft, TDC_REG_DMA_STAT) & TDC_DMA_STAT_MASK;
if(status == TDC_DMA_STAT_DONE)
{
if (status == TDC_DMA_STAT_DONE) {
ret = 0;
break;
} else if (status == TDC_DMA_STAT_ERROR) {
......@@ -122,43 +119,45 @@ static int spec_ft_copy_timestamps (struct fmctdc_dev *dev, int base_addr, int s
udelay(1);
}
if(i == 1000)
{
dev_err(&dev->fmc->dev, "%s: DMA transfer taking way too long. Something's really weird.\n", __func__);
if (i == 1000) {
dev_err(&ft->fmc->dev,
"%s: DMA transfer taking way too long. Something's really weird.\n",
__func__);
ret = -EIO;
}
dma_sync_single_for_cpu(dev->fmc->hwdev, hw->dma_addr, size, DMA_FROM_DEVICE);
dma_unmap_single(dev->fmc->hwdev, hw->dma_addr, size, DMA_FROM_DEVICE);
return ret;
dma_sync_single_for_cpu(ft->fmc->hwdev, cspec->dma_addr, size,
DMA_FROM_DEVICE);
dma_unmap_single(ft->fmc->hwdev, cspec->dma_addr, size,
DMA_FROM_DEVICE);
return ret;
}
/* Unfortunately, on the spec this is GPIO9, i.e. IRQ(1) */
static struct fmc_gpio ft_gpio_on[] = {
{
.gpio = FMC_GPIO_IRQ(1),
.mode = GPIOF_DIR_IN,
.irqmode = IRQF_TRIGGER_RISING,
}
.gpio = FMC_GPIO_IRQ(1),
.mode = GPIOF_DIR_IN,
.irqmode = IRQF_TRIGGER_RISING,
}
};
static struct fmc_gpio ft_gpio_off[] = {
{
.gpio = FMC_GPIO_IRQ(1),
.mode = GPIOF_DIR_IN,
.irqmode = 0,
}
.gpio = FMC_GPIO_IRQ(1),
.mode = GPIOF_DIR_IN,
.irqmode = 0,
}
};
static int spec_ft_setup_irqs (struct fmctdc_dev *ft, irq_handler_t handler)
static int ft_spec_setup_irqs(struct fmctdc_dev *ft, irq_handler_t handler)
{
struct fmc_device *fmc = ft->fmc;
int ret;
ret = fmc->op->irq_request(fmc, handler, "fmc-tdc", IRQF_SHARED);
if(ret < 0)
{
if (ret < 0) {
dev_err(&fmc->dev, "Request interrupt failed: %d\n", ret);
return ret;
}
......@@ -167,7 +166,7 @@ static int spec_ft_setup_irqs (struct fmctdc_dev *ft, irq_handler_t handler)
return 0;
}
static int spec_ft_disable_irqs (struct fmctdc_dev *ft)
static int ft_spec_disable_irqs(struct fmctdc_dev *ft)
{
struct fmc_device *fmc = ft->fmc;
......@@ -177,18 +176,23 @@ static int spec_ft_disable_irqs (struct fmctdc_dev *ft)
return 0;
}
static int spec_ft_ack_irq (struct fmctdc_dev *ft)
static int ft_spec_ack_irq(struct fmctdc_dev *ft, int irq_id)
{
return 0;
}
static void ft_spec_exit(struct fmctdc_dev *ft)
{
kfree(ft->carrier_data);
}
struct ft_carrier_specific ft_carrier_spec = {
FT_GATEWARE_SPEC,
spec_ft_init,
spec_ft_reset,
spec_ft_copy_timestamps,
spec_ft_setup_irqs,
spec_ft_disable_irqs,
spec_ft_ack_irq
};
\ No newline at end of file
ft_spec_init,
ft_spec_reset,
ft_spec_copy_timestamps,
ft_spec_setup_irqs,
ft_spec_disable_irqs,
ft_spec_ack_irq,
ft_spec_exit,
};
/*
* SVEC-specific workarounds for the fmc-tdc driver.
*
* Copyright (C) 2012-2013 CERN (http://www.cern.ch)
* Author: 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 Lesser General Public License
* version 2 as published by the Free Software Foundation.
*/
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/moduleparam.h>
#include <linux/delay.h>
#include <linux/fmc.h>
#include "fmc-tdc.h"
#include "hw/tdc_regs.h"
static int ft_poll_interval = 200;
module_param_named(poll_interval, ft_poll_interval, int, 0444);
MODULE_PARM_DESC(poll_interval,
"Buffer polling interval in milliseconds. Applies to SVEC version only.");
/* SVEC-specific private data structure */
struct ft_svec_data {
irq_handler_t fake_irq_handler;
struct timer_list poll_timer;
};
static void ft_poll_timer_handler(unsigned long arg)
{
struct fmctdc_dev *ft = (struct fmctdc_dev *)arg;
struct ft_svec_data *cdata = ft->carrier_data;
uint32_t irq_stat;
irq_stat = fmc_readl(ft->fmc, ft->ft_irq_base + TDC_REG_IRQ_STATUS);
irq_stat >>= ft->irq_shift;
/* irq status bit set for the TS buffer irq? call the "real" handler */
if (irq_stat & TDC_IRQ_TDC_TSTAMP)
cdata->fake_irq_handler(TDC_IRQ_TDC_TSTAMP, ft->fmc);
mod_timer(&cdata->poll_timer, jiffies + (ft_poll_interval * HZ / 1000));
}
static int ft_svec_init(struct fmctdc_dev *ft)
{
struct ft_svec_data *cdata;;
ft->carrier_data = kzalloc(sizeof(struct ft_svec_data), GFP_KERNEL);
if (!ft->carrier_data)
return -ENOMEM;
/* FIXME: use SDB (after fixing the HDL) */
cdata = ft->carrier_data;
return 0;
}
static int ft_svec_reset(struct fmctdc_dev *ft)
{
unsigned long tmo;
/* FIXME: An UGLY hack: ft_svec_reset() executed on slot 0 (first mezzanine to
be initialized) resets BOTH cards. The reason is that we need both mezzanines PLLs
running to read the entire SDB tree (parts of the system interconnect are clocked from
FMC clock lines - a f***up in the HDL. */
if (ft->fmc->slot_id != 0)
return 0;
dev_info(&ft->fmc->dev, "Resetting FMCs...\n");
fmc_writel(ft->fmc, TDC_CARRIER_CTL1_RSTN_FMC0 |
TDC_CARRIER_CTL1_RSTN_FMC1,
TDC_SVEC_CARRIER_BASE + TDC_REG_CARRIER_CTL1);
tmo = jiffies + 2 * HZ;
while (time_before(jiffies, tmo)) {
uint32_t stat;
stat =
fmc_readl(ft->fmc,
TDC_SVEC_CARRIER_BASE + TDC_REG_CARRIER_CTL0);
if ((stat & TDC_CARRIER_CTL0_PLL_STAT_FMC0) &&
(stat & TDC_CARRIER_CTL0_PLL_STAT_FMC1))
return 0;
msleep(10);
}
dev_err(&ft->fmc->dev, "PLL lock timeout.\n");
return -EIO;
}
static int ft_svec_copy_timestamps(struct fmctdc_dev *ft, int base_addr,
int size, void *dst)
{
int i;
uint32_t addr;
uint32_t *dptr;
if (unlikely(size & 3 || base_addr & 3)) /* no unaligned reads, please. */
return -EIO;
/* FIXME: use SDB to determine buffer base address (after fixing the HDL) */
addr = ft->ft_core_base + 0x4000 + base_addr;
for (i = 0, dptr = (uint32_t *) dst; i < size / 4; i++, dptr++)
*dptr = fmc_readl(ft->fmc, addr + i * 4);
return 0;
}
static int ft_svec_setup_irqs(struct fmctdc_dev *ft, irq_handler_t handler)
{
struct ft_svec_data *cdata = ft->carrier_data;
/* FIXME: The code below doesn't work because current SVEC driver... does not support
interrupts. We use a timer instead. */
#if 0
ret = fmc->op->irq_request(fmc, handler, "fmc-tdc", IRQF_SHARED);
if (ret < 0) {
dev_err(&fmc->dev, "Request interrupt failed: %d\n", ret);
return ret;
}
#endif
cdata->fake_irq_handler = handler;
setup_timer(&cdata->poll_timer, ft_poll_timer_handler,
(unsigned long)ft);
mod_timer(&cdata->poll_timer, jiffies + (ft_poll_interval * HZ / 1000));
return 0;
}
static int ft_svec_disable_irqs(struct fmctdc_dev *ft)
{
struct ft_svec_data *cdata = ft->carrier_data;
del_timer_sync(&cdata->poll_timer);
/* fmc->op->irq_free(fmc);*/
return 0;
}
static int ft_svec_ack_irq(struct fmctdc_dev *ft, int irq_id)
{
return 0;
}
static void ft_svec_exit(struct fmctdc_dev *ft)
{
kfree(ft->carrier_data);
}
struct ft_carrier_specific ft_carrier_svec = {
FT_GATEWARE_SVEC,
ft_svec_init,
ft_svec_reset,
ft_svec_copy_timestamps,
ft_svec_setup_irqs,
ft_svec_disable_irqs,
ft_svec_ack_irq,
ft_svec_exit
};
......@@ -18,7 +18,10 @@
#include "hw/tdc_regs.h"
void ft_ts_from_picos ( uint32_t picos, struct ft_wr_timestamp *result )
/* WARNING: the seconds register name is a bit misleading - it is not UTC time
as the core is not aware of leap seconds, making it TAI time. */
void ft_ts_from_picos(uint32_t picos, struct ft_wr_timestamp *result)
{
result->frac = picos % 4096;
picos -= picos % 4096;
......@@ -29,55 +32,56 @@ void ft_ts_from_picos ( uint32_t picos, struct ft_wr_timestamp *result )
result->seconds = picos;
}
void ft_ts_add (struct ft_wr_timestamp *a, struct ft_wr_timestamp *b)
void ft_ts_add(struct ft_wr_timestamp *a, struct ft_wr_timestamp *b)
{
a->frac += b->frac;
if (unlikely(a->frac >= 4096)) {
a->frac -= 4096;
a->coarse++;
}
a->coarse += b->coarse;
if (unlikely(a->coarse >= 125000000)) {
a->coarse -= 125000000;
a->seconds ++;
}
a->seconds += b->seconds;
if (unlikely(a->frac >= 4096)) {
a->frac -= 4096;
a->coarse++;
}
a->coarse += b->coarse;
if (unlikely(a->coarse >= 125000000)) {
a->coarse -= 125000000;
a->seconds++;
}
a->seconds += b->seconds;
}
void ft_ts_sub (struct ft_wr_timestamp *a, struct ft_wr_timestamp *b)
void ft_ts_sub(struct ft_wr_timestamp *a, struct ft_wr_timestamp *b)
{
int32_t d_frac, d_coarse = 0;
d_frac = a->frac - b->frac;
if (unlikely(d_frac < 0)) {
d_frac += 4096;
d_coarse--;
}
d_coarse += a->coarse - b->coarse;
if (unlikely(d_coarse < 0)) {
d_coarse += 125000000;
a->seconds --;
}
a->coarse = d_coarse;
a->frac = d_frac;
a->seconds -= b->seconds;
d_frac = a->frac - b->frac;
if (unlikely(d_frac < 0)) {
d_frac += 4096;
d_coarse--;
}
d_coarse += a->coarse - b->coarse;
if (unlikely(d_coarse < 0)) {
d_coarse += 125000000;
a->seconds--;
}
a->coarse = d_coarse;
a->frac = d_frac;
a->seconds -= b->seconds;
}
void ft_ts_apply_offset(struct ft_wr_timestamp *ts, int32_t offset_picos )
void ft_ts_apply_offset(struct ft_wr_timestamp *ts, int32_t offset_picos)
{
struct ft_wr_timestamp offset_ts;
ft_ts_from_picos(offset_picos < 0 ? -offset_picos : offset_picos, &offset_ts);
ft_ts_from_picos(offset_picos < 0 ? -offset_picos : offset_picos,
&offset_ts);
if(offset_picos < 0)
if (offset_picos < 0)
ft_ts_sub(ts, &offset_ts);
else
ft_ts_add(ts, &offset_ts);
......@@ -85,26 +89,28 @@ void ft_ts_apply_offset(struct ft_wr_timestamp *ts, int32_t offset_picos )
int ft_set_tai_time(struct fmctdc_dev *ft, uint64_t seconds, uint32_t coarse)
{
if(ft->verbose)
dev_info(&ft->fmc->dev, "setting TAI time to %lld:%d\n", seconds, coarse);
if (ft->verbose)
dev_info(&ft->fmc->dev, "Setting TAI time to %lld:%d\n",
seconds, coarse);
ft_writel(ft, seconds & 0xffffffff, TDC_REG_CURRENT_UTC);
ft_writel(ft, TDC_CTRL_LOAD_UTC, TDC_REG_CTRL);
return 0;
}
int ft_get_tai_time(struct fmctdc_dev *ft, uint64_t *seconds, uint32_t *coarse)
int ft_get_tai_time(struct fmctdc_dev *ft, uint64_t * seconds,
uint32_t * coarse)
{
*seconds = ft_readl(ft, TDC_REG_CURRENT_UTC);
*coarse = 0;
return 0;
}
int ft_enable_wr_mode (struct fmctdc_dev *ft, int enable)
int ft_enable_wr_mode(struct fmctdc_dev *ft, int enable)
{
return -ENOTSUPP;
}
int ft_check_wr_mode (struct fmctdc_dev *ft)
int ft_check_wr_mode(struct fmctdc_dev *ft)
{
return -ENOTSUPP;
}
......@@ -120,5 +126,4 @@ int ft_time_init(struct fmctdc_dev *ft)
void ft_time_exit(struct fmctdc_dev *ft)
{
}
\ No newline at end of file
}
......@@ -28,35 +28,34 @@
#include "fmc-tdc.h"
#define _RW_ (S_IRUGO | S_IWUGO) /* I want 80-col lines so this lazy thing */
#define _RW_ (S_IRUGO | S_IWUGO) /* I want 80-col lines so this lazy thing */
/* The sample size. Mandatory, device-wide */
ZIO_ATTR_DEFINE_STD(ZIO_DEV, ft_zattr_dev_std) = {
ZIO_ATTR(zdev, ZIO_ATTR_NBITS, S_IRUGO, 0, 32), /* 32 bits. Really? */
ZIO_ATTR(zdev, ZIO_ATTR_NBITS, S_IRUGO, 0, 32), /* 32 bits. Really? */
};
/* Extended attributes for the device */
static struct zio_attribute ft_zattr_dev[] = {
ZIO_ATTR_EXT("version", S_IRUGO, FT_ATTR_DEV_VERSION, FT_VERSION),
ZIO_ATTR_EXT("seconds", _RW_, FT_ATTR_DEV_SECONDS, 0),
ZIO_ATTR_EXT("coarse", _RW_, FT_ATTR_DEV_COARSE, 0),
ZIO_ATTR_EXT("command", S_IWUGO, FT_ATTR_DEV_COMMAND, 0),
ZIO_ATTR_EXT("temperature", _RW_, FT_ATTR_DEV_TEMP, 0)
ZIO_ATTR_EXT("version", S_IRUGO, FT_ATTR_DEV_VERSION, FT_VERSION),
ZIO_ATTR_EXT("seconds", _RW_, FT_ATTR_DEV_SECONDS, 0),
ZIO_ATTR_EXT("coarse", _RW_, FT_ATTR_DEV_COARSE, 0),
ZIO_ATTR_EXT("command", S_IWUGO, FT_ATTR_DEV_COMMAND, 0),
ZIO_ATTR_EXT("enable_inputs", S_IWUGO, FT_ATTR_DEV_ENABLE_INPUTS, 0),
ZIO_ATTR_EXT("temperature", _RW_, FT_ATTR_DEV_TEMP, 0)
};
/* Extended attributes for the TDC (== input) cset */
static struct zio_attribute ft_zattr_input[] = {
ZIO_ATTR_EXT("seconds", S_IRUGO, FT_ATTR_TDC_SECONDS, 0),
ZIO_ATTR_EXT("coarse", S_IRUGO, FT_ATTR_TDC_COARSE, 0),
ZIO_ATTR_EXT("frac", S_IRUGO, FT_ATTR_TDC_FRAC, 0),
ZIO_ATTR_EXT("seq_id", S_IRUGO, FT_ATTR_TDC_SEQ, 0),
ZIO_ATTR_EXT("termination", _RW_, FT_ATTR_TDC_TERMINATION, 0),
ZIO_ATTR_EXT("offset", S_IRUGO, FT_ATTR_TDC_OFFSET, 0),
ZIO_ATTR_EXT("user-offset", _RW_, FT_ATTR_TDC_USER_OFFSET, 0),
ZIO_ATTR_EXT("purge-fifo", S_IWUGO, FT_ATTR_TDC_PURGE_FIFO, 0)
ZIO_ATTR_EXT("seconds", S_IRUGO, FT_ATTR_TDC_SECONDS, 0),
ZIO_ATTR_EXT("coarse", S_IRUGO, FT_ATTR_TDC_COARSE, 0),
ZIO_ATTR_EXT("frac", S_IRUGO, FT_ATTR_TDC_FRAC, 0),
ZIO_ATTR_EXT("seq_id", S_IRUGO, FT_ATTR_TDC_SEQ, 0),
ZIO_ATTR_EXT("termination", _RW_, FT_ATTR_TDC_TERMINATION, 0),
ZIO_ATTR_EXT("offset", S_IRUGO, FT_ATTR_TDC_OFFSET, 0),
ZIO_ATTR_EXT("user-offset", _RW_, FT_ATTR_TDC_USER_OFFSET, 0),
};
/* This identifies if our "struct device" is device, input, output */
enum ft_devtype {
FT_TYPE_WHOLEDEV,
......@@ -66,7 +65,7 @@ enum ft_devtype {
static enum ft_devtype __ft_get_type(struct device *dev)
{
struct zio_obj_head *head = to_zio_head(dev);
if (head->zobj_type == ZIO_DEV)
return FT_TYPE_WHOLEDEV;
return FT_TYPE_INPUT;
......@@ -74,7 +73,7 @@ static enum ft_devtype __ft_get_type(struct device *dev)
/* TDC input attributes: only the user offset is special */
static int ft_zio_info_channel(struct device *dev, struct zio_attribute *zattr,
uint32_t *usr_val)
uint32_t * usr_val)
{
struct zio_cset *cset;
struct fmctdc_dev *ft;
......@@ -84,28 +83,26 @@ static int ft_zio_info_channel(struct device *dev, struct zio_attribute *zattr,
ft = cset->zdev->priv_d;
st = &ft->channels[cset->index];
switch(zattr->id)
{
case FT_ATTR_TDC_USER_OFFSET:
*usr_val = st->user_offset;
break;
switch (zattr->id) {
case FT_ATTR_TDC_USER_OFFSET:
*usr_val = st->user_offset;
break;
case FT_ATTR_TDC_OFFSET:
*usr_val = ft->calib.zero_offset[cset->index];
break;
case FT_ATTR_TDC_OFFSET:
*usr_val = ft->calib.zero_offset[cset->index];
break;
case FT_ATTR_TDC_TERMINATION:
*usr_val = test_bit(FT_FLAG_CH_TERMINATED, &st->flags);
break;
case FT_ATTR_TDC_TERMINATION:
*usr_val = test_bit(FT_FLAG_CH_TERMINATED, &st->flags);
break;
}
return 0;
}
/* Overall and device-wide attributes: only get_time is special */
static int ft_zio_info_get(struct device *dev, struct zio_attribute *zattr,
uint32_t *usr_val)
uint32_t * usr_val)
{
struct zio_device *zdev;
struct fmctdc_dev *ft;
......@@ -113,45 +110,45 @@ static int ft_zio_info_get(struct device *dev, struct zio_attribute *zattr,
if (__ft_get_type(dev) == FT_TYPE_INPUT)
return ft_zio_info_channel(dev, zattr, usr_val);
/* reading temperature */
zdev = to_zio_dev(dev);
attr = zdev->zattr_set.ext_zattr;
ft = zdev->priv_d;
switch(zattr->id)
{
case FT_ATTR_DEV_VERSION:
switch (zattr->id) {
case FT_ATTR_DEV_VERSION:
return 0;
case FT_ATTR_DEV_TEMP:
if (ft->temp_ready) {
attr[FT_ATTR_DEV_TEMP].value = ft->temp;
return 0;
case FT_ATTR_DEV_TEMP:
if (ft->temp_ready) {
attr[FT_ATTR_DEV_TEMP].value = ft->temp;
return 0;
} else
return -EAGAIN;
case FT_ATTR_DEV_COARSE:
case FT_ATTR_DEV_SECONDS:
} else
return -EAGAIN;
case FT_ATTR_DEV_COARSE:
case FT_ATTR_DEV_SECONDS:
{
uint64_t seconds;
uint32_t coarse;
if( ft_get_tai_time(ft, &seconds, &coarse) < 0)
if (ft_get_tai_time(ft, &seconds, &coarse) < 0)
return -EAGAIN;
attr[FT_ATTR_DEV_COARSE].value = coarse;
attr[FT_ATTR_DEV_SECONDS].value = (uint32_t) seconds;
return 0;
}
case FT_ATTR_DEV_ENABLE_INPUTS:
attr[FT_ATTR_DEV_ENABLE_INPUTS].value =
ft->acquisition_on ? 1 : 0;
return 0;
}
return -EINVAL;
}
/* TDC input attributes: the flags */
static int ft_zio_conf_channel(struct device *dev, struct zio_attribute *zattr,
uint32_t usr_val)
uint32_t usr_val)
{
struct zio_cset *cset;
struct fmctdc_dev *ft;
......@@ -161,23 +158,16 @@ static int ft_zio_conf_channel(struct device *dev, struct zio_attribute *zattr,
ft = cset->zdev->priv_d;
st = &ft->channels[cset->index];
switch (zattr->id)
{
case FT_ATTR_TDC_TERMINATION:
ft_enable_termination(ft, cset->index + 1, usr_val);
return 0;
case FT_ATTR_TDC_USER_OFFSET:
spin_lock(&ft->lock);
st->user_offset = usr_val;
spin_unlock(&ft->lock);
return 0;
switch (zattr->id) {
case FT_ATTR_TDC_TERMINATION:
ft_enable_termination(ft, cset->index + 1, usr_val);
return 0;
case FT_ATTR_TDC_PURGE_FIFO:
spin_lock(&ft->lock);
st->fifo.head = st->fifo.tail = st->fifo.count = 0;
spin_unlock(&ft->lock);
return 0;
case FT_ATTR_TDC_USER_OFFSET:
spin_lock(&ft->lock);
st->user_offset = usr_val;
spin_unlock(&ft->lock);
return 0;
}
return -EINVAL;
......@@ -193,17 +183,17 @@ static int ft_zio_input(struct zio_cset *cset)
{
struct fmctdc_dev *ft;
struct ft_channel_state *st;
ft = cset->zdev->priv_d;
if(!ft->initialized)
if (!ft->initialized)
return -EAGAIN;
st = &ft->channels[ cset->index ];
st = &ft->channels[cset->index];
/* Ready for input. If there's already something, return it now */
if (ft_read_sw_fifo(ft, cset->index + 1, cset->chan) == 0) {
return 0; /* don't call data_done, let the caller do it */
return 0; /* don't call data_done, let the caller do it */
}
/* Mark the active block is valid, and return EAGAIN */
......@@ -211,10 +201,9 @@ static int ft_zio_input(struct zio_cset *cset)
return -EAGAIN;
}
/* conf_set dispatcher and and device-wide attributes */
static int ft_zio_conf_set(struct device *dev, struct zio_attribute *zattr,
uint32_t usr_val)
uint32_t usr_val)
{
struct zio_device *zdev;
struct fmctdc_dev *ft;
......@@ -222,39 +211,41 @@ static int ft_zio_conf_set(struct device *dev, struct zio_attribute *zattr,
if (__ft_get_type(dev) == FT_TYPE_INPUT)
return ft_zio_conf_channel(dev, zattr, usr_val);
/* Remains: wholedev */
zdev = to_zio_dev(dev);
attr = zdev->zattr_set.ext_zattr;
ft = zdev->priv_d;
if (zattr->id == FT_ATTR_DEV_SECONDS)
{
if (zattr->id == FT_ATTR_DEV_SECONDS) {
/* current gw does not allow changing time when acquisition is enabled */
dev_err(&ft->fmc->dev, "%s: no time setting supported due to bugs in gateware.\n", __func__);
/*return ft_set_tai_time( ft, attr[FT_ATTR_DEV_SECONDS].value,
attr[FT_ATTR_DEV_COARSE].value
);*/
dev_err(&ft->fmc->dev,
"%s: no time setting supported due to bugs in gateware.\n",
__func__);
/*return ft_set_tai_time( ft, attr[FT_ATTR_DEV_SECONDS].value,
attr[FT_ATTR_DEV_COARSE].value
); */
return -ENOTSUPP;
}
} else if (zattr->id == FT_ATTR_DEV_ENABLE_INPUTS)
ft_enable_acquisition(ft, zattr->value);
/* Not command, nothing to do */
if (zattr->id != FT_ATTR_DEV_COMMAND)
return 0;
switch(usr_val) {
switch (usr_val) {
case FT_CMD_WR_ENABLE:
case FT_CMD_WR_DISABLE:
case FT_CMD_WR_QUERY:
dev_warn(&ft->fmc->dev, "%s: sorry, no White Rabbit support yet.", __func__);
dev_warn(&ft->fmc->dev,
"%s: sorry, no White Rabbit support yet.", __func__);
return -ENOTSUPP;
default:
return -EINVAL;
}
}
/*
* The probe function receives a new zio_device, which is different from
* what we allocated (that one is the "hardwre" device) but has the
......@@ -291,7 +282,6 @@ static const struct zio_sysfs_operations ft_zio_sysfs_ops = {
},\
}
/* We have 5 csets, since each output triggers separately */
static struct zio_cset ft_cset[] = {
DECLARE_CHANNEL("ft-ch1"),
......@@ -302,16 +292,16 @@ static struct zio_cset ft_cset[] = {
};
static struct zio_device ft_tmpl = {
.owner = THIS_MODULE,
.preferred_trigger = "user",
.s_op = &ft_zio_sysfs_ops,
.cset = ft_cset,
.n_cset = ARRAY_SIZE(ft_cset),
.owner = THIS_MODULE,
.preferred_trigger = "user",
.s_op = &ft_zio_sysfs_ops,
.cset = ft_cset,
.n_cset = ARRAY_SIZE(ft_cset),
.zattr_set = {
.std_zattr = ft_zattr_dev_std,
.ext_zattr = ft_zattr_dev,
.n_ext_attr = ARRAY_SIZE(ft_zattr_dev),
},
.std_zattr = ft_zattr_dev_std,
.ext_zattr = ft_zattr_dev,
.n_ext_attr = ARRAY_SIZE(ft_zattr_dev),
},
};
static const struct zio_device_id ft_table[] = {
......@@ -321,14 +311,13 @@ static const struct zio_device_id ft_table[] = {
static struct zio_driver ft_zdrv = {
.driver = {
.name = "ft",
.owner = THIS_MODULE,
},
.name = "ft",
.owner = THIS_MODULE,
},
.id_table = ft_table,
.probe = ft_zio_probe,
};
/* Register and unregister are used to set up the template driver */
int ft_zio_register(void)
{
......
......@@ -60,10 +60,15 @@
#define TDC_EVENT_DACAPO_FLAG BIT(0)
/* Carrier CSRs */
#define TDC_REG_CARRIER_CTL0 0x0
#define TDC_REG_CARRIER_CTL1 0x4
#define TDC_REG_CARRIER_CTL0 0x0 /* a.k.a. Carrier revision/PCB id reg */
#define TDC_REG_CARRIER_STATUS 0x4
#define TDC_REG_CARRIER_CTL1 0x8
#define TDC_CARRIER_CTL0_PLL_STAT BIT(4)
#define TDC_CARRIER_CTL0_PLL_STAT_FMC0 BIT(4)
#define TDC_CARRIER_CTL0_PLL_STAT_FMC1 BIT(5)
#define TDC_CARRIER_CTL1_RSTN_FMC0 BIT(3)
#define TDC_CARRIER_CTL1_RSTN_FMC1 BIT(4)
/* Gennum DMA registers (not defined in the SPEC driver headers) */
#define TDC_REG_DMA_CTRL 0x0
......@@ -81,4 +86,6 @@
#define TDC_DMA_STAT_DONE 0x1
#define TDC_DMA_STAT_ERROR 0x3
#define TDC_SVEC_CARRIER_BASE 0x20000
#endif /* __TDC_REGISTERS_H */
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