forked from M-Labs/artiq
1
0
Fork 0

Merge branch 'spimaster'

* spimaster: (52 commits)
  runtime/rtio: rtio_process_exceptional_status() has only one user
  coredevice.spi, doc/manual: add spi
  kc705: move ttl channels together again, update doc
  runtime: rt2wb_input -> rtio_input_data
  examples/tdr: adapt to compiler changes
  bridge: really fix O/OE
  runtime: define constants for ttl addresses
  coredevice.ttl: fix sensitivity
  bridge: fix ttl o/oe addresses
  runtime: refactor ttl*()
  rtio: rm rtio_write_and_process_status
  coredevice.spi: unused import
  rt2wb, exceptions: remove RTIOTimeout
  gateware.spi: delay only writes to data register, update doc
  nist_clock: disable spi1/2
  runtime/rt2wb: use input/output terminology and add (async) input
  examples: update device_db for nist_clock spi
  gateware.spi: rework wb bus sequence
  nist_clock: rename spi*.ce to spi*.cs_n
  nist_clock: add SPIMasters to spi buses
  ...
This commit is contained in:
Robert Jördens 2016-03-01 22:08:08 +01:00
commit f754d2c117
21 changed files with 976 additions and 162 deletions

View File

@ -1,4 +1,4 @@
from artiq.coredevice import exceptions, dds
from artiq.coredevice import exceptions, dds, spi
from artiq.coredevice.exceptions import (RTIOUnderflow, RTIOSequenceError,
RTIOCollisionError, RTIOOverflow,
DDSBatchError, CacheError)

18
artiq/coredevice/rtio.py Normal file
View File

@ -0,0 +1,18 @@
from artiq.language.core import syscall
from artiq.language.types import TInt64, TInt32, TNone
@syscall
def rtio_output(time_mu: TInt64, channel: TInt32, addr: TInt32, data: TInt32
) -> TNone:
raise NotImplementedError("syscall not simulated")
@syscall
def rtio_input_timestamp(timeout_mu: TInt64, channel: TInt32) -> TInt64:
raise NotImplementedError("syscall not simulated")
@syscall
def rtio_input_data(channel: TInt32) -> TInt32:
raise NotImplementedError("syscall not simulated")

246
artiq/coredevice/spi.py Normal file
View File

@ -0,0 +1,246 @@
from artiq.language.core import (kernel, seconds_to_mu, now_mu,
delay_mu, int)
from artiq.language.units import MHz
from artiq.coredevice.rtio import rtio_output, rtio_input_data
SPI_DATA_ADDR, SPI_XFER_ADDR, SPI_CONFIG_ADDR = range(3)
(
SPI_OFFLINE,
SPI_ACTIVE,
SPI_PENDING,
SPI_CS_POLARITY,
SPI_CLK_POLARITY,
SPI_CLK_PHASE,
SPI_LSB_FIRST,
SPI_HALF_DUPLEX,
) = (1 << i for i in range(8))
SPI_RT2WB_READ = 1 << 2
class SPIMaster:
"""Core device Serial Peripheral Interface (SPI) bus master.
Owns one SPI bus.
**Transfer Sequence**:
* If desired, write the ``config`` register (:meth:`set_config`)
to configure and activate the core.
* If desired, write the ``xfer`` register (:meth:`set_xfer`)
to set ``cs_n``, ``write_length``, and ``read_length``.
* :meth:`write` to the ``data`` register (also for transfers with
zero bits to be written). Writing starts the transfer.
* If desired, :meth:`read_sync` (or :meth:`read_async` followed by a
:meth:`input_async` later) the ``data`` register corresponding to
the last completed transfer.
* If desired, :meth:`set_xfer` for the next transfer.
* If desired, :meth:`write` ``data`` queuing the next
(possibly chained) transfer.
:param ref_period: clock period of the SPI core.
:param channel: RTIO channel number of the SPI bus to control.
"""
def __init__(self, dmgr, ref_period, channel):
self.core = dmgr.get("core")
self.ref_period = ref_period
self.ref_period_mu = int(seconds_to_mu(ref_period, self.core))
self.channel = channel
self.write_period_mu = int(0)
self.read_period_mu = int(0)
self.xfer_period_mu = int(0)
# A full transfer takes write_period_mu + xfer_period_mu.
# Chained transfers can happen every xfer_period_mu.
# The second transfer of a chain can be written 2*ref_period_mu
# after the first. Read data is available every xfer_period_mu starting
# a bit after xfer_period_mu (depending on clk_phase).
# To chain transfers together, new data must be written before
# pending transfer's read data becomes available.
@kernel
def set_config(self, flags=0, write_freq=20*MHz, read_freq=20*MHz):
"""Set the configuration register.
* If ``config.cs_polarity`` == 0 (```cs`` active low, the default),
"``cs_n`` all deasserted" means "all ``cs_n`` bits high".
* ``cs_n`` is not mandatory in the pads supplied to the gateware core.
Framing and chip selection can also be handled independently
through other means, e.g. ``TTLOut``.
* If there is a ``miso`` wire in the pads supplied in the gateware,
input and output may be two signals ("4-wire SPI"),
otherwise ``mosi`` must be used for both output and input
("3-wire SPI") and ``config.half_duplex`` must to be set
when reading data is desired or when the slave drives the
``mosi`` signal at any point.
* The first bit output on ``mosi`` is always the MSB/LSB (depending
on ``config.lsb_first``) of the ``data`` register, independent of
``xfer.write_length``. The last bit input from ``miso`` always ends
up in the LSB/MSB (respectively) of the ``data`` register,
independent of ``xfer.read_length``.
* Writes to the ``config`` register take effect immediately.
**Configuration flags**:
* :const:`SPI_OFFLINE`: all pins high-z (reset=1)
* :const:`SPI_ACTIVE`: transfer in progress (read-only)
* :const:`SPI_PENDING`: transfer pending in intermediate buffer
(read-only)
* :const:`SPI_CS_POLARITY`: active level of ``cs_n`` (reset=0)
* :const:`SPI_CLK_POLARITY`: idle level of ``clk`` (reset=0)
* :const:`SPI_CLK_PHASE`: first edge after ``cs`` assertion to sample
data on (reset=0). In Motorola/Freescale SPI language
(:const:`SPI_CLK_POLARITY`, :const:`SPI_CLK_PHASE`) == (CPOL, CPHA):
- (0, 0): idle low, output on falling, input on rising
- (0, 1): idle low, output on rising, input on falling
- (1, 0): idle high, output on rising, input on falling
- (1, 1): idle high, output on falling, input on rising
* :const:`SPI_LSB_FIRST`: LSB is the first bit on the wire (reset=0)
* :const:`SPI_HALF_DUPLEX`: 3-wire SPI, in/out on ``mosi`` (reset=0)
This method advances the timeline by the duration of the
RTIO-to-Wishbone bus transaction (three RTIO clock cycles).
:param flags: A bit map of `SPI_*` flags.
:param write_freq: Desired SPI clock frequency during write bits.
:param read_freq: Desired SPI clock frequency during read bits.
"""
write_div = round(1/(write_freq*self.ref_period))
read_div = round(1/(read_freq*self.ref_period))
self.set_config_mu(flags, write_div, read_div)
@kernel
def set_config_mu(self, flags=0, write_div=6, read_div=6):
"""Set the ``config`` register (in SPI bus machine units).
.. seealso:: :meth:`set_config`
:param write_div: Counter load value to divide the RTIO
clock by to generate the SPI write clk. (minimum=2, reset=2)
``f_rtio_clk/f_spi_write == write_div``. If ``write_div`` is odd,
the setup phase of the SPI clock is biased to longer lengths
by one RTIO clock cycle.
:param read_div: Ditto for the read clock.
"""
rtio_output(now_mu(), self.channel, SPI_CONFIG_ADDR, flags |
((write_div - 2) << 16) | ((read_div - 2) << 24))
self.write_period_mu = int(write_div*self.ref_period_mu)
self.read_period_mu = int(read_div*self.ref_period_mu)
delay_mu(3*self.ref_period_mu)
@kernel
def set_xfer(self, chip_select=0, write_length=0, read_length=0):
"""Set the ``xfer`` register.
* Every transfer consists of a write of ``write_length`` bits
immediately followed by a read of ``read_length`` bits.
* ``cs_n`` is asserted at the beginning and deasserted at the end
of the transfer if there is no other transfer pending.
* ``cs_n`` handling is agnostic to whether it is one-hot or decoded
somewhere downstream. If it is decoded, "``cs_n`` all deasserted"
should be handled accordingly (no slave selected).
If it is one-hot, asserting multiple slaves should only be attempted
if ``miso`` is either not connected between slaves, or open
collector, or correctly multiplexed externally.
* For 4-wire SPI only the sum of ``read_length`` and ``write_length``
matters. The behavior is the same (except for clock speeds) no matter
how the total transfer length is divided between the two. For
3-wire SPI, the direction of ``mosi`` is switched from output to
input after ``write_length`` bits.
* Data output on ``mosi`` in 4-wire SPI during the read cycles is what
is found in the data register at the time.
Data in the ``data`` register outside the least/most (depending
on ``config.lsb_first``) significant ``read_length`` bits is what is
seen on ``miso`` (or ``mosi`` if ``config.half_duplex``)
during the write cycles.
* Writes to ``xfer`` are synchronized to the start of the next
(possibly chained) transfer.
This method advances the timeline by the duration of the
RTIO-to-Wishbone bus transaction (three RTIO clock cycles).
:param chip_select: Bit mask of chip selects to assert. Or number of
the chip select to assert if ``cs`` is decoded downstream.
(reset=0)
:param write_length: Number of bits to write during the next transfer.
(reset=0)
:param read_length: Number of bits to read during the next transfer.
(reset=0)
"""
rtio_output(now_mu(), self.channel, SPI_XFER_ADDR,
chip_select | (write_length << 16) | (read_length << 24))
self.xfer_period_mu = int(write_length*self.write_period_mu +
read_length*self.read_period_mu)
delay_mu(3*self.ref_period_mu)
@kernel
def write(self, data):
"""Write data to data register.
* The ``data`` register and the shift register are 32 bits wide.
If there are no writes to the register, ``miso`` data reappears on
``mosi`` after 32 cycles.
* A wishbone data register write is acknowledged when the
transfer has been written to the intermediate buffer.
It will be started when there are no other transactions being
executed, either beginning a new SPI transfer of chained
to an in-flight transfer.
* Writes take three ``ref_period`` cycles unless another
chained transfer is pending and the transfer being
executed is not complete.
* The SPI ``data`` register is double-buffered: Once a transfer has
started, new write data can be written, queuing a new transfer.
Transfers submitted this way are chained and executed without
deasserting ``cs`` in between. Once a transfer completes,
the previous transfer's read data is available in the
``data`` register.
This method advances the timeline by the duration of the
RTIO-to-Wishbone bus transaction (three RTIO clock cycles).
"""
rtio_output(now_mu(), self.channel, SPI_DATA_ADDR, data)
delay_mu(3*self.ref_period_mu)
@kernel
def read_async(self):
"""Trigger an asynchronous read from the data register.
Reads always finish in two cycles.
Every data register read triggered by a :meth:`read_async`
must be matched by a :meth:`input_async` to retrieve the data.
This method advances the timeline by the duration of the
RTIO-to-Wishbone bus transaction (three RTIO clock cycles).
"""
rtio_output(now_mu(), self.channel, SPI_DATA_ADDR | SPI_RT2WB_READ, 0)
delay_mu(3*self.ref_period_mu)
@kernel
def input_async(self):
"""Retrieves data written asynchronously.
:meth:`input_async` must match a preeeding :meth:`read_async`.
"""
return rtio_input_data(self.channel)
@kernel
def read_sync(self):
"""Read the ``data`` register synchronously.
This is a shortcut for :meth:`read_async` followed by
:meth:`input_async`.
"""
self.read_async()
return self.input_async()
@kernel
def _get_xfer_sync(self):
rtio_output(now_mu(), self.channel, SPI_XFER_ADDR | SPI_RT2WB_READ, 0)
return rtio_input_data(self.channel)
@kernel
def _get_config_sync(self):
rtio_output(now_mu(), self.channel, SPI_CONFIG_ADDR | SPI_RT2WB_READ,
0)
return rtio_input_data(self.channel)

View File

@ -1,26 +1,6 @@
from artiq.language.core import *
from artiq.language.types import *
@syscall
def ttl_set_o(time_mu: TInt64, channel: TInt32, enabled: TBool) -> TNone:
raise NotImplementedError("syscall not simulated")
@syscall
def ttl_set_oe(time_mu: TInt64, channel: TInt32, enabled: TBool) -> TNone:
raise NotImplementedError("syscall not simulated")
@syscall
def ttl_set_sensitivity(time_mu: TInt64, channel: TInt32, sensitivity: TInt32) -> TNone:
raise NotImplementedError("syscall not simulated")
@syscall
def ttl_get(channel: TInt32, time_limit_mu: TInt64) -> TInt64:
raise NotImplementedError("syscall not simulated")
@syscall
def ttl_clock_set(time_mu: TInt64, channel: TInt32, ftw: TInt32) -> TNone:
raise NotImplementedError("syscall not simulated")
from artiq.coredevice.rtio import rtio_output, rtio_input_timestamp
class TTLOut:
@ -43,7 +23,7 @@ class TTLOut:
@kernel
def set_o(self, o):
ttl_set_o(now_mu(), self.channel, o)
rtio_output(now_mu(), self.channel, 0, 1 if o else 0)
self.o_previous_timestamp = now_mu()
@kernel
@ -112,7 +92,7 @@ class TTLInOut:
@kernel
def set_oe(self, oe):
ttl_set_oe(now_mu(), self.channel, oe)
rtio_output(now_mu(), self.channel, 1, 1 if oe else 0)
@kernel
def output(self):
@ -132,7 +112,7 @@ class TTLInOut:
@kernel
def set_o(self, o):
ttl_set_o(now_mu(), self.channel, o)
rtio_output(now_mu(), self.channel, 0, 1 if o else 0)
self.o_previous_timestamp = now_mu()
@kernel
@ -174,7 +154,7 @@ class TTLInOut:
@kernel
def _set_sensitivity(self, value):
ttl_set_sensitivity(now_mu(), self.channel, value)
rtio_output(now_mu(), self.channel, 2, value)
self.i_previous_timestamp = now_mu()
@kernel
@ -230,7 +210,7 @@ class TTLInOut:
"""Poll the RTIO input during all the previously programmed gate
openings, and returns the number of registered events."""
count = 0
while ttl_get(self.channel, self.i_previous_timestamp) >= 0:
while rtio_input_timestamp(self.i_previous_timestamp, self.channel) >= 0:
count += 1
return count
@ -241,7 +221,7 @@ class TTLInOut:
If the gate is permanently closed, returns a negative value.
"""
return ttl_get(self.channel, self.i_previous_timestamp)
return rtio_input_timestamp(self.i_previous_timestamp, self.channel)
class TTLClockGen:
@ -292,7 +272,7 @@ class TTLClockGen:
that are not powers of two cause jitter of one RTIO clock cycle at the
output.
"""
ttl_clock_set(now_mu(), self.channel, frequency)
rtio_output(now_mu(), self.channel, 0, frequency)
self.previous_timestamp = now_mu()
@kernel

View File

@ -53,21 +53,21 @@ fmc_adapter_io = [
("spi", 0,
Subsignal("clk", Pins("LPC:LA13_N")),
Subsignal("ce", Pins("LPC:LA14_N")),
Subsignal("cs_n", Pins("LPC:LA14_N")),
Subsignal("mosi", Pins("LPC:LA17_CC_P")),
Subsignal("miso", Pins("LPC:LA17_CC_N")),
IOStandard("LVTTL")),
("spi", 1,
Subsignal("clk", Pins("LPC:LA23_N")),
Subsignal("ce", Pins("LPC:LA23_P")),
Subsignal("cs_n", Pins("LPC:LA23_P")),
Subsignal("mosi", Pins("LPC:LA18_CC_N")),
Subsignal("miso", Pins("LPC:LA18_CC_P")),
IOStandard("LVTTL")),
("spi", 2,
Subsignal("clk", Pins("LPC:LA27_P")),
Subsignal("ce", Pins("LPC:LA26_P")),
Subsignal("cs_n", Pins("LPC:LA26_P")),
Subsignal("mosi", Pins("LPC:LA27_N")),
Subsignal("miso", Pins("LPC:LA26_N")),
IOStandard("LVTTL")),

View File

@ -0,0 +1,13 @@
from migen import *
from artiq.gateware.spi import SPIMaster as SPIMasterWB
from artiq.gateware.rtio.phy.wishbone import RT2WB
class SPIMaster(Module):
def __init__(self, pads, **kwargs):
self.submodules._ll = ClockDomainsRenamer("rio")(
SPIMasterWB(pads, **kwargs))
self.submodules._rt2wb = RT2WB(2, self._ll.bus)
self.rtlink = self._rt2wb.rtlink
self.probes = []

487
artiq/gateware/spi.py Normal file
View File

@ -0,0 +1,487 @@
from itertools import product
from migen import *
from migen.genlib.fsm import FSM, NextState
from misoc.interconnect import wishbone
class SPIClockGen(Module):
def __init__(self, width):
self.load = Signal(width)
self.bias = Signal() # bias this clock phase to longer times
self.edge = Signal()
self.clk = Signal(reset=1)
cnt = Signal.like(self.load)
bias = Signal()
zero = Signal()
self.comb += [
zero.eq(cnt == 0),
self.edge.eq(zero & ~bias),
]
self.sync += [
If(zero,
bias.eq(0),
).Else(
cnt.eq(cnt - 1),
),
If(self.edge,
cnt.eq(self.load[1:]),
bias.eq(self.load[0] & (self.clk ^ self.bias)),
self.clk.eq(~self.clk),
)
]
class SPIRegister(Module):
def __init__(self, width):
self.data = Signal(width)
self.o = Signal()
self.i = Signal()
self.lsb = Signal()
self.shift = Signal()
self.sample = Signal()
self.comb += [
self.o.eq(Mux(self.lsb, self.data[0], self.data[-1])),
]
self.sync += [
If(self.shift,
If(self.lsb,
self.data[:-1].eq(self.data[1:]),
).Else(
self.data[1:].eq(self.data[:-1]),
)
),
If(self.sample,
If(self.lsb,
self.data[-1].eq(self.i),
).Else(
self.data[0].eq(self.i),
)
)
]
class SPIBitCounter(Module):
def __init__(self, width):
self.n_read = Signal(width)
self.n_write = Signal(width)
self.read = Signal()
self.write = Signal()
self.done = Signal()
self.comb += [
self.write.eq(self.n_write != 0),
self.read.eq(self.n_read != 0),
self.done.eq(~(self.write | self.read)),
]
self.sync += [
If(self.write,
self.n_write.eq(self.n_write - 1),
).Elif(self.read,
self.n_read.eq(self.n_read - 1),
)
]
class SPIMachine(Module):
def __init__(self, data_width, clock_width, bits_width):
ce = CEInserter()
self.submodules.cg = ce(SPIClockGen(clock_width))
self.submodules.reg = ce(SPIRegister(data_width))
self.submodules.bits = ce(SPIBitCounter(bits_width))
self.div_write = Signal.like(self.cg.load)
self.div_read = Signal.like(self.cg.load)
self.clk_phase = Signal()
self.start = Signal()
self.cs = Signal()
self.oe = Signal()
self.done = Signal()
# # #
fsm = CEInserter()(FSM("IDLE"))
self.submodules += fsm
fsm.act("IDLE",
If(self.start,
If(self.clk_phase,
NextState("WAIT"),
).Else(
NextState("SETUP"),
)
)
)
fsm.act("SETUP",
self.reg.sample.eq(1),
NextState("HOLD"),
)
fsm.act("HOLD",
If(self.bits.done & ~self.start,
If(self.clk_phase,
NextState("IDLE"),
).Else(
NextState("WAIT"),
)
).Else(
self.reg.shift.eq(1),
NextState("SETUP"),
)
)
fsm.act("WAIT",
If(self.bits.done,
NextState("IDLE"),
).Else(
NextState("SETUP"),
)
)
write0 = Signal()
self.sync += [
If(self.cg.edge & self.reg.shift,
write0.eq(self.bits.write),
)
]
self.comb += [
self.cg.ce.eq(self.start | self.cs | ~self.cg.edge),
If(self.bits.write | ~self.bits.read,
self.cg.load.eq(self.div_write),
).Else(
self.cg.load.eq(self.div_read),
),
self.cg.bias.eq(self.clk_phase),
fsm.ce.eq(self.cg.edge),
self.cs.eq(~fsm.ongoing("IDLE")),
self.reg.ce.eq(self.cg.edge),
self.bits.ce.eq(self.cg.edge & self.reg.sample),
self.done.eq(self.cg.edge & self.bits.done & fsm.ongoing("HOLD")),
self.oe.eq(write0 | self.bits.write),
]
class SPIMaster(Module):
"""SPI Master.
Notes:
* M = 32 is the data width (width of the data register,
maximum write bits, maximum read bits)
* Every transfer consists of a write_length 0-M bit write followed
by a read_length 0-M bit read.
* cs_n is asserted at the beginning and deasserted at the end of the
transfer if there is no other transfer pending.
* cs_n handling is agnostic to whether it is one-hot or decoded
somewhere downstream. If it is decoded, "cs_n all deasserted"
should be handled accordingly (no slave selected).
If it is one-hot, asserting multiple slaves should only be attempted
if miso is either not connected between slaves, or open collector,
or correctly multiplexed externally.
* If config.cs_polarity == 0 (cs active low, the default),
"cs_n all deasserted" means "all cs_n bits high".
* cs is not mandatory in pads. Framing and chip selection can also
be handled independently through other means.
* If there is a miso wire in pads, the input and output can be done
with two signals (a.k.a. 4-wire SPI), else mosi must be used for
both output and input (a.k.a. 3-wire SPI) and config.half_duplex
must to be set when reading data is desired.
* For 4-wire SPI only the sum of read_length and write_length matters.
The behavior is the same no matter how the total transfer length is
divided between the two. For 3-wire SPI, the direction of mosi/miso
is switched from output to input after write_len cycles, at the
"shift_out" clk edge corresponding to bit write_length + 1 of the
transfer.
* The first bit output on mosi is always the MSB/LSB (depending on
config.lsb_first) of the data register, independent of
xfer.write_len. The last bit input from miso always ends up in
the LSB/MSB (respectively) of the data register, independent of
read_len.
* Data output on mosi in 4-wire SPI during the read cycles is what
is found in the data register at the time.
Data in the data register outside the least/most (depending
on config.lsb_first) significant read_length bits is what is
seen on miso during the write cycles.
* The SPI data register is double-buffered: Once a transfer has
started, new write data can be written, queuing a new transfer.
Transfers submitted this way are chained and executed without
deasserting cs. Once a transfer completes, the previous transfer's
read data is available in the data register.
* Writes to the config register take effect immediately. Writes to xfer
and data are synchronized to the start of a transfer.
* A wishbone data register write is ack-ed when the transfer has
been written to the intermediate buffer. It will be started when
there are no other transactions being executed, either starting
a new SPI transfer of chained to an in-flight transfer.
Writes take two cycles unless the write is to the data register
and another chained transfer is pending and the transfer being
executed is not complete. Reads always finish in two cycles.
Transaction Sequence:
* If desired, write the config register to set up the core.
* If desired, write the xfer register to change lengths and cs_n.
* Write the data register (also for zero-length writes),
writing triggers the transfer and when the transfer is accepted to
the inermediate buffer, the write is ack-ed.
* If desired, read the data register corresponding to the last
completed transfer.
* If desired, change xfer register for the next transfer.
* If desired, write data queuing the next (possibly chained) transfer.
Register address and bit map:
config (address 2):
1 offline: all pins high-z (reset=1)
1 active: cs/transfer active (read-only)
1 pending: transfer pending in intermediate buffer (read-only)
1 cs_polarity: active level of chip select (reset=0)
1 clk_polarity: idle level of clk (reset=0)
1 clk_phase: first edge after cs assertion to sample data on (reset=0)
(clk_polarity, clk_phase) == (CPOL, CPHA) in Freescale language.
(0, 0): idle low, output on falling, input on rising
(0, 1): idle low, output on rising, input on falling
(1, 0): idle high, output on rising, input on falling
(1, 1): idle high, output on falling, input on rising
There is never a clk edge during a cs edge.
1 lsb_first: LSB is the first bit on the wire (reset=0)
1 half_duplex: 3-wire SPI, in/out on mosi (reset=0)
8 undefined
8 div_write: counter load value to divide this module's clock
to generate the SPI write clk (reset=0)
f_clk/f_spi_write == div_write + 2
8 div_read: ditto for the read clock
xfer (address 1):
16 cs: active high bit mask of chip selects to assert (reset=0)
6 write_len: 0-M bits (reset=0)
2 undefined
6 read_len: 0-M bits (reset=0)
2 undefined
data (address 0):
M write/read data (reset=0)
"""
def __init__(self, pads, bus=None):
if bus is None:
bus = wishbone.Interface(data_width=32)
self.bus = bus
###
# Wishbone
config = Record([
("offline", 1),
("active", 1),
("pending", 1),
("cs_polarity", 1),
("clk_polarity", 1),
("clk_phase", 1),
("lsb_first", 1),
("half_duplex", 1),
("padding", 8),
("div_write", 8),
("div_read", 8),
])
config.offline.reset = 1
assert len(config) <= len(bus.dat_w)
xfer = Record([
("cs", 16),
("write_length", 6),
("padding0", 2),
("read_length", 6),
("padding1", 2),
])
assert len(xfer) <= len(bus.dat_w)
self.submodules.spi = spi = SPIMachine(
data_width=len(bus.dat_w),
clock_width=len(config.div_read),
bits_width=len(xfer.read_length))
pending = Signal()
cs = Signal.like(xfer.cs)
data_read = Signal.like(spi.reg.data)
data_write = Signal.like(spi.reg.data)
self.comb += [
bus.dat_r.eq(
Array([data_read, xfer.raw_bits(), config.raw_bits()
])[bus.adr]),
spi.start.eq(pending & (~spi.cs | spi.done)),
spi.clk_phase.eq(config.clk_phase),
spi.reg.lsb.eq(config.lsb_first),
spi.div_write.eq(config.div_write),
spi.div_read.eq(config.div_read),
]
self.sync += [
If(spi.done,
data_read.eq(spi.reg.data),
),
If(spi.start,
cs.eq(xfer.cs),
spi.bits.n_write.eq(xfer.write_length),
spi.bits.n_read.eq(xfer.read_length),
spi.reg.data.eq(data_write),
pending.eq(0),
),
# wb.ack a transaction if any of the following:
# a) reading,
# b) writing to non-data register
# c) writing to data register and no pending transfer
# d) writing to data register and pending and swapping buffers
bus.ack.eq(bus.cyc & bus.stb &
(~bus.we | (bus.adr != 0) | ~pending | spi.done)),
If(bus.ack,
bus.ack.eq(0),
If(bus.we,
Array([data_write, xfer.raw_bits(), config.raw_bits()
])[bus.adr].eq(bus.dat_w),
If(bus.adr == 0, # data register
pending.eq(1),
),
),
),
config.active.eq(spi.cs),
config.pending.eq(pending),
]
# I/O
if hasattr(pads, "cs_n"):
cs_n_t = TSTriple(len(pads.cs_n))
self.specials += cs_n_t.get_tristate(pads.cs_n)
self.comb += [
cs_n_t.oe.eq(~config.offline),
cs_n_t.o.eq((cs & Replicate(spi.cs, len(cs))) ^
Replicate(~config.cs_polarity, len(cs))),
]
clk_t = TSTriple()
self.specials += clk_t.get_tristate(pads.clk)
self.comb += [
clk_t.oe.eq(~config.offline),
clk_t.o.eq((spi.cg.clk & spi.cs) ^ config.clk_polarity),
]
mosi_t = TSTriple()
self.specials += mosi_t.get_tristate(pads.mosi)
self.comb += [
mosi_t.oe.eq(~config.offline & spi.cs &
(spi.oe | ~config.half_duplex)),
mosi_t.o.eq(spi.reg.o),
spi.reg.i.eq(Mux(config.half_duplex, mosi_t.i,
getattr(pads, "miso", mosi_t.i))),
]
SPI_DATA_ADDR, SPI_XFER_ADDR, SPI_CONFIG_ADDR = range(3)
(
SPI_OFFLINE,
SPI_ACTIVE,
SPI_PENDING,
SPI_CS_POLARITY,
SPI_CLK_POLARITY,
SPI_CLK_PHASE,
SPI_LSB_FIRST,
SPI_HALF_DUPLEX,
) = (1 << i for i in range(8))
def SPI_DIV_WRITE(i):
return i << 16
def SPI_DIV_READ(i):
return i << 24
def SPI_CS(i):
return i << 0
def SPI_WRITE_LENGTH(i):
return i << 16
def SPI_READ_LENGTH(i):
return i << 24
def _test_xfer(bus, cs, wlen, rlen, wdata):
yield from bus.write(SPI_XFER_ADDR, SPI_CS(cs) |
SPI_WRITE_LENGTH(wlen) | SPI_READ_LENGTH(rlen))
yield from bus.write(SPI_DATA_ADDR, wdata)
yield
def _test_read(bus, sync=SPI_ACTIVE | SPI_PENDING):
while (yield from bus.read(SPI_CONFIG_ADDR)) & sync:
pass
return (yield from bus.read(SPI_DATA_ADDR))
def _test_gen(bus):
yield from bus.write(SPI_CONFIG_ADDR,
0*SPI_CLK_PHASE | 0*SPI_LSB_FIRST |
1*SPI_HALF_DUPLEX |
SPI_DIV_WRITE(3) | SPI_DIV_READ(5))
yield from _test_xfer(bus, 0b01, 4, 0, 0x90000000)
print(hex((yield from _test_read(bus))))
yield from _test_xfer(bus, 0b10, 0, 4, 0x90000000)
print(hex((yield from _test_read(bus))))
yield from _test_xfer(bus, 0b11, 4, 4, 0x81000000)
print(hex((yield from _test_read(bus))))
yield from _test_xfer(bus, 0b01, 8, 32, 0x87654321)
yield from _test_xfer(bus, 0b01, 0, 32, 0x12345678)
print(hex((yield from _test_read(bus, SPI_PENDING))))
print(hex((yield from _test_read(bus, SPI_ACTIVE))))
return
for cpol, cpha, lsb, clk in product(
(0, 1), (0, 1), (0, 1), (0, 1)):
yield from bus.write(SPI_CONFIG_ADDR,
cpol*SPI_CLK_POLARITY | cpha*SPI_CLK_PHASE |
lsb*SPI_LSB_FIRST | SPI_DIV_WRITE(clk) |
SPI_DIV_READ(clk))
for wlen, rlen, wdata in product((0, 8, 32), (0, 8, 32),
(0, 0xffffffff, 0xdeadbeef)):
rdata = (yield from _test_xfer(bus, 0b1, wlen, rlen, wdata, True))
len = (wlen + rlen) % 32
mask = (1 << len) - 1
if lsb:
shift = (wlen + rlen) % 32
else:
shift = 0
a = (wdata >> wshift) & wmask
b = (rdata >> rshift) & rmask
if a != b:
print("ERROR", end=" ")
print(cpol, cpha, lsb, clk, wlen, rlen,
hex(wdata), hex(rdata), hex(a), hex(b))
class _TestPads:
def __init__(self):
self.cs_n = Signal(2)
self.clk = Signal()
self.mosi = Signal()
self.miso = Signal()
class _TestTristate(Module):
def __init__(self, t):
oe = Signal()
self.comb += [
t.target.eq(t.o),
oe.eq(t.oe),
t.i.eq(t.o),
]
if __name__ == "__main__":
from migen.fhdl.specials import Tristate
pads = _TestPads()
dut = SPIMaster(pads)
dut.comb += pads.miso.eq(pads.mosi)
# from migen.fhdl.verilog import convert
# print(convert(dut))
Tristate.lower = _TestTristate
run_simulation(dut, _test_gen(dut.bus), vcd_name="spi_master.vcd")

View File

@ -19,7 +19,7 @@ from misoc.targets.kc705 import MiniSoC, soc_kc705_args, soc_kc705_argdict
from artiq.gateware.soc import AMPSoC
from artiq.gateware import rtio, nist_qc1, nist_clock, nist_qc2
from artiq.gateware.rtio.phy import ttl_simple, ttl_serdes_7series, dds
from artiq.gateware.rtio.phy import ttl_simple, ttl_serdes_7series, dds, spi
from artiq import __artiq_dir__ as artiq_dir
from artiq import __version__ as artiq_version
@ -80,6 +80,18 @@ class _RTIOCRG(Module, AutoCSR):
]
_ams101_dac = [
("ams101_dac", 0,
Subsignal("ldac", Pins("XADC:GPIO0")),
Subsignal("clk", Pins("XADC:GPIO1")),
Subsignal("mosi", Pins("XADC:GPIO2")),
Subsignal("cs_n", Pins("XADC:GPIO3")),
IOStandard("LVTTL")
)
]
class _NIST_Ions(MiniSoC, AMPSoC):
csr_map = {
"rtio": None, # mapped on Wishbone instead
@ -115,6 +127,8 @@ class _NIST_Ions(MiniSoC, AMPSoC):
self.platform.request("user_led", 0),
self.platform.request("user_led", 1)))
self.platform.add_extension(_ams101_dac)
def add_rtio(self, rtio_channels):
self.submodules.rtio_crg = _RTIOCRG(self.platform, self.crg.cd_sys.clk)
self.submodules.rtio = rtio.RTIO(rtio_channels)
@ -235,12 +249,29 @@ class NIST_CLOCK(_NIST_Ions):
phy = ttl_simple.Output(platform.request("user_led", 2))
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(phy))
ams101_dac = self.platform.request("ams101_dac", 0)
phy = ttl_simple.Output(ams101_dac.ldac)
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(phy))
self.config["RTIO_REGULAR_TTL_COUNT"] = len(rtio_channels)
phy = ttl_simple.ClockGen(platform.request("la32_p"))
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(phy))
phy = spi.SPIMaster(ams101_dac)
self.submodules += phy
self.config["RTIO_FIRST_SPI_CHANNEL"] = len(rtio_channels)
rtio_channels.append(rtio.Channel.from_phy(
phy, ofifo_depth=4, ififo_depth=4))
for i in range(1): # spi1 and spi2 collide in pinout with ttl
phy = spi.SPIMaster(self.platform.request("spi", i))
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(
phy, ofifo_depth=128, ififo_depth=128))
self.config["RTIO_DDS_CHANNEL"] = len(rtio_channels)
self.config["DDS_CHANNEL_COUNT"] = 11
self.config["DDS_AD9914"] = True

View File

@ -19,7 +19,7 @@ from misoc.targets.pipistrello import *
from artiq.gateware.soc import AMPSoC
from artiq.gateware import rtio, nist_qc1
from artiq.gateware.rtio.phy import ttl_simple, ttl_serdes_spartan6, dds
from artiq.gateware.rtio.phy import ttl_simple, ttl_serdes_spartan6, dds, spi
from artiq import __artiq_dir__ as artiq_dir
from artiq import __version__ as artiq_version
@ -152,12 +152,12 @@ trce -v 12 -fastpaths -tsi {build_name}.tsi -o {build_name}.twr {build_name}.ncd
rtio_channels.append(rtio.Channel.from_phy(phy, ififo_depth=512,
ofifo_depth=4))
# ttl2 can run on a 8x serdes if xtrig is not used
# the last TTL is used for ClockGen
for i in range(15):
if i in (0, 1):
phy = ttl_serdes_spartan6.Output_4X(platform.request("ttl", i),
self.rtio_crg.rtiox4_stb)
elif i in (2,):
elif i in (2,): # ttl2 can run on a 8x serdes if xtrig is not used
phy = ttl_serdes_spartan6.Output_8X(platform.request("ttl", i),
self.rtio_crg.rtiox8_stb)
else:
@ -192,6 +192,18 @@ trce -v 12 -fastpaths -tsi {build_name}.tsi -o {build_name}.twr {build_name}.ncd
ofifo_depth=512,
ififo_depth=4))
pmod = self.platform.request("pmod", 0)
spi_pins = Module()
spi_pins.clk = pmod.d[0]
spi_pins.mosi = pmod.d[1]
spi_pins.miso = pmod.d[2]
spi_pins.cs_n = pmod.d[3:]
phy = spi.SPIMaster(spi_pins)
self.submodules += phy
self.config["RTIO_FIRST_SPI_CHANNEL"] = len(rtio_channels)
rtio_channels.append(rtio.Channel.from_phy(
phy, ofifo_depth=4, ififo_depth=4))
self.config["RTIO_LOG_CHANNEL"] = len(rtio_channels)
rtio_channels.append(rtio.LogChannel())

View File

@ -7,7 +7,7 @@ OBJECTS := isr.o clock.o rtiocrg.o flash_storage.o mailbox.o \
session.o log.o analyzer.o moninj.o net_server.o bridge_ctl.o \
ksupport_data.o kloader.o test_mode.o main.o
OBJECTS_KSUPPORT := ksupport.o artiq_personality.o mailbox.o \
bridge.o rtio.o ttl.o dds.o
bridge.o rtio.o dds.o
CFLAGS += -I$(LIBALLOC_DIRECTORY) \
-I$(MISOC_DIRECTORY)/software/include/dyld \

View File

@ -7,15 +7,20 @@
#define TIME_BUFFER (8000 << CONFIG_RTIO_FINE_TS_WIDTH)
static void dds_write(int addr, int data)
static void rtio_output_blind(int channel, int addr, int data)
{
rtio_chan_sel_write(CONFIG_RTIO_DDS_CHANNEL);
rtio_chan_sel_write(channel);
rtio_o_address_write(addr);
rtio_o_data_write(data);
rtio_o_timestamp_write(rtio_get_counter() + TIME_BUFFER);
rtio_o_we_write(1);
}
static void dds_write(int addr, int data)
{
rtio_output_blind(CONFIG_RTIO_DDS_CHANNEL, addr, data);
}
static int dds_read(int addr)
{
int r;
@ -54,7 +59,7 @@ void bridge_main(void)
struct msg_brg_ttl_out *msg;
msg = (struct msg_brg_ttl_out *)umsg;
ttl_set_oe(rtio_get_counter() + TIME_BUFFER, msg->channel, msg->value);
rtio_output_blind(msg->channel, TTL_OE_ADDR, msg->value);
mailbox_acknowledge();
break;
}
@ -62,7 +67,7 @@ void bridge_main(void)
struct msg_brg_ttl_out *msg;
msg = (struct msg_brg_ttl_out *)umsg;
ttl_set_o(rtio_get_counter() + TIME_BUFFER, msg->channel, msg->value);
rtio_output_blind(msg->channel, TTL_O_ADDR, msg->value);
mailbox_acknowledge();
break;
}

View File

@ -26,10 +26,7 @@
#endif
#define DDS_WRITE(addr, data) do { \
rtio_o_address_write(addr); \
rtio_o_data_write(data); \
rtio_o_timestamp_write(now); \
rtio_write_and_process_status(now, CONFIG_RTIO_DDS_CHANNEL); \
rtio_output(now, CONFIG_RTIO_DDS_CHANNEL, addr, data); \
now += DURATION_WRITE; \
} while(0)
@ -37,8 +34,6 @@ void dds_init(long long int timestamp, int channel)
{
long long int now;
rtio_chan_sel_write(CONFIG_RTIO_DDS_CHANNEL);
now = timestamp - DURATION_INIT;
#ifdef CONFIG_DDS_ONEHOT_SEL
@ -190,7 +185,6 @@ void dds_batch_exit(void)
if(!batch_mode)
artiq_raise_from_c("DDSBatchError", "DDS batch error", 0, 0, 0);
rtio_chan_sel_write(CONFIG_RTIO_DDS_CHANNEL);
/* + FUD time */
now = batch_ref_time - batch_count*(DURATION_PROGRAM + DURATION_WRITE);
for(i=0;i<batch_count;i++) {
@ -216,7 +210,6 @@ void dds_set(long long int timestamp, int channel,
batch[batch_count].amplitude = amplitude;
batch_count++;
} else {
rtio_chan_sel_write(CONFIG_RTIO_DDS_CHANNEL);
dds_set_one(timestamp - DURATION_PROGRAM, timestamp, channel, ftw, pow, phase_mode,
amplitude);
}

View File

@ -13,7 +13,6 @@
#include "messages.h"
#include "bridge.h"
#include "artiq_personality.h"
#include "ttl.h"
#include "dds.h"
#include "rtio.h"
@ -109,12 +108,9 @@ static const struct symbol runtime_exports[] = {
/* direct syscalls */
{"rtio_get_counter", &rtio_get_counter},
{"rtio_log", &rtio_log},
{"ttl_set_o", &ttl_set_o},
{"ttl_set_oe", &ttl_set_oe},
{"ttl_set_sensitivity", &ttl_set_sensitivity},
{"ttl_get", &ttl_get},
{"ttl_clock_set", &ttl_clock_set},
{"rtio_output", &rtio_output},
{"rtio_input_timestamp", &rtio_input_timestamp},
{"rtio_input_data", &rtio_input_data},
{"dds_init", &dds_init},
{"dds_batch_enter", &dds_batch_enter},

View File

@ -15,7 +15,8 @@ long long int rtio_get_counter(void)
return rtio_counter_read();
}
void rtio_process_exceptional_status(int status, long long int timestamp, int channel)
static void rtio_process_exceptional_status(
long long int timestamp, int channel, int status)
{
if(status & RTIO_O_STATUS_FULL)
while(rtio_o_status_read() & RTIO_O_STATUS_FULL);
@ -39,6 +40,79 @@ void rtio_process_exceptional_status(int status, long long int timestamp, int ch
}
}
void rtio_output(long long int timestamp, int channel, unsigned int addr,
unsigned int data)
{
int status;
rtio_chan_sel_write(channel);
rtio_o_timestamp_write(timestamp);
rtio_o_address_write(addr);
rtio_o_data_write(data);
rtio_o_we_write(1);
status = rtio_o_status_read();
if(status)
rtio_process_exceptional_status(timestamp, channel, status);
}
long long int rtio_input_timestamp(long long int timeout, int channel)
{
long long int r;
int status;
rtio_chan_sel_write(channel);
while((status = rtio_i_status_read())) {
if(status & RTIO_I_STATUS_OVERFLOW) {
rtio_i_overflow_reset_write(1);
break;
}
if(rtio_get_counter() >= timeout) {
/* check empty flag again to prevent race condition.
* now we are sure that the time limit has been exceeded.
*/
status = rtio_i_status_read();
if(status & RTIO_I_STATUS_EMPTY)
break;
}
/* input FIFO is empty - keep waiting */
}
if (status & RTIO_I_STATUS_OVERFLOW)
artiq_raise_from_c("RTIOOverflow",
"RTIO input overflow on channel {0}",
channel, 0, 0);
if (status & RTIO_I_STATUS_EMPTY)
return -1;
r = rtio_i_timestamp_read();
rtio_i_re_write(1);
return r;
}
unsigned int rtio_input_data(int channel)
{
unsigned int data;
int status;
rtio_chan_sel_write(channel);
while((status = rtio_i_status_read())) {
if(status & RTIO_I_STATUS_OVERFLOW) {
rtio_i_overflow_reset_write(1);
artiq_raise_from_c("RTIOOverflow",
"RTIO input overflow on channel {0}",
channel, 0, 0);
}
}
data = rtio_i_data_read();
rtio_i_re_write(1);
return data;
}
void rtio_log_va(long long int timestamp, const char *fmt, va_list args)
{
// This executes on the kernel CPU's stack, which is specifically designed

View File

@ -14,18 +14,21 @@
void rtio_init(void);
long long int rtio_get_counter(void);
void rtio_process_exceptional_status(int status, long long int timestamp, int channel);
void rtio_log(long long int timestamp, const char *format, ...);
void rtio_log_va(long long int timestamp, const char *format, va_list args);
void rtio_output(long long int timestamp, int channel, unsigned int address,
unsigned int data);
static inline void rtio_write_and_process_status(long long int timestamp, int channel)
{
int status;
/*
* Waits at least until timeout and returns the timestamp of the first
* input event on the chanel, -1 if there was no event.
*/
long long int rtio_input_timestamp(long long int timeout, int channel);
rtio_o_we_write(1);
status = rtio_o_status_read();
if(status)
rtio_process_exceptional_status(status, timestamp, channel);
}
/*
* Assumes that there is or will be an event in the channel and returns only
* its data.
*/
unsigned int rtio_input_data(int channel);
#endif /* __RTIO_H */

View File

@ -1,67 +0,0 @@
#include <generated/csr.h>
#include "artiq_personality.h"
#include "rtio.h"
#include "ttl.h"
void ttl_set_o(long long int timestamp, int channel, int value)
{
rtio_chan_sel_write(channel);
rtio_o_timestamp_write(timestamp);
rtio_o_address_write(0);
rtio_o_data_write(value);
rtio_write_and_process_status(timestamp, channel);
}
void ttl_set_oe(long long int timestamp, int channel, int oe)
{
rtio_chan_sel_write(channel);
rtio_o_timestamp_write(timestamp);
rtio_o_address_write(1);
rtio_o_data_write(oe);
rtio_write_and_process_status(timestamp, channel);
}
void ttl_set_sensitivity(long long int timestamp, int channel, int sensitivity)
{
rtio_chan_sel_write(channel);
rtio_o_timestamp_write(timestamp);
rtio_o_address_write(2);
rtio_o_data_write(sensitivity);
rtio_write_and_process_status(timestamp, channel);
}
long long int ttl_get(int channel, long long int time_limit)
{
long long int r;
int status;
rtio_chan_sel_write(channel);
while((status = rtio_i_status_read())) {
if(rtio_i_status_read() & RTIO_I_STATUS_OVERFLOW) {
rtio_i_overflow_reset_write(1);
artiq_raise_from_c("RTIOOverflow",
"RTIO overflow at channel {0}",
channel, 0, 0);
}
if(rtio_get_counter() >= time_limit) {
/* check empty flag again to prevent race condition.
* now we are sure that the time limit has been exceeded.
*/
if(rtio_i_status_read() & RTIO_I_STATUS_EMPTY)
return -1;
}
/* input FIFO is empty - keep waiting */
}
r = rtio_i_timestamp_read();
rtio_i_re_write(1);
return r;
}
void ttl_clock_set(long long int timestamp, int channel, int ftw)
{
rtio_chan_sel_write(channel);
rtio_o_timestamp_write(timestamp);
rtio_o_data_write(ftw);
rtio_write_and_process_status(timestamp, channel);
}

View File

@ -1,10 +1,8 @@
#ifndef __TTL_H
#define __TTL_H
void ttl_set_o(long long int timestamp, int channel, int value);
void ttl_set_oe(long long int timestamp, int channel, int oe);
void ttl_set_sensitivity(long long int timestamp, int channel, int sensitivity);
long long int ttl_get(int channel, long long int time_limit);
void ttl_clock_set(long long int timestamp, int channel, int ftw);
#define TTL_O_ADDR 0
#define TTL_OE_ADDR 1
#define TTL_SENSITIVITY_ADDR 2
#endif /* __TTL_H */

View File

@ -64,7 +64,9 @@ With the CLOCK hardware, the TTL lines are mapped as follows:
+--------------------+-----------------------+--------------+
| 19 | LED | Output |
+--------------------+-----------------------+--------------+
| 20 | LA32_P | Clock |
| 20 | AMS101_LDAC_B | Output |
+--------------------+-----------------------+--------------+
| 21 | LA32_P | Clock |
+--------------------+-----------------------+--------------+
@ -101,6 +103,4 @@ When plugged to an adapter, the NIST QC1 hardware can be used. The TTL lines are
The input only limitation on channels 0 and 1 comes from the QC-DAQ adapter. When the adapter is not used (and physically unplugged from the Pipistrello board), the corresponding pins on the Pipistrello can be used as outputs. Do not configure these channels as outputs when the adapter is plugged, as this would cause electrical contention.
The board can accept an external RTIO clock connected to PMT2. If the DDS box
does not drive the PMT2 pair, use XTRIG and patch the XTRIG transceiver output
on the adapter board onto C:15 disconnecting PMT2.
The board can accept an external RTIO clock connected to PMT2. If the DDS box does not drive the PMT2 pair, use XTRIG and patch the XTRIG transceiver output on the adapter board onto C:15 disconnecting PMT2.

View File

@ -24,6 +24,13 @@ These drivers are for the core device and the peripherals closely integrated int
.. automodule:: artiq.coredevice.dds
:members:
:mod:`artiq.coredevice.spi` module
----------------------------------
.. automodule:: artiq.coredevice.spi
:members:
:mod:`artiq.coredevice.exceptions` module
-----------------------------------------

View File

@ -74,14 +74,6 @@
"class": "TTLInOut",
"arguments": {"channel": 18}
},
"ttl_clock_la32_p": {
"type": "local",
"module": "artiq.coredevice.ttl",
"class": "TTLClockGen",
"arguments": {"channel": 20}
},
"led": {
"type": "local",
"module": "artiq.coredevice.ttl",
@ -89,6 +81,33 @@
"arguments": {"channel": 19}
},
"ams101_ldac": {
"type": "local",
"module": "artiq.coredevice.ttl",
"class": "TTLOut",
"arguments": {"channel": 20}
},
"ttl_clock_la32_p": {
"type": "local",
"module": "artiq.coredevice.ttl",
"class": "TTLClockGen",
"arguments": {"channel": 21}
},
"ams101_spi": {
"type": "local",
"module": "artiq.coredevice.spi",
"class": "SPIMaster",
"arguments": {"channel": 22}
},
"spi0": {
"type": "local",
"module": "artiq.coredevice.spi",
"class": "SPIMaster",
"arguments": {"channel": 23}
},
"dds_bus": {
"type": "local",
"module": "artiq.coredevice.dds",

View File

@ -39,6 +39,7 @@ class TDR(EnvExperiment):
n = 1000 # repetitions
latency = 50e-9 # calibrated latency without a transmission line
pulse = 1e-6 # pulse length, larger than rtt
self.t = [0 for i in range(2)]
try:
self.many(n, seconds_to_mu(pulse, self.core))
except PulseNotReceivedError:
@ -53,21 +54,19 @@ class TDR(EnvExperiment):
@kernel
def many(self, n, p):
t = [0 for i in range(2)]
self.core.break_realtime()
for i in range(n):
self.one(t, p)
self.t = t
self.one(p)
@kernel
def one(self, t, p):
def one(self, p):
t0 = now_mu()
with parallel:
self.pmt0.gate_both_mu(2*p)
self.ttl2.pulse_mu(p)
for i in range(len(t)):
for i in range(len(self.t)):
ti = self.pmt0.timestamp_mu()
if ti <= 0:
raise PulseNotReceivedError
t[i] += ti - t0
raise PulseNotReceivedError()
self.t[i] = int(self.t[i] + ti - t0)
self.pmt0.count() # flush