Revert "drtio: remove KC705/GTX support"

This reverts commit ebdbaaad32.
pull/1699/head
Harry Ho 2020-12-31 13:29:50 +08:00
parent ebdbaaad32
commit dc7addf394
4 changed files with 721 additions and 0 deletions

View File

@ -0,0 +1,265 @@
from migen import *
from migen.genlib.resetsync import AsyncResetSynchronizer
from misoc.cores.code_8b10b import Encoder, Decoder
from misoc.interconnect.csr import *
from artiq.gateware.drtio.core import TransceiverInterface, ChannelInterface
from artiq.gateware.drtio.transceiver.gtx_7series_init import *
class GTX_20X(Module, TransceiverInterface):
# Only one channel is supported.
#
# The transceiver clock on clock_pads must be at the RTIO clock
# frequency when clock_div2=False, and 2x that frequency when
# clock_div2=True.
def __init__(self, clock_pads, tx_pads, rx_pads, sys_clk_freq,
clock_div2=False):
encoder = ClockDomainsRenamer("rtio")(
Encoder(2, True))
self.submodules += encoder
decoders = [ClockDomainsRenamer("rtio_rx0")(
(Decoder(True))) for _ in range(2)]
self.submodules += decoders
TransceiverInterface.__init__(self, [ChannelInterface(encoder, decoders)])
# transceiver direct clock outputs
# useful to specify clock constraints in a way palatable to Vivado
self.txoutclk = Signal()
self.rxoutclk = Signal()
# # #
refclk = Signal()
if clock_div2:
self.specials += Instance("IBUFDS_GTE2",
i_CEB=0,
i_I=clock_pads.p,
i_IB=clock_pads.n,
o_ODIV2=refclk
)
else:
self.specials += Instance("IBUFDS_GTE2",
i_CEB=0,
i_I=clock_pads.p,
i_IB=clock_pads.n,
o_O=refclk
)
cplllock = Signal()
# TX generates RTIO clock, init must be in system domain
tx_init = GTXInit(sys_clk_freq, False)
# RX receives restart commands from RTIO domain
rx_init = ClockDomainsRenamer("rtio")(
GTXInit(self.rtio_clk_freq, True))
self.submodules += tx_init, rx_init
self.comb += tx_init.cplllock.eq(cplllock), \
rx_init.cplllock.eq(cplllock)
txdata = Signal(20)
rxdata = Signal(20)
self.specials += \
Instance("GTXE2_CHANNEL",
# PMA Attributes
p_PMA_RSV=0x00018480,
p_PMA_RSV2=0x2050,
p_PMA_RSV3=0,
p_PMA_RSV4=0,
p_RX_BIAS_CFG=0b100,
p_RX_CM_TRIM=0b010,
p_RX_OS_CFG=0b10000000,
p_RX_CLK25_DIV=5,
p_TX_CLK25_DIV=5,
# Power-Down Attributes
p_PD_TRANS_TIME_FROM_P2=0x3c,
p_PD_TRANS_TIME_NONE_P2=0x3c,
p_PD_TRANS_TIME_TO_P2=0x64,
# CPLL
p_CPLL_CFG=0xBC07DC,
p_CPLL_FBDIV=4,
p_CPLL_FBDIV_45=5,
p_CPLL_REFCLK_DIV=1,
p_RXOUT_DIV=2,
p_TXOUT_DIV=2,
o_CPLLLOCK=cplllock,
i_CPLLLOCKEN=1,
i_CPLLREFCLKSEL=0b001,
i_TSTIN=2**20-1,
i_GTREFCLK0=refclk,
# TX clock
p_TXBUF_EN="FALSE",
p_TX_XCLK_SEL="TXUSR",
o_TXOUTCLK=self.txoutclk,
i_TXSYSCLKSEL=0b00,
i_TXOUTCLKSEL=0b11,
# TX Startup/Reset
i_GTTXRESET=tx_init.gtXxreset,
o_TXRESETDONE=tx_init.Xxresetdone,
i_TXDLYSRESET=tx_init.Xxdlysreset,
o_TXDLYSRESETDONE=tx_init.Xxdlysresetdone,
o_TXPHALIGNDONE=tx_init.Xxphaligndone,
i_TXUSERRDY=tx_init.Xxuserrdy,
# TX data
p_TX_DATA_WIDTH=20,
p_TX_INT_DATAWIDTH=0,
i_TXCHARDISPMODE=Cat(txdata[9], txdata[19]),
i_TXCHARDISPVAL=Cat(txdata[8], txdata[18]),
i_TXDATA=Cat(txdata[:8], txdata[10:18]),
i_TXUSRCLK=ClockSignal("rtio"),
i_TXUSRCLK2=ClockSignal("rtio"),
# TX electrical
i_TXBUFDIFFCTRL=0b100,
i_TXDIFFCTRL=0b1000,
# RX Startup/Reset
i_GTRXRESET=rx_init.gtXxreset,
o_RXRESETDONE=rx_init.Xxresetdone,
i_RXDLYSRESET=rx_init.Xxdlysreset,
o_RXDLYSRESETDONE=rx_init.Xxdlysresetdone,
o_RXPHALIGNDONE=rx_init.Xxphaligndone,
i_RXUSERRDY=rx_init.Xxuserrdy,
# RX AFE
p_RX_DFE_XYD_CFG=0,
i_RXDFEXYDEN=1,
i_RXDFEXYDHOLD=0,
i_RXDFEXYDOVRDEN=0,
i_RXLPMEN=0,
# RX clock
p_RXBUF_EN="FALSE",
p_RX_XCLK_SEL="RXUSR",
i_RXDDIEN=1,
i_RXSYSCLKSEL=0b00,
i_RXOUTCLKSEL=0b010,
o_RXOUTCLK=self.rxoutclk,
i_RXUSRCLK=ClockSignal("rtio_rx0"),
i_RXUSRCLK2=ClockSignal("rtio_rx0"),
p_RXCDR_CFG=0x03000023FF10100020,
# RX Clock Correction Attributes
p_CLK_CORRECT_USE="FALSE",
p_CLK_COR_SEQ_1_1=0b0100000000,
p_CLK_COR_SEQ_2_1=0b0100000000,
p_CLK_COR_SEQ_1_ENABLE=0b1111,
p_CLK_COR_SEQ_2_ENABLE=0b1111,
# RX data
p_RX_DATA_WIDTH=20,
p_RX_INT_DATAWIDTH=0,
o_RXDISPERR=Cat(rxdata[9], rxdata[19]),
o_RXCHARISK=Cat(rxdata[8], rxdata[18]),
o_RXDATA=Cat(rxdata[:8], rxdata[10:18]),
# Pads
i_GTXRXP=rx_pads.p,
i_GTXRXN=rx_pads.n,
o_GTXTXP=tx_pads.p,
o_GTXTXN=tx_pads.n,
)
tx_reset_deglitched = Signal()
tx_reset_deglitched.attr.add("no_retiming")
self.sync += tx_reset_deglitched.eq(~tx_init.done)
self.specials += [
Instance("BUFG", i_I=self.txoutclk, o_O=self.cd_rtio.clk),
AsyncResetSynchronizer(self.cd_rtio, tx_reset_deglitched)
]
rx_reset_deglitched = Signal()
rx_reset_deglitched.attr.add("no_retiming")
self.sync.rtio += rx_reset_deglitched.eq(~rx_init.done)
self.specials += [
Instance("BUFG", i_I=self.rxoutclk, o_O=self.cd_rtio_rx0.clk),
AsyncResetSynchronizer(self.cd_rtio_rx0, rx_reset_deglitched)
]
chan = self.channels[0]
self.comb += [
txdata.eq(Cat(chan.encoder.output[0], chan.encoder.output[1])),
chan.decoders[0].input.eq(rxdata[:10]),
chan.decoders[1].input.eq(rxdata[10:])
]
clock_aligner = ClockDomainsRenamer({"rtio_rx": "rtio_rx0"})(
BruteforceClockAligner(0b0101111100, self.rtio_clk_freq))
self.submodules += clock_aligner
self.comb += [
clock_aligner.rxdata.eq(rxdata),
rx_init.restart.eq(clock_aligner.restart),
chan.rx_ready.eq(clock_aligner.ready)
]
class GTX_1000BASE_BX10(GTX_20X):
rtio_clk_freq = 62.5e6
class RXSynchronizer(Module, AutoCSR):
"""Delays the data received in the rtio_rx domain by a configurable amount
so that it meets s/h in the rtio domain, and recapture it in the rtio
domain. This has fixed latency.
Since Xilinx doesn't provide decent on-chip delay lines, we implement the
delay with MMCM that provides a clock and a finely configurable phase, used
to resample the data.
The phase has to be determined either empirically or by making sense of the
Xilinx scriptures (when existent) and should be constant for a given design
placement.
"""
def __init__(self, rtio_clk_freq, initial_phase=0.0):
self.phase_shift = CSR()
self.phase_shift_done = CSRStatus()
self.clock_domains.cd_rtio_delayed = ClockDomain()
mmcm_output = Signal()
mmcm_fb = Signal()
mmcm_locked = Signal()
# maximize VCO frequency to maximize phase shift resolution
mmcm_mult = 1200e6//rtio_clk_freq
self.specials += [
Instance("MMCME2_ADV",
p_CLKIN1_PERIOD=1e9/rtio_clk_freq,
i_CLKIN1=ClockSignal("rtio_rx"),
i_RST=ResetSignal("rtio_rx"),
i_CLKINSEL=1, # yes, 1=CLKIN1 0=CLKIN2
p_CLKFBOUT_MULT_F=mmcm_mult,
p_CLKOUT0_DIVIDE_F=mmcm_mult,
p_CLKOUT0_PHASE=initial_phase,
p_DIVCLK_DIVIDE=1,
# According to Xilinx, there is no guarantee of input/output
# phase relationship when using internal feedback. We assume
# here that the input/ouput skew is constant to save BUFGs.
o_CLKFBOUT=mmcm_fb,
i_CLKFBIN=mmcm_fb,
p_CLKOUT0_USE_FINE_PS="TRUE",
o_CLKOUT0=mmcm_output,
o_LOCKED=mmcm_locked,
i_PSCLK=ClockSignal(),
i_PSEN=self.phase_shift.re,
i_PSINCDEC=self.phase_shift.r,
o_PSDONE=self.phase_shift_done.status,
),
Instance("BUFR", i_I=mmcm_output, o_O=self.cd_rtio_delayed.clk),
AsyncResetSynchronizer(self.cd_rtio_delayed, ~mmcm_locked)
]
def resync(self, signal):
delayed = Signal.like(signal, related=signal)
synchronized = Signal.like(signal, related=signal)
self.sync.rtio_delayed += delayed.eq(signal)
self.sync.rtio += synchronized.eq(delayed)
return synchronized

View File

@ -0,0 +1,226 @@
from math import ceil
from functools import reduce
from operator import add
from migen import *
from migen.genlib.cdc import MultiReg, PulseSynchronizer
from migen.genlib.misc import WaitTimer
from migen.genlib.fsm import FSM
class GTXInit(Module):
# Based on LiteSATA by Enjoy-Digital
def __init__(self, sys_clk_freq, rx):
self.done = Signal()
self.restart = Signal()
# GTX signals
self.cplllock = Signal()
self.gtXxreset = Signal()
self.Xxresetdone = Signal()
self.Xxdlysreset = Signal()
self.Xxdlysresetdone = Signal()
self.Xxphaligndone = Signal()
self.Xxuserrdy = Signal()
# # #
# Double-latch transceiver asynch outputs
cplllock = Signal()
Xxresetdone = Signal()
Xxdlysresetdone = Signal()
Xxphaligndone = Signal()
self.specials += [
MultiReg(self.cplllock, cplllock),
MultiReg(self.Xxresetdone, Xxresetdone),
MultiReg(self.Xxdlysresetdone, Xxdlysresetdone),
MultiReg(self.Xxphaligndone, Xxphaligndone),
]
# Deglitch FSM outputs driving transceiver asynch inputs
gtXxreset = Signal()
Xxdlysreset = Signal()
Xxuserrdy = Signal()
self.sync += [
self.gtXxreset.eq(gtXxreset),
self.Xxdlysreset.eq(Xxdlysreset),
self.Xxuserrdy.eq(Xxuserrdy)
]
# After configuration, transceiver resets have to stay low for
# at least 500ns (see AR43482)
startup_cycles = ceil(500*sys_clk_freq/1000000000)
startup_timer = WaitTimer(startup_cycles)
self.submodules += startup_timer
startup_fsm = FSM(reset_state="INITIAL")
self.submodules += startup_fsm
if rx:
cdr_stable_timer = WaitTimer(1024)
self.submodules += cdr_stable_timer
Xxphaligndone_r = Signal(reset=1)
Xxphaligndone_rising = Signal()
self.sync += Xxphaligndone_r.eq(Xxphaligndone)
self.comb += Xxphaligndone_rising.eq(Xxphaligndone & ~Xxphaligndone_r)
startup_fsm.act("INITIAL",
startup_timer.wait.eq(1),
If(startup_timer.done, NextState("RESET_GTX"))
)
startup_fsm.act("RESET_GTX",
gtXxreset.eq(1),
NextState("WAIT_CPLL")
)
startup_fsm.act("WAIT_CPLL",
gtXxreset.eq(1),
If(cplllock, NextState("RELEASE_RESET"))
)
# Release GTX reset and wait for GTX resetdone
# (from UG476, GTX is reset on falling edge
# of gttxreset)
if rx:
startup_fsm.act("RELEASE_RESET",
Xxuserrdy.eq(1),
cdr_stable_timer.wait.eq(1),
If(Xxresetdone & cdr_stable_timer.done, NextState("ALIGN"))
)
else:
startup_fsm.act("RELEASE_RESET",
Xxuserrdy.eq(1),
If(Xxresetdone, NextState("ALIGN"))
)
# Start delay alignment (pulse)
startup_fsm.act("ALIGN",
Xxuserrdy.eq(1),
Xxdlysreset.eq(1),
NextState("WAIT_ALIGN")
)
# Wait for delay alignment
startup_fsm.act("WAIT_ALIGN",
Xxuserrdy.eq(1),
If(Xxdlysresetdone, NextState("WAIT_FIRST_ALIGN_DONE"))
)
# Wait 2 rising edges of rxphaligndone
# (from UG476 in buffer bypass config)
startup_fsm.act("WAIT_FIRST_ALIGN_DONE",
Xxuserrdy.eq(1),
If(Xxphaligndone_rising, NextState("WAIT_SECOND_ALIGN_DONE"))
)
startup_fsm.act("WAIT_SECOND_ALIGN_DONE",
Xxuserrdy.eq(1),
If(Xxphaligndone_rising, NextState("READY"))
)
startup_fsm.act("READY",
Xxuserrdy.eq(1),
self.done.eq(1),
If(self.restart, NextState("RESET_GTX"))
)
# Changes the phase of the transceiver RX clock to align the comma to
# the LSBs of RXDATA, fixing the latency.
#
# This is implemented by repeatedly resetting the transceiver until it
# gives out the correct phase. Each reset gives a random phase.
#
# If Xilinx had designed the GTX transceiver correctly, RXSLIDE_MODE=PMA
# would achieve this faster and in a cleaner way. But:
# * the phase jumps are of 2 UI at every second RXSLIDE pulse, instead
# of 1 UI at every pulse. It is unclear what the latency becomes.
# * RXSLIDE_MODE=PMA cannot be used with the RX buffer bypassed.
# Those design flaws make RXSLIDE_MODE=PMA yet another broken and useless
# transceiver "feature".
#
# Warning: Xilinx transceivers are LSB first, and comma needs to be flipped
# compared to the usual 8b10b binary representation.
class BruteforceClockAligner(Module):
def __init__(self, comma, rtio_clk_freq, check_period=6e-3):
self.rxdata = Signal(20)
self.restart = Signal()
self.ready = Signal()
check_max_val = ceil(check_period*rtio_clk_freq)
check_counter = Signal(max=check_max_val+1)
check = Signal()
reset_check_counter = Signal()
self.sync.rtio += [
check.eq(0),
If(reset_check_counter,
check_counter.eq(check_max_val)
).Else(
If(check_counter == 0,
check.eq(1),
check_counter.eq(check_max_val)
).Else(
check_counter.eq(check_counter-1)
)
)
]
checks_reset = PulseSynchronizer("rtio", "rtio_rx")
self.submodules += checks_reset
comma_n = ~comma & 0b1111111111
comma_seen_rxclk = Signal()
comma_seen = Signal()
comma_seen_rxclk.attr.add("no_retiming")
self.specials += MultiReg(comma_seen_rxclk, comma_seen)
self.sync.rtio_rx += \
If(checks_reset.o,
comma_seen_rxclk.eq(0)
).Elif((self.rxdata[:10] == comma) | (self.rxdata[:10] == comma_n),
comma_seen_rxclk.eq(1)
)
error_seen_rxclk = Signal()
error_seen = Signal()
error_seen_rxclk.attr.add("no_retiming")
self.specials += MultiReg(error_seen_rxclk, error_seen)
rx1cnt = Signal(max=11)
self.sync.rtio_rx += [
rx1cnt.eq(reduce(add, [self.rxdata[i] for i in range(10)])),
If(checks_reset.o,
error_seen_rxclk.eq(0)
).Elif((rx1cnt != 4) & (rx1cnt != 5) & (rx1cnt != 6),
error_seen_rxclk.eq(1)
)
]
fsm = ClockDomainsRenamer("rtio")(FSM(reset_state="WAIT_COMMA"))
self.submodules += fsm
fsm.act("WAIT_COMMA",
If(check,
# Errors are still OK at this stage, as the transceiver
# has just been reset and may output garbage data.
If(comma_seen,
NextState("WAIT_NOERROR")
).Else(
self.restart.eq(1)
),
checks_reset.i.eq(1)
)
)
fsm.act("WAIT_NOERROR",
If(check,
If(comma_seen & ~error_seen,
NextState("READY")
).Else(
self.restart.eq(1),
NextState("WAIT_COMMA")
),
checks_reset.i.eq(1)
)
)
fsm.act("READY",
reset_check_counter.eq(1),
self.ready.eq(1),
If(error_seen,
checks_reset.i.eq(1),
self.restart.eq(1),
NextState("WAIT_COMMA")
)
)

View File

@ -0,0 +1,116 @@
#!/usr/bin/env python3
import argparse
from migen import *
from migen.build.generic_platform import *
from misoc.cores import spi as spi_csr
from misoc.targets.kc705 import MiniSoC, soc_kc705_args, soc_kc705_argdict
from misoc.integration.builder import builder_args, builder_argdict
from artiq.gateware.amp import AMPSoC, build_artiq_soc
from artiq.gateware import rtio
from artiq.gateware.rtio.phy import ttl_simple
from artiq.gateware.drtio.transceiver import gtx_7series
from artiq.gateware.drtio import DRTIOMaster
from artiq import __version__ as artiq_version
class Master(MiniSoC, AMPSoC):
mem_map = {
"cri_con": 0x10000000,
"rtio": 0x20000000,
"rtio_dma": 0x30000000,
"drtio_aux": 0x50000000,
"mailbox": 0x70000000
}
mem_map.update(MiniSoC.mem_map)
def __init__(self, **kwargs):
MiniSoC.__init__(self,
cpu_type="or1k",
sdram_controller_type="minicon",
l2_size=128*1024,
ident=artiq_version,
ethmac_nrxslots=4,
ethmac_ntxslots=4,
**kwargs)
AMPSoC.__init__(self)
platform = self.platform
self.comb += platform.request("sfp_tx_disable_n").eq(1)
tx_pads = platform.request("sfp_tx")
rx_pads = platform.request("sfp_rx")
# 1000BASE_BX10 Ethernet compatible, 62.5MHz RTIO clock
self.submodules.transceiver = gtx_7series.GTX_1000BASE_BX10(
clock_pads=platform.request("sgmii_clock"),
tx_pads=tx_pads,
rx_pads=rx_pads,
sys_clk_freq=self.clk_freq,
clock_div2=True)
self.submodules.drtio0 = ClockDomainsRenamer({"rtio_rx": "rtio_rx0"})(
DRTIOMaster(self.transceiver.channels[0]))
self.csr_devices.append("drtio0")
self.add_wb_slave(self.mem_map["drtio_aux"], 0x800,
self.drtio0.aux_controller.bus)
self.add_memory_region("drtio0_aux", self.mem_map["drtio_aux"] | self.shadow_base, 0x800)
self.config["HAS_DRTIO"] = None
self.add_csr_group("drtio", ["drtio0"])
self.add_memory_group("drtio_aux", ["drtio0_aux"])
self.comb += [
platform.request("user_sma_clock_p").eq(ClockSignal("rtio_rx0")),
platform.request("user_sma_clock_n").eq(ClockSignal("rtio"))
]
rtio_clk_period = 1e9/self.transceiver.rtio_clk_freq
platform.add_period_constraint(self.transceiver.txoutclk, rtio_clk_period)
platform.add_period_constraint(self.transceiver.rxoutclk, rtio_clk_period)
platform.add_false_path_constraints(
self.crg.cd_sys.clk,
self.transceiver.txoutclk, self.transceiver.rxoutclk)
rtio_channels = []
for i in range(8):
phy = ttl_simple.Output(platform.request("user_led", i))
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(phy))
for sma in "user_sma_gpio_p", "user_sma_gpio_n":
phy = ttl_simple.InOut(platform.request(sma))
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(phy))
self.submodules.rtio_moninj = rtio.MonInj(rtio_channels)
self.csr_devices.append("rtio_moninj")
self.submodules.rtio_core = rtio.Core(rtio_channels, 3)
self.csr_devices.append("rtio_core")
self.submodules.rtio = rtio.KernelInitiator()
self.submodules.rtio_dma = ClockDomainsRenamer("sys_kernel")(
rtio.DMA(self.get_native_sdram_if()))
self.register_kernel_cpu_csrdevice("rtio")
self.register_kernel_cpu_csrdevice("rtio_dma")
self.submodules.cri_con = rtio.CRIInterconnectShared(
[self.rtio.cri, self.rtio_dma.cri],
[self.rtio_core.cri, self.drtio0.cri])
self.register_kernel_cpu_csrdevice("cri_con")
def main():
parser = argparse.ArgumentParser(
description="ARTIQ device binary builder / KC705 DRTIO master")
builder_args(parser)
soc_kc705_args(parser)
args = parser.parse_args()
soc = Master(**soc_kc705_argdict(args))
build_artiq_soc(soc, builder_argdict(args))
if __name__ == "__main__":
main()

View File

@ -0,0 +1,114 @@
#!/usr/bin/env python3
import argparse
import os
from migen import *
from migen.build.generic_platform import *
from misoc.cores import spi as spi_csr
from misoc.cores import gpio
from misoc.integration.builder import *
from misoc.targets.kc705 import BaseSoC, soc_kc705_args, soc_kc705_argdict
from artiq.gateware import rtio
from artiq.gateware.rtio.phy import ttl_simple
from artiq.gateware.drtio.transceiver import gtx_7series
from artiq.gateware.drtio import DRTIOSatellite
from artiq import __version__ as artiq_version
from artiq import __artiq_dir__ as artiq_dir
class Satellite(BaseSoC):
mem_map = {
"drtio_aux": 0x50000000,
}
mem_map.update(BaseSoC.mem_map)
def __init__(self, **kwargs):
BaseSoC.__init__(self,
cpu_type="or1k",
sdram_controller_type="minicon",
l2_size=128*1024,
ident=artiq_version,
**kwargs)
platform = self.platform
rtio_channels = []
for i in range(8):
phy = ttl_simple.Output(platform.request("user_led", i))
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(phy))
for sma in "user_sma_gpio_p", "user_sma_gpio_n":
phy = ttl_simple.InOut(platform.request(sma))
self.submodules += phy
rtio_channels.append(rtio.Channel.from_phy(phy))
self.submodules.rtio_moninj = rtio.MonInj(rtio_channels)
self.csr_devices.append("rtio_moninj")
self.comb += platform.request("sfp_tx_disable_n").eq(1)
# 1000BASE_BX10 Ethernet compatible, 62.5MHz RTIO clock
self.submodules.transceiver = gtx_7series.GTX_1000BASE_BX10(
clock_pads=platform.request("si5324_clkout"),
tx_pads=platform.request("sfp_tx"),
rx_pads=platform.request("sfp_rx"),
sys_clk_freq=self.clk_freq)
rx0 = ClockDomainsRenamer({"rtio_rx": "rtio_rx0"})
self.submodules.rx_synchronizer0 = rx0(gtx_7series.RXSynchronizer(
self.transceiver.rtio_clk_freq, initial_phase=180.0))
self.submodules.drtio0 = rx0(DRTIOSatellite(
self.transceiver.channels[0], rtio_channels, self.rx_synchronizer0))
self.csr_devices.append("rx_synchronizer0")
self.csr_devices.append("drtio0")
self.add_wb_slave(self.mem_map["drtio_aux"], 0x800,
self.drtio0.aux_controller.bus)
self.add_memory_region("drtio0_aux", self.mem_map["drtio_aux"] | self.shadow_base, 0x800)
self.config["HAS_DRTIO"] = None
self.add_csr_group("drtio", ["drtio0"])
self.add_memory_group("drtio_aux", ["drtio0_aux"])
self.config["RTIO_FREQUENCY"] = str(self.transceiver.rtio_clk_freq/1e6)
si5324_clkin = platform.request("si5324_clkin")
self.specials += \
Instance("OBUFDS",
i_I=ClockSignal("rtio_rx0"),
o_O=si5324_clkin.p, o_OB=si5324_clkin.n
)
self.submodules.si5324_rst_n = gpio.GPIOOut(platform.request("si5324").rst_n)
self.csr_devices.append("si5324_rst_n")
i2c = self.platform.request("i2c")
self.submodules.i2c = gpio.GPIOTristate([i2c.scl, i2c.sda])
self.csr_devices.append("i2c")
self.config["I2C_BUS_COUNT"] = 1
self.config["HAS_SI5324"] = None
self.comb += [
platform.request("user_sma_clock_p").eq(ClockSignal("rtio_rx0")),
platform.request("user_sma_clock_n").eq(ClockSignal("rtio"))
]
rtio_clk_period = 1e9/self.transceiver.rtio_clk_freq
platform.add_period_constraint(self.transceiver.txoutclk, rtio_clk_period)
platform.add_period_constraint(self.transceiver.rxoutclk, rtio_clk_period)
platform.add_false_path_constraints(
platform.lookup_request("clk200"),
self.transceiver.txoutclk, self.transceiver.rxoutclk)
def main():
parser = argparse.ArgumentParser(
description="ARTIQ device binary builder / KC705 DRTIO satellite")
builder_args(parser)
soc_kc705_args(parser)
args = parser.parse_args()
soc = Satellite(**soc_kc705_argdict(args))
builder = Builder(soc, **builder_argdict(args))
builder.add_software_package("satman", os.path.join(artiq_dir, "firmware", "satman"))
builder.build()
if __name__ == "__main__":
main()